Merge changes I92756522,I31487d03

* changes:
  Check that the end of the splines are continuous
  Follow multiple 6 splines
diff --git a/frc971/wpilib/ADIS16448.cc b/frc971/wpilib/ADIS16448.cc
index 3696e2f..6c4a6d1 100644
--- a/frc971/wpilib/ADIS16448.cc
+++ b/frc971/wpilib/ADIS16448.cc
@@ -1,6 +1,6 @@
 #include "frc971/wpilib/ADIS16448.h"
 
-#include "InterruptableSensorBase.h"
+#include "frc971/wpilib/ahal/InterruptableSensorBase.h"
 #undef ERROR
 
 #include <inttypes.h>
@@ -118,8 +118,8 @@
 
 }  // namespace
 
-ADIS16448::ADIS16448(SPI::Port port, DigitalInput *dio1)
-    : spi_(new SPI(port)), dio1_(dio1) {
+ADIS16448::ADIS16448(frc::SPI::Port port, frc::DigitalInput *dio1)
+    : spi_(new frc::SPI(port)), dio1_(dio1) {
   // 1MHz is the maximum supported for burst reads, but we
   // want to go slower to hopefully make it more reliable.
   spi_->SetClockRate(1e5);
@@ -132,8 +132,8 @@
   dio1_->SetUpSourceEdge(true, false);
 }
 
-void ADIS16448::SetDummySPI(SPI::Port port) {
-  dummy_spi_.reset(new SPI(port));
+void ADIS16448::SetDummySPI(frc::SPI::Port port) {
+  dummy_spi_.reset(new frc::SPI(port));
   // Pick the same settings here in case the roboRIO decides to try something
   // stupid when switching.
   if (dummy_spi_) {
@@ -168,8 +168,8 @@
 void ADIS16448::operator()() {
   // NI's SPI driver defaults to SCHED_OTHER.  Find it's PID with ps, and change
   // it to a RT priority of 33.
-  PCHECK(system(
-             "ps -ef | grep '\\[spi0\\]' | awk '{print $1}' | xargs chrt -f -p "
+  PCHECK(
+      system("ps -ef | grep '\\[spi0\\]' | awk '{print $1}' | xargs chrt -f -p "
              "33") == 0);
 
   ::aos::SetCurrentThreadName("IMU");
@@ -186,9 +186,9 @@
   bool got_an_interrupt = false;
   while (run_) {
     {
-      const InterruptableSensorBase::WaitResult result =
+      const frc::InterruptableSensorBase::WaitResult result =
           dio1_->WaitForInterrupt(0.1, !got_an_interrupt);
-      if (result == InterruptableSensorBase::kTimeout) {
+      if (result == frc::InterruptableSensorBase::kTimeout) {
         LOG(WARNING, "IMU read timed out\n");
         InitializeUntilSuccessful();
         continue;
@@ -209,7 +209,7 @@
     // scenario.
     if (!dio1_->Get() ||
         dio1_->WaitForInterrupt(0, false) !=
-            InterruptableSensorBase::kTimeout) {
+            frc::InterruptableSensorBase::kTimeout) {
       LOG(ERROR, "IMU read took too long\n");
       continue;
     }
diff --git a/frc971/wpilib/ADIS16448.h b/frc971/wpilib/ADIS16448.h
index 0d5c93a..a631fee 100644
--- a/frc971/wpilib/ADIS16448.h
+++ b/frc971/wpilib/ADIS16448.h
@@ -3,12 +3,12 @@
 
 #include <stdint.h>
 
-#include <memory>
 #include <atomic>
+#include <memory>
 
-#include "SPI.h"
-#include "DigitalInput.h"
-#include "DigitalOutput.h"
+#include "frc971/wpilib/ahal/DigitalInput.h"
+#include "frc971/wpilib/ahal/DigitalOutput.h"
+#include "frc971/wpilib/ahal/SPI.h"
 #undef ERROR
 
 #include "aos/logging/logging.h"
@@ -29,15 +29,15 @@
  public:
   // port is where to find the sensor over SPI.
   // dio1 must be connected to DIO1 on the sensor.
-  ADIS16448(SPI::Port port, DigitalInput *dio1);
+  ADIS16448(frc::SPI::Port port, frc::DigitalInput *dio1);
 
   // Sets the dummy SPI port to send values on to make the roboRIO deassert the
   // chip select line. This is mainly useful when there are no other devices
   // sharing the bus.
-  void SetDummySPI(SPI::Port port);
+  void SetDummySPI(frc::SPI::Port port);
 
   // Sets the reset line for the IMU to use for error recovery.
-  void set_reset(DigitalOutput *output) { reset_ = output; }
+  void set_reset(frc::DigitalOutput *output) { reset_ = output; }
 
   // For ::std::thread to call.
   //
@@ -84,10 +84,10 @@
   bool Initialize();
 
   // TODO(Brian): This object has no business owning these ones.
-  const ::std::unique_ptr<SPI> spi_;
-  ::std::unique_ptr<SPI> dummy_spi_;
-  DigitalInput *const dio1_;
-  DigitalOutput *reset_ = nullptr;
+  const ::std::unique_ptr<frc::SPI> spi_;
+  ::std::unique_ptr<frc::SPI> dummy_spi_;
+  frc::DigitalInput *const dio1_;
+  frc::DigitalOutput *reset_ = nullptr;
 
   ::std::atomic<bool> run_{true};
 
diff --git a/frc971/wpilib/LPD8806.cc b/frc971/wpilib/LPD8806.cc
index d82e38f..6db54d5 100644
--- a/frc971/wpilib/LPD8806.cc
+++ b/frc971/wpilib/LPD8806.cc
@@ -2,7 +2,7 @@
 
 #include "frc971/queues/gyro.q.h"
 
-#include "SPI.h"
+#include "frc971/wpilib/ahal/SPI.h"
 #undef ERROR
 
 namespace frc971 {
@@ -11,7 +11,7 @@
 LPD8806::LPD8806(int chips)
     : chips_(chips),
       data_(new LED[chips * 2]),
-      spi_(new SPI(SPI::kOnboardCS1)) {
+      spi_(new frc::SPI(frc::SPI::kOnboardCS1)) {
   memset(data_.get(), 0, sizeof(LED[chips_ * 2]));
 
   // 2 MHz is the maximum frequency the datasheet recommends.
diff --git a/frc971/wpilib/LPD8806.h b/frc971/wpilib/LPD8806.h
index 91915bf..697f180 100644
--- a/frc971/wpilib/LPD8806.h
+++ b/frc971/wpilib/LPD8806.h
@@ -1,12 +1,12 @@
 #ifndef FRC971_WPILIB_LPD8806_H_
 #define FRC971_WPILIB_LPD8806_H_
 
-#include <memory>
 #include <atomic>
+#include <memory>
 
 #include "aos/mutex/mutex.h"
 
-#include "SPI.h"
+#include "frc971/wpilib/ahal/SPI.h"
 #undef ERROR
 
 namespace frc971 {
@@ -59,7 +59,7 @@
   ::std::unique_ptr<LED[]> data_;
   ::aos::Mutex data_mutex_;
 
-  ::std::unique_ptr<SPI> spi_;
+  ::std::unique_ptr<frc::SPI> spi_;
 
   ::std::atomic<bool> run_{true};
 };
diff --git a/frc971/wpilib/ahal/AnalogInput.cc b/frc971/wpilib/ahal/AnalogInput.cc
new file mode 100644
index 0000000..fc2e5a7
--- /dev/null
+++ b/frc971/wpilib/ahal/AnalogInput.cc
@@ -0,0 +1,266 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/AnalogInput.h"
+#include "HAL/AnalogInput.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Construct an analog input.
+ *
+ * @param channel The channel number on the roboRIO to represent. 0-3 are
+ *                on-board 4-7 are on the MXP port.
+ */
+AnalogInput::AnalogInput(int channel) {
+  std::stringstream buf;
+  buf << "Analog Input " << channel;
+
+  if (!CheckAnalogInputChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_PortHandle port = HAL_GetPort(channel);
+  int32_t status = 0;
+  m_port = HAL_InitializeAnalogInputPort(port, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumAnalogInputs(), channel,
+                                 HAL_GetErrorMessage(status));
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogChannel, channel);
+}
+
+/**
+ * Channel destructor.
+ */
+AnalogInput::~AnalogInput() {
+  HAL_FreeAnalogInputPort(m_port);
+  m_port = HAL_kInvalidHandle;
+}
+
+/**
+ * Get a sample straight from this channel.
+ *
+ * The sample is a 12-bit value representing the 0V to 5V range of the A/D
+ * converter in the module.  The units are in A/D converter codes.  Use
+ * GetVoltage() to get the analog value in calibrated units.
+ *
+ * @return A sample straight from this channel.
+ */
+int AnalogInput::GetValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogValue(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Get a sample from the output of the oversample and average engine for this
+ * channel.
+ *
+ * The sample is 12-bit + the bits configured in SetOversampleBits().
+ * The value configured in SetAverageBits() will cause this value to be averaged
+ * 2**bits number of samples.
+ * This is not a sliding window.  The sample will not change until
+ * 2**(OversampleBits + AverageBits) samples
+ * have been acquired from the module on this channel.
+ * Use GetAverageVoltage() to get the analog value in calibrated units.
+ *
+ * @return A sample from the oversample and average engine for this channel.
+ */
+int AnalogInput::GetAverageValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogAverageValue(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Get a scaled sample straight from this channel.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from
+ * GetLSBWeight() and GetOffset().
+ *
+ * @return A scaled sample straight from this channel.
+ */
+double AnalogInput::GetVoltage() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogVoltage(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return voltage;
+}
+
+/**
+ * Get a scaled sample from the output of the oversample and average engine for
+ * this channel.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from
+ * GetLSBWeight() and GetOffset().
+ * Using oversampling will cause this value to be higher resolution, but it will
+ * update more slowly.
+ * Using averaging will cause this value to be more stable, but it will update
+ * more slowly.
+ *
+ * @return A scaled sample from the output of the oversample and average engine
+ * for this channel.
+ */
+double AnalogInput::GetAverageVoltage() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogAverageVoltage(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return voltage;
+}
+
+/**
+ * Get the factory scaling least significant bit weight constant.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @return Least significant bit weight.
+ */
+int AnalogInput::GetLSBWeight() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return lsbWeight;
+}
+
+/**
+ * Get the factory scaling offset constant.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @return Offset constant.
+ */
+int AnalogInput::GetOffset() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int offset = HAL_GetAnalogOffset(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return offset;
+}
+
+/**
+ * Get the channel number.
+ *
+ * @return The channel number.
+ */
+int AnalogInput::GetChannel() const {
+  if (StatusIsFatal()) return 0;
+  return m_channel;
+}
+
+/**
+ * Set the number of averaging bits.
+ *
+ * This sets the number of averaging bits. The actual number of averaged samples
+ * is 2^bits.
+ * Use averaging to improve the stability of your measurement at the expense of
+ * sampling rate.
+ * The averaging is done automatically in the FPGA.
+ *
+ * @param bits Number of bits of averaging.
+ */
+void AnalogInput::SetAverageBits(int bits) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogAverageBits(m_port, bits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Get the number of averaging bits previously configured.
+ *
+ * This gets the number of averaging bits from the FPGA. The actual number of
+ * averaged samples is 2^bits. The averaging is done automatically in the FPGA.
+ *
+ * @return Number of bits of averaging previously configured.
+ */
+int AnalogInput::GetAverageBits() const {
+  int32_t status = 0;
+  int averageBits = HAL_GetAnalogAverageBits(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return averageBits;
+}
+
+/**
+ * Set the number of oversample bits.
+ *
+ * This sets the number of oversample bits. The actual number of oversampled
+ * values is 2^bits. Use oversampling to improve the resolution of your
+ * measurements at the expense of sampling rate. The oversampling is done
+ * automatically in the FPGA.
+ *
+ * @param bits Number of bits of oversampling.
+ */
+void AnalogInput::SetOversampleBits(int bits) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogOversampleBits(m_port, bits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Get the number of oversample bits previously configured.
+ *
+ * This gets the number of oversample bits from the FPGA. The actual number of
+ * oversampled values is 2^bits. The oversampling is done automatically in the
+ * FPGA.
+ *
+ * @return Number of bits of oversampling previously configured.
+ */
+int AnalogInput::GetOversampleBits() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int oversampleBits = HAL_GetAnalogOversampleBits(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return oversampleBits;
+}
+
+/**
+ * Set the sample rate per channel for all analog channels.
+ *
+ * The maximum rate is 500kS/s divided by the number of channels in use.
+ * This is 62500 samples/s per channel.
+ *
+ * @param samplesPerSecond The number of samples per second.
+ */
+void AnalogInput::SetSampleRate(double samplesPerSecond) {
+  int32_t status = 0;
+  HAL_SetAnalogSampleRate(samplesPerSecond, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Get the current sample rate for all channels
+ *
+ * @return Sample rate.
+ */
+double AnalogInput::GetSampleRate() {
+  int32_t status = 0;
+  double sampleRate = HAL_GetAnalogSampleRate(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return sampleRate;
+}
diff --git a/frc971/wpilib/ahal/AnalogInput.h b/frc971/wpilib/ahal/AnalogInput.h
new file mode 100644
index 0000000..5398eec
--- /dev/null
+++ b/frc971/wpilib/ahal/AnalogInput.h
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "HAL/Types.h"
+#include "frc971/wpilib/ahal/SensorBase.h"
+
+namespace frc {
+
+/**
+ * Analog input class.
+ *
+ * Connected to each analog channel is an averaging and oversampling engine.
+ * This engine accumulates the specified ( by SetAverageBits() and
+ * SetOversampleBits() ) number of samples before returning a new value.  This
+ * is not a sliding window average.  The only difference between the oversampled
+ * samples and the averaged samples is that the oversampled samples are simply
+ * accumulated effectively increasing the resolution, while the averaged samples
+ * are divided by the number of samples to retain the resolution, but get more
+ * stable values.
+ */
+class AnalogInput {
+  friend class AnalogTrigger;
+  friend class AnalogGyro;
+
+ public:
+  explicit AnalogInput(int channel);
+  virtual ~AnalogInput();
+
+  int GetValue() const;
+  int GetAverageValue() const;
+
+  double GetVoltage() const;
+  double GetAverageVoltage() const;
+
+  int GetChannel() const;
+
+  void SetAverageBits(int bits);
+  int GetAverageBits() const;
+  void SetOversampleBits(int bits);
+  int GetOversampleBits() const;
+
+  int GetLSBWeight() const;
+  int GetOffset() const;
+
+  static void SetSampleRate(double samplesPerSecond);
+  static double GetSampleRate();
+
+ private:
+  int m_channel;
+  HAL_AnalogInputHandle m_port;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/AnalogTrigger.cc b/frc971/wpilib/ahal/AnalogTrigger.cc
new file mode 100644
index 0000000..c9028ae
--- /dev/null
+++ b/frc971/wpilib/ahal/AnalogTrigger.cc
@@ -0,0 +1,186 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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 "frc971/wpilib/ahal/AnalogTrigger.h"
+
+#include <memory>
+
+#include <HAL/HAL.h>
+
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Constructor for an analog trigger given a channel number.
+ *
+ * @param channel The channel number on the roboRIO to represent. 0-3 are
+ *                on-board 4-7 are on the MXP port.
+ */
+AnalogTrigger::AnalogTrigger(int channel)
+    : AnalogTrigger(new AnalogInput(channel)) {
+  m_ownsAnalog = true;
+}
+
+/**
+ * Construct an analog trigger given an analog input.
+ *
+ * This should be used in the case of sharing an analog channel between the
+ * trigger and an analog input object.
+ *
+ * @param channel The pointer to the existing AnalogInput object
+ */
+AnalogTrigger::AnalogTrigger(AnalogInput *input) {
+  m_analogInput = input;
+  int32_t status = 0;
+  int index = 0;
+  m_trigger = HAL_InitializeAnalogTrigger(input->m_port, &index, &status);
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    m_index = std::numeric_limits<int>::max();
+    m_trigger = HAL_kInvalidHandle;
+    return;
+  }
+  m_index = index;
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, input->m_channel);
+}
+
+AnalogTrigger::~AnalogTrigger() {
+  int32_t status = 0;
+  HAL_CleanAnalogTrigger(m_trigger, &status);
+
+  if (m_ownsAnalog && m_analogInput != nullptr) {
+    delete m_analogInput;
+  }
+}
+
+/**
+ * Set the upper and lower limits of the analog trigger.
+ *
+ * The limits are given in ADC codes.  If oversampling is used, the units must
+ * be scaled appropriately.
+ *
+ * @param lower The lower limit of the trigger in ADC codes (12-bit values).
+ * @param upper The upper limit of the trigger in ADC codes (12-bit values).
+ */
+void AnalogTrigger::SetLimitsRaw(int lower, int upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsRaw(m_trigger, lower, upper, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the upper and lower limits of the analog trigger.
+ *
+ * The limits are given as floating point voltage values.
+ *
+ * @param lower The lower limit of the trigger in Volts.
+ * @param upper The upper limit of the trigger in Volts.
+ */
+void AnalogTrigger::SetLimitsVoltage(double lower, double upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsVoltage(m_trigger, lower, upper, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Configure the analog trigger to use the averaged vs. raw values.
+ *
+ * If the value is true, then the averaged value is selected for the analog
+ * trigger, otherwise the immediate value is used.
+ *
+ * @param useAveragedValue If true, use the Averaged value, otherwise use the
+ *                         instantaneous reading
+ */
+void AnalogTrigger::SetAveraged(bool useAveragedValue) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerAveraged(m_trigger, useAveragedValue, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Configure the analog trigger to use a filtered value.
+ *
+ * The analog trigger will operate with a 3 point average rejection filter. This
+ * is designed to help with 360 degree pot applications for the period where
+ * the pot crosses through zero.
+ *
+ * @param useFilteredValue If true, use the 3 point rejection filter, otherwise
+ *                         use the unfiltered value
+ */
+void AnalogTrigger::SetFiltered(bool useFilteredValue) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerFiltered(m_trigger, useFilteredValue, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Return the index of the analog trigger.
+ *
+ * This is the FPGA index of this analog trigger instance.
+ *
+ * @return The index of the analog trigger.
+ */
+int AnalogTrigger::GetIndex() const {
+  if (StatusIsFatal()) return -1;
+  return m_index;
+}
+
+/**
+ * Return the InWindow output of the analog trigger.
+ *
+ * True if the analog input is between the upper and lower limits.
+ *
+ * @return True if the analog input is between the upper and lower limits.
+ */
+bool AnalogTrigger::GetInWindow() {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerInWindow(m_trigger, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return result;
+}
+
+/**
+ * Return the TriggerState output of the analog trigger.
+ *
+ * True if above upper limit.
+ * False if below lower limit.
+ * If in Hysteresis, maintain previous state.
+ *
+ * @return True if above upper limit. False if below lower limit. If in
+ *         Hysteresis, maintain previous state.
+ */
+bool AnalogTrigger::GetTriggerState() {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerTriggerState(m_trigger, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return result;
+}
+
+/**
+ * Creates an AnalogTriggerOutput object.
+ *
+ * Gets an output object that can be used for routing.
+ * Caller is responsible for deleting the AnalogTriggerOutput object.
+ *
+ * @param type An enum of the type of output object to create.
+ * @return A pointer to a new AnalogTriggerOutput object.
+ */
+std::shared_ptr<AnalogTriggerOutput> AnalogTrigger::CreateOutput(
+    AnalogTriggerType type) const {
+  if (StatusIsFatal()) return nullptr;
+  return std::shared_ptr<AnalogTriggerOutput>(
+      new AnalogTriggerOutput(*this, type), NullDeleter<AnalogTriggerOutput>());
+}
diff --git a/frc971/wpilib/ahal/AnalogTrigger.h b/frc971/wpilib/ahal/AnalogTrigger.h
new file mode 100644
index 0000000..7b6fc92
--- /dev/null
+++ b/frc971/wpilib/ahal/AnalogTrigger.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "HAL/Types.h"
+#include "frc971/wpilib/ahal/AnalogTriggerOutput.h"
+#include "frc971/wpilib/ahal/SensorBase.h"
+
+namespace frc {
+
+class AnalogInput;
+
+class AnalogTrigger {
+  friend class AnalogTriggerOutput;
+
+ public:
+  explicit AnalogTrigger(int channel);
+  explicit AnalogTrigger(AnalogInput *channel);
+  virtual ~AnalogTrigger();
+
+  void SetLimitsVoltage(double lower, double upper);
+  void SetLimitsRaw(int lower, int upper);
+  void SetAveraged(bool useAveragedValue);
+  void SetFiltered(bool useFilteredValue);
+  int GetIndex() const;
+  bool GetInWindow();
+  bool GetTriggerState();
+  std::shared_ptr<AnalogTriggerOutput> CreateOutput(
+      AnalogTriggerType type) const;
+
+ private:
+  int m_index;
+  HAL_AnalogTriggerHandle m_trigger;
+  AnalogInput *m_analogInput = nullptr;
+  bool m_ownsAnalog = false;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/AnalogTriggerOutput.cc b/frc971/wpilib/ahal/AnalogTriggerOutput.cc
new file mode 100644
index 0000000..bdc47b6
--- /dev/null
+++ b/frc971/wpilib/ahal/AnalogTriggerOutput.cc
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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 "frc971/wpilib/ahal/AnalogTriggerOutput.h"
+
+#include <HAL/HAL.h>
+
+#include "frc971/wpilib/ahal/AnalogTrigger.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Create an object that represents one of the four outputs from an analog
+ * trigger.
+ *
+ * Because this class derives from DigitalSource, it can be passed into routing
+ * functions for Counter, Encoder, etc.
+ *
+ * @param trigger    A pointer to the trigger for which this is an output.
+ * @param outputType An enum that specifies the output on the trigger to
+ *                   represent.
+ */
+AnalogTriggerOutput::AnalogTriggerOutput(const AnalogTrigger &trigger,
+                                         AnalogTriggerType outputType)
+    : m_trigger(trigger), m_outputType(outputType) {
+  HAL_Report(HALUsageReporting::kResourceType_AnalogTriggerOutput,
+             trigger.GetIndex(), static_cast<uint8_t>(outputType));
+}
+
+AnalogTriggerOutput::~AnalogTriggerOutput() {
+  if (m_interrupt != HAL_kInvalidHandle) {
+    int32_t status = 0;
+    HAL_CleanInterrupts(m_interrupt, &status);
+    // ignore status, as an invalid handle just needs to be ignored.
+    m_interrupt = HAL_kInvalidHandle;
+  }
+}
+
+/**
+ * Get the state of the analog trigger output.
+ *
+ * @return The state of the analog trigger output.
+ */
+bool AnalogTriggerOutput::Get() const {
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerOutput(
+      m_trigger.m_trigger, static_cast<HAL_AnalogTriggerType>(m_outputType),
+      &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return result;
+}
+
+/**
+ * @return The HAL Handle to the specified source.
+ */
+HAL_Handle AnalogTriggerOutput::GetPortHandleForRouting() const {
+  return m_trigger.m_trigger;
+}
+
+/**
+ * Is source an AnalogTrigger
+ */
+bool AnalogTriggerOutput::IsAnalogTrigger() const { return true; }
+
+/**
+ * @return The type of analog trigger output to be used.
+ */
+AnalogTriggerType AnalogTriggerOutput::GetAnalogTriggerTypeForRouting() const {
+  return m_outputType;
+}
+
+/**
+ * @return The channel of the source.
+ */
+int AnalogTriggerOutput::GetChannel() const { return m_trigger.m_index; }
diff --git a/frc971/wpilib/ahal/AnalogTriggerOutput.h b/frc971/wpilib/ahal/AnalogTriggerOutput.h
new file mode 100644
index 0000000..0ddaae0
--- /dev/null
+++ b/frc971/wpilib/ahal/AnalogTriggerOutput.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HAL/AnalogTrigger.h"
+#include "frc971/wpilib/ahal/DigitalSource.h"
+
+namespace frc {
+
+class AnalogTrigger;
+
+/**
+ * Class to represent a specific output from an analog trigger.
+ *
+ * This class is used to get the current output value and also as a
+ * DigitalSource to provide routing of an output to digital subsystems on the
+ * FPGA such as Counter, Encoder, and Interrupt.
+ *
+ * The TriggerState output indicates the primary output value of the trigger.
+ * If the analog signal is less than the lower limit, the output is false. If
+ * the analog value is greater than the upper limit, then the output is true.
+ * If the analog value is in between, then the trigger output state maintains
+ * its most recent value.
+ *
+ * The InWindow output indicates whether or not the analog signal is inside the
+ * range defined by the limits.
+ *
+ * The RisingPulse and FallingPulse outputs detect an instantaneous transition
+ * from above the upper limit to below the lower limit, and vise versa. These
+ * pulses represent a rollover condition of a sensor and can be routed to an up
+ * / down counter or to interrupts. Because the outputs generate a pulse, they
+ * cannot be read directly. To help ensure that a rollover condition is not
+ * missed, there is an average rejection filter available that operates on the
+ * upper 8 bits of a 12 bit number and selects the nearest outlyer of 3 samples.
+ * This will reject a sample that is (due to averaging or sampling) errantly
+ * between the two limits. This filter will fail if more than one sample in a
+ * row is errantly in between the two limits. You may see this problem if
+ * attempting to use this feature with a mechanical rollover sensor, such as a
+ * 360 degree no-stop potentiometer without signal conditioning, because the
+ * rollover transition is not sharp / clean enough. Using the averaging engine
+ * may help with this, but rotational speeds of the sensor will then be limited.
+ */
+class AnalogTriggerOutput : public DigitalSource {
+  friend class AnalogTrigger;
+
+ public:
+  virtual ~AnalogTriggerOutput();
+  bool Get() const;
+
+  // DigitalSource interface
+  HAL_Handle GetPortHandleForRouting() const override;
+  AnalogTriggerType GetAnalogTriggerTypeForRouting() const override;
+  bool IsAnalogTrigger() const override;
+  int GetChannel() const override;
+
+ protected:
+  AnalogTriggerOutput(const AnalogTrigger &trigger,
+                      AnalogTriggerType outputType);
+
+ private:
+  // Uses reference rather than smart pointer because a user can not construct
+  // an AnalogTriggerOutput themselves and because the AnalogTriggerOutput
+  // should always be in scope at the same time as an AnalogTrigger.
+  const AnalogTrigger &m_trigger;
+  AnalogTriggerType m_outputType;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/AnalogTriggerType.h b/frc971/wpilib/ahal/AnalogTriggerType.h
new file mode 100644
index 0000000..9105e99
--- /dev/null
+++ b/frc971/wpilib/ahal/AnalogTriggerType.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+enum class AnalogTriggerType {
+  kInWindow = 0,
+  kState = 1,
+  kRisingPulse = 2,
+  kFallingPulse = 3
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/BUILD b/frc971/wpilib/ahal/BUILD
new file mode 100644
index 0000000..f643f57
--- /dev/null
+++ b/frc971/wpilib/ahal/BUILD
@@ -0,0 +1,24 @@
+genrule(
+    name = "wpilib_version",
+    outs = ["WPILibVersion.cc"],
+    cmd = "\n".join([
+        "cat > \"$@\" << EOF",
+        "// Autogenerated file! Do not manually edit this file.",
+        "#include \"frc971/wpilib/ahal/WPILibVersion.h\"",
+        "const char *WPILibVersion = \"2018-frc971\";",
+        "EOF",
+    ]),
+)
+
+cc_library(
+    name = "ahal",
+    srcs = glob(["*.cc"]) + [":wpilib_version"],
+    hdrs = glob(["*.h"]),
+    linkopts = ["-lpthread"],
+    restricted_to = ["//tools:roborio"],
+    visibility = ["//third_party:__pkg__"],
+    deps = [
+        "//aos/logging",
+        "//third_party:wpilib_hal",
+    ],
+)
diff --git a/frc971/wpilib/ahal/Base.h b/frc971/wpilib/ahal/Base.h
new file mode 100644
index 0000000..3a3d5a2
--- /dev/null
+++ b/frc971/wpilib/ahal/Base.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HAL/cpp/make_unique.h"
+
+namespace frc {
+
+// A struct to use as a deleter when a std::shared_ptr must wrap a raw pointer
+// that is being deleted by someone else.
+template <class T>
+struct NullDeleter {
+  void operator()(T *) const noexcept {};
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/Compressor.cc b/frc971/wpilib/ahal/Compressor.cc
new file mode 100644
index 0000000..2967f05
--- /dev/null
+++ b/frc971/wpilib/ahal/Compressor.cc
@@ -0,0 +1,299 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2017. 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 "frc971/wpilib/ahal/Compressor.h"
+#include "HAL/Compressor.h"
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "HAL/Solenoid.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Constructor.
+ *
+ * @param module The PCM ID to use (0-62)
+ */
+Compressor::Compressor(int pcmID) : m_module(pcmID) {
+  int32_t status = 0;
+  m_compressorHandle = HAL_InitializeCompressor(m_module, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumPCMModules(), pcmID,
+                                 HAL_GetErrorMessage(status));
+    return;
+  }
+  SetClosedLoopControl(true);
+}
+
+/**
+ * Starts closed-loop control. Note that closed loop control is enabled by
+ * default.
+ */
+void Compressor::Start() {
+  if (StatusIsFatal()) return;
+  SetClosedLoopControl(true);
+}
+
+/**
+ * Stops closed-loop control. Note that closed loop control is enabled by
+ * default.
+ */
+void Compressor::Stop() {
+  if (StatusIsFatal()) return;
+  SetClosedLoopControl(false);
+}
+
+/**
+ * Check if compressor output is active.
+ *
+ * @return true if the compressor is on
+ */
+bool Compressor::Enabled() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressor(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Check if the pressure switch is triggered.
+ *
+ * @return true if pressure is low
+ */
+bool Compressor::GetPressureSwitchValue() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorPressureSwitch(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query how much current the compressor is drawing.
+ *
+ * @return The current through the compressor, in amps
+ */
+double Compressor::GetCompressorCurrent() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  double value;
+
+  value = HAL_GetCompressorCurrent(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Enables or disables automatically turning the compressor on when the
+ * pressure is low.
+ *
+ * @param on Set to true to enable closed loop control of the compressor. False
+ *           to disable.
+ */
+void Compressor::SetClosedLoopControl(bool on) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+
+  HAL_SetCompressorClosedLoopControl(m_compressorHandle, on, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+}
+
+/**
+ * Returns true if the compressor will automatically turn on when the
+ * pressure is low.
+ *
+ * @return True if closed loop control of the compressor is enabled. False if
+ *         disabled.
+ */
+bool Compressor::GetClosedLoopControl() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorClosedLoopControl(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query if the compressor output has been disabled due to high current draw.
+ *
+ * @return true if PCM is in fault state : Compressor Drive is
+ *         disabled due to compressor current being too high.
+ */
+bool Compressor::GetCompressorCurrentTooHighFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorCurrentTooHighFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query if the compressor output has been disabled due to high current draw
+ * (sticky).
+ *
+ * A sticky fault will not clear on device reboot, it must be cleared through
+ * code or the webdash.
+ *
+ * @return true if PCM sticky fault is set : Compressor Drive is
+ *         disabled due to compressor current being too high.
+ */
+bool Compressor::GetCompressorCurrentTooHighStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value =
+      HAL_GetCompressorCurrentTooHighStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query if the compressor output has been disabled due to a short circuit
+ * (sticky).
+ *
+ * A sticky fault will not clear on device reboot, it must be cleared through
+ * code or the webdash.
+ *
+ * @return true if PCM sticky fault is set : Compressor output
+ *         appears to be shorted.
+ */
+bool Compressor::GetCompressorShortedStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorShortedStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query if the compressor output has been disabled due to a short circuit.
+ *
+ * @return true if PCM is in fault state : Compressor output
+ *         appears to be shorted.
+ */
+bool Compressor::GetCompressorShortedFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorShortedFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query if the compressor output does not appear to be wired (sticky).
+ *
+ * A sticky fault will not clear on device reboot, it must be cleared through
+ * code or the webdash.
+ *
+ * @return true if PCM sticky fault is set : Compressor does not
+ *         appear to be wired, i.e. compressor is not drawing enough current.
+ */
+bool Compressor::GetCompressorNotConnectedStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorNotConnectedStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Query if the compressor output does not appear to be wired.
+ *
+ * @return true if PCM is in fault state : Compressor does not
+ *         appear to be wired, i.e. compressor is not drawing enough current.
+ */
+bool Compressor::GetCompressorNotConnectedFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorNotConnectedFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+/**
+ * Clear ALL sticky faults inside PCM that Compressor is wired to.
+ *
+ * If a sticky fault is set, then it will be persistently cleared.  Compressor
+ * drive maybe momentarily disable while flags are being cleared. Care should
+ * be taken to not call this too frequently, otherwise normal compressor
+ * functionality may be prevented.
+ *
+ * If no sticky faults are set then this call will have no effect.
+ */
+void Compressor::ClearAllPCMStickyFaults() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+
+  HAL_ClearAllPCMStickyFaults(m_module, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+}
diff --git a/frc971/wpilib/ahal/Compressor.h b/frc971/wpilib/ahal/Compressor.h
new file mode 100644
index 0000000..60e21d9
--- /dev/null
+++ b/frc971/wpilib/ahal/Compressor.h
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "HAL/Types.h"
+#include "frc971/wpilib/ahal/SensorBase.h"
+
+namespace frc {
+
+/**
+ * PCM compressor
+ */
+class Compressor {
+ public:
+  // Default PCM ID is 0
+  explicit Compressor(int pcmID = GetDefaultSolenoidModule());
+  virtual ~Compressor() = default;
+
+  void Start();
+  void Stop();
+  bool Enabled() const;
+
+  bool GetPressureSwitchValue() const;
+
+  double GetCompressorCurrent() const;
+
+  void SetClosedLoopControl(bool on);
+  bool GetClosedLoopControl() const;
+
+  bool GetCompressorCurrentTooHighFault() const;
+  bool GetCompressorCurrentTooHighStickyFault() const;
+  bool GetCompressorShortedStickyFault() const;
+  bool GetCompressorShortedFault() const;
+  bool GetCompressorNotConnectedStickyFault() const;
+  bool GetCompressorNotConnectedFault() const;
+  void ClearAllPCMStickyFaults();
+
+ protected:
+  HAL_CompressorHandle m_compressorHandle;
+
+ private:
+  void SetCompressor(bool on);
+  int m_module;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/ControllerPower.cc b/frc971/wpilib/ahal/ControllerPower.cc
new file mode 100644
index 0000000..e045fdc
--- /dev/null
+++ b/frc971/wpilib/ahal/ControllerPower.cc
@@ -0,0 +1,190 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011-2017. 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 "frc971/wpilib/ahal/ControllerPower.h"
+
+#include <stdint.h>
+
+#include "HAL/HAL.h"
+#include "HAL/Power.h"
+#include "frc971/wpilib/ahal/ErrorBase.h"
+
+using namespace frc;
+
+/**
+ * Get the input voltage to the robot controller.
+ *
+ * @return The controller input voltage value in Volts
+ */
+double ControllerPower::GetInputVoltage() {
+  int32_t status = 0;
+  double retVal = HAL_GetVinVoltage(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the input current to the robot controller.
+ *
+ * @return The controller input current value in Amps
+ */
+double ControllerPower::GetInputCurrent() {
+  int32_t status = 0;
+  double retVal = HAL_GetVinCurrent(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the voltage of the 6V rail.
+ *
+ * @return The controller 6V rail voltage value in Volts
+ */
+double ControllerPower::GetVoltage6V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the current output of the 6V rail.
+ *
+ * @return The controller 6V rail output current value in Amps
+ */
+double ControllerPower::GetCurrent6V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the enabled state of the 6V rail. The rail may be disabled due to a
+ * controller brownout, a short circuit on the rail, or controller over-voltage.
+ *
+ * @return The controller 6V rail enabled value. True for enabled.
+ */
+bool ControllerPower::GetEnabled6V() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the count of the total current faults on the 6V rail since the controller
+ * has booted.
+ *
+ * @return The number of faults.
+ */
+int ControllerPower::GetFaultCount6V() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the voltage of the 5V rail.
+ *
+ * @return The controller 5V rail voltage value in Volts
+ */
+double ControllerPower::GetVoltage5V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the current output of the 5V rail.
+ *
+ * @return The controller 5V rail output current value in Amps
+ */
+double ControllerPower::GetCurrent5V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the enabled state of the 5V rail. The rail may be disabled due to a
+ * controller brownout, a short circuit on the rail, or controller over-voltage.
+ *
+ * @return The controller 5V rail enabled value. True for enabled.
+ */
+bool ControllerPower::GetEnabled5V() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the count of the total current faults on the 5V rail since the controller
+ * has booted.
+ *
+ * @return The number of faults
+ */
+int ControllerPower::GetFaultCount5V() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the voltage of the 3.3V rail.
+ *
+ * @return The controller 3.3V rail voltage value in Volts
+ */
+double ControllerPower::GetVoltage3V3() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the current output of the 3.3V rail.
+ *
+ * @return The controller 3.3V rail output current value in Amps
+ */
+double ControllerPower::GetCurrent3V3() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the enabled state of the 3.3V rail. The rail may be disabled due to a
+ * controller brownout, a short circuit on the rail, or controller over-voltage.
+ *
+ * @return The controller 3.3V rail enabled value. True for enabled.
+ */
+bool ControllerPower::GetEnabled3V3() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Get the count of the total current faults on the 3.3V rail since the
+ * controller has booted.
+ *
+ * @return The number of faults
+ */
+int ControllerPower::GetFaultCount3V3() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
diff --git a/frc971/wpilib/ahal/ControllerPower.h b/frc971/wpilib/ahal/ControllerPower.h
new file mode 100644
index 0000000..f6b4720
--- /dev/null
+++ b/frc971/wpilib/ahal/ControllerPower.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2011-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+class ControllerPower {
+ public:
+  static double GetInputVoltage();
+  static double GetInputCurrent();
+  static double GetVoltage3V3();
+  static double GetCurrent3V3();
+  static bool GetEnabled3V3();
+  static int GetFaultCount3V3();
+  static double GetVoltage5V();
+  static double GetCurrent5V();
+  static bool GetEnabled5V();
+  static int GetFaultCount5V();
+  static double GetVoltage6V();
+  static double GetCurrent6V();
+  static bool GetEnabled6V();
+  static int GetFaultCount6V();
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/Counter.cc b/frc971/wpilib/ahal/Counter.cc
new file mode 100644
index 0000000..352904b
--- /dev/null
+++ b/frc971/wpilib/ahal/Counter.cc
@@ -0,0 +1,570 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/Counter.h"
+
+#include "HAL/HAL.h"
+#include "frc971/wpilib/ahal/AnalogTrigger.h"
+#include "frc971/wpilib/ahal/DigitalInput.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Create an instance of a counter where no sources are selected.
+ *
+ * They all must be selected by calling functions to specify the upsource and
+ * the downsource independently.
+ *
+ * This creates a ChipObject counter and initializes status variables
+ * appropriately.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param mode The counter mode
+ */
+Counter::Counter(Mode mode) {
+  int32_t status = 0;
+  m_counter = HAL_InitializeCounter((HAL_Counter_Mode)mode, &m_index, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  SetMaxPeriod(.5);
+
+  HAL_Report(HALUsageReporting::kResourceType_Counter, m_index, mode);
+}
+
+/**
+ * Create an instance of a counter from a Digital Source (such as a Digital
+ * Input).
+ *
+ * This is used if an existing digital input is to be shared by multiple other
+ * objects such as encoders or if the Digital Source is not a Digital Input
+ * channel (such as an Analog Trigger).
+ *
+ * The counter will start counting immediately.
+ * @param source A pointer to the existing DigitalSource object. It will be set
+ *               as the Up Source.
+ */
+Counter::Counter(DigitalSource *source) : Counter(kTwoPulse) {
+  SetUpSource(source);
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a counter from a Digital Source (such as a Digital
+ * Input).
+ *
+ * This is used if an existing digital input is to be shared by multiple other
+ * objects such as encoders or if the Digital Source is not a Digital Input
+ * channel (such as an Analog Trigger).
+ *
+ * The counter will start counting immediately.
+ *
+ * @param source A pointer to the existing DigitalSource object. It will be
+ *               set as the Up Source.
+ */
+Counter::Counter(std::shared_ptr<DigitalSource> source) : Counter(kTwoPulse) {
+  SetUpSource(source);
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ *
+ * Create an up-Counter instance given a channel.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+ *                10-25 are on the MXP
+ */
+Counter::Counter(int channel) : Counter(kTwoPulse) {
+  SetUpSource(channel);
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ *
+ * Create an instance of a simple up-Counter given an analog trigger.
+ * Use the trigger state output from the analog trigger.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param trigger The reference to the existing AnalogTrigger object.
+ */
+Counter::Counter(const AnalogTrigger &trigger) : Counter(kTwoPulse) {
+  SetUpSource(trigger.CreateOutput(AnalogTriggerType::kState));
+  ClearDownSource();
+}
+
+/**
+ * Create an instance of a Counter object.
+ *
+ * Creates a full up-down counter given two Digital Sources.
+ *
+ * @param encodingType The quadrature decoding mode (1x or 2x)
+ * @param upSource     The pointer to the DigitalSource to set as the up source
+ * @param downSource   The pointer to the DigitalSource to set as the down
+ *                     source
+ * @param inverted     True to invert the output (reverse the direction)
+ */
+Counter::Counter(EncodingType encodingType, DigitalSource *upSource,
+                 DigitalSource *downSource, bool inverted)
+    : Counter(encodingType, std::shared_ptr<DigitalSource>(
+                                upSource, NullDeleter<DigitalSource>()),
+              std::shared_ptr<DigitalSource>(downSource,
+                                             NullDeleter<DigitalSource>()),
+              inverted) {}
+
+/**
+ * Create an instance of a Counter object.
+ *
+ * Creates a full up-down counter given two Digital Sources.
+ *
+ * @param encodingType The quadrature decoding mode (1x or 2x)
+ * @param upSource     The pointer to the DigitalSource to set as the up source
+ * @param downSource   The pointer to the DigitalSource to set as the down
+ *                     source
+ * @param inverted     True to invert the output (reverse the direction)
+ */
+Counter::Counter(EncodingType encodingType,
+                 std::shared_ptr<DigitalSource> upSource,
+                 std::shared_ptr<DigitalSource> downSource, bool inverted)
+    : Counter(kExternalDirection) {
+  if (encodingType != k1X && encodingType != k2X) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Counter only supports 1X and 2X quadrature decoding.");
+    return;
+  }
+  SetUpSource(upSource);
+  SetDownSource(downSource);
+  int32_t status = 0;
+
+  if (encodingType == k1X) {
+    SetUpSourceEdge(true, false);
+    HAL_SetCounterAverageSize(m_counter, 1, &status);
+  } else {
+    SetUpSourceEdge(true, true);
+    HAL_SetCounterAverageSize(m_counter, 2, &status);
+  }
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  SetDownSourceEdge(inverted, true);
+}
+
+/**
+ * Delete the Counter object.
+ */
+Counter::~Counter() {
+  SetUpdateWhenEmpty(true);
+
+  int32_t status = 0;
+  HAL_FreeCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  m_counter = HAL_kInvalidHandle;
+}
+
+/**
+ * Set the upsource for the counter as a digital input channel.
+ *
+ * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+ *                10-25 are on the MXP
+ */
+void Counter::SetUpSource(int channel) {
+  SetUpSource(std::make_shared<DigitalInput>(channel));
+}
+
+/**
+ * Set the up counting source to be an analog trigger.
+ *
+ * @param analogTrigger The analog trigger object that is used for the Up Source
+ * @param triggerType   The analog trigger output that will trigger the counter.
+ */
+void Counter::SetUpSource(AnalogTrigger *analogTrigger,
+                          AnalogTriggerType triggerType) {
+  SetUpSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
+                                             NullDeleter<AnalogTrigger>()),
+              triggerType);
+}
+
+/**
+ * Set the up counting source to be an analog trigger.
+ *
+ * @param analogTrigger The analog trigger object that is used for the Up Source
+ * @param triggerType   The analog trigger output that will trigger the counter.
+ */
+void Counter::SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                          AnalogTriggerType triggerType) {
+  SetUpSource(analogTrigger->CreateOutput(triggerType));
+}
+
+/**
+ * Set the source object that causes the counter to count up.
+ *
+ * Set the up counting DigitalSource.
+ *
+ * @param source Pointer to the DigitalSource object to set as the up source
+ */
+void Counter::SetUpSource(std::shared_ptr<DigitalSource> source) {
+  m_upSource = source;
+  int32_t status = 0;
+  HAL_SetCounterUpSource(
+      m_counter, source->GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)source->GetAnalogTriggerTypeForRouting(), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetUpSource(DigitalSource *source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * Set the source object that causes the counter to count up.
+ *
+ * Set the up counting DigitalSource.
+ *
+ * @param source Reference to the DigitalSource object to set as the up source
+ */
+void Counter::SetUpSource(DigitalSource &source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * Set the edge sensitivity on an up counting source.
+ *
+ * Set the up source to either detect rising edges or falling edges or both.
+ *
+ * @param risingEdge  True to trigger on rising edges
+ * @param fallingEdge True to trigger on falling edges
+ */
+void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) {
+  if (m_upSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr UpSource before setting UpSourceEdge");
+  }
+  int32_t status = 0;
+  HAL_SetCounterUpSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Disable the up counting source to the counter.
+ */
+void Counter::ClearUpSource() {
+  m_upSource.reset();
+  int32_t status = 0;
+  HAL_ClearCounterUpSource(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set the down counting source to be a digital input channel.
+ *
+ * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+ *                10-25 are on the MXP
+ */
+void Counter::SetDownSource(int channel) {
+  SetDownSource(std::make_shared<DigitalInput>(channel));
+}
+
+/**
+ * Set the down counting source to be an analog trigger.
+ *
+ * @param analogTrigger The analog trigger object that is used for the Down
+ *                      Source
+ * @param triggerType   The analog trigger output that will trigger the counter.
+ */
+void Counter::SetDownSource(AnalogTrigger *analogTrigger,
+                            AnalogTriggerType triggerType) {
+  SetDownSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
+                                               NullDeleter<AnalogTrigger>()),
+                triggerType);
+}
+
+/**
+ * Set the down counting source to be an analog trigger.
+ *
+ * @param analogTrigger The analog trigger object that is used for the Down
+ *                      Source
+ * @param triggerType   The analog trigger output that will trigger the counter.
+ */
+void Counter::SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                            AnalogTriggerType triggerType) {
+  SetDownSource(analogTrigger->CreateOutput(triggerType));
+}
+
+/**
+ * Set the source object that causes the counter to count down.
+ *
+ * Set the down counting DigitalSource.
+ *
+ * @param source Pointer to the DigitalSource object to set as the down source
+ */
+void Counter::SetDownSource(std::shared_ptr<DigitalSource> source) {
+  m_downSource = source;
+  int32_t status = 0;
+  HAL_SetCounterDownSource(
+      m_counter, source->GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)source->GetAnalogTriggerTypeForRouting(), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetDownSource(DigitalSource *source) {
+  SetDownSource(
+      std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * Set the source object that causes the counter to count down.
+ *
+ * Set the down counting DigitalSource.
+ *
+ * @param source Reference to the DigitalSource object to set as the down source
+ */
+void Counter::SetDownSource(DigitalSource &source) {
+  SetDownSource(
+      std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
+}
+
+/**
+ * Set the edge sensitivity on a down counting source.
+ *
+ * Set the down source to either detect rising edges or falling edges.
+ *
+ * @param risingEdge  True to trigger on rising edges
+ * @param fallingEdge True to trigger on falling edges
+ */
+void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) {
+  if (m_downSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr DownSource before setting DownSourceEdge");
+  }
+  int32_t status = 0;
+  HAL_SetCounterDownSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Disable the down counting source to the counter.
+ */
+void Counter::ClearDownSource() {
+  m_downSource.reset();
+  int32_t status = 0;
+  HAL_ClearCounterDownSource(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set standard up / down counting mode on this counter.
+ *
+ * Up and down counts are sourced independently from two inputs.
+ */
+void Counter::SetUpDownCounterMode() {
+  int32_t status = 0;
+  HAL_SetCounterUpDownMode(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set external direction mode on this counter.
+ *
+ * Counts are sourced on the Up counter input.
+ * The Down counter input represents the direction to count.
+ */
+void Counter::SetExternalDirectionMode() {
+  int32_t status = 0;
+  HAL_SetCounterExternalDirectionMode(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Set Semi-period mode on this counter.
+ *
+ * Counts up on both rising and falling edges.
+ */
+void Counter::SetSemiPeriodMode(bool highSemiPeriod) {
+  int32_t status = 0;
+  HAL_SetCounterSemiPeriodMode(m_counter, highSemiPeriod, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Configure the counter to count in up or down based on the length of the input
+ * pulse.
+ *
+ * This mode is most useful for direction sensitive gear tooth sensors.
+ *
+ * @param threshold The pulse length beyond which the counter counts the
+ *                  opposite direction.  Units are seconds.
+ */
+void Counter::SetPulseLengthMode(double threshold) {
+  int32_t status = 0;
+  HAL_SetCounterPulseLengthMode(m_counter, threshold, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Get the Samples to Average which specifies the number of samples of the timer
+ * to average when calculating the period.
+ *
+ * Perform averaging to account for mechanical imperfections or as oversampling
+ * to increase resolution.
+ *
+ * @return The number of samples being averaged (from 1 to 127)
+ */
+int Counter::GetSamplesToAverage() const {
+  int32_t status = 0;
+  int samples = HAL_GetCounterSamplesToAverage(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return samples;
+}
+
+/**
+ * Set the Samples to Average which specifies the number of samples of the timer
+ * to average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ *
+ * @param samplesToAverage The number of samples to average from 1 to 127.
+ */
+void Counter::SetSamplesToAverage(int samplesToAverage) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Average counter values must be between 1 and 127");
+  }
+  int32_t status = 0;
+  HAL_SetCounterSamplesToAverage(m_counter, samplesToAverage, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Read the current counter value.
+ *
+ * Read the value at this instant. It may still be running, so it reflects the
+ * current value. Next time it is read, it might have a different value.
+ */
+int Counter::Get() const {
+  int32_t status = 0;
+  int value = HAL_GetCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Reset the Counter to zero.
+ *
+ * Set the counter value to zero. This doesn't effect the running state of the
+ * counter, just sets the current value to zero.
+ */
+void Counter::Reset() {
+  int32_t status = 0;
+  HAL_ResetCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Get the Period of the most recent count.
+ *
+ * Returns the time interval of the most recent count. This can be used for
+ * velocity calculations to determine shaft speed.
+ *
+ * @returns The period between the last two pulses in units of seconds.
+ */
+double Counter::GetPeriod() const {
+  int32_t status = 0;
+  double value = HAL_GetCounterPeriod(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Set the maximum period where the device is still considered "moving".
+ *
+ * Sets the maximum period where the device is considered moving. This value is
+ * used to determine the "stopped" state of the counter using the GetStopped
+ * method.
+ *
+ * @param maxPeriod The maximum period where the counted device is considered
+ *                  moving in seconds.
+ */
+void Counter::SetMaxPeriod(double maxPeriod) {
+  int32_t status = 0;
+  HAL_SetCounterMaxPeriod(m_counter, maxPeriod, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Select whether you want to continue updating the event timer output when
+ * there are no samples captured.
+ *
+ * The output of the event timer has a buffer of periods that are averaged and
+ * posted to a register on the FPGA.  When the timer detects that the event
+ * source has stopped (based on the MaxPeriod) the buffer of samples to be
+ * averaged is emptied.  If you enable the update when empty, you will be
+ * notified of the stopped source and the event time will report 0 samples.
+ * If you disable update when empty, the most recent average will remain on
+ * the output until a new sample is acquired.  You will never see 0 samples
+ * output (except when there have been no events since an FPGA reset) and you
+ * will likely not see the stopped bit become true (since it is updated at the
+ * end of an average and there are no samples to average).
+ *
+ * @param enabled True to enable update when empty
+ */
+void Counter::SetUpdateWhenEmpty(bool enabled) {
+  int32_t status = 0;
+  HAL_SetCounterUpdateWhenEmpty(m_counter, enabled, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Determine if the clock is stopped.
+ *
+ * Determine if the clocked input is stopped based on the MaxPeriod value set
+ * using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
+ * device (and counter) are assumed to be stopped and it returns true.
+ *
+ * @return Returns true if the most recent counter period exceeds the MaxPeriod
+ *         value set by SetMaxPeriod.
+ */
+bool Counter::GetStopped() const {
+  int32_t status = 0;
+  bool value = HAL_GetCounterStopped(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * The last direction the counter value changed.
+ *
+ * @return The last direction the counter value changed.
+ */
+bool Counter::GetDirection() const {
+  int32_t status = 0;
+  bool value = HAL_GetCounterDirection(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Set the Counter to return reversed sensing on the direction.
+ *
+ * This allows counters to change the direction they are counting in the case of
+ * 1X and 2X quadrature encoding only. Any other counter mode isn't supported.
+ *
+ * @param reverseDirection true if the value counted should be negated.
+ */
+void Counter::SetReverseDirection(bool reverseDirection) {
+  int32_t status = 0;
+  HAL_SetCounterReverseDirection(m_counter, reverseDirection, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/frc971/wpilib/ahal/Counter.h b/frc971/wpilib/ahal/Counter.h
new file mode 100644
index 0000000..c32dd33
--- /dev/null
+++ b/frc971/wpilib/ahal/Counter.h
@@ -0,0 +1,106 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "HAL/Counter.h"
+#include "HAL/Types.h"
+#include "frc971/wpilib/ahal/AnalogTrigger.h"
+#include "frc971/wpilib/ahal/CounterBase.h"
+#include "frc971/wpilib/ahal/SensorBase.h"
+
+namespace frc {
+
+class DigitalGlitchFilter;
+
+/**
+ * Class for counting the number of ticks on a digital input channel.
+ * This is a general purpose class for counting repetitive events. It can return
+ * the number of counts, the period of the most recent cycle, and detect when
+ * the signal being counted has stopped by supplying a maximum cycle time.
+ *
+ * All counters will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class Counter : public CounterBase {
+ public:
+  enum Mode {
+    kTwoPulse = 0,
+    kSemiperiod = 1,
+    kPulseLength = 2,
+    kExternalDirection = 3
+  };
+  explicit Counter(Mode mode = kTwoPulse);
+  explicit Counter(int channel);
+  explicit Counter(DigitalSource *source);
+  explicit Counter(std::shared_ptr<DigitalSource> source);
+  explicit Counter(const AnalogTrigger &trigger);
+  Counter(EncodingType encodingType, DigitalSource *upSource,
+          DigitalSource *downSource, bool inverted);
+  Counter(EncodingType encodingType, std::shared_ptr<DigitalSource> upSource,
+          std::shared_ptr<DigitalSource> downSource, bool inverted);
+  virtual ~Counter();
+
+  void SetUpSource(int channel);
+  void SetUpSource(AnalogTrigger *analogTrigger, AnalogTriggerType triggerType);
+  void SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                   AnalogTriggerType triggerType);
+  void SetUpSource(DigitalSource *source);
+  void SetUpSource(std::shared_ptr<DigitalSource> source);
+  void SetUpSource(DigitalSource &source);
+  void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+  void ClearUpSource();
+
+  void SetDownSource(int channel);
+  void SetDownSource(AnalogTrigger *analogTrigger,
+                     AnalogTriggerType triggerType);
+  void SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                     AnalogTriggerType triggerType);
+  void SetDownSource(DigitalSource *source);
+  void SetDownSource(std::shared_ptr<DigitalSource> source);
+  void SetDownSource(DigitalSource &source);
+  void SetDownSourceEdge(bool risingEdge, bool fallingEdge);
+  void ClearDownSource();
+
+  void SetUpDownCounterMode();
+  void SetExternalDirectionMode();
+  void SetSemiPeriodMode(bool highSemiPeriod);
+  void SetPulseLengthMode(double threshold);
+
+  void SetReverseDirection(bool reverseDirection);
+
+  // CounterBase interface
+  int Get() const override;
+  void Reset() override;
+  double GetPeriod() const override;
+  void SetMaxPeriod(double maxPeriod) override;
+  void SetUpdateWhenEmpty(bool enabled);
+  bool GetStopped() const override;
+  bool GetDirection() const override;
+
+  void SetSamplesToAverage(int samplesToAverage);
+  int GetSamplesToAverage() const;
+  int GetFPGAIndex() const { return m_index; }
+
+ protected:
+  // Makes the counter count up.
+  std::shared_ptr<DigitalSource> m_upSource;
+  // Makes the counter count down.
+  std::shared_ptr<DigitalSource> m_downSource;
+  // The FPGA counter object
+  HAL_CounterHandle m_counter = HAL_kInvalidHandle;
+
+ private:
+  int m_index = 0;  ///< The index of this counter.
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/CounterBase.h b/frc971/wpilib/ahal/CounterBase.h
new file mode 100644
index 0000000..868dbe6
--- /dev/null
+++ b/frc971/wpilib/ahal/CounterBase.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+namespace frc {
+
+/**
+ * Interface for counting the number of ticks on a digital input channel.
+ * Encoders, Gear tooth sensors, and counters should all subclass this so it can
+ * be used to build more advanced classes for control and driving.
+ *
+ * All counters will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class CounterBase {
+ public:
+  enum EncodingType { k1X, k2X, k4X };
+
+  virtual ~CounterBase() = default;
+  virtual int Get() const = 0;
+  virtual void Reset() = 0;
+  virtual double GetPeriod() const = 0;
+  virtual void SetMaxPeriod(double maxPeriod) = 0;
+  virtual bool GetStopped() const = 0;
+  virtual bool GetDirection() const = 0;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/DigitalGlitchFilter.cc b/frc971/wpilib/ahal/DigitalGlitchFilter.cc
new file mode 100644
index 0000000..2c18376
--- /dev/null
+++ b/frc971/wpilib/ahal/DigitalGlitchFilter.cc
@@ -0,0 +1,197 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2017. 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 "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+
+#include <algorithm>
+#include <array>
+
+#include "HAL/Constants.h"
+#include "HAL/DIO.h"
+#include "HAL/HAL.h"
+#include "frc971/wpilib/ahal/Counter.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Utility.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+std::array<bool, 3> DigitalGlitchFilter::m_filterAllocated = {
+    {false, false, false}};
+
+DigitalGlitchFilter::DigitalGlitchFilter() {
+  auto index =
+      std::find(m_filterAllocated.begin(), m_filterAllocated.end(), false);
+  wpi_assert(index != m_filterAllocated.end());
+
+  m_channelIndex = std::distance(m_filterAllocated.begin(), index);
+  *index = true;
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalFilter, m_channelIndex);
+}
+
+DigitalGlitchFilter::~DigitalGlitchFilter() {
+  if (m_channelIndex >= 0) {
+    m_filterAllocated[m_channelIndex] = false;
+  }
+}
+
+/**
+ * Assigns the DigitalSource to this glitch filter.
+ *
+ * @param input The DigitalSource to add.
+ */
+void DigitalGlitchFilter::Add(DigitalSource *input) {
+  DoAdd(input, m_channelIndex + 1);
+}
+
+void DigitalGlitchFilter::DoAdd(DigitalSource *input, int requested_index) {
+  // Some sources from Counters and Encoders are null.  By pushing the check
+  // here, we catch the issue more generally.
+  if (input) {
+    // we don't support GlitchFilters on AnalogTriggers.
+    if (input->IsAnalogTrigger()) {
+      wpi_setErrorWithContext(
+          -1, "Analog Triggers not supported for DigitalGlitchFilters");
+      return;
+    }
+    int32_t status = 0;
+    HAL_SetFilterSelect(input->GetPortHandleForRouting(), requested_index,
+                        &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+    // Validate that we set it correctly.
+    int actual_index =
+        HAL_GetFilterSelect(input->GetPortHandleForRouting(), &status);
+    wpi_assertEqual(actual_index, requested_index);
+
+    HAL_Report(HALUsageReporting::kResourceType_DigitalInput,
+               input->GetChannel());
+  }
+}
+
+/**
+ * Assigns the Encoder to this glitch filter.
+ *
+ * @param input The Encoder to add.
+ */
+void DigitalGlitchFilter::Add(Encoder *input) {
+  Add(input->m_aSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_bSource.get());
+}
+
+/**
+ * Assigns the Counter to this glitch filter.
+ *
+ * @param input The Counter to add.
+ */
+void DigitalGlitchFilter::Add(Counter *input) {
+  Add(input->m_upSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_downSource.get());
+}
+
+/**
+ * Removes a digital input from this filter.
+ *
+ * Removes the DigitalSource from this glitch filter and re-assigns it to
+ * the default filter.
+ *
+ * @param input The DigitalSource to remove.
+ */
+void DigitalGlitchFilter::Remove(DigitalSource *input) { DoAdd(input, 0); }
+
+/**
+ * Removes an encoder from this filter.
+ *
+ * Removes the Encoder from this glitch filter and re-assigns it to
+ * the default filter.
+ *
+ * @param input The Encoder to remove.
+ */
+void DigitalGlitchFilter::Remove(Encoder *input) {
+  Remove(input->m_aSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_bSource.get());
+}
+
+/**
+ * Removes a counter from this filter.
+ *
+ * Removes the Counter from this glitch filter and re-assigns it to
+ * the default filter.
+ *
+ * @param input The Counter to remove.
+ */
+void DigitalGlitchFilter::Remove(Counter *input) {
+  Remove(input->m_upSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_downSource.get());
+}
+
+/**
+ * Sets the number of cycles that the input must not change state for.
+ *
+ * @param fpga_cycles The number of FPGA cycles.
+ */
+void DigitalGlitchFilter::SetPeriodCycles(int fpga_cycles) {
+  int32_t status = 0;
+  HAL_SetFilterPeriod(m_channelIndex, fpga_cycles, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Sets the number of nanoseconds that the input must not change state for.
+ *
+ * @param nanoseconds The number of nanoseconds.
+ */
+void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) {
+  int32_t status = 0;
+  int fpga_cycles =
+      nanoseconds * HAL_GetSystemClockTicksPerMicrosecond() / 4 / 1000;
+  HAL_SetFilterPeriod(m_channelIndex, fpga_cycles, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Gets the number of cycles that the input must not change state for.
+ *
+ * @return The number of cycles.
+ */
+int DigitalGlitchFilter::GetPeriodCycles() {
+  int32_t status = 0;
+  int fpga_cycles = HAL_GetFilterPeriod(m_channelIndex, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  return fpga_cycles;
+}
+
+/**
+ * Gets the number of nanoseconds that the input must not change state for.
+ *
+ * @return The number of nanoseconds.
+ */
+uint64_t DigitalGlitchFilter::GetPeriodNanoSeconds() {
+  int32_t status = 0;
+  int fpga_cycles = HAL_GetFilterPeriod(m_channelIndex, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  return static_cast<uint64_t>(fpga_cycles) * 1000L /
+         static_cast<uint64_t>(HAL_GetSystemClockTicksPerMicrosecond() / 4);
+}
diff --git a/frc971/wpilib/ahal/DigitalGlitchFilter.h b/frc971/wpilib/ahal/DigitalGlitchFilter.h
new file mode 100644
index 0000000..fae4267
--- /dev/null
+++ b/frc971/wpilib/ahal/DigitalGlitchFilter.h
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+
+#include "frc971/wpilib/ahal/DigitalSource.h"
+// #include "HAL/cpp/priority_mutex.h"
+
+namespace frc {
+
+class Encoder;
+class Counter;
+
+/**
+ * Class to enable glitch filtering on a set of digital inputs.
+ * This class will manage adding and removing digital inputs from a FPGA glitch
+ * filter. The filter lets the user configure the time that an input must remain
+ * high or low before it is classified as high or low.
+ */
+class DigitalGlitchFilter {
+ public:
+  DigitalGlitchFilter();
+  ~DigitalGlitchFilter();
+
+  void Add(DigitalSource *input);
+  void Add(Encoder *input);
+  void Add(Counter *input);
+
+  void Remove(DigitalSource *input);
+  void Remove(Encoder *input);
+  void Remove(Counter *input);
+
+  void SetPeriodCycles(int fpga_cycles);
+  void SetPeriodNanoSeconds(uint64_t nanoseconds);
+
+  int GetPeriodCycles();
+  uint64_t GetPeriodNanoSeconds();
+
+ private:
+  // Sets the filter for the input to be the requested index.  A value of 0
+  // disables the filter, and the filter value must be between 1 and 3,
+  // inclusive.
+  void DoAdd(DigitalSource *input, int requested_index);
+
+  int m_channelIndex = -1;
+  static ::std::array<bool, 3> m_filterAllocated;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/DigitalInput.cc b/frc971/wpilib/ahal/DigitalInput.cc
new file mode 100644
index 0000000..45e405d
--- /dev/null
+++ b/frc971/wpilib/ahal/DigitalInput.cc
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/DigitalInput.h"
+
+#include <limits>
+#include <sstream>
+
+#include "HAL/DIO.h"
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Create an instance of a Digital Input class.
+ *
+ * Creates a digital input given a channel.
+ *
+ * @param channel The DIO channel 0-9 are on-board, 10-25 are on the MXP port
+ */
+DigitalInput::DigitalInput(int channel) {
+  std::stringstream buf;
+
+  if (!CheckDigitalChannel(channel)) {
+    buf << "Digital Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+  m_channel = channel;
+
+  int32_t status = 0;
+  m_handle = HAL_InitializeDIOPort(HAL_GetPort(channel), true, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumDigitalChannels(),
+                                 channel, HAL_GetErrorMessage(status));
+    m_handle = HAL_kInvalidHandle;
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalInput, channel);
+}
+
+/**
+ * Free resources associated with the Digital Input class.
+ */
+DigitalInput::~DigitalInput() {
+  if (StatusIsFatal()) return;
+  if (m_interrupt != HAL_kInvalidHandle) {
+    int32_t status = 0;
+    HAL_CleanInterrupts(m_interrupt, &status);
+    // ignore status, as an invalid handle just needs to be ignored.
+    m_interrupt = HAL_kInvalidHandle;
+  }
+
+  HAL_FreeDIOPort(m_handle);
+}
+
+/**
+ * Get the value from a digital input channel.
+ *
+ * Retrieve the value of a single digital input channel from the FPGA.
+ */
+bool DigitalInput::Get() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetDIO(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * @return The GPIO channel number that this object represents.
+ */
+int DigitalInput::GetChannel() const { return m_channel; }
+
+/**
+ * @return The HAL Handle to the specified source.
+ */
+HAL_Handle DigitalInput::GetPortHandleForRouting() const { return m_handle; }
+
+/**
+ * Is source an AnalogTrigger
+ */
+bool DigitalInput::IsAnalogTrigger() const { return false; }
+
+/**
+ * @return The type of analog trigger output to be used. 0 for Digitals
+ */
+AnalogTriggerType DigitalInput::GetAnalogTriggerTypeForRouting() const {
+  return (AnalogTriggerType)0;
+}
diff --git a/frc971/wpilib/ahal/DigitalInput.h b/frc971/wpilib/ahal/DigitalInput.h
new file mode 100644
index 0000000..2053e4e
--- /dev/null
+++ b/frc971/wpilib/ahal/DigitalInput.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <string>
+
+#include "frc971/wpilib/ahal/DigitalSource.h"
+
+namespace frc {
+
+class DigitalGlitchFilter;
+
+/**
+ * Class to read a digital input.
+ * This class will read digital inputs and return the current value on the
+ * channel. Other devices such as encoders, gear tooth sensors, etc. that are
+ * implemented elsewhere will automatically allocate digital inputs and outputs
+ * as required. This class is only for devices like switches etc. that aren't
+ * implemented anywhere else.
+ */
+class DigitalInput : public DigitalSource {
+ public:
+  explicit DigitalInput(int channel);
+  virtual ~DigitalInput();
+  bool Get() const;
+  int GetChannel() const override;
+
+  // Digital Source Interface
+  HAL_Handle GetPortHandleForRouting() const override;
+  AnalogTriggerType GetAnalogTriggerTypeForRouting() const override;
+  bool IsAnalogTrigger() const override;
+
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle;
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/DigitalOutput.cc b/frc971/wpilib/ahal/DigitalOutput.cc
new file mode 100644
index 0000000..7f8495b
--- /dev/null
+++ b/frc971/wpilib/ahal/DigitalOutput.cc
@@ -0,0 +1,229 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/DigitalOutput.h"
+
+#include <limits>
+#include <sstream>
+
+#include "HAL/DIO.h"
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Create an instance of a digital output.
+ *
+ * Create a digital output given a channel.
+ *
+ * @param channel The digital channel 0-9 are on-board, 10-25 are on the MXP
+ *                port
+ */
+DigitalOutput::DigitalOutput(int channel) {
+  std::stringstream buf;
+
+  m_pwmGenerator = HAL_kInvalidHandle;
+  if (!CheckDigitalChannel(channel)) {
+    buf << "Digital Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+  m_channel = channel;
+
+  int32_t status = 0;
+  m_handle = HAL_InitializeDIOPort(HAL_GetPort(channel), false, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumDigitalChannels(),
+                                 channel, HAL_GetErrorMessage(status));
+    m_channel = std::numeric_limits<int>::max();
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalOutput, channel);
+}
+
+/**
+ * Free the resources associated with a digital output.
+ */
+DigitalOutput::~DigitalOutput() {
+  if (StatusIsFatal()) return;
+  // Disable the PWM in case it was running.
+  DisablePWM();
+
+  HAL_FreeDIOPort(m_handle);
+}
+
+/**
+ * Set the value of a digital output.
+ *
+ * Set the value of a digital output to either one (true) or zero (false).
+ *
+ * @param value 1 (true) for high, 0 (false) for disabled
+ */
+void DigitalOutput::Set(bool value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDIO(m_handle, value, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+   * Gets the value being output from the Digital Output.
+   *
+   * @return the state of the digital output.
+   */
+bool DigitalOutput::Get() const {
+  if (StatusIsFatal()) return false;
+
+  int32_t status = 0;
+  bool val = HAL_GetDIO(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+/**
+ * @return The GPIO channel number that this object represents.
+ */
+int DigitalOutput::GetChannel() const { return m_channel; }
+
+/**
+ * Output a single pulse on the digital output line.
+ *
+ * Send a single pulse on the digital output line where the pulse duration is
+ * specified in seconds. Maximum pulse length is 0.0016 seconds.
+ *
+ * @param length The pulse length in seconds
+ */
+void DigitalOutput::Pulse(double length) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_Pulse(m_handle, length, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Determine if the pulse is still going.
+ *
+ * Determine if a previously started pulse is still going.
+ */
+bool DigitalOutput::IsPulsing() const {
+  if (StatusIsFatal()) return false;
+
+  int32_t status = 0;
+  bool value = HAL_IsPulsing(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+/**
+ * Change the PWM frequency of the PWM output on a Digital Output line.
+ *
+ * The valid range is from 0.6 Hz to 19 kHz.  The frequency resolution is
+ * logarithmic.
+ *
+ * There is only one PWM frequency for all digital channels.
+ *
+ * @param rate The frequency to output all digital output PWM signals.
+ */
+void DigitalOutput::SetPWMRate(double rate) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDigitalPWMRate(rate, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Enable a PWM Output on this line.
+ *
+ * Allocate one of the 6 DO PWM generator resources from this module.
+ *
+ * Supply the initial duty-cycle to output so as to avoid a glitch when first
+ * starting.
+ *
+ * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less)
+ * but is reduced the higher the frequency of the PWM signal is.
+ *
+ * @param initialDutyCycle The duty-cycle to start generating. [0..1]
+ */
+void DigitalOutput::EnablePWM(double initialDutyCycle) {
+  if (m_pwmGenerator != HAL_kInvalidHandle) return;
+
+  int32_t status = 0;
+
+  if (StatusIsFatal()) return;
+  m_pwmGenerator = HAL_AllocateDigitalPWM(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  if (StatusIsFatal()) return;
+  HAL_SetDigitalPWMDutyCycle(m_pwmGenerator, initialDutyCycle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  if (StatusIsFatal()) return;
+  HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, m_channel, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Change this line from a PWM output back to a static Digital Output line.
+ *
+ * Free up one of the 6 DO PWM generator resources that were in use.
+ */
+void DigitalOutput::DisablePWM() {
+  if (StatusIsFatal()) return;
+  if (m_pwmGenerator == HAL_kInvalidHandle) return;
+
+  int32_t status = 0;
+
+  // Disable the output by routing to a dead bit.
+  HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, kDigitalChannels, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_FreeDigitalPWM(m_pwmGenerator, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  m_pwmGenerator = HAL_kInvalidHandle;
+}
+
+/**
+ * Change the duty-cycle that is being generated on the line.
+ *
+ * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less)
+ * but is reduced the higher the frequency of the PWM signal is.
+ *
+ * @param dutyCycle The duty-cycle to change to. [0..1]
+ */
+void DigitalOutput::UpdateDutyCycle(double dutyCycle) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDigitalPWMDutyCycle(m_pwmGenerator, dutyCycle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * @return The HAL Handle to the specified source.
+ */
+HAL_Handle DigitalOutput::GetPortHandleForRouting() const { return m_handle; }
+
+/**
+ * Is source an AnalogTrigger
+ */
+bool DigitalOutput::IsAnalogTrigger() const { return false; }
+
+/**
+ * @return The type of analog trigger output to be used. 0 for Digitals
+ */
+AnalogTriggerType DigitalOutput::GetAnalogTriggerTypeForRouting() const {
+  return (AnalogTriggerType)0;
+}
diff --git a/frc971/wpilib/ahal/DigitalOutput.h b/frc971/wpilib/ahal/DigitalOutput.h
new file mode 100644
index 0000000..e1f7080
--- /dev/null
+++ b/frc971/wpilib/ahal/DigitalOutput.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "HAL/Types.h"
+#include "frc971/wpilib/ahal/DigitalSource.h"
+
+namespace frc {
+
+/**
+ * Class to write to digital outputs.
+ * Write values to the digital output channels. Other devices implemented
+ * elsewhere will allocate channels automatically so for those devices it
+ * shouldn't be done here.
+ */
+class DigitalOutput : public DigitalSource {
+ public:
+  explicit DigitalOutput(int channel);
+  virtual ~DigitalOutput();
+  void Set(bool value);
+  bool Get() const;
+  int GetChannel() const override;
+  void Pulse(double length);
+  bool IsPulsing() const;
+  void SetPWMRate(double rate);
+  void EnablePWM(double initialDutyCycle);
+  void DisablePWM();
+  void UpdateDutyCycle(double dutyCycle);
+
+  // Digital Source Interface
+  HAL_Handle GetPortHandleForRouting() const override;
+  AnalogTriggerType GetAnalogTriggerTypeForRouting() const override;
+  bool IsAnalogTrigger() const override;
+
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle;
+  HAL_DigitalPWMHandle m_pwmGenerator;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/DigitalSource.h b/frc971/wpilib/ahal/DigitalSource.h
new file mode 100644
index 0000000..6844923
--- /dev/null
+++ b/frc971/wpilib/ahal/DigitalSource.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HAL/Types.h"
+#include "frc971/wpilib/ahal/InterruptableSensorBase.h"
+
+namespace frc {
+
+/**
+ * DigitalSource Interface.
+ * The DigitalSource represents all the possible inputs for a counter or a
+ * quadrature encoder. The source may be
+ * either a digital input or an analog input. If the caller just provides a
+ * channel, then a digital input will be
+ * constructed and freed when finished for the source. The source can either be
+ * a digital input or analog trigger
+ * but not both.
+ */
+class DigitalSource : public InterruptableSensorBase {
+ public:
+  virtual ~DigitalSource() = default;
+  virtual HAL_Handle GetPortHandleForRouting() const = 0;
+  virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const = 0;
+  virtual bool IsAnalogTrigger() const = 0;
+  virtual int GetChannel() const = 0;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/DriverStation.cc b/frc971/wpilib/ahal/DriverStation.cc
new file mode 100644
index 0000000..f4c2e5d
--- /dev/null
+++ b/frc971/wpilib/ahal/DriverStation.cc
@@ -0,0 +1,446 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/DriverStation.h"
+
+#include <chrono>
+
+#include "FRC_NetworkCommunication/FRCComm.h"
+#include "HAL/HAL.h"
+#include "HAL/Power.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Utility.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+#include "llvm/SmallString.h"
+
+using namespace frc;
+
+#define WPI_LIB_FATAL(error_tag) \
+  do {                           \
+  } while (false)
+
+const int DriverStation::kJoystickPorts;
+
+DriverStation::~DriverStation() {}
+
+/**
+ * Return a pointer to the singleton DriverStation.
+ *
+ * @return Pointer to the DS instance
+ */
+DriverStation &DriverStation::GetInstance() {
+  static DriverStation instance;
+  return instance;
+}
+
+/**
+ * Report an error to the DriverStation messages window.
+ *
+ * The error is also printed to the program console.
+ */
+void DriverStation::ReportError(llvm::StringRef error) {
+  llvm::SmallString<128> temp;
+  HAL_SendError(1, 1, 0, error.c_str(temp), "", "", 1);
+}
+
+/**
+ * Report a warning to the DriverStation messages window.
+ *
+ * The warning is also printed to the program console.
+ */
+void DriverStation::ReportWarning(llvm::StringRef error) {
+  llvm::SmallString<128> temp;
+  HAL_SendError(0, 1, 0, error.c_str(temp), "", "", 1);
+}
+
+/**
+ * Report an error to the DriverStation messages window.
+ *
+ * The error is also printed to the program console.
+ */
+void DriverStation::ReportError(bool is_error, int32_t code,
+                                llvm::StringRef error, llvm::StringRef location,
+                                llvm::StringRef stack) {
+  llvm::SmallString<128> errorTemp;
+  llvm::SmallString<128> locationTemp;
+  llvm::SmallString<128> stackTemp;
+  HAL_SendError(is_error, code, 0, error.c_str(errorTemp),
+                location.c_str(locationTemp), stack.c_str(stackTemp), 1);
+}
+
+/**
+ * Get the value of the axis on a joystick.
+ *
+ * This depends on the mapping of the joystick connected to the specified port.
+ *
+ * @param stick The joystick to read.
+ * @param axis  The analog axis value to read from the joystick.
+ * @return The value of the axis on the joystick.
+ */
+double DriverStation::GetStickAxis(int stick, int axis) {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return 0;
+  }
+  if (axis >= m_joystickAxes[stick].count) {
+    if (axis >= HAL_kMaxJoystickAxes) WPI_LIB_FATAL(BadJoystickAxis);
+    return 0.0;
+  }
+
+  return m_joystickAxes[stick].axes[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 DriverStation::GetStickPOV(int stick, int pov) {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return -1;
+  }
+  if (pov >= m_joystickPOVs[stick].count) {
+    if (pov >= HAL_kMaxJoystickPOVs) WPI_LIB_FATAL(BadJoystickAxis);
+    return -1;
+  }
+
+  return m_joystickPOVs[stick].povs[pov];
+}
+
+/**
+ * The state of the buttons on the joystick.
+ *
+ * @param stick The joystick to read.
+ * @return The state of the buttons on the joystick.
+ */
+int DriverStation::GetStickButtons(int stick) const {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return 0;
+  }
+  return m_joystickButtons[stick].buttons;
+}
+
+/**
+ * The state of one joystick button. Button indexes begin at 1.
+ *
+ * @param stick  The joystick to read.
+ * @param button The button index, beginning at 1.
+ * @return The state of the joystick button.
+ */
+bool DriverStation::GetStickButton(int stick, int button) {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return false;
+  }
+  if (button == 0) {
+    return false;
+  }
+  if (button > m_joystickButtons[stick].count) {
+    return false;
+  }
+
+  return ((0x1 << (button - 1)) & m_joystickButtons[stick].buttons) != 0;
+}
+
+/**
+ * Returns the number of axes on a given joystick port.
+ *
+ * @param stick The joystick port number
+ * @return The number of axes on the indicated joystick
+ */
+int DriverStation::GetStickAxisCount(int stick) const {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return 0;
+  }
+  return m_joystickAxes[stick].count;
+}
+
+/**
+ * Returns the number of POVs on a given joystick port.
+ *
+ * @param stick The joystick port number
+ * @return The number of POVs on the indicated joystick
+ */
+int DriverStation::GetStickPOVCount(int stick) const {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return 0;
+  }
+  return m_joystickPOVs[stick].count;
+}
+
+/**
+ * Returns the number of buttons on a given joystick port.
+ *
+ * @param stick The joystick port number
+ * @return The number of buttons on the indicated joystick
+ */
+int DriverStation::GetStickButtonCount(int stick) const {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return 0;
+  }
+  return m_joystickButtons[stick].count;
+}
+
+/**
+ * Returns a boolean indicating if the controller is an xbox controller.
+ *
+ * @param stick The joystick port number
+ * @return A boolean that is true if the controller is an xbox controller.
+ */
+bool DriverStation::GetJoystickIsXbox(int stick) const {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return false;
+  }
+  return static_cast<bool>(m_joystickDescriptor[stick].isXbox);
+}
+
+/**
+ * Returns the type of joystick at a given port.
+ *
+ * @param stick The joystick port number
+ * @return The HID type of joystick at the given port
+ */
+int DriverStation::GetJoystickType(int stick) const {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return -1;
+  }
+  return static_cast<int>(m_joystickDescriptor[stick].type);
+}
+
+/**
+ * Returns the name of the joystick at the given port.
+ *
+ * @param stick The joystick port number
+ * @return The name of the joystick at the given port
+ */
+std::string DriverStation::GetJoystickName(int stick) const {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+  }
+  std::string retVal(m_joystickDescriptor[stick].name);
+  return retVal;
+}
+
+/**
+ * Returns the types of Axes on a given joystick port.
+ *
+ * @param stick The joystick port number and the target axis
+ * @return What type of axis the axis is reporting to be
+ */
+int DriverStation::GetJoystickAxisType(int stick, int axis) const {
+  if (stick >= kJoystickPorts) {
+    WPI_LIB_FATAL(BadJoystickIndex);
+    return -1;
+  }
+  return m_joystickDescriptor[stick].axisTypes[axis];
+}
+
+/**
+ * Check if the FPGA outputs are enabled.
+ *
+ * The outputs may be disabled if the robot is disabled or e-stopped, the
+ * watchdog has expired, or if the roboRIO browns out.
+ *
+ * @return True if the FPGA outputs are enabled.
+ */
+bool DriverStation::IsSysActive() const {
+  int32_t status = 0;
+  bool retVal = HAL_GetSystemActive(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Check if the system is browned out.
+ *
+ * @return True if the system is browned out
+ */
+bool DriverStation::IsBrownedOut() const {
+  int32_t status = 0;
+  bool retVal = HAL_GetBrownedOut(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+/**
+ * Return the alliance that the driver station says it is on.
+ *
+ * This could return kRed or kBlue.
+ *
+ * @return The Alliance enum (kRed, kBlue or kInvalid)
+ */
+DriverStation::Alliance DriverStation::GetAlliance() const {
+  int32_t status = 0;
+  auto allianceStationID = HAL_GetAllianceStation(&status);
+  switch (allianceStationID) {
+    case HAL_AllianceStationID_kRed1:
+    case HAL_AllianceStationID_kRed2:
+    case HAL_AllianceStationID_kRed3:
+      return kRed;
+    case HAL_AllianceStationID_kBlue1:
+    case HAL_AllianceStationID_kBlue2:
+    case HAL_AllianceStationID_kBlue3:
+      return kBlue;
+    default:
+      return kInvalid;
+  }
+}
+
+/**
+ * Return the driver station location on the field.
+ *
+ * This could return 1, 2, or 3.
+ *
+ * @return The location of the driver station (1-3, 0 for invalid)
+ */
+int DriverStation::GetLocation() const {
+  int32_t status = 0;
+  auto allianceStationID = HAL_GetAllianceStation(&status);
+  switch (allianceStationID) {
+    case HAL_AllianceStationID_kRed1:
+    case HAL_AllianceStationID_kBlue1:
+      return 1;
+    case HAL_AllianceStationID_kRed2:
+    case HAL_AllianceStationID_kBlue2:
+      return 2;
+    case HAL_AllianceStationID_kRed3:
+    case HAL_AllianceStationID_kBlue3:
+      return 3;
+    default:
+      return 0;
+  }
+}
+
+/**
+ * Return the approximate match time.
+ *
+ * The FMS does not send an official match time to the robots, but does send an
+ * approximate match time.  The value will count down the time remaining in the
+ * current period (auto or teleop).
+ *
+ * Warning: This is not an official time (so it cannot be used to dispute ref
+ * calls or guarantee that a function will trigger before the match ends).
+ *
+ * The Practice Match function of the DS approximates the behaviour seen on the
+ * field.
+ *
+ * @return Time remaining in current match period (auto or teleop)
+ */
+double DriverStation::GetMatchTime() const {
+  int32_t status;
+  return HAL_GetMatchTime(&status);
+}
+
+/**
+ * Read the battery voltage.
+ *
+ * @return The battery voltage in Volts.
+ */
+double DriverStation::GetBatteryVoltage() const {
+  int32_t status = 0;
+  double voltage = HAL_GetVinVoltage(&status);
+  wpi_setErrorWithContext(status, "getVinVoltage");
+
+  return voltage;
+}
+
+/**
+ * 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 DriverStation::GetData() {
+  // Get the status of all of the joysticks, and save to the cache
+  for (uint8_t stick = 0; stick < kJoystickPorts; stick++) {
+    HAL_GetJoystickAxes(stick, &m_joystickAxesCache[stick]);
+    HAL_GetJoystickPOVs(stick, &m_joystickPOVsCache[stick]);
+    HAL_GetJoystickButtons(stick, &m_joystickButtonsCache[stick]);
+    HAL_GetJoystickDescriptor(stick, &m_joystickDescriptorCache[stick]);
+  }
+  m_joystickAxes.swap(m_joystickAxesCache);
+  m_joystickPOVs.swap(m_joystickPOVsCache);
+  m_joystickButtons.swap(m_joystickButtonsCache);
+  m_joystickDescriptor.swap(m_joystickDescriptorCache);
+
+  HAL_ControlWord control_word;
+  HAL_GetControlWord(&control_word);
+  is_enabled_ = control_word.enabled;
+  is_autonomous_ = control_word.autonomous;
+  is_test_mode_ = control_word.test;
+  is_fms_attached_ = control_word.fmsAttached;
+}
+
+/**
+ * DriverStation constructor.
+ *
+ * This is only called once the first time GetInstance() is called
+ */
+DriverStation::DriverStation() {
+  // The HAL_Observe* functions let the Driver Station know that the
+  // robot code is alive (this influences the Robot Code status light on the
+  // DS, and if the DS thinks you don't have robot code, then you can't enable).
+  HAL_ObserveUserProgramStarting();
+
+  m_joystickAxes = std::make_unique<HAL_JoystickAxes[]>(kJoystickPorts);
+  m_joystickPOVs = std::make_unique<HAL_JoystickPOVs[]>(kJoystickPorts);
+  m_joystickButtons = std::make_unique<HAL_JoystickButtons[]>(kJoystickPorts);
+  m_joystickDescriptor =
+      std::make_unique<HAL_JoystickDescriptor[]>(kJoystickPorts);
+  m_joystickAxesCache = std::make_unique<HAL_JoystickAxes[]>(kJoystickPorts);
+  m_joystickPOVsCache = std::make_unique<HAL_JoystickPOVs[]>(kJoystickPorts);
+  m_joystickButtonsCache =
+      std::make_unique<HAL_JoystickButtons[]>(kJoystickPorts);
+  m_joystickDescriptorCache =
+      std::make_unique<HAL_JoystickDescriptor[]>(kJoystickPorts);
+
+  // 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_joystickAxes[i].count = 0;
+    m_joystickPOVs[i].count = 0;
+    m_joystickButtons[i].count = 0;
+    m_joystickDescriptor[i].isXbox = 0;
+    m_joystickDescriptor[i].type = -1;
+    m_joystickDescriptor[i].name[0] = '\0';
+
+    m_joystickAxesCache[i].count = 0;
+    m_joystickPOVsCache[i].count = 0;
+    m_joystickButtonsCache[i].count = 0;
+    m_joystickDescriptorCache[i].isXbox = 0;
+    m_joystickDescriptorCache[i].type = -1;
+    m_joystickDescriptorCache[i].name[0] = '\0';
+  }
+}
+
+void DriverStation::RunIteration(std::function<void()> on_data) {
+  HAL_WaitForDSData();
+  GetData();
+
+  // We have to feed some sort of watchdog so that the driver's station knows
+  // that the robot code is still alive. HAL_ObserveUserProgramStarting must be
+  // called during initialization (currently called in the constructor of this
+  // class).
+  if (!IsEnabled()) {
+    HAL_ObserveUserProgramDisabled();
+  } else if (IsAutonomous()) {
+    HAL_ObserveUserProgramAutonomous();
+  } else if (IsTestMode()) {
+    HAL_ObserveUserProgramTest();
+  } else {
+    HAL_ObserveUserProgramTeleop();
+  }
+
+  on_data();
+}
diff --git a/frc971/wpilib/ahal/DriverStation.h b/frc971/wpilib/ahal/DriverStation.h
new file mode 100644
index 0000000..f1d0804
--- /dev/null
+++ b/frc971/wpilib/ahal/DriverStation.h
@@ -0,0 +1,92 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+// #include <condition_variable>
+#include <memory>
+#include <string>
+#include <thread>
+
+#include "HAL/DriverStation.h"
+#include "frc971/wpilib/ahal/SensorBase.h"
+#include "llvm/StringRef.h"
+
+namespace frc {
+
+/**
+ * Provide access to the network communication data to / from the Driver
+ * Station.
+ */
+class DriverStation {
+ public:
+  enum Alliance { kRed, kBlue, kInvalid };
+
+  virtual ~DriverStation();
+  static DriverStation &GetInstance();
+  static void ReportError(llvm::StringRef error);
+  static void ReportWarning(llvm::StringRef error);
+  static void ReportError(bool is_error, int code, llvm::StringRef error,
+                          llvm::StringRef location, llvm::StringRef stack);
+
+  static const int kJoystickPorts = 6;
+
+  double GetStickAxis(int stick, int axis);
+  int GetStickPOV(int stick, int pov);
+  int GetStickButtons(int stick) const;
+  bool GetStickButton(int stick, int button);
+
+  int GetStickAxisCount(int stick) const;
+  int GetStickPOVCount(int stick) const;
+  int GetStickButtonCount(int stick) const;
+
+  bool GetJoystickIsXbox(int stick) const;
+  int GetJoystickType(int stick) const;
+  std::string GetJoystickName(int stick) const;
+  int GetJoystickAxisType(int stick, int axis) const;
+
+  bool IsEnabled() const { return is_enabled_; }
+  bool IsTestMode() const { return is_test_mode_; }
+  bool IsFmsAttached() const { return is_fms_attached_; }
+  bool IsAutonomous() const { return is_autonomous_; }
+
+  bool IsSysActive() const;
+  bool IsBrownedOut() const;
+
+  Alliance GetAlliance() const;
+  int GetLocation() const;
+  double GetMatchTime() const;
+  double GetBatteryVoltage() const;
+
+  void RunIteration(std::function<void()> on_data);
+
+ protected:
+  void GetData();
+
+ private:
+  DriverStation();
+
+  // Joystick User Data
+  std::unique_ptr<HAL_JoystickAxes[]> m_joystickAxes;
+  std::unique_ptr<HAL_JoystickPOVs[]> m_joystickPOVs;
+  std::unique_ptr<HAL_JoystickButtons[]> m_joystickButtons;
+  std::unique_ptr<HAL_JoystickDescriptor[]> m_joystickDescriptor;
+
+  // Joystick Cached Data
+  std::unique_ptr<HAL_JoystickAxes[]> m_joystickAxesCache;
+  std::unique_ptr<HAL_JoystickPOVs[]> m_joystickPOVsCache;
+  std::unique_ptr<HAL_JoystickButtons[]> m_joystickButtonsCache;
+  std::unique_ptr<HAL_JoystickDescriptor[]> m_joystickDescriptorCache;
+
+  bool is_enabled_ = false;
+  bool is_test_mode_ = false;
+  bool is_autonomous_ = false;
+  bool is_fms_attached_ = false;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/Encoder.cc b/frc971/wpilib/ahal/Encoder.cc
new file mode 100644
index 0000000..8d57eda
--- /dev/null
+++ b/frc971/wpilib/ahal/Encoder.cc
@@ -0,0 +1,162 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/Encoder.h"
+
+#include "HAL/HAL.h"
+#include "frc971/wpilib/ahal/DigitalInput.h"
+
+using namespace frc;
+
+#define HAL_FATAL_WITH_STATUS(status)
+
+/**
+ * Common initialization code for Encoders.
+ *
+ * This code allocates resources for Encoders and is common to all constructors.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param reverseDirection If true, counts down instead of up (this is all
+ *                         relative)
+ * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+ *                         decoding. If 4X is selected, then an encoder FPGA
+ *                         object is used and the returned counts will be 4x
+ *                         the encoder spec'd value since all rising and
+ *                         falling edges are counted. If 1X or 2X are selected
+ *                         then a counter object will be used and the returned
+ *                         value will either exactly match the spec'd count or
+ *                         be double (2x) the spec'd count.
+ */
+void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
+  int32_t status = 0;
+  m_encoder = HAL_InitializeEncoder(
+      m_aSource->GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)m_aSource->GetAnalogTriggerTypeForRouting(),
+      m_bSource->GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)m_bSource->GetAnalogTriggerTypeForRouting(),
+      reverseDirection, (HAL_EncoderEncodingType)encodingType, &status);
+  HAL_FATAL_WITH_STATUS(status);
+
+  HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex(),
+             encodingType);
+}
+
+/**
+ * Encoder constructor.
+ *
+ * Construct a Encoder given a and b channels.
+ *
+ * The counter will start counting immediately.
+ *
+ * @param aChannel         The a channel DIO channel. 0-9 are on-board, 10-25
+ *                         are on the MXP port
+ * @param bChannel         The b channel DIO channel. 0-9 are on-board, 10-25
+ *                         are on the MXP port
+ * @param reverseDirection represents the orientation of the encoder and
+ *                         inverts the output values if necessary so forward
+ *                         represents positive values.
+ * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+ *                         decoding. If 4X is selected, then an encoder FPGA
+ *                         object is used and the returned counts will be 4x
+ *                         the encoder spec'd value since all rising and
+ *                         falling edges are counted. If 1X or 2X are selected
+ *                         then a counter object will be used and the returned
+ *                         value will either exactly match the spec'd count or
+ *                         be double (2x) the spec'd count.
+ */
+Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection,
+                 EncodingType encodingType) {
+  m_aSource = std::make_shared<DigitalInput>(aChannel);
+  m_bSource = std::make_shared<DigitalInput>(bChannel);
+  InitEncoder(reverseDirection, encodingType);
+}
+
+/**
+ * Free the resources for an Encoder.
+ *
+ * Frees the FPGA resources associated with an Encoder.
+ */
+Encoder::~Encoder() {
+  int32_t status = 0;
+  HAL_FreeEncoder(m_encoder, &status);
+  HAL_FATAL_WITH_STATUS(status);
+}
+
+/**
+ * The encoding scale factor 1x, 2x, or 4x, per the requested encodingType.
+ *
+ * Used to divide raw edge counts down to spec'd counts.
+ */
+int Encoder::GetEncodingScale() const {
+  int32_t status = 0;
+  int val = HAL_GetEncoderEncodingScale(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+/**
+ * Gets the raw value from the encoder.
+ *
+ * The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
+ * factor.
+ *
+ * @return Current raw count from the encoder
+ */
+int Encoder::GetRaw() const {
+  int32_t status = 0;
+  int value = HAL_GetEncoderRaw(m_encoder, &status);
+  HAL_FATAL_WITH_STATUS(status);
+  return value;
+}
+
+/**
+ * Returns the period of the most recent pulse.
+ *
+ * Returns the period of the most recent Encoder pulse in seconds.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use GetRate() in favor of this method.  This returns unscaled
+ *             periods and GetRate() scales using value from
+ *             SetDistancePerPulse().
+ *
+ * @return Period in seconds of the most recent pulse.
+ */
+double Encoder::GetPeriod() const {
+  int32_t status = 0;
+  double value = HAL_GetEncoderPeriod(m_encoder, &status);
+  HAL_FATAL_WITH_STATUS(status);
+  return value;
+}
+/**
+ * Sets the maximum period for stopped detection.
+ *
+ * Sets the value that represents the maximum period of the Encoder before it
+ * will assume that the attached device is stopped. This timeout allows users
+ * to determine if the wheels or other shaft has stopped rotating.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use SetMinRate() in favor of this method.  This takes unscaled
+ *             periods and SetMinRate() scales using value from
+ *             SetDistancePerPulse().
+ *
+ * @param maxPeriod The maximum time between rising and falling edges before
+ *                  the FPGA will report the device stopped. This is expressed
+ *                  in seconds.
+ */
+void Encoder::SetMaxPeriod(double maxPeriod) {
+  int32_t status = 0;
+  HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod, &status);
+  HAL_FATAL_WITH_STATUS(status);
+}
+
+int Encoder::GetFPGAIndex() const {
+  int32_t status = 0;
+  int val = HAL_GetEncoderFPGAIndex(m_encoder, &status);
+  HAL_FATAL_WITH_STATUS(status);
+  return val;
+}
diff --git a/frc971/wpilib/ahal/Encoder.h b/frc971/wpilib/ahal/Encoder.h
new file mode 100644
index 0000000..2f06e65
--- /dev/null
+++ b/frc971/wpilib/ahal/Encoder.h
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "HAL/Encoder.h"
+
+namespace frc {
+
+class DigitalSource;
+class DigitalGlitchFilter;
+
+/**
+ * Class to read quad encoders.
+ * Quadrature encoders are devices that count shaft rotation and can sense
+ * direction. The output of the QuadEncoder class is an integer that can count
+ * either up or down, and can go negative for reverse direction counting. When
+ * creating QuadEncoders, a direction is supplied that changes the sense of the
+ * output to make code more readable if the encoder is mounted such that forward
+ * movement generates negative values. Quadrature encoders have two digital
+ * outputs, an A Channel and a B Channel that are out of phase with each other
+ * to allow the FPGA to do direction sensing.
+ *
+ * All encoders will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class Encoder {
+ public:
+  enum EncodingType { k1X, k2X, k4X };
+
+  Encoder(int aChannel, int bChannel, bool reverseDirection = false,
+          EncodingType encodingType = k4X);
+  virtual ~Encoder();
+
+  int GetEncodingScale() const;
+
+  int GetRaw() const;
+
+  double GetPeriod() const;
+  void SetMaxPeriod(double maxPeriod);
+
+  int GetFPGAIndex() const;
+
+ private:
+  void InitEncoder(bool reverseDirection, EncodingType encodingType);
+
+  double DecodingScaleFactor() const;
+
+  std::shared_ptr<DigitalSource> m_aSource;  // the A phase of the quad encoder
+  std::shared_ptr<DigitalSource> m_bSource;  // the B phase of the quad encoder
+  std::unique_ptr<DigitalSource> m_indexSource = nullptr;
+  HAL_EncoderHandle m_encoder = HAL_kInvalidHandle;
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/ErrorBase.h b/frc971/wpilib/ahal/ErrorBase.h
new file mode 100644
index 0000000..0f4e377
--- /dev/null
+++ b/frc971/wpilib/ahal/ErrorBase.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc971/wpilib/ahal/Base.h"
+#include "llvm/StringRef.h"
+
+#define wpi_setErrnoErrorWithContext(context) \
+  this->SetErrnoError((context), __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setErrnoError() wpi_setErrnoErrorWithContext("")
+#define wpi_setImaqErrorWithContext(code, context) \
+  do {                                             \
+  } while (0)
+#define wpi_setErrorWithContext(code, context) \
+  do {                                         \
+  } while (0)
+#define wpi_setErrorWithContextRange(code, min, max, req, context) \
+  do {                                                             \
+  } while (0)
+#define wpi_setError(code) wpi_setErrorWithContext(code, "")
+#define wpi_setStaticErrorWithContext(object, code, context) \
+  do {                                                       \
+  } while (0)
+#define wpi_setStaticError(object, code) \
+  wpi_setStaticErrorWithContext(object, code, "")
+#define wpi_setGlobalErrorWithContext(code, context) \
+  do {                                               \
+  } while (0)
+#define wpi_setGlobalError(code) wpi_setGlobalErrorWithContext(code, "")
+#define wpi_setWPIErrorWithContext(error, context) \
+  do {                                             \
+  } while (0)
+#define wpi_setWPIError(error) wpi_setWPIErrorWithContext(error, "")
+#define wpi_setStaticWPIErrorWithContext(object, error, context)  \
+  object->SetWPIError((wpi_error_s_##error), (context), __FILE__, \
+                      __FUNCTION__, __LINE__)
+#define wpi_setStaticWPIError(object, error) \
+  wpi_setStaticWPIErrorWithContext(object, error, "")
+#define wpi_setGlobalWPIErrorWithContext(error, context)                \
+  ::frc::ErrorBase::SetGlobalWPIError((wpi_error_s_##error), (context), \
+                                      __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setGlobalWPIError(error) wpi_setGlobalWPIErrorWithContext(error, "")
+
+namespace frc {
+
+inline bool StatusIsFatal() { return false; }
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/InterruptableSensorBase.cc b/frc971/wpilib/ahal/InterruptableSensorBase.cc
new file mode 100644
index 0000000..a757bee
--- /dev/null
+++ b/frc971/wpilib/ahal/InterruptableSensorBase.cc
@@ -0,0 +1,202 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/InterruptableSensorBase.h"
+
+#include "HAL/HAL.h"
+#include "frc971/wpilib/ahal/Utility.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+InterruptableSensorBase::InterruptableSensorBase() {}
+
+/**
+ * Request one of the 8 interrupts asynchronously on this digital input.
+ *
+ * Request interrupts in asynchronous mode where the user's interrupt handler
+ * will be called when the interrupt fires. Users that want control over the
+ * thread priority should use the synchronous method with their own spawned
+ * thread. The default is interrupt on rising edges only.
+ */
+void InterruptableSensorBase::RequestInterrupts(
+    HAL_InterruptHandlerFunction handler, void *param) {
+  if (StatusIsFatal()) return;
+
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  AllocateInterrupts(false);
+  if (StatusIsFatal()) return;  // if allocate failed, out of interrupts
+
+  int32_t status = 0;
+  HAL_RequestInterrupts(
+      m_interrupt, GetPortHandleForRouting(),
+      static_cast<HAL_AnalogTriggerType>(GetAnalogTriggerTypeForRouting()),
+      &status);
+  SetUpSourceEdge(true, false);
+  HAL_AttachInterruptHandler(m_interrupt, handler, param, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Request one of the 8 interrupts synchronously on this digital input.
+ *
+ * Request interrupts in synchronous mode where the user program will have to
+ * explicitly wait for the interrupt to occur using WaitForInterrupt.
+ * The default is interrupt on rising edges only.
+ */
+void InterruptableSensorBase::RequestInterrupts() {
+  if (StatusIsFatal()) return;
+
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  AllocateInterrupts(true);
+  if (StatusIsFatal()) return;  // if allocate failed, out of interrupts
+
+  int32_t status = 0;
+  HAL_RequestInterrupts(
+      m_interrupt, GetPortHandleForRouting(),
+      static_cast<HAL_AnalogTriggerType>(GetAnalogTriggerTypeForRouting()),
+      &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  SetUpSourceEdge(true, false);
+}
+
+void InterruptableSensorBase::AllocateInterrupts(bool watcher) {
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  // Expects the calling leaf class to allocate an interrupt index.
+  int32_t status = 0;
+  m_interrupt = HAL_InitializeInterrupts(watcher, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Cancel interrupts on this device.
+ *
+ * This deallocates all the chipobject structures and disables any interrupts.
+ */
+void InterruptableSensorBase::CancelInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_CleanInterrupts(m_interrupt, &status);
+  // ignore status, as an invalid handle just needs to be ignored.
+  m_interrupt = HAL_kInvalidHandle;
+}
+
+/**
+ * In synchronous mode, wait for the defined interrupt to occur.
+ *
+ * You should <b>NOT</b> attempt to read the sensor from another thread while
+ * waiting for an interrupt. This is not threadsafe, and can cause memory
+ * corruption
+ *
+ * @param timeout        Timeout in seconds
+ * @param ignorePrevious If true, ignore interrupts that happened before
+ *                       WaitForInterrupt was called.
+ * @return What interrupts fired
+ */
+InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt(
+    double timeout, bool ignorePrevious) {
+  if (StatusIsFatal()) return InterruptableSensorBase::kTimeout;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  int result;
+
+  result = HAL_WaitForInterrupt(m_interrupt, timeout, ignorePrevious, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  // Rising edge result is the interrupt bit set in the byte 0xFF
+  // Falling edge result is the interrupt bit set in the byte 0xFF00
+  // Set any bit set to be true for that edge, and AND the 2 results
+  // together to match the existing enum for all interrupts
+  int32_t rising = (result & 0xFF) ? 0x1 : 0x0;
+  int32_t falling = ((result & 0xFF00) ? 0x0100 : 0x0);
+  return static_cast<WaitResult>(falling | rising);
+}
+
+/**
+ * Enable interrupts to occur on this input.
+ *
+ * Interrupts are disabled when the RequestInterrupt call is made. This gives
+ * time to do the setup of the other options before starting to field
+ * interrupts.
+ */
+void InterruptableSensorBase::EnableInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_EnableInterrupts(m_interrupt, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Disable Interrupts without without deallocating structures.
+ */
+void InterruptableSensorBase::DisableInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_DisableInterrupts(m_interrupt, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Return the timestamp for the rising interrupt that occurred most recently.
+ *
+ * This is in the same time domain as GetClock().
+ * The rising-edge interrupt should be enabled with
+ * {@link #DigitalInput.SetUpSourceEdge}
+ *
+ * @return Timestamp in seconds since boot.
+ */
+double InterruptableSensorBase::ReadRisingTimestamp() {
+  if (StatusIsFatal()) return 0.0;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  double timestamp = HAL_ReadInterruptRisingTimestamp(m_interrupt, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return timestamp;
+}
+
+/**
+ * Return the timestamp for the falling interrupt that occurred most recently.
+ *
+ * This is in the same time domain as GetClock().
+ * The falling-edge interrupt should be enabled with
+ * {@link #DigitalInput.SetUpSourceEdge}
+ *
+ * @return Timestamp in seconds since boot.
+*/
+double InterruptableSensorBase::ReadFallingTimestamp() {
+  if (StatusIsFatal()) return 0.0;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  double timestamp = HAL_ReadInterruptFallingTimestamp(m_interrupt, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return timestamp;
+}
+
+/**
+ * Set which edge to trigger interrupts on
+ *
+ * @param risingEdge  true to interrupt on rising edge
+ * @param fallingEdge true to interrupt on falling edge
+ */
+void InterruptableSensorBase::SetUpSourceEdge(bool risingEdge,
+                                              bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_interrupt == HAL_kInvalidHandle) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "You must call RequestInterrupts before SetUpSourceEdge");
+    return;
+  }
+  if (m_interrupt != HAL_kInvalidHandle) {
+    int32_t status = 0;
+    HAL_SetInterruptUpSourceEdge(m_interrupt, risingEdge, fallingEdge, &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  }
+}
diff --git a/frc971/wpilib/ahal/InterruptableSensorBase.h b/frc971/wpilib/ahal/InterruptableSensorBase.h
new file mode 100644
index 0000000..e19e09b
--- /dev/null
+++ b/frc971/wpilib/ahal/InterruptableSensorBase.h
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "HAL/Interrupts.h"
+#include "frc971/wpilib/ahal/AnalogTriggerType.h"
+#include "frc971/wpilib/ahal/SensorBase.h"
+
+namespace frc {
+
+class InterruptableSensorBase {
+ public:
+  enum WaitResult {
+    kTimeout = 0x0,
+    kRisingEdge = 0x1,
+    kFallingEdge = 0x100,
+    kBoth = 0x101,
+  };
+
+  InterruptableSensorBase();
+  virtual ~InterruptableSensorBase() = default;
+  virtual HAL_Handle GetPortHandleForRouting() const = 0;
+  virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const = 0;
+  virtual void RequestInterrupts(
+      HAL_InterruptHandlerFunction handler,
+      void *param);                  ///< Asynchronous handler version.
+  virtual void RequestInterrupts();  ///< Synchronous Wait version.
+  virtual void
+  CancelInterrupts();  ///< Free up the underlying chipobject functions.
+  virtual WaitResult WaitForInterrupt(
+      double timeout,
+      bool ignorePrevious = true);  ///< Synchronous version.
+  virtual void
+  EnableInterrupts();  ///< Enable interrupts - after finishing setup.
+  virtual void DisableInterrupts();       ///< Disable, but don't deallocate.
+  virtual double ReadRisingTimestamp();   ///< Return the timestamp for the
+                                          /// rising interrupt that occurred.
+  virtual double ReadFallingTimestamp();  ///< Return the timestamp for the
+                                          /// falling interrupt that occurred.
+  virtual void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+
+ protected:
+  HAL_InterruptHandle m_interrupt = HAL_kInvalidHandle;
+  void AllocateInterrupts(bool watcher);
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/PWM.cc b/frc971/wpilib/ahal/PWM.cc
new file mode 100644
index 0000000..9407a9c
--- /dev/null
+++ b/frc971/wpilib/ahal/PWM.cc
@@ -0,0 +1,296 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "HAL/PWM.h"
+#include "frc971/wpilib/ahal/PWM.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "frc971/wpilib/ahal/Utility.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+#define HAL_FATAL_ERROR()
+
+/**
+ * Allocate a PWM given a channel number.
+ *
+ * Checks channel value range and allocates the appropriate channel.
+ * The allocation is only done to help users ensure that they don't double
+ * assign channels.
+ *
+ * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the
+ *                MXP port
+ */
+PWM::PWM(int channel) {
+  if (!CheckPWMChannel(channel)) {
+    fprintf(stderr, "Channel Index out of range: PWM Channel %d\n", channel);
+    exit(-1);
+    return;
+  }
+
+  int32_t status = 0;
+  m_handle = HAL_InitializePWMPort(HAL_GetPort(channel), &status);
+  if (status != 0) {
+    //    wpi_setErrorWithContextRange(status, 0, HAL_GetNumPWMChannels(),
+    //    channel,
+    //                                 HAL_GetErrorMessage(status));
+    HAL_FATAL_ERROR();
+    m_channel = std::numeric_limits<int>::max();
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  HAL_FATAL_ERROR();
+  status = 0;
+  HAL_SetPWMEliminateDeadband(m_handle, false, &status);
+  HAL_FATAL_ERROR();
+
+  HAL_Report(HALUsageReporting::kResourceType_PWM, channel);
+}
+
+/**
+ * Free the PWM channel.
+ *
+ * Free the resource associated with the PWM channel and set the value to 0.
+ */
+PWM::~PWM() {
+  int32_t status = 0;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  HAL_FATAL_ERROR();
+
+  HAL_FreePWMPort(m_handle, &status);
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Optionally eliminate the deadband from a speed controller.
+ *
+ * @param eliminateDeadband If true, set the motor curve on the Jaguar to
+ *                          eliminate the deadband in the middle of the range.
+ *                          Otherwise, keep the full range without modifying
+ *                          any values.
+ */
+void PWM::EnableDeadbandElimination(bool eliminateDeadband) {
+  int32_t status = 0;
+  HAL_SetPWMEliminateDeadband(m_handle, eliminateDeadband, &status);
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Set the bounds on the PWM pulse widths.
+ *
+ * This sets the bounds on the PWM values for a particular type of controller.
+ * The values determine the upper and lower speeds as well as the deadband
+ * bracket.
+ *
+ * @param max         The max PWM pulse width in ms
+ * @param deadbandMax The high end of the deadband range pulse width in ms
+ * @param center      The center (off) pulse width in ms
+ * @param deadbandMin The low end of the deadband pulse width in ms
+ * @param min         The minimum pulse width in ms
+ */
+void PWM::SetBounds(double max, double deadbandMax, double center,
+                    double deadbandMin, double min) {
+  int32_t status = 0;
+  HAL_SetPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min,
+                   &status);
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Set the bounds on the PWM values.
+ *
+ * This sets the bounds on the PWM values for a particular each type of
+ * controller. The values determine the upper and lower speeds as well as the
+ * deadband bracket.
+ *
+ * @param max         The Minimum pwm value
+ * @param deadbandMax The high end of the deadband range
+ * @param center      The center speed (off)
+ * @param deadbandMin The low end of the deadband range
+ * @param min         The minimum pwm value
+ */
+void PWM::SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
+                       int min) {
+  int32_t status = 0;
+  HAL_SetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
+                      &status);
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Get the bounds on the PWM values.
+ *
+ * This Gets the bounds on the PWM values for a particular each type of
+ * controller. The values determine the upper and lower speeds as well as the
+ * deadband bracket.
+ *
+ * @param max         The Minimum pwm value
+ * @param deadbandMax The high end of the deadband range
+ * @param center      The center speed (off)
+ * @param deadbandMin The low end of the deadband range
+ * @param min         The minimum pwm value
+ */
+void PWM::GetRawBounds(int *max, int *deadbandMax, int *center,
+                       int *deadbandMin, int *min) {
+  int32_t status = 0;
+  HAL_GetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
+                      &status);
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Set the PWM value based on a position.
+ *
+ * This is intended to be used by servos.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @param pos The position to set the servo between 0.0 and 1.0.
+ */
+void PWM::SetPosition(double pos) {
+  int32_t status = 0;
+  HAL_SetPWMPosition(m_handle, pos, &status);
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Get the PWM value in terms of a position.
+ *
+ * This is intended to be used by servos.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @return The position the servo is set to between 0.0 and 1.0.
+ */
+double PWM::GetPosition() const {
+  int32_t status = 0;
+  double position = HAL_GetPWMPosition(m_handle, &status);
+  HAL_FATAL_ERROR();
+  return position;
+}
+
+/**
+ * Set the PWM value based on a speed.
+ *
+ * This is intended to be used by speed controllers.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinPositivePwm() called.
+ * @pre SetCenterPwm() called.
+ * @pre SetMaxNegativePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @param speed The speed to set the speed controller between -1.0 and 1.0.
+ */
+void PWM::SetSpeed(double speed) {
+  int32_t status = 0;
+  HAL_SetPWMSpeed(m_handle, speed, &status);
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Get the PWM value in terms of speed.
+ *
+ * This is intended to be used by speed controllers.
+ *
+ * @pre SetMaxPositivePwm() called.
+ * @pre SetMinPositivePwm() called.
+ * @pre SetMaxNegativePwm() called.
+ * @pre SetMinNegativePwm() called.
+ *
+ * @return The most recently set speed between -1.0 and 1.0.
+ */
+double PWM::GetSpeed() const {
+  int32_t status = 0;
+  double speed = HAL_GetPWMSpeed(m_handle, &status);
+  HAL_FATAL_ERROR();
+  return speed;
+}
+
+/**
+ * Set the PWM value directly to the hardware.
+ *
+ * Write a raw value to a PWM channel.
+ *
+ * @param value Raw PWM value.
+ */
+void PWM::SetRaw(uint16_t value) {
+  int32_t status = 0;
+  HAL_SetPWMRaw(m_handle, value, &status);
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Get the PWM value directly from the hardware.
+ *
+ * Read a raw value from a PWM channel.
+ *
+ * @return Raw PWM control value.
+ */
+uint16_t PWM::GetRaw() const {
+  int32_t status = 0;
+  uint16_t value = HAL_GetPWMRaw(m_handle, &status);
+  HAL_FATAL_ERROR();
+
+  return value;
+}
+
+/**
+ * Slow down the PWM signal for old devices.
+ *
+ * @param mult The period multiplier to apply to this channel
+ */
+void PWM::SetPeriodMultiplier(PeriodMultiplier mult) {
+  int32_t status = 0;
+
+  switch (mult) {
+    case kPeriodMultiplier_4X:
+      HAL_SetPWMPeriodScale(m_handle, 3,
+                            &status);  // Squelch 3 out of 4 outputs
+      break;
+    case kPeriodMultiplier_2X:
+      HAL_SetPWMPeriodScale(m_handle, 1,
+                            &status);  // Squelch 1 out of 2 outputs
+      break;
+    case kPeriodMultiplier_1X:
+      HAL_SetPWMPeriodScale(m_handle, 0, &status);  // Don't squelch any outputs
+      break;
+    default:
+      wpi_assert(false);
+  }
+
+  HAL_FATAL_ERROR();
+}
+
+/**
+ * Temporarily disables the PWM output. The next set call will reenable
+ * the output.
+ */
+void PWM::SetDisabled() {
+  int32_t status = 0;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  HAL_FATAL_ERROR();
+}
+
+void PWM::SetZeroLatch() {
+  int32_t status = 0;
+
+  HAL_LatchPWMZero(m_handle, &status);
+  HAL_FATAL_ERROR();
+}
diff --git a/frc971/wpilib/ahal/PWM.h b/frc971/wpilib/ahal/PWM.h
new file mode 100644
index 0000000..9af8d0f
--- /dev/null
+++ b/frc971/wpilib/ahal/PWM.h
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "HAL/Types.h"
+#include "frc971/wpilib/ahal/SensorBase.h"
+
+namespace frc {
+
+/**
+ * Class implements the PWM generation in the FPGA.
+ *
+ * The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They
+ * are mapped to the hardware dependent values, in this case 0-2000 for the
+ * FPGA. Changes are immediately sent to the FPGA, and the update occurs at the
+ * next FPGA cycle. There is no delay.
+ *
+ * As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-2000 values as
+ * follows:
+ *   - 2000 = maximum pulse width
+ *   - 1999 to 1001 = linear scaling from "full forward" to "center"
+ *   - 1000 = center value
+ *   - 999 to 2 = linear scaling from "center" to "full reverse"
+ *   - 1 = minimum pulse width (currently .5ms)
+ *   - 0 = disabled (i.e. PWM output is held low)
+ */
+class PWM {
+ public:
+  enum PeriodMultiplier {
+    kPeriodMultiplier_1X = 1,
+    kPeriodMultiplier_2X = 2,
+    kPeriodMultiplier_4X = 4
+  };
+
+  explicit PWM(int channel);
+  virtual ~PWM();
+  virtual void SetRaw(uint16_t value);
+  virtual uint16_t GetRaw() const;
+  virtual void SetPosition(double pos);
+  virtual double GetPosition() const;
+  virtual void SetSpeed(double speed);
+  virtual double GetSpeed() const;
+  virtual void SetDisabled();
+  void SetPeriodMultiplier(PeriodMultiplier mult);
+  void SetZeroLatch();
+  void EnableDeadbandElimination(bool eliminateDeadband);
+  void SetBounds(double max, double deadbandMax, double center,
+                 double deadbandMin, double min);
+  void SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
+                    int min);
+  void GetRawBounds(int32_t *max, int32_t *deadbandMax, int32_t *center,
+                    int32_t *deadbandMin, int32_t *min);
+  int GetChannel() const { return m_channel; }
+
+ protected:
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/PowerDistributionPanel.cc b/frc971/wpilib/ahal/PowerDistributionPanel.cc
new file mode 100644
index 0000000..90655c2
--- /dev/null
+++ b/frc971/wpilib/ahal/PowerDistributionPanel.cc
@@ -0,0 +1,170 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2017. 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 "frc971/wpilib/ahal/PowerDistributionPanel.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/PDP.h"
+#include "HAL/Ports.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+#define WPI_LIB_FATAL_ERROR(tag, msg)
+
+PowerDistributionPanel::PowerDistributionPanel() : PowerDistributionPanel(0) {}
+
+/**
+ * Initialize the PDP.
+ */
+PowerDistributionPanel::PowerDistributionPanel(int module) : m_module(module) {
+  int32_t status = 0;
+  HAL_InitializePDP(m_module, &status);
+  if (status != 0) {
+    // wpi_setErrorWithContextRange(status, 0, HAL_GetNumPDPModules(), module,
+    //                              HAL_GetErrorMessage(status));
+    m_module = -1;
+    return;
+  }
+}
+
+/**
+ * Query the input voltage of the PDP.
+ *
+ * @return The voltage of the PDP in volts
+ */
+double PowerDistributionPanel::GetVoltage() const {
+  int32_t status = 0;
+
+  double voltage = HAL_GetPDPVoltage(m_module, &status);
+
+  if (status) {
+    WPI_LIB_FATAL_ERROR(Timeout, "");
+  }
+
+  return voltage;
+}
+
+/**
+ * Query the temperature of the PDP.
+ *
+ * @return The temperature of the PDP in degrees Celsius
+ */
+double PowerDistributionPanel::GetTemperature() const {
+  int32_t status = 0;
+
+  double temperature = HAL_GetPDPTemperature(m_module, &status);
+
+  if (status) {
+    WPI_LIB_FATAL_ERROR(Timeout, "");
+  }
+
+  return temperature;
+}
+
+/**
+ * Query the current of a single channel of the PDP.
+ *
+ * @return The current of one of the PDP channels (channels 0-15) in Amperes
+ */
+double PowerDistributionPanel::GetCurrent(int channel) const {
+  int32_t status = 0;
+
+  if (!CheckPDPChannel(channel)) {
+    std::stringstream buf;
+    buf << "PDP Channel " << channel;
+    WPI_LIB_FATAL_ERROR(ChannelIndexOutOfRange, buf.str());
+  }
+
+  double current = HAL_GetPDPChannelCurrent(m_module, channel, &status);
+
+  if (status) {
+    WPI_LIB_FATAL_ERROR(Timeout, "");
+  }
+
+  return current;
+}
+
+/**
+ * Query the total current of all monitored PDP channels (0-15).
+ *
+ * @return The the total current drawn from the PDP channels in Amperes
+ */
+double PowerDistributionPanel::GetTotalCurrent() const {
+  int32_t status = 0;
+
+  double current = HAL_GetPDPTotalCurrent(m_module, &status);
+
+  if (status) {
+    WPI_LIB_FATAL_ERROR(Timeout, "");
+  }
+
+  return current;
+}
+
+/**
+ * Query the total power drawn from the monitored PDP channels.
+ *
+ * @return The the total power drawn from the PDP channels in Watts
+ */
+double PowerDistributionPanel::GetTotalPower() const {
+  int32_t status = 0;
+
+  double power = HAL_GetPDPTotalPower(m_module, &status);
+
+  if (status) {
+    WPI_LIB_FATAL_ERROR(Timeout, "");
+  }
+
+  return power;
+}
+
+/**
+ * Query the total energy drawn from the monitored PDP channels.
+ *
+ * @return The the total energy drawn from the PDP channels in Joules
+ */
+double PowerDistributionPanel::GetTotalEnergy() const {
+  int32_t status = 0;
+
+  double energy = HAL_GetPDPTotalEnergy(m_module, &status);
+
+  if (status) {
+    WPI_LIB_FATAL_ERROR(Timeout, "");
+  }
+
+  return energy;
+}
+
+/**
+ * Reset the total energy drawn from the PDP.
+ *
+ * @see PowerDistributionPanel#GetTotalEnergy
+ */
+void PowerDistributionPanel::ResetTotalEnergy() {
+  int32_t status = 0;
+
+  HAL_ResetPDPTotalEnergy(m_module, &status);
+
+  if (status) {
+    WPI_LIB_FATAL_ERROR(Timeout, "");
+  }
+}
+
+/**
+ * Remove all of the fault flags on the PDP.
+ */
+void PowerDistributionPanel::ClearStickyFaults() {
+  int32_t status = 0;
+
+  HAL_ClearPDPStickyFaults(m_module, &status);
+
+  if (status) {
+    WPI_LIB_FATAL_ERROR(Timeout, "");
+  }
+}
diff --git a/frc971/wpilib/ahal/PowerDistributionPanel.h b/frc971/wpilib/ahal/PowerDistributionPanel.h
new file mode 100644
index 0000000..fcb14ed
--- /dev/null
+++ b/frc971/wpilib/ahal/PowerDistributionPanel.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2014-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "frc971/wpilib/ahal/SensorBase.h"
+
+namespace frc {
+
+/**
+ * Class for getting voltage, current, temperature, power and energy from the
+ * CAN PDP.
+ */
+class PowerDistributionPanel {
+ public:
+  PowerDistributionPanel();
+  explicit PowerDistributionPanel(int module);
+
+  double GetVoltage() const;
+  double GetTemperature() const;
+  double GetCurrent(int channel) const;
+  double GetTotalCurrent() const;
+  double GetTotalPower() const;
+  double GetTotalEnergy() const;
+  void ResetTotalEnergy();
+  void ClearStickyFaults();
+
+ private:
+  int m_module;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/Relay.cc b/frc971/wpilib/ahal/Relay.cc
new file mode 100644
index 0000000..b69e7af
--- /dev/null
+++ b/frc971/wpilib/ahal/Relay.cc
@@ -0,0 +1,204 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "HAL/Relay.h"
+#include "frc971/wpilib/ahal/Relay.h"
+
+#include <sstream>
+
+#include "HAL/HAL.h"
+#include "HAL/Ports.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+using namespace frc;
+
+/**
+ * Relay constructor given a channel.
+ *
+ * This code initializes the relay and reserves all resources that need to be
+ * locked. Initially the relay is set to both lines at 0v.
+ *
+ * @param channel   The channel number (0-3).
+ * @param direction The direction that the Relay object will control.
+ */
+Relay::Relay(int channel, Relay::Direction direction)
+    : m_channel(channel), m_direction(direction) {
+  std::stringstream buf;
+  if (!CheckRelayChannel(m_channel)) {
+    buf << "Relay Channel " << m_channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+    return;
+  }
+
+  HAL_PortHandle portHandle = HAL_GetPort(channel);
+
+  if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+    int32_t status = 0;
+    m_forwardHandle = HAL_InitializeRelayPort(portHandle, true, &status);
+    if (status != 0) {
+      wpi_setErrorWithContextRange(status, 0, HAL_GetNumRelayChannels(),
+                                   channel, HAL_GetErrorMessage(status));
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+    HAL_Report(HALUsageReporting::kResourceType_Relay, m_channel);
+  }
+  if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+    int32_t status = 0;
+    m_reverseHandle = HAL_InitializeRelayPort(portHandle, false, &status);
+    if (status != 0) {
+      wpi_setErrorWithContextRange(status, 0, HAL_GetNumRelayChannels(),
+                                   channel, HAL_GetErrorMessage(status));
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+
+    HAL_Report(HALUsageReporting::kResourceType_Relay, m_channel + 128);
+  }
+
+  int32_t status = 0;
+  if (m_forwardHandle != HAL_kInvalidHandle) {
+    HAL_SetRelay(m_forwardHandle, false, &status);
+    if (status != 0) {
+      wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+  if (m_reverseHandle != HAL_kInvalidHandle) {
+    HAL_SetRelay(m_reverseHandle, false, &status);
+    if (status != 0) {
+      wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+}
+
+/**
+ * Free the resource associated with a relay.
+ *
+ * The relay channels are set to free and the relay output is turned off.
+ */
+Relay::~Relay() {
+  int32_t status = 0;
+  HAL_SetRelay(m_forwardHandle, false, &status);
+  HAL_SetRelay(m_reverseHandle, false, &status);
+  // ignore errors, as we want to make sure a free happens.
+  if (m_forwardHandle != HAL_kInvalidHandle) HAL_FreeRelayPort(m_forwardHandle);
+  if (m_reverseHandle != HAL_kInvalidHandle) HAL_FreeRelayPort(m_reverseHandle);
+}
+
+/**
+ * Set the relay state.
+ *
+ * Valid values depend on which directions of the relay are controlled by the
+ * object.
+ *
+ * When set to kBothDirections, the relay can be any of the four states:
+ * 0v-0v, 0v-12v, 12v-0v, 12v-12v
+ *
+ * When set to kForwardOnly or kReverseOnly, you can specify the constant for
+ * the direction or you can simply specify kOff and kOn.  Using only kOff and
+ * kOn is recommended.
+ *
+ * @param value The state to set the relay.
+ */
+void Relay::Set(Relay::Value value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  switch (value) {
+    case kOff:
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, false, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, false, &status);
+      }
+      break;
+    case kOn:
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, true, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, true, &status);
+      }
+      break;
+    case kForward:
+      if (m_direction == kReverseOnly) {
+        wpi_setWPIError(IncompatibleMode);
+        break;
+      }
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, true, &status);
+      }
+      if (m_direction == kBothDirections) {
+        HAL_SetRelay(m_reverseHandle, false, &status);
+      }
+      break;
+    case kReverse:
+      if (m_direction == kForwardOnly) {
+        wpi_setWPIError(IncompatibleMode);
+        break;
+      }
+      if (m_direction == kBothDirections) {
+        HAL_SetRelay(m_forwardHandle, false, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, true, &status);
+      }
+      break;
+  }
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+/**
+ * Get the Relay State
+ *
+ * Gets the current state of the relay.
+ *
+ * When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff not
+ * kForward/kReverse (per the recommendation in Set)
+ *
+ * @return The current state of the relay as a Relay::Value
+ */
+Relay::Value Relay::Get() const {
+  int32_t status;
+
+  if (HAL_GetRelay(m_forwardHandle, &status)) {
+    if (HAL_GetRelay(m_reverseHandle, &status)) {
+      return kOn;
+    } else {
+      if (m_direction == kForwardOnly) {
+        return kOn;
+      } else {
+        return kForward;
+      }
+    }
+  } else {
+    if (HAL_GetRelay(m_reverseHandle, &status)) {
+      if (m_direction == kReverseOnly) {
+        return kOn;
+      } else {
+        return kReverse;
+      }
+    } else {
+      return kOff;
+    }
+  }
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int Relay::GetChannel() const { return m_channel; }
diff --git a/frc971/wpilib/ahal/Relay.h b/frc971/wpilib/ahal/Relay.h
new file mode 100644
index 0000000..ecdd8af
--- /dev/null
+++ b/frc971/wpilib/ahal/Relay.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "HAL/Types.h"
+#include "frc971/wpilib/ahal/SensorBase.h"
+
+namespace frc {
+
+/**
+ * Class for Spike style relay outputs.
+ * Relays are intended to be connected to spikes or similar relays. The relay
+ * channels controls a pair of pins that are either both off, one on, the other
+ * on, or both on. This translates into two spike outputs at 0v, one at 12v and
+ * one at 0v, one at 0v and the other at 12v, or two spike outputs at 12V. This
+ * allows off, full forward, or full reverse control of motors without variable
+ * speed.  It also allows the two channels (forward and reverse) to be used
+ * independently for something that does not care about voltage polarity (like
+ * a solenoid).
+ */
+class Relay {
+ public:
+  enum Value { kOff, kOn, kForward, kReverse };
+  enum Direction { kBothDirections, kForwardOnly, kReverseOnly };
+
+  explicit Relay(int channel, Direction direction = kBothDirections);
+  virtual ~Relay();
+
+  void Set(Value value);
+  Value Get() const;
+  int GetChannel() const;
+
+ private:
+  int m_channel;
+  Direction m_direction;
+
+  HAL_RelayHandle m_forwardHandle = HAL_kInvalidHandle;
+  HAL_RelayHandle m_reverseHandle = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/RobotBase.cc b/frc971/wpilib/ahal/RobotBase.cc
new file mode 100644
index 0000000..35e5570
--- /dev/null
+++ b/frc971/wpilib/ahal/RobotBase.cc
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/RobotBase.h"
+
+#include <cstdio>
+
+#include "HAL/HAL.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Utility.h"
+#include "frc971/wpilib/ahal/WPILibVersion.h"
+
+using namespace frc;
+
+/**
+ * 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 completion
+ * before Autonomous is entered.
+ *
+ * This must be used to ensure that the communications code starts. In the
+ * future it would be nice to put this code into it's own task that loads on
+ * boot so ensure that it runs.
+ */
+RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
+  std::FILE *file = nullptr;
+  file = std::fopen("/tmp/frc_versions/FRC_Lib_Version.ini", "w");
+
+  if (file != nullptr) {
+    std::fputs("C++ ", file);
+    std::fputs(WPILibVersion, file);
+    std::fclose(file);
+  }
+}
diff --git a/frc971/wpilib/ahal/RobotBase.h b/frc971/wpilib/ahal/RobotBase.h
new file mode 100644
index 0000000..da37e06
--- /dev/null
+++ b/frc971/wpilib/ahal/RobotBase.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cstdio>
+#include <iostream>
+#include <thread>
+
+#include "HAL/HAL.h"
+#include "frc971/wpilib/ahal/Base.h"
+
+namespace frc {
+
+class DriverStation;
+
+#ifdef WPILIB2017
+#define START_ROBOT_CLASS(_ClassName_)                                       \
+  int main() {                                                               \
+    if (!HAL_Initialize(0)) {                                                \
+      std::cerr << "FATAL ERROR: HAL could not be initialized" << std::endl; \
+      return -1;                                                             \
+    }                                                                        \
+    HAL_Report(HALUsageReporting::kResourceType_Language,                    \
+               HALUsageReporting::kLanguage_CPlusPlus);                      \
+    static _ClassName_ robot;                                                \
+    std::printf("\n********** Robot program starting **********\n");         \
+    robot.StartCompetition();                                                \
+  }
+#else
+#define START_ROBOT_CLASS(_ClassName_)                                       \
+  int main() {                                                               \
+    if (!HAL_Initialize(500, 0)) {                                           \
+      std::cerr << "FATAL ERROR: HAL could not be initialized" << std::endl; \
+      return -1;                                                             \
+    }                                                                        \
+    HAL_Report(HALUsageReporting::kResourceType_Language,                    \
+               HALUsageReporting::kLanguage_CPlusPlus);                      \
+    static _ClassName_ robot;                                                \
+    std::printf("\n********** Robot program starting **********\n");         \
+    robot.StartCompetition();                                                \
+  }
+#endif
+
+/**
+ * Implement a Robot Program framework.
+ * The RobotBase class is intended to be subclassed by a user creating a robot
+ * program. Overridden Autonomous() and OperatorControl() methods are called at
+ * the appropriate time as the match proceeds. In the current implementation,
+ * the Autonomous code will run to completion before the OperatorControl code
+ * could start. In the future the Autonomous code might be spawned as a task,
+ * then killed at the end of the Autonomous period.
+ */
+class RobotBase {
+ public:
+  virtual void StartCompetition() = 0;
+
+ protected:
+  RobotBase();
+  virtual ~RobotBase() = default;
+
+  RobotBase(const RobotBase &) = delete;
+  RobotBase &operator=(const RobotBase &) = delete;
+
+  DriverStation &m_ds;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/SPI.cc b/frc971/wpilib/ahal/SPI.cc
new file mode 100644
index 0000000..5e18fc1
--- /dev/null
+++ b/frc971/wpilib/ahal/SPI.cc
@@ -0,0 +1,176 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "HAL/SPI.h"
+#include "frc971/wpilib/ahal/SPI.h"
+
+#include <cstring>
+
+#include "HAL/HAL.h"
+#include "llvm/SmallVector.h"
+
+using namespace frc;
+
+#define HAL_FATAL_WITH_STATUS(status)
+
+/**
+ * Constructor
+ *
+ * @param SPIport the physical SPI port
+ */
+SPI::SPI(Port SPIport) {
+#ifdef WPILIB2017
+  m_port = SPIport;
+#else
+  m_port = static_cast<HAL_SPIPort>(SPIport);
+#endif
+  int32_t status = 0;
+  HAL_InitializeSPI(m_port, &status);
+  HAL_FATAL_WITH_STATUS(status);
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_SPI, instances);
+}
+
+/**
+ * Destructor.
+ */
+SPI::~SPI() { HAL_CloseSPI(m_port); }
+
+/**
+ * Configure the rate of the generated clock signal.
+ *
+ * The default value is 500,000Hz.
+ * The maximum value is 4,000,000Hz.
+ *
+ * @param hz The clock rate in Hertz.
+ */
+void SPI::SetClockRate(double hz) { HAL_SetSPISpeed(m_port, hz); }
+
+/**
+ * Configure the order that bits are sent and received on the wire
+ * to be most significant bit first.
+ */
+void SPI::SetMSBFirst() {
+  m_msbFirst = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
+}
+
+/**
+ * Configure the order that bits are sent and received on the wire
+ * to be least significant bit first.
+ */
+void SPI::SetLSBFirst() {
+  m_msbFirst = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
+}
+
+/**
+ * Configure that the data is stable on the falling edge and the data
+ * changes on the rising edge.
+ */
+void SPI::SetSampleDataOnFalling() {
+  m_sampleOnTrailing = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
+}
+
+/**
+ * Configure that the data is stable on the rising edge and the data
+ * changes on the falling edge.
+ */
+void SPI::SetSampleDataOnRising() {
+  m_sampleOnTrailing = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
+}
+
+/**
+ * Configure the clock output line to be active low.
+ * This is sometimes called clock polarity high or clock idle high.
+ */
+void SPI::SetClockActiveLow() {
+  m_clk_idle_high = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
+}
+
+/**
+ * Configure the clock output line to be active high.
+ * This is sometimes called clock polarity low or clock idle low.
+ */
+void SPI::SetClockActiveHigh() {
+  m_clk_idle_high = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clk_idle_high);
+}
+
+/**
+ * Configure the chip select line to be active high.
+ */
+void SPI::SetChipSelectActiveHigh() {
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveHigh(m_port, &status);
+  HAL_FATAL_WITH_STATUS(status);
+}
+
+/**
+ * Configure the chip select line to be active low.
+ */
+void SPI::SetChipSelectActiveLow() {
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveLow(m_port, &status);
+  HAL_FATAL_WITH_STATUS(status);
+}
+
+/**
+ * Write data to the slave device.  Blocks until there is space in the
+ * output FIFO.
+ *
+ * If not running in output only mode, also saves the data received
+ * on the MISO input during the transfer into the receive FIFO.
+ */
+int SPI::Write(uint8_t *data, int size) {
+  int retVal = 0;
+  retVal = HAL_WriteSPI(m_port, data, size);
+  return retVal;
+}
+
+/**
+ * Read a word from the receive FIFO.
+ *
+ * Waits for the current transfer to complete if the receive FIFO is empty.
+ *
+ * If the receive FIFO is empty, there is no active transfer, and initiate
+ * is false, errors.
+ *
+ * @param initiate If true, this function pushes "0" into the transmit buffer
+ *                 and initiates a transfer. If false, this function assumes
+ *                 that data is already in the receive FIFO from a previous
+ *                 write.
+ */
+int SPI::Read(bool initiate, uint8_t *dataReceived, int size) {
+  int retVal = 0;
+  if (initiate) {
+    llvm::SmallVector<uint8_t, 32> dataToSend;
+    dataToSend.resize(size);
+    retVal = HAL_TransactionSPI(m_port, dataToSend.data(), dataReceived, size);
+  } else {
+    retVal = HAL_ReadSPI(m_port, dataReceived, size);
+  }
+  return retVal;
+}
+
+/**
+ * Perform a simultaneous read/write transaction with the device
+ *
+ * @param dataToSend   The data to be written out to the device
+ * @param dataReceived Buffer to receive data from the device
+ * @param size         The length of the transaction, in bytes
+ */
+int SPI::Transaction(uint8_t *dataToSend, uint8_t *dataReceived, int size) {
+  int retVal = 0;
+  retVal = HAL_TransactionSPI(m_port, dataToSend, dataReceived, size);
+  return retVal;
+}
diff --git a/frc971/wpilib/ahal/SPI.h b/frc971/wpilib/ahal/SPI.h
new file mode 100644
index 0000000..c1172ce
--- /dev/null
+++ b/frc971/wpilib/ahal/SPI.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HAL/SPI.h"
+
+namespace frc {
+
+class DigitalOutput;
+class DigitalInput;
+
+/**
+ * SPI bus interface class.
+ *
+ * This class is intended to be used by sensor (and other SPI device) drivers.
+ * It probably should not be used directly.
+ *
+ */
+class SPI {
+ public:
+  enum Port : int32_t {
+    kOnboardCS0 = 0,
+    kOnboardCS1,
+    kOnboardCS2,
+    kOnboardCS3,
+    kMXP
+  };
+  explicit SPI(Port SPIport);
+  virtual ~SPI();
+
+  SPI(const SPI &) = delete;
+  SPI &operator=(const SPI &) = delete;
+
+  void SetClockRate(double hz);
+
+  void SetMSBFirst();
+  void SetLSBFirst();
+
+  void SetSampleDataOnFalling();
+  void SetSampleDataOnRising();
+
+  void SetClockActiveLow();
+  void SetClockActiveHigh();
+
+  void SetChipSelectActiveHigh();
+  void SetChipSelectActiveLow();
+
+  virtual int Write(uint8_t *data, int size);
+  virtual int Read(bool initiate, uint8_t *dataReceived, int size);
+  virtual int Transaction(uint8_t *dataToSend, uint8_t *dataReceived, int size);
+
+ protected:
+#ifdef WPILIB2017
+  int m_port;
+#else
+  HAL_SPIPort m_port;
+#endif
+  bool m_msbFirst = false;          // default little-endian
+  bool m_sampleOnTrailing = false;  // default data updated on falling edge
+  bool m_clk_idle_high = false;     // default clock active high
+
+ private:
+  void Init();
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/SensorBase.cc b/frc971/wpilib/ahal/SensorBase.cc
new file mode 100644
index 0000000..c6db447
--- /dev/null
+++ b/frc971/wpilib/ahal/SensorBase.cc
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/SensorBase.h"
+
+#include "FRC_NetworkCommunication/LoadOut.h"
+#include "HAL/AnalogInput.h"
+#include "HAL/AnalogOutput.h"
+#include "HAL/DIO.h"
+#include "HAL/HAL.h"
+#include "HAL/PDP.h"
+#include "HAL/PWM.h"
+#include "HAL/Ports.h"
+#include "HAL/Relay.h"
+#include "HAL/Solenoid.h"
+#include "frc971/wpilib/ahal/WPIErrors.h"
+
+namespace frc {
+
+const int kDigitalChannels = HAL_GetNumDigitalChannels();
+const int kAnalogInputs = HAL_GetNumAnalogInputs();
+const int kSolenoidChannels = HAL_GetNumSolenoidChannels();
+const int kSolenoidModules = HAL_GetNumPCMModules();
+const int kPwmChannels = HAL_GetNumPWMChannels();
+const int kRelayChannels = HAL_GetNumRelayHeaders();
+const int kPDPChannels = HAL_GetNumPDPChannels();
+
+/**
+ * Check that the solenoid module number is valid.
+ *
+ * @return Solenoid module is valid and present
+ */
+bool CheckSolenoidModule(int moduleNumber) {
+  return HAL_CheckSolenoidModule(moduleNumber);
+}
+
+/**
+ * Check that the digital channel number is valid.
+ *
+ * Verify that the channel number is one of the legal channel numbers. Channel
+ * numbers are 1-based.
+ *
+ * @return Digital channel is valid
+ */
+bool CheckDigitalChannel(int channel) { return HAL_CheckDIOChannel(channel); }
+
+/**
+ * Check that the relay channel number is valid.
+ *
+ * Verify that the channel number is one of the legal channel numbers. Channel
+ * numbers are 0-based.
+ *
+ * @return Relay channel is valid
+ */
+bool CheckRelayChannel(int channel) { return HAL_CheckRelayChannel(channel); }
+
+/**
+ * Check that the digital channel number is valid.
+ *
+ * Verify that the channel number is one of the legal channel numbers. Channel
+ * numbers are 1-based.
+ *
+ * @return PWM channel is valid
+ */
+bool CheckPWMChannel(int channel) { return HAL_CheckPWMChannel(channel); }
+
+/**
+ * Check that the analog input number is value.
+ *
+ * Verify that the analog input number is one of the legal channel numbers.
+ * Channel numbers are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+bool CheckAnalogInputChannel(int channel) {
+  return HAL_CheckAnalogInputChannel(channel);
+}
+
+/**
+ * Check that the analog output number is valid.
+ *
+ * Verify that the analog output number is one of the legal channel numbers.
+ * Channel numbers are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+bool CheckAnalogOutputChannel(int channel) {
+  return HAL_CheckAnalogOutputChannel(channel);
+}
+
+/**
+ * Verify that the solenoid channel number is within limits.
+ *
+ * @return Solenoid channel is valid
+ */
+bool CheckSolenoidChannel(int channel) {
+  return HAL_CheckSolenoidChannel(channel);
+}
+
+/**
+ * Verify that the power distribution channel number is within limits.
+ *
+ * @return PDP channel is valid
+ */
+bool CheckPDPChannel(int channel) { return HAL_CheckPDPModule(channel); }
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/SensorBase.h b/frc971/wpilib/ahal/SensorBase.h
new file mode 100644
index 0000000..1d95330
--- /dev/null
+++ b/frc971/wpilib/ahal/SensorBase.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "frc971/wpilib/ahal/ErrorBase.h"
+
+namespace frc {
+
+inline int GetDefaultSolenoidModule() { return 0; }
+
+bool CheckSolenoidModule(int moduleNumber);
+bool CheckDigitalChannel(int channel);
+bool CheckRelayChannel(int channel);
+bool CheckPWMChannel(int channel);
+bool CheckAnalogInputChannel(int channel);
+bool CheckAnalogOutputChannel(int channel);
+bool CheckSolenoidChannel(int channel);
+bool CheckPDPChannel(int channel);
+
+extern const int kDigitalChannels;
+extern const int kAnalogInputs;
+extern const int kAnalogOutputs;
+extern const int kSolenoidChannels;
+extern const int kSolenoidModules;
+extern const int kPwmChannels;
+extern const int kRelayChannels;
+extern const int kPDPChannels;
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/Servo.cc b/frc971/wpilib/ahal/Servo.cc
new file mode 100644
index 0000000..0cebf80
--- /dev/null
+++ b/frc971/wpilib/ahal/Servo.cc
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/Servo.h"
+
+using namespace frc;
+
+constexpr double Servo::kDefaultMaxServoPWM;
+constexpr double Servo::kDefaultMinServoPWM;
+
+/**
+ * @param channel The PWM channel to which the servo is attached. 0-9 are
+ *                on-board, 10-19 are on the MXP port
+ */
+Servo::Servo(int channel) : PWM(channel) {
+  // Set minimum and maximum PWM values supported by the servo
+  SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM);
+
+  // Assign defaults for period multiplier for the servo PWM control signal
+  SetPeriodMultiplier(kPeriodMultiplier_4X);
+}
+
+Servo::~Servo() {}
diff --git a/frc971/wpilib/ahal/Servo.h b/frc971/wpilib/ahal/Servo.h
new file mode 100644
index 0000000..c216920
--- /dev/null
+++ b/frc971/wpilib/ahal/Servo.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "frc971/wpilib/ahal/PWM.h"
+
+namespace frc {
+
+/**
+ * Standard hobby style servo.
+ *
+ * The range parameters default to the appropriate values for the Hitec HS-322HD
+ * servo provided
+ * in the FIRST Kit of Parts in 2008.
+ */
+class Servo : public PWM {
+ public:
+  explicit Servo(int channel);
+  virtual ~Servo();
+
+ private:
+  static constexpr double kDefaultMaxServoPWM = 2.4;
+  static constexpr double kDefaultMinServoPWM = .6;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/Talon.cc b/frc971/wpilib/ahal/Talon.cc
new file mode 100644
index 0000000..40d8a77
--- /dev/null
+++ b/frc971/wpilib/ahal/Talon.cc
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/Talon.h"
+
+#include "HAL/HAL.h"
+
+using namespace frc;
+
+/**
+ * Constructor for a Talon (original or Talon SR).
+ *
+ * @param channel The PWM channel number that the Talon is attached to. 0-9 are
+ *                on-board, 10-19 are on the MXP port
+ */
+Talon::Talon(int channel) : PWM(channel) {
+  /* Note that the Talon uses the following bounds for PWM values. These values
+   * should work reasonably well for most controllers, but if users experience
+   * issues such as asymmetric behavior around the deadband or inability to
+   * saturate the controller in either direction, calibration is recommended.
+   * The calibration procedure can be found in the Talon User Manual available
+   * from CTRE.
+   *
+   *   2.037ms = full "forward"
+   *   1.539ms = the "high end" of the deadband range
+   *   1.513ms = center of the deadband range (off)
+   *   1.487ms = the "low end" of the deadband range
+   *   0.989ms = full "reverse"
+   */
+  SetBounds(2.037, 1.539, 1.513, 1.487, .989);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Talon, GetChannel());
+}
diff --git a/frc971/wpilib/ahal/Talon.h b/frc971/wpilib/ahal/Talon.h
new file mode 100644
index 0000000..147af3c
--- /dev/null
+++ b/frc971/wpilib/ahal/Talon.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc971/wpilib/ahal/PWM.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Talon and Talon SR Speed Controller
+ */
+class Talon : public PWM {
+ public:
+  explicit Talon(int channel);
+  virtual ~Talon() = default;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/Utility.cc b/frc971/wpilib/ahal/Utility.cc
new file mode 100644
index 0000000..7a00e42
--- /dev/null
+++ b/frc971/wpilib/ahal/Utility.cc
@@ -0,0 +1,234 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/Utility.h"
+
+#include <cxxabi.h>
+#include <execinfo.h>
+
+#include <cstdio>
+#include <cstdlib>
+#include <cstring>
+#include <sstream>
+
+#include "HAL/DriverStation.h"
+#include "HAL/HAL.h"
+#include "frc971/wpilib/ahal/ErrorBase.h"
+#include "llvm/SmallString.h"
+
+using namespace frc;
+
+/**
+ * Assert implementation.
+ * This allows breakpoints to be set on an assert.
+ * The users don't call this, but instead use the wpi_assert macros in
+ * Utility.h.
+ */
+bool wpi_assert_impl(bool conditionValue, llvm::StringRef conditionText,
+                     llvm::StringRef message, llvm::StringRef fileName,
+                     int lineNumber, llvm::StringRef funcName) {
+  if (!conditionValue) {
+    std::stringstream locStream;
+    locStream << funcName << " [";
+    llvm::SmallString<128> fileTemp;
+    locStream << basename(fileName.c_str(fileTemp)) << ":" << lineNumber << "]";
+
+    std::stringstream errorStream;
+
+    errorStream << "Assertion \"" << conditionText << "\" ";
+
+    if (message[0] != '\0') {
+      errorStream << "failed: " << message << std::endl;
+    } else {
+      errorStream << "failed." << std::endl;
+    }
+
+    std::string stack = GetStackTrace(2);
+    std::string location = locStream.str();
+    std::string error = errorStream.str();
+
+    // Print the error and send it to the DriverStation
+    HAL_SendError(1, 1, 0, error.c_str(), location.c_str(), stack.c_str(), 1);
+  }
+
+  return conditionValue;
+}
+
+/**
+ * Common error routines for wpi_assertEqual_impl and wpi_assertNotEqual_impl
+ * This should not be called directly; it should only be used by
+ * wpi_assertEqual_impl and wpi_assertNotEqual_impl.
+ */
+void wpi_assertEqual_common_impl(llvm::StringRef valueA, llvm::StringRef valueB,
+                                 llvm::StringRef equalityType,
+                                 llvm::StringRef message,
+                                 llvm::StringRef fileName, int lineNumber,
+                                 llvm::StringRef funcName) {
+  std::stringstream locStream;
+  locStream << funcName << " [";
+  llvm::SmallString<128> fileTemp;
+  locStream << basename(fileName.c_str(fileTemp)) << ":" << lineNumber << "]";
+
+  std::stringstream errorStream;
+
+  errorStream << "Assertion \"" << valueA << " " << equalityType << " "
+              << valueB << "\" ";
+
+  if (message[0] != '\0') {
+    errorStream << "failed: " << message << std::endl;
+  } else {
+    errorStream << "failed." << std::endl;
+  }
+
+  std::string trace = GetStackTrace(3);
+  std::string location = locStream.str();
+  std::string error = errorStream.str();
+
+  // Print the error and send it to the DriverStation
+  HAL_SendError(1, 1, 0, error.c_str(), location.c_str(), trace.c_str(), 1);
+}
+
+/**
+ * Assert equal implementation.
+ * This determines whether the two given integers are equal. If not,
+ * the value of each is printed along with an optional message string.
+ * The users don't call this, but instead use the wpi_assertEqual macros in
+ * Utility.h.
+ */
+bool wpi_assertEqual_impl(int valueA, int valueB, llvm::StringRef valueAString,
+                          llvm::StringRef valueBString, llvm::StringRef message,
+                          llvm::StringRef fileName, int lineNumber,
+                          llvm::StringRef funcName) {
+  if (!(valueA == valueB)) {
+    wpi_assertEqual_common_impl(valueAString, valueBString, "==", message,
+                                fileName, lineNumber, funcName);
+  }
+  return valueA == valueB;
+}
+
+/**
+ * Assert not equal implementation.
+ * This determines whether the two given integers are equal. If so,
+ * the value of each is printed along with an optional message string.
+ * The users don't call this, but instead use the wpi_assertNotEqual macros in
+ * Utility.h.
+ */
+bool wpi_assertNotEqual_impl(int valueA, int valueB,
+                             llvm::StringRef valueAString,
+                             llvm::StringRef valueBString,
+                             llvm::StringRef message, llvm::StringRef fileName,
+                             int lineNumber, llvm::StringRef funcName) {
+  if (!(valueA != valueB)) {
+    wpi_assertEqual_common_impl(valueAString, valueBString, "!=", message,
+                                fileName, lineNumber, funcName);
+  }
+  return valueA != valueB;
+}
+
+namespace frc {
+
+/**
+ * Return the FPGA Version number.
+ *
+ * For now, expect this to be competition year.
+ * @return FPGA Version number.
+ */
+int GetFPGAVersion() {
+  int32_t status = 0;
+  int version = HAL_GetFPGAVersion(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return version;
+}
+
+/**
+ * Return the FPGA Revision number.
+ * The format of the revision is 3 numbers.
+ * The 12 most significant bits are the Major Revision.
+ * the next 8 bits are the Minor Revision.
+ * The 12 least significant bits are the Build Number.
+ * @return FPGA Revision number.
+ */
+int64_t GetFPGARevision() {
+  int32_t status = 0;
+  int64_t revision = HAL_GetFPGARevision(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return revision;
+}
+
+/**
+ * Read the microsecond-resolution timer on the FPGA.
+ *
+ * @return The current time in microseconds according to the FPGA (since FPGA
+ *         reset).
+ */
+uint64_t GetFPGATime() {
+  int32_t status = 0;
+  uint64_t time = HAL_GetFPGATime(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return time;
+}
+
+/**
+ * Get the state of the "USER" button on the roboRIO.
+ *
+ * @return True if the button is currently pressed down
+ */
+bool GetUserButton() {
+  int32_t status = 0;
+
+  bool value = HAL_GetFPGAButton(&status);
+  wpi_setGlobalError(status);
+
+  return value;
+}
+
+/**
+ * Demangle a C++ symbol, used for printing stack traces.
+ */
+static std::string demangle(char const *mangledSymbol) {
+  char buffer[256];
+  size_t length;
+  int32_t status;
+
+  if (std::sscanf(mangledSymbol, "%*[^(]%*[(]%255[^)+]", buffer)) {
+    char *symbol = abi::__cxa_demangle(buffer, nullptr, &length, &status);
+    if (status == 0) {
+      return symbol;
+    } else {
+      // If the symbol couldn't be demangled, it's probably a C function,
+      // so just return it as-is.
+      return buffer;
+    }
+  }
+
+  // If everything else failed, just return the mangled symbol
+  return mangledSymbol;
+}
+
+/**
+ * Get a stack trace, ignoring the first "offset" symbols.
+ * @param offset The number of symbols at the top of the stack to ignore
+ */
+std::string GetStackTrace(int offset) {
+  void *stackTrace[128];
+  int stackSize = backtrace(stackTrace, 128);
+  char **mangledSymbols = backtrace_symbols(stackTrace, stackSize);
+  std::stringstream trace;
+
+  for (int i = offset; i < stackSize; i++) {
+    // Only print recursive functions once in a row.
+    if (i == 0 || stackTrace[i] != stackTrace[i - 1]) {
+      trace << "\tat " << demangle(mangledSymbols[i]) << std::endl;
+    }
+  }
+
+  std::free(mangledSymbols);
+
+  return trace.str();
+}
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/Utility.h b/frc971/wpilib/ahal/Utility.h
new file mode 100644
index 0000000..bf97692
--- /dev/null
+++ b/frc971/wpilib/ahal/Utility.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/** @file
+ * Contains global utility functions
+ */
+
+#include <stdint.h>
+
+#include <string>
+
+#include "llvm/StringRef.h"
+
+#define wpi_assert(condition) \
+  wpi_assert_impl(condition, #condition, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertWithMessage(condition, message)                     \
+  wpi_assert_impl(condition, #condition, message, __FILE__, __LINE__, \
+                  __FUNCTION__)
+
+#define wpi_assertEqual(a, b) \
+  wpi_assertEqual_impl(a, b, #a, #b, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertEqualWithMessage(a, b, message) \
+  wpi_assertEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, __FUNCTION__)
+
+#define wpi_assertNotEqual(a, b) \
+  wpi_assertNotEqual_impl(a, b, #a, #b, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertNotEqualWithMessage(a, b, message)                 \
+  wpi_assertNotEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, \
+                          __FUNCTION__)
+
+bool wpi_assert_impl(bool conditionValue, llvm::StringRef conditionText,
+                     llvm::StringRef message, llvm::StringRef fileName,
+                     int lineNumber, llvm::StringRef funcName);
+bool wpi_assertEqual_impl(int valueA, int valueB, llvm::StringRef valueAString,
+                          llvm::StringRef valueBString, llvm::StringRef message,
+                          llvm::StringRef fileName, int lineNumber,
+                          llvm::StringRef funcName);
+bool wpi_assertNotEqual_impl(int valueA, int valueB,
+                             llvm::StringRef valueAString,
+                             llvm::StringRef valueBString,
+                             llvm::StringRef message, llvm::StringRef fileName,
+                             int lineNumber, llvm::StringRef funcName);
+
+void wpi_suspendOnAssertEnabled(bool enabled);
+
+namespace frc {
+
+int GetFPGAVersion();
+int64_t GetFPGARevision();
+uint64_t GetFPGATime();
+bool GetUserButton();
+std::string GetStackTrace(int offset);
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/VictorSP.cc b/frc971/wpilib/ahal/VictorSP.cc
new file mode 100644
index 0000000..7d1741b
--- /dev/null
+++ b/frc971/wpilib/ahal/VictorSP.cc
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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 "frc971/wpilib/ahal/VictorSP.h"
+
+#include "HAL/HAL.h"
+
+using namespace frc;
+
+/**
+ * Constructor for a VictorSP.
+ *
+ * @param channel The PWM channel that the VictorSP is attached to. 0-9 are
+ *                on-board, 10-19 are on the MXP port
+ */
+VictorSP::VictorSP(int channel) : PWM(channel) {
+  /**
+   * Note that the VictorSP uses the following bounds for PWM values. These
+   * values should work reasonably well for most controllers, but if users
+   * experience issues such as asymmetric behavior around the deadband or
+   * inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the VictorSP User
+   * Manual available from Vex.
+   *
+   *   2.004ms = full "forward"
+   *   1.52ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.48ms = the "low end" of the deadband range
+   *   0.997ms = full "reverse"
+   */
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_VictorSP, GetChannel());
+}
diff --git a/frc971/wpilib/ahal/VictorSP.h b/frc971/wpilib/ahal/VictorSP.h
new file mode 100644
index 0000000..4d9d840
--- /dev/null
+++ b/frc971/wpilib/ahal/VictorSP.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc971/wpilib/ahal/PWM.h"
+
+namespace frc {
+
+/**
+ * Vex Robotics Victor SP Speed Controller
+ */
+class VictorSP : public PWM {
+ public:
+  explicit VictorSP(int channel);
+  virtual ~VictorSP() = default;
+};
+
+}  // namespace frc
diff --git a/frc971/wpilib/ahal/WPIErrors.h b/frc971/wpilib/ahal/WPIErrors.h
new file mode 100644
index 0000000..da72d00
--- /dev/null
+++ b/frc971/wpilib/ahal/WPIErrors.h
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#ifdef WPI_ERRORS_DEFINE_STRINGS
+#define S(label, offset, message)            \
+  const char *wpi_error_s_##label = message; \
+  const int wpi_error_value_##label = offset
+#else
+#define S(label, offset, message)         \
+  extern const char *wpi_error_s_##label; \
+  const int wpi_error_value_##label = offset
+#endif
+
+/*
+ * Fatal errors
+ */
+S(ModuleIndexOutOfRange, -1,
+  "Allocating module that is out of range or not found");
+S(ChannelIndexOutOfRange, -1, "Allocating channel that is out of range");
+S(NotAllocated, -2, "Attempting to free unallocated resource");
+S(ResourceAlreadyAllocated, -3, "Attempted to reuse an allocated resource");
+S(NoAvailableResources, -4, "No available resources to allocate");
+S(NullParameter, -5, "A pointer parameter to a method is nullptr");
+S(Timeout, -6, "A timeout has been exceeded");
+S(CompassManufacturerError, -7, "Compass manufacturer doesn't match HiTechnic");
+S(CompassTypeError, -8,
+  "Compass type doesn't match expected type for HiTechnic compass");
+S(IncompatibleMode, -9, "The object is in an incompatible mode");
+S(AnalogTriggerLimitOrderError, -10,
+  "AnalogTrigger limits error.  Lower limit > Upper Limit");
+S(AnalogTriggerPulseOutputError, -11,
+  "Attempted to read AnalogTrigger pulse output.");
+S(TaskError, -12, "Task can't be started");
+S(TaskIDError, -13, "Task error: Invalid ID.");
+S(TaskDeletedError, -14, "Task error: Task already deleted.");
+S(TaskOptionsError, -15, "Task error: Invalid options.");
+S(TaskMemoryError, -16, "Task can't be started due to insufficient memory.");
+S(TaskPriorityError, -17, "Task error: Invalid priority [1-255].");
+S(DriveUninitialized, -18, "RobotDrive not initialized for the C interface");
+S(CompressorNonMatching, -19,
+  "Compressor slot/channel doesn't match previous instance");
+S(CompressorAlreadyDefined, -20, "Creating a second compressor instance");
+S(CompressorUndefined, -21,
+  "Using compressor functions without defining compressor");
+S(InconsistentArrayValueAdded, -22,
+  "When packing data into an array to the dashboard, not all values added were "
+  "of the same type.");
+S(MismatchedComplexTypeClose, -23,
+  "When packing data to the dashboard, a Close for a complex type was called "
+  "without a matching Open.");
+S(DashboardDataOverflow, -24,
+  "When packing data to the dashboard, too much data was packed and the buffer "
+  "overflowed.");
+S(DashboardDataCollision, -25,
+  "The same buffer was used for packing data and for printing.");
+S(EnhancedIOMissing, -26, "IO is not attached or Enhanced IO is not enabled.");
+S(LineNotOutput, -27,
+  "Cannot SetDigitalOutput for a line not configured for output.");
+S(ParameterOutOfRange, -28, "A parameter is out of range.");
+S(SPIClockRateTooLow, -29, "SPI clock rate was below the minimum supported");
+S(JaguarVersionError, -30, "Jaguar firmware version error");
+S(JaguarMessageNotFound, -31, "Jaguar message not found");
+S(NetworkTablesReadError, -40, "Error reading NetworkTables socket");
+S(NetworkTablesBufferFull, -41, "Buffer full writing to NetworkTables socket");
+S(NetworkTablesWrongType, -42,
+  "The wrong type was read from the NetworkTables entry");
+S(NetworkTablesCorrupt, -43, "NetworkTables data stream is corrupt");
+S(SmartDashboardMissingKey, -43, "SmartDashboard data does not exist");
+S(CommandIllegalUse, -50, "Illegal use of Command");
+S(UnsupportedInSimulation, -80, "Unsupported in simulation");
+S(CameraServerError, -90, "CameraServer error");
+
+/*
+ * Warnings
+ */
+S(SampleRateTooHigh, 1, "Analog module sample rate is too high");
+S(VoltageOutOfRange, 2,
+  "Voltage to convert to raw value is out of range [-10; 10]");
+S(CompressorTaskError, 3, "Compressor task won't start");
+S(LoopTimingError, 4, "Digital module loop timing is not the expected value");
+S(NonBinaryDigitalValue, 5, "Digital output value is not 0 or 1");
+S(IncorrectBatteryChannel, 6,
+  "Battery measurement channel is not correct value");
+S(BadJoystickIndex, 7, "Joystick index is out of range, should be 0-3");
+S(BadJoystickAxis, 8, "Joystick axis or POV is out of range");
+S(InvalidMotorIndex, 9, "Motor index is out of range, should be 0-3");
+S(DriverStationTaskError, 10, "Driver Station task won't start");
+S(EnhancedIOPWMPeriodOutOfRange, 11,
+  "Driver Station Enhanced IO PWM Output period out of range.");
+S(SPIWriteNoMOSI, 12, "Cannot write to SPI port with no MOSI output");
+S(SPIReadNoMISO, 13, "Cannot read from SPI port with no MISO input");
+S(SPIReadNoData, 14, "No data available to read from SPI");
+S(IncompatibleState, 15,
+  "Incompatible State: The operation cannot be completed");
+
+#undef S
diff --git a/frc971/wpilib/ahal/WPILibVersion.h b/frc971/wpilib/ahal/WPILibVersion.h
new file mode 100644
index 0000000..327033a
--- /dev/null
+++ b/frc971/wpilib/ahal/WPILibVersion.h
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2008-2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/*
+ * The corresponding WPILibVersion.cc file is autogenerated by the build
+ * system. If it does not exist, make sure that you run a build.
+ */
+extern const char *WPILibVersion;
diff --git a/frc971/wpilib/dma.cc b/frc971/wpilib/dma.cc
index 8dca72c..a379262 100644
--- a/frc971/wpilib/dma.cc
+++ b/frc971/wpilib/dma.cc
@@ -5,21 +5,21 @@
 #include <algorithm>
 #include <type_traits>
 
-#include "DigitalSource.h"
-#include "AnalogInput.h"
-#include "Encoder.h"
 #include "HAL/HAL.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/DigitalSource.h"
+#include "frc971/wpilib/ahal/Encoder.h"
 
 // Interface to the roboRIO FPGA's DMA features.
 
 // Like tEncoder::tOutput with the bitfields reversed.
 typedef union {
   struct {
-    unsigned Direction: 1;
-    signed Value: 31;
+    unsigned Direction : 1;
+    signed Value : 31;
   };
   struct {
-    unsigned value: 32;
+    unsigned value : 32;
   };
 } t1Output;
 
@@ -85,12 +85,12 @@
   wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
 }
 
-void DMA::Add(Encoder *encoder) {
+void DMA::Add(frc::Encoder *encoder) {
   tRioStatusCode status = 0;
 
   if (manager_) {
     wpi_setErrorWithContext(NiFpga_Status_InvalidParameter,
-        "DMA::Add() only works before DMA::Start()");
+                            "DMA::Add() only works before DMA::Start()");
     return;
   }
   const int index = encoder->GetFPGAIndex();
@@ -111,12 +111,12 @@
   wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
 }
 
-void DMA::Add(DigitalSource * /*input*/) {
+void DMA::Add(frc::DigitalSource * /*input*/) {
   tRioStatusCode status = 0;
 
   if (manager_) {
     wpi_setErrorWithContext(NiFpga_Status_InvalidParameter,
-        "DMA::Add() only works before DMA::Start()");
+                            "DMA::Add() only works before DMA::Start()");
     return;
   }
 
@@ -124,12 +124,12 @@
   wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
 }
 
-void DMA::Add(AnalogInput *input) {
+void DMA::Add(frc::AnalogInput *input) {
   tRioStatusCode status = 0;
 
   if (manager_) {
     wpi_setErrorWithContext(NiFpga_Status_InvalidParameter,
-        "DMA::Add() only works before DMA::Start()");
+                            "DMA::Add() only works before DMA::Start()");
     return;
   }
 
@@ -141,11 +141,13 @@
   wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
 }
 
-void DMA::SetExternalTrigger(DigitalSource *input, bool rising, bool falling) {
+void DMA::SetExternalTrigger(frc::DigitalSource *input, bool rising,
+                             bool falling) {
   tRioStatusCode status = 0;
 
   if (manager_) {
-    wpi_setErrorWithContext(NiFpga_Status_InvalidParameter,
+    wpi_setErrorWithContext(
+        NiFpga_Status_InvalidParameter,
         "DMA::SetExternalTrigger() only works before DMA::Start()");
     return;
   }
@@ -193,7 +195,7 @@
   new_trigger.ExternalClockSource_Module = module;
   new_trigger.ExternalClockSource_Channel = channel;
 
-// Configures the trigger to be external, not off the FPGA clock.
+  // Configures the trigger to be external, not off the FPGA clock.
   tdma_config_->writeExternalTriggers(channel_index / 4, channel_index % 4,
                                       new_trigger, &status);
   if (status != 0) {
@@ -210,7 +212,7 @@
 
   if (!manager_.get()) {
     wpi_setErrorWithContext(NiFpga_Status_InvalidParameter,
-        "DMA::Read() only works after DMA::Start()");
+                            "DMA::Read() only works after DMA::Start()");
     return STATUS_ERROR;
   }
 
@@ -236,10 +238,14 @@
 
 const char *DMA::NameOfReadStatus(ReadStatus s) {
   switch (s) {
-    case STATUS_OK:      return "OK";
-    case STATUS_TIMEOUT: return "TIMEOUT";
-    case STATUS_ERROR:   return "ERROR";
-    default:             return "(bad ReadStatus code)";
+    case STATUS_OK:
+      return "OK";
+    case STATUS_TIMEOUT:
+      return "TIMEOUT";
+    case STATUS_ERROR:
+      return "ERROR";
+    default:
+      return "(bad ReadStatus code)";
   }
 }
 
@@ -308,7 +314,6 @@
   if (status != 0) {
     return;
   }
-
 }
 
 static_assert(::std::is_pod<DMASample>::value, "DMASample needs to be POD");
@@ -336,7 +341,7 @@
   return static_cast<double>(GetTime()) * 0.000001;
 }
 
-bool DMASample::Get(DigitalSource *input) const {
+bool DMASample::Get(frc::DigitalSource *input) const {
   if (offset(kEnable_DI) == -1) {
     wpi_setStaticErrorWithContext(
         dma_, NiFpga_Status_ResourceNotFound,
@@ -351,7 +356,7 @@
   }
 }
 
-int32_t DMASample::GetRaw(Encoder *input) const {
+int32_t DMASample::GetRaw(frc::Encoder *input) const {
   int index = input->GetFPGAIndex();
   uint32_t dmaWord = 0;
   if (index < 4) {
@@ -391,13 +396,13 @@
   return result;
 }
 
-int32_t DMASample::Get(Encoder *input) const {
+int32_t DMASample::Get(frc::Encoder *input) const {
   int32_t raw = GetRaw(input);
 
   return raw / input->GetEncodingScale();
 }
 
-uint16_t DMASample::GetValue(AnalogInput *input) const {
+uint16_t DMASample::GetValue(frc::AnalogInput *input) const {
   uint32_t channel = input->GetChannel();
   uint32_t dmaWord;
   if (channel < 4) {
@@ -430,7 +435,7 @@
   return static_cast<int16_t>(dmaWord);
 }
 
-float DMASample::GetVoltage(AnalogInput *input) const {
+float DMASample::GetVoltage(frc::AnalogInput *input) const {
   uint16_t value = GetValue(input);
   if (value == 0xffff) return 0.0;
   uint32_t lsb_weight = input->GetLSBWeight();
diff --git a/frc971/wpilib/dma.h b/frc971/wpilib/dma.h
index 0869b0d..c870728 100644
--- a/frc971/wpilib/dma.h
+++ b/frc971/wpilib/dma.h
@@ -9,30 +9,14 @@
 #include <array>
 #include <memory>
 
-#if defined(WPILIB2017) || defined(WPILIB2018)
 #include "HAL/ChipObject.h"
-#else
-#include "ChipObject.h"
-#endif
-#include "ErrorBase.h"
 
 class DMA;
-#if defined(WPILIB2017) || defined(WPILIB2018)
 namespace frc {
 class DigitalSource;
 class AnalogInput;
 class Encoder;
 }  // namespace frc
-#else
-class DigitalSource;
-class AnalogInput;
-class Encoder;
-namespace frc {
-using ::DigitalSource;
-using ::AnalogInput;
-using ::Encoder;
-}  // namespace frc
-#endif
 
 // A POD class which stores the data from a DMA sample and provides safe ways to
 // access it.
@@ -48,15 +32,15 @@
   // All Get methods either return the requested value, or set the Error.
 
   // Returns the value of the digital input in the sample.
-  bool Get(DigitalSource *input) const;
+  bool Get(frc::DigitalSource *input) const;
   // Returns the raw value of the encoder in the sample.
-  int32_t GetRaw(Encoder *input) const;
+  int32_t GetRaw(frc::Encoder *input) const;
   // Returns the {1, 2, or 4} X scaled value of the encoder in the sample.
-  int32_t Get(Encoder *input) const;
+  int32_t Get(frc::Encoder *input) const;
   // Returns the raw 12-bit value from the ADC.
-  uint16_t GetValue(AnalogInput *input) const;
+  uint16_t GetValue(frc::AnalogInput *input) const;
   // Returns the scaled value of an analog input.
-  float GetVoltage(AnalogInput *input) const;
+  float GetVoltage(frc::AnalogInput *input) const;
 
  private:
   friend DMA;
@@ -75,8 +59,7 @@
   uint32_t read_buffer_[64];
 };
 
-// TODO(austin): ErrorBase...
-class DMA : public ErrorBase {
+class DMA {
  public:
   DMA();
   virtual ~DMA();
@@ -93,14 +76,14 @@
   // It is safe to add the same input multiple times, but there is currently
   // no way to remove one once it has been added.
   // Call Add() and SetExternalTrigger() before Start().
-  void Add(Encoder *encoder);
-  void Add(DigitalSource *input);
-  void Add(AnalogInput *input);
+  void Add(frc::Encoder *encoder);
+  void Add(frc::DigitalSource *input);
+  void Add(frc::AnalogInput *input);
 
   // Configures DMA to trigger on an external trigger.  There can only be 4
   // external triggers.
   // Call Add() and SetExternalTrigger() before Start().
-  void SetExternalTrigger(DigitalSource *input, bool rising, bool falling);
+  void SetExternalTrigger(frc::DigitalSource *input, bool rising, bool falling);
 
   // Starts reading samples into the buffer.  Clears all previous samples before
   // starting.
@@ -131,8 +114,8 @@
   typedef nFPGA::nRoboRIO_FPGANamespace::tDMA tDMA;
   friend DMASample;
 
-  // The offsets into the sample structure for each DMA type, or -1 if it isn't
-  // in the set of values.
+// The offsets into the sample structure for each DMA type, or -1 if it isn't
+// in the set of values.
 #ifdef WPILIB2015
   ssize_t channel_offsets_[18];
 #else
diff --git a/frc971/wpilib/dma_edge_counting.h b/frc971/wpilib/dma_edge_counting.h
index 779e78a..a6f2da4 100644
--- a/frc971/wpilib/dma_edge_counting.h
+++ b/frc971/wpilib/dma_edge_counting.h
@@ -8,10 +8,10 @@
 
 #include "frc971/wpilib/dma.h"
 
-#include "DigitalInput.h"
-#include "Encoder.h"
-#include "AnalogInput.h"
-#include "Utility.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/DigitalInput.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Utility.h"
 #undef ERROR
 
 namespace frc971 {
@@ -40,10 +40,10 @@
 // TODO(brian): Timeout old data.
 class DMAPulseWidthReader : public DMASampleHandlerInterface {
  public:
-  DMAPulseWidthReader(DigitalInput *input) : input_(input) {}
+  DMAPulseWidthReader(frc::DigitalInput *input) : input_(input) {}
   DMAPulseWidthReader() = default;
 
-  void set_input(DigitalInput *input) { input_ = input; }
+  void set_input(frc::DigitalInput *input) { input_ = input; }
 
   double last_width() const { return last_width_; }
 
@@ -57,7 +57,7 @@
     dma->SetExternalTrigger(input_, true, true);
   }
 
-  DigitalInput *input_ = nullptr;
+  frc::DigitalInput *input_ = nullptr;
 
   // The last DMA reading we got.
   DMASample prev_sample_;
@@ -73,12 +73,12 @@
 // corresponding to those edges.
 class DMAEdgeCounter : public DMASampleHandlerInterface {
  public:
-  DMAEdgeCounter(Encoder *encoder, DigitalInput *input)
+  DMAEdgeCounter(frc::Encoder *encoder, frc::DigitalInput *input)
       : encoder_(encoder), input_(input) {}
   DMAEdgeCounter() = default;
 
-  void set_encoder(Encoder *encoder) { encoder_ = encoder; }
-  void set_input(DigitalInput *input) { input_ = input; }
+  void set_encoder(frc::Encoder *encoder) { encoder_ = encoder; }
+  void set_input(frc::DigitalInput *input) { input_ = input; }
 
   int positive_count() const { return pos_edge_count_; }
   int negative_count() const { return neg_edge_count_; }
@@ -112,8 +112,8 @@
 
   bool ExtractValue(const DMASample &sample) const;
 
-  Encoder *encoder_ = nullptr;
-  DigitalInput *input_ = nullptr;
+  frc::Encoder *encoder_ = nullptr;
+  frc::DigitalInput *input_ = nullptr;
 
   // The last DMA reading we got.
   DMASample prev_sample_;
@@ -138,7 +138,7 @@
 // Reads a hall effect in sync with DMA samples.
 class DMADigitalReader : public DMASampleHandlerInterface {
  public:
-  DMADigitalReader(DigitalInput *input) : input_(input) {}
+  DMADigitalReader(frc::DigitalInput *input) : input_(input) {}
 
   bool value() const { return value_; }
 
@@ -148,11 +148,9 @@
   void PollFromSample(const DMASample &sample) override {
     value_ = sample.Get(input_);
   }
-  void AddToDMA(DMA *dma) override {
-    dma->Add(input_);
-  }
+  void AddToDMA(DMA *dma) override { dma->Add(input_); }
 
-  DigitalInput *const input_;
+  frc::DigitalInput *const input_;
 
   bool value_;
 
@@ -162,7 +160,7 @@
 // Reads an analog sensor in sync with DMA samples.
 class DMAAnalogReader : public DMASampleHandlerInterface {
  public:
-  DMAAnalogReader(AnalogInput *input) : input_(input) {}
+  DMAAnalogReader(frc::AnalogInput *input) : input_(input) {}
 
   double value() const { return value_; }
 
@@ -172,11 +170,9 @@
   void PollFromSample(const DMASample &sample) override {
     value_ = sample.GetVoltage(input_);
   }
-  void AddToDMA(DMA *dma) override {
-    dma->Add(input_);
-  }
+  void AddToDMA(DMA *dma) override { dma->Add(input_); }
 
-  AnalogInput *const input_;
+  frc::AnalogInput *const input_;
 
   double value_;
 
@@ -200,9 +196,7 @@
 
   // Actually starts watching for DMA samples.
   // Add may not be called any more after this.
-  void Start() {
-    dma_->Start(1024);
-  }
+  void Start() { dma_->Start(1024); }
 
   // Updates all sensor values.
   void RunIteration() {
@@ -214,7 +208,7 @@
   // Reads the state of all the sensors and records it as the polled values of
   // all the inputs.
   void SampleSensors() {
-    sample_time_ = GetFPGATime();
+    sample_time_ = frc::GetFPGATime();
     for (auto &c : handlers_) {
       c->UpdatePolledValue();
     }
diff --git a/frc971/wpilib/encoder_and_potentiometer.cc b/frc971/wpilib/encoder_and_potentiometer.cc
index 379a29f..8fe8c25 100644
--- a/frc971/wpilib/encoder_and_potentiometer.cc
+++ b/frc971/wpilib/encoder_and_potentiometer.cc
@@ -37,11 +37,12 @@
 
   ::aos::SetCurrentThreadRealtimePriority(priority_);
 
-  InterruptableSensorBase::WaitResult result = InterruptableSensorBase::kBoth;
+  frc::InterruptableSensorBase::WaitResult result =
+      frc::InterruptableSensorBase::kBoth;
   while (run_) {
     result = index_->WaitForInterrupt(
-        0.1, result != InterruptableSensorBase::kTimeout);
-    if (result == InterruptableSensorBase::kTimeout) {
+        0.1, result != frc::InterruptableSensorBase::kTimeout);
+    if (result == frc::InterruptableSensorBase::kTimeout) {
       continue;
     }
 
diff --git a/frc971/wpilib/encoder_and_potentiometer.h b/frc971/wpilib/encoder_and_potentiometer.h
index ec45657..3516168 100644
--- a/frc971/wpilib/encoder_and_potentiometer.h
+++ b/frc971/wpilib/encoder_and_potentiometer.h
@@ -2,17 +2,19 @@
 #define FRC971_ENCODER_AND_POTENTIOMETER_H_
 
 #include <atomic>
+#include <cmath>
 #include <thread>
 
 #include "aos/macros.h"
 #include "aos/mutex/mutex.h"
 
-#include "Encoder.h"
-#include "DigitalSource.h"
-#include "AnalogInput.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Counter.h"
+#include "frc971/wpilib/ahal/DigitalSource.h"
+#include "frc971/wpilib/ahal/Encoder.h"
 
-#include "frc971/wpilib/dma_edge_counting.h"
 #include "frc971/wpilib/dma.h"
+#include "frc971/wpilib/dma_edge_counting.h"
 
 namespace frc971 {
 namespace wpilib {
@@ -42,20 +44,20 @@
   // Holding this mutex will increase the handling latency.
   ::aos::Mutex *mutex() { return &mutex_; }
 
-  void set_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     encoder_ = ::std::move(encoder);
   }
-  Encoder *encoder() const { return encoder_.get(); }
+  frc::Encoder *encoder() const { return encoder_.get(); }
 
-  void set_index(::std::unique_ptr<DigitalSource> index) {
+  void set_index(::std::unique_ptr<frc::DigitalSource> index) {
     index_ = ::std::move(index);
   }
-  DigitalSource *index() const { return index_.get(); }
+  frc::DigitalSource *index() const { return index_.get(); }
 
-  void set_potentiometer(::std::unique_ptr<AnalogInput> potentiometer) {
+  void set_potentiometer(::std::unique_ptr<frc::AnalogInput> potentiometer) {
     potentiometer_ = ::std::move(potentiometer);
   }
-  AnalogInput *potentiometer() const { return potentiometer_.get(); }
+  frc::AnalogInput *potentiometer() const { return potentiometer_.get(); }
 
   // Returns the number of poseges that have happened on the index input.
   // mutex() must be held while calling this.
@@ -70,9 +72,9 @@
   }
 
  private:
-  ::std::unique_ptr<Encoder> encoder_;
-  ::std::unique_ptr<DigitalSource> index_;
-  ::std::unique_ptr<AnalogInput> potentiometer_;
+  ::std::unique_ptr<frc::Encoder> encoder_;
+  ::std::unique_ptr<frc::DigitalSource> index_;
+  ::std::unique_ptr<frc::AnalogInput> potentiometer_;
 
   int32_t last_encoder_value_{0};
   float last_potentiometer_voltage_{0.0f};
@@ -94,15 +96,15 @@
  public:
   DMAEncoder() {}
 
-  void set_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     encoder_ = ::std::move(encoder);
   }
-  Encoder *encoder() const { return encoder_.get(); }
+  frc::Encoder *encoder() const { return encoder_.get(); }
 
-  void set_index(::std::unique_ptr<DigitalSource> index) {
+  void set_index(::std::unique_ptr<frc::DigitalSource> index) {
     index_ = ::std::move(index);
   }
-  DigitalSource *index() const { return index_.get(); }
+  frc::DigitalSource *index() const { return index_.get(); }
 
   // Returns the most recent polled value of the encoder.
   uint32_t polled_encoder_value() const { return polled_encoder_value_; }
@@ -136,8 +138,8 @@
   bool DoUpdateFromSample(const DMASample &sample);
 
  private:
-  ::std::unique_ptr<Encoder> encoder_;
-  ::std::unique_ptr<DigitalSource> index_;
+  ::std::unique_ptr<frc::Encoder> encoder_;
+  ::std::unique_ptr<frc::DigitalSource> index_;
 
   int32_t polled_encoder_value_ = 0;
 
@@ -157,10 +159,10 @@
  public:
   DMAEncoderAndPotentiometer() {}
 
-  void set_potentiometer(::std::unique_ptr<AnalogInput> potentiometer) {
+  void set_potentiometer(::std::unique_ptr<frc::AnalogInput> potentiometer) {
     potentiometer_ = ::std::move(potentiometer);
   }
-  AnalogInput *potentiometer() const { return potentiometer_.get(); }
+  frc::AnalogInput *potentiometer() const { return potentiometer_.get(); }
 
   // Returns the most recent polled voltage of the potentiometer.
   float polled_potentiometer_voltage() const {
@@ -194,7 +196,7 @@
   }
 
  private:
-  ::std::unique_ptr<AnalogInput> potentiometer_;
+  ::std::unique_ptr<frc::AnalogInput> potentiometer_;
 
   float polled_potentiometer_voltage_ = 0.0f;
 
@@ -245,15 +247,15 @@
 // Class to hold a CTRE encoder with absolute angle pwm and potentiometer pair.
 class AbsoluteEncoderAndPotentiometer {
  public:
-  void set_absolute_pwm(::std::unique_ptr<DigitalInput> input) {
+  void set_absolute_pwm(::std::unique_ptr<frc::DigitalInput> input) {
     duty_cycle_.set_input(::std::move(input));
   }
 
-  void set_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     encoder_ = ::std::move(encoder);
   }
 
-  void set_potentiometer(::std::unique_ptr<AnalogInput> potentiometer) {
+  void set_potentiometer(::std::unique_ptr<frc::AnalogInput> potentiometer) {
     potentiometer_ = ::std::move(potentiometer);
   }
 
@@ -265,8 +267,8 @@
 
  private:
   DutyCycleReader duty_cycle_;
-  ::std::unique_ptr<Encoder> encoder_;
-  ::std::unique_ptr<AnalogInput> potentiometer_;
+  ::std::unique_ptr<frc::Encoder> encoder_;
+  ::std::unique_ptr<frc::AnalogInput> potentiometer_;
 };
 
 }  // namespace wpilib
diff --git a/frc971/wpilib/gyro_interface.cc b/frc971/wpilib/gyro_interface.cc
index a892d6a..da0c01b 100644
--- a/frc971/wpilib/gyro_interface.cc
+++ b/frc971/wpilib/gyro_interface.cc
@@ -13,7 +13,7 @@
 namespace frc971 {
 namespace wpilib {
 
-GyroInterface::GyroInterface() : gyro_(new SPI(SPI::kOnboardCS0)) {
+GyroInterface::GyroInterface() : gyro_(new frc::SPI(frc::SPI::kOnboardCS0)) {
   // The gyro goes up to 8.08MHz.
   // The myRIO goes up to 4MHz, so the roboRIO probably does too.
   gyro_->SetClockRate(4e6);
diff --git a/frc971/wpilib/gyro_interface.h b/frc971/wpilib/gyro_interface.h
index cd734a9..3568a47 100644
--- a/frc971/wpilib/gyro_interface.h
+++ b/frc971/wpilib/gyro_interface.h
@@ -3,7 +3,7 @@
 
 #include <memory>
 
-#include "SPI.h"
+#include "frc971/wpilib/ahal/SPI.h"
 #undef ERROR
 
 namespace frc971 {
@@ -47,7 +47,7 @@
   uint32_t GetReading();
 
  private:
-  ::std::unique_ptr<SPI> gyro_;
+  ::std::unique_ptr<frc::SPI> gyro_;
 };
 
 }  // namespace wpilib
diff --git a/frc971/wpilib/interrupt_edge_counting.cc b/frc971/wpilib/interrupt_edge_counting.cc
index 2291735..a06df8f 100644
--- a/frc971/wpilib/interrupt_edge_counting.cc
+++ b/frc971/wpilib/interrupt_edge_counting.cc
@@ -32,11 +32,12 @@
   }
 
   ::aos::SetCurrentThreadRealtimePriority(priority());
-  InterruptableSensorBase::WaitResult result = InterruptableSensorBase::kBoth;
+  frc::InterruptableSensorBase::WaitResult result =
+      frc::InterruptableSensorBase::kBoth;
   while (should_run()) {
     result = input_->WaitForInterrupt(
-        0.1, result != InterruptableSensorBase::kTimeout);
-    if (result == InterruptableSensorBase::kTimeout) {
+        0.1, result != frc::InterruptableSensorBase::kTimeout);
+    if (result == frc::InterruptableSensorBase::kTimeout) {
       continue;
     }
     interrupt_received();
diff --git a/frc971/wpilib/interrupt_edge_counting.h b/frc971/wpilib/interrupt_edge_counting.h
index e4eec35..50dc94d 100644
--- a/frc971/wpilib/interrupt_edge_counting.h
+++ b/frc971/wpilib/interrupt_edge_counting.h
@@ -1,18 +1,16 @@
 #ifndef FRC971_WPILIB_INTERRUPT_EDGE_COUNTING_H_
 #define FRC971_WPILIB_INTERRUPT_EDGE_COUNTING_H_
 
-#include <memory>
 #include <atomic>
+#include <memory>
 #include <thread>
 #include <vector>
 
 #include "aos/stl_mutex/stl_mutex.h"
 #include "aos/macros.h"
 
-#include "DigitalInput.h"
-#include "Encoder.h"
-#include "AnalogInput.h"
-#include "Utility.h"
+#include "frc971/wpilib/ahal/DigitalInput.h"
+#include "frc971/wpilib/ahal/Encoder.h"
 
 namespace frc971 {
 namespace wpilib {
@@ -109,7 +107,7 @@
 // input.
 class EdgeCounter : public InterruptHandler {
  public:
-  EdgeCounter(Encoder *encoder, DigitalInput *input)
+  EdgeCounter(frc::Encoder *encoder, frc::DigitalInput *input)
       : encoder_(encoder), input_(input) {}
 
   // Returns the current interrupt edge counts and encoder values.
@@ -139,8 +137,8 @@
   void CommitValue() override { output_ = shadow_values_; }
   void operator()() override;
 
-  Encoder *encoder_;
-  DigitalInput *input_;
+  frc::Encoder *encoder_;
+  frc::DigitalInput *input_;
 
   // The following variables represent the current "shadow" state.
   bool current_value_ = false;
@@ -156,7 +154,7 @@
 // Synchronizes reading an encoder with interrupt handling.
 class InterruptSynchronizedEncoder : public InterruptHandler {
  public:
-  InterruptSynchronizedEncoder(Encoder *encoder) : encoder_(encoder) {}
+  InterruptSynchronizedEncoder(frc::Encoder *encoder) : encoder_(encoder) {}
 
   int32_t get() const { return output_; }
 
@@ -165,7 +163,7 @@
   void CommitValue() override { output_ = shadow_; }
   void operator()() override {}
 
-  Encoder *const encoder_;
+  frc::Encoder *const encoder_;
 
   int32_t shadow_, output_;
 };
diff --git a/frc971/wpilib/joystick_sender.cc b/frc971/wpilib/joystick_sender.cc
index 3984d70..e005475 100644
--- a/frc971/wpilib/joystick_sender.cc
+++ b/frc971/wpilib/joystick_sender.cc
@@ -5,63 +5,54 @@
 #include "aos/network/team_number.h"
 #include "aos/logging/queue_logging.h"
 
-#include "DriverStation.h"
-#if defined(WPILIB2017) || defined(WPILIB2018)
 #include "HAL/HAL.h"
-#else
-#include "HAL/HAL.hpp"
-#endif
+#include "frc971/wpilib/ahal/DriverStation.h"
 
 namespace frc971 {
 namespace wpilib {
 
 void JoystickSender::operator()() {
-  DriverStation *ds =
-#ifdef WPILIB2015
-      DriverStation::GetInstance();
-#else
-      &DriverStation::GetInstance();
-#endif
+  frc::DriverStation *const ds = &frc::DriverStation::GetInstance();
   ::aos::SetCurrentThreadName("DSReader");
   uint16_t team_id = ::aos::network::GetTeamNumber();
 
   ::aos::SetCurrentThreadRealtimePriority(29);
 
+  // TODO(Brian): Fix the potential deadlock when stopping here (condition
+  // variable / mutex needs to get exposed all the way out or something).
   while (run_) {
-    ds->WaitForData();
-    auto new_state = ::aos::joystick_state.MakeMessage();
+    ds->RunIteration([&]() {
+      auto new_state = ::aos::joystick_state.MakeMessage();
 
-    HAL_ControlWord control_word;
-    HAL_GetControlWord(&control_word);
-    HAL_MatchInfo match_info;
-    auto status = HAL_GetMatchInfo(&match_info);
-    if (status == 0) {
-      new_state->switch_left = match_info.gameSpecificMessage[0] == 'L' ||
-                               match_info.gameSpecificMessage[0] == 'l';
-      new_state->scale_left = match_info.gameSpecificMessage[1] == 'L' ||
-                              match_info.gameSpecificMessage[1] == 'l';
-    }
-    HAL_FreeMatchInfo(&match_info);
-
-    new_state->test_mode = control_word.test;
-    new_state->fms_attached = control_word.fmsAttached;
-    new_state->enabled = control_word.enabled;
-    new_state->autonomous = control_word.autonomous;
-    new_state->team_id = team_id;
-    new_state->fake = false;
-
-    for (int i = 0; i < 4; ++i) {
-      new_state->joysticks[i].buttons = ds->GetStickButtons(i);
-      for (int j = 0; j < 6; ++j) {
-        new_state->joysticks[i].axis[j] = ds->GetStickAxis(i, j);
+      HAL_MatchInfo match_info;
+      auto status = HAL_GetMatchInfo(&match_info);
+      if (status == 0) {
+        new_state->switch_left = match_info.gameSpecificMessage[0] == 'L' ||
+                                 match_info.gameSpecificMessage[0] == 'l';
+        new_state->scale_left = match_info.gameSpecificMessage[1] == 'L' ||
+                                match_info.gameSpecificMessage[1] == 'l';
       }
-      new_state->joysticks[i].pov = ds->GetStickPOV(i, 0);
-    }
-    LOG_STRUCT(DEBUG, "joystick_state", *new_state);
+      HAL_FreeMatchInfo(&match_info);
 
-    if (!new_state.Send()) {
-      LOG(WARNING, "sending joystick_state failed\n");
-    }
+      new_state->test_mode = ds->IsTestMode();
+      new_state->fms_attached = ds->IsFmsAttached();
+      new_state->enabled = ds->IsEnabled();
+      new_state->autonomous = ds->IsAutonomous();
+      new_state->team_id = team_id;
+      new_state->fake = false;
+
+      for (int i = 0; i < 4; ++i) {
+        new_state->joysticks[i].buttons = ds->GetStickButtons(i);
+        for (int j = 0; j < 6; ++j) {
+          new_state->joysticks[i].axis[j] = ds->GetStickAxis(i, j);
+        }
+        LOG_STRUCT(DEBUG, "joystick_state", *new_state);
+
+      }
+      if (!new_state.Send()) {
+        LOG(WARNING, "sending joystick_state failed\n");
+      }
+    });
   }
 }
 
diff --git a/frc971/wpilib/pdp_fetcher.cc b/frc971/wpilib/pdp_fetcher.cc
index 83a4105..81f9fcf 100644
--- a/frc971/wpilib/pdp_fetcher.cc
+++ b/frc971/wpilib/pdp_fetcher.cc
@@ -5,6 +5,7 @@
 #include "aos/logging/queue_logging.h"
 #include "aos/init.h"
 #include "aos/util/phased_loop.h"
+#include "frc971/wpilib/ahal/PowerDistributionPanel.h"
 #include "frc971/wpilib/pdp_values.q.h"
 
 namespace frc971 {
@@ -12,7 +13,8 @@
 
 void PDPFetcher::operator()() {
   ::aos::SetCurrentThreadName("PDPFetcher");
-  ::std::unique_ptr<PowerDistributionPanel> pdp(new PowerDistributionPanel());
+  ::std::unique_ptr<frc::PowerDistributionPanel> pdp(
+      new frc::PowerDistributionPanel());
 
   ::aos::time::PhasedLoop phased_loop(::std::chrono::milliseconds(20),
                                       ::std::chrono::milliseconds(4));
diff --git a/frc971/wpilib/pdp_fetcher.h b/frc971/wpilib/pdp_fetcher.h
index 5979f96..513f5fc 100644
--- a/frc971/wpilib/pdp_fetcher.h
+++ b/frc971/wpilib/pdp_fetcher.h
@@ -1,10 +1,8 @@
 #ifndef FRC971_WPILIB_PDP_FETCHER_H_
 #define FRC971_WPILIB_PDP_FETCHER_H_
 
-#include <memory>
 #include <atomic>
-
-#include "PowerDistributionPanel.h"
+#include <memory>
 
 namespace frc971 {
 namespace wpilib {
diff --git a/frc971/wpilib/wpilib_robot_base.h b/frc971/wpilib/wpilib_robot_base.h
index 50ef970..3deb0e4 100644
--- a/frc971/wpilib/wpilib_robot_base.h
+++ b/frc971/wpilib/wpilib_robot_base.h
@@ -1,11 +1,7 @@
 #ifndef FRC971_WPILIB_NEWROBOTBASE_H_
 #define FRC971_WPILIB_NEWROBOTBASE_H_
 
-#ifdef WPILIB2015
-#include "RobotBase.h"
-#else
-#include "SampleRobot.h"
-#endif
+#include "frc971/wpilib/ahal/RobotBase.h"
 
 namespace frc971 {
 namespace wpilib {
@@ -19,17 +15,9 @@
   START_ROBOT_CLASS(::frc971::wpilib::WPILibAdapterRobot<_ClassName_>)
 
 template <typename T>
-#ifdef WPILIB2015
-class WPILibAdapterRobot : public RobotBase {
-#else
-class WPILibAdapterRobot : public SampleRobot {
-#endif
+class WPILibAdapterRobot : public frc::RobotBase {
  public:
-#ifdef WPILIB2015
   void StartCompetition() override { robot_.Run(); }
-#else
-  void RobotMain() override { robot_.Run(); }
-#endif
 
  private:
   T robot_;
diff --git a/motors/packages/0612.fp b/motors/packages/0612.fp
new file mode 100644
index 0000000..b49f458
--- /dev/null
+++ b/motors/packages/0612.fp
@@ -0,0 +1,8 @@
+# This is the footprint at
+# http://www.susumu-usa.com/pdf/FootPrint_8_9.pdf
+# for a 0612 (sideways 1206) part.
+Element[0x0 "" "" "" 0 0 0 0 0 100 0x0]
+(
+	Pad[-1.05mm 1.3mm -1.05mm -1.3mm 1.4mm 2000 1.65mm "1" "1" "square"]
+	Pad[1.05mm 1.3mm 1.05mm -1.3mm 1.4mm 2000 1.65mm "2" "2" "square"]
+)
diff --git a/motors/packages/1365.fp b/motors/packages/1365.fp
new file mode 100644
index 0000000..696c772
--- /dev/null
+++ b/motors/packages/1365.fp
@@ -0,0 +1,14 @@
+# This is the footprint at
+# https://katalog.we-online.de/pbs/datasheet/7443551200.pdf
+# for a 1365 inductor.
+Element[0x0 "" "" "" 0 0 0 0 0 100 0x0]
+(
+	Pad[-5.25mm 0.25mm -5.25mm -0.25mm 4.8mm 2000 4.5mm "1" "1" "square"]
+	Pad[5.25mm 0.25mm 5.25mm -0.25mm 4.8mm 2000 4.5mm "2" "2" "square"]
+	ElementLine[-7.4mm -4mm -7.4mm -8.4mm 800]
+	ElementLine[-7.4mm 4mm -7.4mm 8.4mm 800]
+	ElementLine[7.4mm -4mm 7.4mm -8.4mm 800]
+	ElementLine[7.4mm 4mm 7.4mm 8.4mm 800]
+	ElementLine[7.4mm 8.4mm -7.4mm 8.4mm 800]
+	ElementLine[7.4mm -8.4mm -7.4mm -8.4mm 800]
+)
diff --git a/motors/packages/1825640000.fp b/motors/packages/1825640000.fp
new file mode 100644
index 0000000..283d17f
--- /dev/null
+++ b/motors/packages/1825640000.fp
@@ -0,0 +1,26 @@
+# This is the footprint at
+# https://media.digikey.com/pdf/Data%20Sheets/Weidmuller%20PDFs/1825640000.pdf
+# for a 2-position big Weidmuller push in spring terminal.
+Element[0x0 "" "" "" 0 0 0 0 0 100 0x0]
+(
+	Pin[-1.75mm 0 1.6mm 2000 1.85mm 1.1mm "1" "1" ""]
+	Pin[1.75mm 0 1.6mm 2000 1.85mm 1.1mm "2" "2" ""]
+	Pin[-1.75mm 5.5mm 1.6mm 2000 1.85mm 1.1mm "1" "1" ""]
+	Pin[1.75mm 5.5mm 1.6mm 2000 1.85mm 1.1mm "2" "2" ""]
+
+	ElementLine[-3.35mm -1.4mm 3.35mm -1.4mm 800]
+	ElementLine[-3.35mm 6.9mm 3.35mm 6.9mm 800]
+	ElementLine[-3.35mm -1.4mm -3.35mm 6.9mm 800]
+	ElementLine[3.35mm -1.4mm 3.35mm 6.9mm 800]
+
+	ElementArc[-1.75mm 1.8mm 0.7mm 0.7mm 0 360 800]
+	ElementLine[-2.45mm 4.3mm -1.05mm 4.3mm 800]
+	ElementLine[-1.05mm 4.3mm -1.05mm 2.9mm 800]
+	ElementLine[-1.05mm 2.9mm -2.45mm 2.9mm 800]
+	ElementLine[-2.45mm 2.9mm -2.45mm 4.3mm 800]
+	ElementArc[1.75mm 1.8mm 0.7mm 0.7mm 0 360 800]
+	ElementLine[2.45mm 4.3mm 1.05mm 4.3mm 800]
+	ElementLine[1.05mm 4.3mm 1.05mm 2.9mm 800]
+	ElementLine[1.05mm 2.9mm 2.45mm 2.9mm 800]
+	ElementLine[2.45mm 2.9mm 2.45mm 4.3mm 800]
+)
diff --git a/motors/packages/22-23-2051.fp b/motors/packages/22-23-2051.fp
new file mode 100644
index 0000000..59c453c
--- /dev/null
+++ b/motors/packages/22-23-2051.fp
@@ -0,0 +1,18 @@
+Element(0x00 "Molex 22-23-2051 1x5 connector" "" "22-23-2051" 360 0 3 100 0x00)
+(
+	Pin(62 147 65 40 "1" 0x101)
+	Pin(162 147 65 40 "2" 0x01)
+	Pin(262 147 65 40 "3" 0x01)
+	Pin(362 147 65 40 "4" 0x01)
+	Pin(462 147 65 40 "5" 0x01)
+	ElementLine(0 0 0 290 10)
+	ElementLine(524 0 524 290 10)
+	ElementLine(524 0 0 0 10)
+	ElementLine(0 90 524 90 10)
+	ElementLine(112 290 112 90 10)
+	ElementLine(212 290 212 90 10)
+	ElementLine(312 290 312 90 10)
+	ElementLine(412 290 412 90 10)
+	ElementLine(0 290 524 290 10)
+	Mark(262 147)
+)
diff --git a/motors/packages/22-23-2061.fp b/motors/packages/22-23-2061.fp
new file mode 100644
index 0000000..1853f10
--- /dev/null
+++ b/motors/packages/22-23-2061.fp
@@ -0,0 +1,20 @@
+Element(0x00 "Molex 22-23-2061 1x6 connector" "" "22-23-2026" 360 0 3 100 0x00)
+(
+	Pin(62 147 65 40 "1" 0x101)
+	Pin(162 147 65 40 "2" 0x01)
+	Pin(262 147 65 40 "3" 0x01)
+	Pin(362 147 65 40 "4" 0x01)
+	Pin(462 147 65 40 "5" 0x01)
+	Pin(562 147 65 40 "6" 0x01)
+	ElementLine(0 0 0 290 10)
+	ElementLine(624 0 624 290 10)
+	ElementLine(624 0 0 0 10)
+	ElementLine(0 90 624 90 10)
+	ElementLine(112 290 112 90 10)
+	ElementLine(212 290 212 90 10)
+	ElementLine(312 290 312 90 10)
+	ElementLine(412 290 412 90 10)
+	ElementLine(512 290 512 90 10)
+	ElementLine(0 290 624 290 10)
+	Mark(312 147)
+)
diff --git a/motors/packages/8-PowerTDFN_5_6.fp b/motors/packages/8-PowerTDFN_5_6.fp
new file mode 100644
index 0000000..ebc7543
--- /dev/null
+++ b/motors/packages/8-PowerTDFN_5_6.fp
@@ -0,0 +1,37 @@
+# This is the footprint at
+# http://www.ti.com/lit/ds/symlink/csd17556q5b.pdf
+# for a SON 5mm x 6mm plastic package.
+Element[0x0 "" "" "" 0 0 0 0 0 100 0x0]
+(
+	Pad[-3.101mm -1.905mm 0.629mm -1.905mm 0.91mm 2000 0.71mm "D" "D" "square,nopaste"]
+	Pad[-3.039mm -1.905mm -2.781mm -1.905mm 0.508mm 2000 0.508mm "D" "D" "square"]
+	Pad[-3.101mm -0.635mm 0.629mm -0.635mm 0.91mm 2000 0.71mm "D" "D" "square,nopaste"]
+	Pad[-3.039mm -0.635mm -2.781mm -0.635mm 0.508mm 2000 0.508mm "D" "D" "square"]
+	Pad[-3.101mm 0.635mm 0.629mm 0.635mm 0.91mm 2000 0.71mm "D" "D" "square,nopaste"]
+	Pad[-3.039mm 0.635mm -2.781mm 0.635mm 0.508mm 2000 0.508mm "D" "D" "square"]
+	Pad[-3.101mm 1.905mm 0.629mm 1.905mm 0.91mm 2000 0.71mm "D" "D" "square,nopaste"]
+	Pad[-3.039mm 1.905mm -2.781mm 1.905mm 0.508mm 2000 0.508mm "D" "D" "square"]
+
+	Pad[-0.941mm 0.335mm -0.941mm -0.335mm 4.05mm 2000 3.85mm "D" "D" "square,nopaste"]
+
+	Pad[-1.868mm -1.569mm -1.32mm -1.569mm 0.746mm 2000 0.746mm "D" "D" "square"]
+	Pad[-0.224mm -1.569mm 0.324mm -1.569mm 0.746mm 2000 0.746mm "D" "D" "square"]
+	Pad[-1.868mm -0.523mm -1.32mm -0.523mm 0.746mm 2000 0.746mm "D" "D" "square"]
+	Pad[-0.224mm -0.523mm 0.324mm -0.523mm 0.746mm 2000 0.746mm "D" "D" "square"]
+	Pad[-1.868mm 0.523mm -1.32mm 0.523mm 0.746mm 2000 0.746mm "D" "D" "square"]
+	Pad[-0.224mm 0.523mm 0.324mm 0.523mm 0.746mm 2000 0.746mm "D" "D" "square"]
+	Pad[-1.868mm 1.569mm -1.32mm 1.569mm 0.746mm 2000 0.746mm "D" "D" "square"]
+	Pad[-0.224mm 1.569mm 0.324mm 1.569mm 0.746mm 2000 0.746mm "D" "D" "square"]
+
+	Pad[2.323mm -1.905mm 2.985mm -1.905mm 0.91mm 2000 0.71mm "G" "G" "square,nopaste"]
+	Pad[2.502mm -1.905mm 3.012mm -1.905mm 0.562mm 2000 0.562mm "G" "G" "square"]
+	Pad[2.323mm -0.635mm 2.985mm -0.635mm 0.91mm 2000 0.71mm "S" "S" "square,nopaste"]
+	Pad[2.502mm -0.635mm 3.012mm -0.635mm 0.562mm 2000 0.562mm "S" "S" "square"]
+	Pad[2.323mm 0.635mm 2.985mm 0.635mm 0.91mm 2000 0.71mm "S" "S" "square,nopaste"]
+	Pad[2.502mm 0.635mm 3.012mm 0.635mm 0.562mm 2000 0.562mm "S" "S" "square"]
+	Pad[2.323mm 1.905mm 2.985mm 1.905mm 0.91mm 2000 0.71mm "S" "S" "square,nopaste"]
+	Pad[2.502mm 1.905mm 3.012mm 1.905mm 0.562mm 2000 0.562mm "S" "S" "square"]
+
+	ElementLine[-3mm -2.55mm 3mm -2.55mm 800]
+	ElementLine[-3mm 2.55mm 3mm 2.55mm 800]
+)
diff --git a/motors/packages/QFN28_4_5_EP.fp b/motors/packages/QFN28_4_5_EP.fp
new file mode 100644
index 0000000..53262d1
--- /dev/null
+++ b/motors/packages/QFN28_4_5_EP.fp
@@ -0,0 +1,49 @@
+Element[0x00000000 "Square Quad Flat Nolead (QFN) package" "" "" 0 0 0 0 0 100 0x0]
+(
+# left row
+	Pad[-8188  -6890  -6772  -6890  945  2000 1325 "1" "1"  0x00000100]
+	Pad[-8188  -4921  -6772  -4921  945  2000 1325 "2" "2"  0x00000100]
+	Pad[-8188  -2953  -6772  -2953  945  2000 1325 "3" "3"  0x00000100]
+	Pad[-8188  -984  -6772  -984  945  2000 1325 "4" "4"  0x00000100]
+	Pad[-8188  984  -6772  984  945  2000 1325 "5" "5"  0x00000100]
+	Pad[-8188  2953  -6772  2953  945  2000 1325 "6" "6"  0x00000100]
+	Pad[-8188  4921  -6772  4921  945  2000 1325 "7" "7"  0x00000100]
+	Pad[-8188  6890  -6772  6890  945  2000 1325 "8" "8"  0x00000100]
+# bottom row
+	Pad[-4921  10157  -4921  8740  945 2000 1325 "9" "9"  0x00000900]
+	Pad[-2953  10157  -2953  8740  945 2000 1325 "10" "10"  0x00000900]
+	Pad[-984  10157  -984  8740  945 2000 1325 "11" "11"  0x00000900]
+	Pad[984  10157  984  8740  945 2000 1325 "12" "12"  0x00000900]
+	Pad[2953  10157  2953  8740  945 2000 1325 "13" "13"  0x00000900]
+	Pad[4921  10157  4921  8740  945 2000 1325 "14" "14"  0x00000900]
+# right row
+	Pad[8188  6890  6772  6890  945  2000 1325 "15" "15"  0x00000100]
+	Pad[8188  4921  6772  4921  945  2000 1325 "16" "16"  0x00000100]
+	Pad[8188  2953  6772  2953  945  2000 1325 "17" "17"  0x00000100]
+	Pad[8188  984  6772  984  945  2000 1325 "18" "18"  0x00000100]
+	Pad[8188  -984  6772  -984  945  2000 1325 "19" "19"  0x00000100]
+	Pad[8188  -2953  6772  -2953  945  2000 1325 "20" "20"  0x00000100]
+	Pad[8188  -4921  6772  -4921  945  2000 1325 "21" "21"  0x00000100]
+	Pad[8188  -6890  6772  -6890  945  2000 1325 "22" "22"  0x00000100]
+# top row
+	Pad[4921  -10157  4921  -8740  945 2000 1325 "23" "23" 0x00000900]
+	Pad[2953  -10157  2953  -8740  945 2000 1325 "24" "24" 0x00000900]
+	Pad[984  -10157  984  -8740  945 2000 1325 "25" "25" 0x00000900]
+	Pad[-984  -10157  -984  -8740  945 2000 1325 "26" "26" 0x00000900]
+	Pad[-2953  -10157  -2953  -8740  945 2000 1325 "27" "27" 0x00000900]
+	Pad[-4921  -10157  -4921  -8740  945 2000 1325 "28" "28" 0x00000900]
+# Exposed paddle (if this is an exposed paddle part)
+	Pad[0 1969 0 -1968 10039 0 10419 "29" "29" "square"]
+	Pin[0 0 0.65mm 2000 0 0.3mm "29" "29" ""]
+	Pin[0.95mm 0 0.65mm 2000 0 0.3mm "29" "29" ""]
+	Pin[-0.95mm 0 0.65mm 2000 0 0.3mm "29" "29" ""]
+	Pin[0 1.45mm 0.65mm 2000 0 0.3mm "29" "29" ""]
+	Pin[0 -1.45mm 0.65mm 2000 0 0.3mm "29" "29" ""]
+# Silk screen around package
+ElementLine[ 9857  11826  9857 -11826 1000]
+ElementLine[ 9857 -11826 -9857 -11826 1000]
+ElementLine[-9857 -11826 -9857  11826 1000]
+ElementLine[-9857  11826  9857  11826 1000]
+# Pin 1 indicator
+ElementLine[-9859 -11826 -11359 -13326 1000]
+)
diff --git a/motors/packages/UE27AEX4X0X.fp b/motors/packages/UE27AEX4X0X.fp
new file mode 100644
index 0000000..fe2f60a
--- /dev/null
+++ b/motors/packages/UE27AEX4X0X.fp
@@ -0,0 +1,16 @@
+# This is the footprint at
+# https://signin.amphenolcanada.com/ProductSearch/drawings/AC/UE27AEX4X0X.pdf
+# for a USB connector.
+Element[0x0 "" "" "" 0 0 0 0 0 100 0x0]
+(
+	Pin[-3.5mm 0 1.4mm 2000 1.65mm 0.9mm "1" "1" ""]
+	Pin[-1mm 0 1.4mm 2000 1.65mm 0.9mm "2" "2" ""]
+	Pin[1mm 0 1.4mm 2000 1.65mm 0.9mm "3" "3" ""]
+	Pin[3.5mm 0 1.4mm 2000 1.65mm 0.9mm "4" "4" ""]
+	Pin[-6.57mm 2.71mm 2.7mm 2000 2.95mm 2.3mm "5" "5" ""]
+	Pin[6.57mm 2.71mm 2.7mm 2000 2.95mm 2.3mm "5" "5" ""]
+	ElementLine[7.25mm -1.5mm -7.25mm -1.5mm 800]
+	ElementLine[7.25mm -1.5mm 7.25mm 1mm 800]
+	ElementLine[-7.25mm -1.5mm -7.25mm 1mm 800]
+	ElementLine[5.5mm 4.22mm -5.5mm 4.22mm 800]
+)
diff --git a/motors/packages/V-DFN3020-14.fp b/motors/packages/V-DFN3020-14.fp
new file mode 100644
index 0000000..e25a87c
--- /dev/null
+++ b/motors/packages/V-DFN3020-14.fp
@@ -0,0 +1,19 @@
+# This is the footprint at
+# https://www.diodes.com/assets/Datasheets/AP22966.pdf
+# for a 14-WFDFN with an exposed pad and some fused pins.
+Element[0x0 "" "" "" 0 0 0 0 0 100 0x0]
+(
+	Pad[-1.075mm 0.85mm -0.925mm 0.85mm 0.5mm 2000 0.6mm "1_2" "1_2" "square"]
+	Pad[-0.4mm 0.725mm -0.4mm 0.975mm 0.25mm 2000 0.35mm "3" "3" "square"]
+	Pad[0 0.725mm 0 0.975mm 0.25mm 2000 0.35mm "4" "4" "square"]
+	Pad[0.4mm 0.725mm 0.4mm 0.975mm 0.25mm 2000 0.35mm "5" "5" "square"]
+	Pad[1.075mm 0.85mm 0.925mm 0.85mm 0.5mm 2000 0.6mm "6_7" "6_7" "square"]
+	Pad[1.075mm -0.85mm 0.925mm -0.85mm 0.5mm 2000 0.6mm "8_9" "8_9" "square"]
+	Pad[0.4mm -0.725mm 0.4mm -0.975mm 0.25mm 2000 0.35mm "10" "10" "square"]
+	Pad[0 -0.725mm 0 -0.975mm 0.25mm 2000 0.35mm "11" "11" "square"]
+	Pad[-0.4mm -0.725mm -0.4mm -0.975mm 0.25mm 2000 0.35mm "12" "12" "square"]
+	Pad[-1.075mm -0.85mm -0.925mm -0.85mm 0.5mm 2000 0.6mm "13_14" "13_14" "square"]
+	Pad[-0.8mm 0 0.8mm 0 0.92mm 2000 1.02mm "15" "15" "square"]
+	ElementLine[-1.525mm 1.025mm -1.525mm -1.025mm 800]
+	ElementLine[1.525mm 1.025mm 1.525mm -1.025mm 800]
+)
diff --git a/motors/symbols/AP22966.sym b/motors/symbols/AP22966.sym
new file mode 100644
index 0000000..20cfd15
--- /dev/null
+++ b/motors/symbols/AP22966.sym
@@ -0,0 +1,131 @@
+v 20130925 2
+B 600 300 1600 1600 3 0 0 0 -1 -1 0 -1 -1 -1 -1 -1
+P 300 1700 600 1700 1 0 0
+{
+T 300 1700 5 10 0 0 0 0 1
+pintype=pwr
+T 655 1695 5 10 1 1 0 0 1
+pinlabel=VBIAS
+T 505 1745 5 10 1 1 0 6 1
+pinnumber=4
+T 300 1700 5 10 0 0 0 0 1
+pinseq=1
+}
+T 300 2800 8 10 0 1 0 0 1
+footprint=V-DFN3020-14
+T 700 1900 8 10 1 1 0 0 1
+device=AP22966
+T 1700 1900 8 10 1 1 0 0 1
+refdes=U?
+P 300 1400 600 1400 1 0 0
+{
+T 300 1400 5 10 0 0 0 0 1
+pintype=pwr
+T 655 1395 5 10 1 1 0 0 1
+pinlabel=VIN1
+T 505 1445 5 10 1 1 0 6 1
+pinnumber=1_2
+T 300 1400 5 10 0 0 0 0 1
+pinseq=2
+}
+P 300 1100 600 1100 1 0 0
+{
+T 300 1100 5 10 0 0 0 0 1
+pintype=pwr
+T 655 1095 5 10 1 1 0 0 1
+pinlabel=VIN2
+T 505 1145 5 10 1 1 0 6 1
+pinnumber=6_7
+T 300 1100 5 10 0 0 0 0 1
+pinseq=3
+}
+P 300 800 600 800 1 0 0
+{
+T 300 800 5 10 0 0 0 0 1
+pintype=out
+T 655 795 5 10 1 1 0 0 1
+pinlabel=VOUT1
+T 505 845 5 10 1 1 0 6 1
+pinnumber=13_14
+T 300 800 5 10 0 0 0 0 1
+pinseq=4
+}
+P 300 500 600 500 1 0 0
+{
+T 300 500 5 10 0 0 0 0 1
+pintype=out
+T 655 495 5 10 1 1 0 0 1
+pinlabel=VOUT2
+T 505 545 5 10 1 1 0 6 1
+pinnumber=8_9
+T 300 500 5 10 0 0 0 0 1
+pinseq=5
+}
+P 2500 1700 2200 1700 1 0 0
+{
+T 2500 1700 5 10 0 0 0 0 1
+pintype=pwr
+T 2145 1695 5 10 1 1 0 6 1
+pinlabel=GND
+T 2295 1745 5 10 1 1 0 0 1
+pinnumber=11
+T 2500 1700 5 10 0 0 0 0 1
+pinseq=6
+}
+P 2500 1400 2200 1400 1 0 0
+{
+T 2500 1400 5 10 0 0 0 0 1
+pintype=in
+T 2145 1395 5 10 1 1 0 6 1
+pinlabel=EN1
+T 2295 1445 5 10 1 1 0 0 1
+pinnumber=3
+T 2500 1400 5 10 0 0 0 0 1
+pinseq=7
+}
+P 2500 1100 2200 1100 1 0 0
+{
+T 2500 1100 5 10 0 0 0 0 1
+pintype=in
+T 2145 1095 5 10 1 1 0 6 1
+pinlabel=EN2
+T 2295 1145 5 10 1 1 0 0 1
+pinnumber=5
+T 2500 1100 5 10 0 0 0 0 1
+pinseq=8
+}
+P 2500 800 2200 800 1 0 0
+{
+T 2500 800 5 10 0 0 0 0 1
+pintype=pas
+T 2145 795 5 10 1 1 0 6 1
+pinlabel=SS1
+T 2295 845 5 10 1 1 0 0 1
+pinnumber=12
+T 2500 800 5 10 0 0 0 0 1
+pinseq=10
+}
+P 2500 500 2200 500 1 0 0
+{
+T 2500 500 5 10 0 0 0 0 1
+pintype=pas
+T 2145 495 5 10 1 1 0 6 1
+pinlabel=SS2
+T 2295 545 5 10 1 1 0 0 1
+pinnumber=10
+T 2500 500 5 10 0 0 0 0 1
+pinseq=11
+}
+P 1500 0 1500 300 1 0 0
+{
+T 1500 0 5 10 0 0 0 0 1
+pintype=pwr
+T 1500 355 5 10 1 1 90 0 1
+pinlabel=PAD
+T 1450 205 5 10 1 1 90 6 1
+pinnumber=15
+T 1500 0 5 10 0 0 0 0 1
+pinseq=9
+}
+T 2000 1400 8 10 0 1 0 0 1
+numslots=0
diff --git a/motors/symbols/LM34936.sym b/motors/symbols/LM34936.sym
new file mode 100644
index 0000000..a6304bb
--- /dev/null
+++ b/motors/symbols/LM34936.sym
@@ -0,0 +1,329 @@
+v 20130925 2
+T 500 4500 8 10 1 1 0 0 1
+device=LM34936
+T 1800 4500 8 10 1 1 0 0 1
+refdes=U?
+B 300 300 2200 4200 3 0 0 0 -1 -1 0 -1 -1 -1 -1 -1
+P 0 4300 300 4300 1 0 0
+{
+T 0 4300 5 10 0 0 0 0 1
+pintype=in
+T 355 4295 5 10 1 1 0 0 1
+pinlabel=MODE
+T 205 4345 5 10 1 1 0 6 1
+pinnumber=1
+T 0 4300 5 10 0 0 0 0 1
+pinseq=1
+}
+P 0 4000 300 4000 1 0 0
+{
+T 0 4000 5 10 0 0 0 0 1
+pintype=in
+T 355 3995 5 10 1 1 0 0 1
+pinlabel=DITH
+T 205 4045 5 10 1 1 0 6 1
+pinnumber=2
+T 0 4000 5 10 0 0 0 0 1
+pinseq=2
+}
+P 0 3700 300 3700 1 0 0
+{
+T 0 3700 5 10 0 0 0 0 1
+pintype=in
+T 355 3695 5 10 1 1 0 0 1
+pinlabel=RT/SYNC
+T 205 3745 5 10 1 1 0 6 1
+pinnumber=3
+T 0 3700 5 10 0 0 0 0 1
+pinseq=3
+}
+P 0 3400 300 3400 1 0 0
+{
+T 0 3400 5 10 0 0 0 0 1
+pintype=pas
+T 355 3395 5 10 1 1 0 0 1
+pinlabel=SLOPE
+T 205 3445 5 10 1 1 0 6 1
+pinnumber=4
+T 0 3400 5 10 0 0 0 0 1
+pinseq=4
+}
+P 0 3100 300 3100 1 0 0
+{
+T 0 3100 5 10 0 0 0 0 1
+pintype=pas
+T 355 3095 5 10 1 1 0 0 1
+pinlabel=SS
+T 205 3145 5 10 1 1 0 6 1
+pinnumber=5
+T 0 3100 5 10 0 0 0 0 1
+pinseq=5
+}
+P 0 2800 300 2800 1 0 0
+{
+T 0 2800 5 10 0 0 0 0 1
+pintype=pas
+T 355 2795 5 10 1 1 0 0 1
+pinlabel=COMP
+T 205 2845 5 10 1 1 0 6 1
+pinnumber=6
+T 0 2800 5 10 0 0 0 0 1
+pinseq=6
+}
+P 0 2500 300 2500 1 0 0
+{
+T 0 2500 5 10 0 0 0 0 1
+pintype=in
+T 355 2495 5 10 1 1 0 0 1
+pinlabel=FB
+T 205 2545 5 10 1 1 0 6 1
+pinnumber=8
+T 0 2500 5 10 0 0 0 0 1
+pinseq=7
+}
+P 0 2200 300 2200 1 0 0
+{
+T 0 2200 5 10 0 0 0 0 1
+pintype=oc
+T 355 2195 5 10 1 1 0 0 1
+pinlabel=PGOOD
+T 205 2245 5 10 1 1 0 6 1
+pinnumber=14
+T 0 2200 5 10 0 0 0 0 1
+pinseq=8
+}
+P 0 1900 300 1900 1 0 0
+{
+T 0 1900 5 10 0 0 0 0 1
+pintype=in
+T 355 1895 5 10 1 1 0 0 1
+pinlabel=EN/UVLO
+T 205 1945 5 10 1 1 0 6 1
+pinnumber=26
+T 0 1900 5 10 0 0 0 0 1
+pinseq=9
+}
+P 0 1600 300 1600 1 0 0
+{
+T 0 1600 5 10 0 0 0 0 1
+pintype=in
+T 355 1595 5 10 1 1 0 0 1
+pinlabel=ISNS(-)
+T 205 1645 5 10 1 1 0 6 1
+pinnumber=10
+T 0 1600 5 10 0 0 0 0 1
+pinseq=10
+}
+P 0 1300 300 1300 1 0 0
+{
+T 0 1300 5 10 0 0 0 0 1
+pintype=in
+T 355 1295 5 10 1 1 0 0 1
+pinlabel=ISNS(+)
+T 205 1345 5 10 1 1 0 6 1
+pinnumber=11
+T 0 1300 5 10 0 0 0 0 1
+pinseq=12
+}
+P 0 1000 300 1000 1 0 0
+{
+T 0 1000 5 10 0 0 0 0 1
+pintype=in
+T 355 995 5 10 1 1 0 0 1
+pinlabel=CSG
+T 205 1045 5 10 1 1 0 6 1
+pinnumber=12
+T 0 1000 5 10 0 0 0 0 1
+pinseq=14
+}
+P 0 700 300 700 1 0 0
+{
+T 0 700 5 10 0 0 0 0 1
+pintype=in
+T 355 695 5 10 1 1 0 0 1
+pinlabel=CS
+T 205 745 5 10 1 1 0 6 1
+pinnumber=13
+T 0 700 5 10 0 0 0 0 1
+pinseq=16
+}
+P 0 400 300 400 1 0 0
+{
+T 0 400 5 10 0 0 0 0 1
+pintype=pwr
+T 355 395 5 10 1 1 0 0 1
+pinlabel=VCC
+T 205 445 5 10 1 1 0 6 1
+pinnumber=20
+T 0 400 5 10 0 0 0 0 1
+pinseq=18
+}
+P 2800 400 2500 400 1 0 0
+{
+T 2800 400 5 10 0 0 0 0 1
+pintype=pwr
+T 2445 395 5 10 1 1 0 6 1
+pinlabel=PGND
+T 2595 445 5 10 1 1 0 0 1
+pinnumber=19
+T 2800 400 5 10 0 0 0 0 1
+pinseq=28
+}
+P 2800 700 2500 700 1 0 0
+{
+T 2800 700 5 10 0 0 0 0 1
+pintype=pwr
+T 2445 695 5 10 1 1 0 6 1
+pinlabel=AGND
+T 2595 745 5 10 1 1 0 0 1
+pinnumber=7
+T 2800 700 5 10 0 0 0 0 1
+pinseq=27
+}
+P 2800 1300 2500 1300 1 0 0
+{
+T 2800 1300 5 10 0 0 0 0 1
+pintype=pwr
+T 2445 1295 5 10 1 1 0 6 1
+pinlabel=BIAS
+T 2595 1345 5 10 1 1 0 0 1
+pinnumber=21
+T 2800 1300 5 10 0 0 0 0 1
+pinseq=25
+}
+P 2800 1000 2500 1000 1 0 0
+{
+T 2800 1000 5 10 0 0 0 0 1
+pintype=pwr
+T 2445 995 5 10 1 1 0 6 1
+pinlabel=VIN
+T 2595 1045 5 10 1 1 0 0 1
+pinnumber=27
+T 2800 1000 5 10 0 0 0 0 1
+pinseq=26
+}
+P 2800 1600 2500 1600 1 0 0
+{
+T 2800 1600 5 10 0 0 0 0 1
+pintype=out
+T 2445 1595 5 10 1 1 0 6 1
+pinlabel=LDRV2
+T 2595 1645 5 10 1 1 0 0 1
+pinnumber=18
+T 2800 1600 5 10 0 0 0 0 1
+pinseq=24
+}
+P 2800 2200 2500 2200 1 0 0
+{
+T 2800 2200 5 10 0 0 0 0 1
+pintype=out
+T 2445 2195 5 10 1 1 0 6 1
+pinlabel=HDRV2
+T 2800 2200 5 10 0 0 0 0 1
+pinseq=22
+T 2595 2245 5 10 1 1 0 0 1
+pinnumber=16
+}
+P 2800 2500 2500 2500 1 0 0
+{
+T 2800 2500 5 10 0 0 0 0 1
+pintype=pas
+T 2445 2495 5 10 1 1 0 6 1
+pinlabel=SW2
+T 2595 2545 5 10 1 1 0 0 1
+pinnumber=15
+T 2800 2500 5 10 0 0 0 0 1
+pinseq=21
+}
+P 2800 2800 2500 2800 1 0 0
+{
+T 2800 2800 5 10 0 0 0 0 1
+pintype=out
+T 2445 2795 5 10 1 1 0 6 1
+pinlabel=LDRV1
+T 2595 2845 5 10 1 1 0 0 1
+pinnumber=22
+T 2800 2800 5 10 0 0 0 0 1
+pinseq=20
+}
+P 2800 3100 2500 3100 1 0 0
+{
+T 2800 3100 5 10 0 0 0 0 1
+pintype=pas
+T 2445 3095 5 10 1 1 0 6 1
+pinlabel=BOOT1
+T 2800 3100 5 10 0 0 0 0 1
+pinseq=19
+T 2595 3145 5 10 1 1 0 0 1
+pinnumber=23
+}
+P 2800 1900 2500 1900 1 0 0
+{
+T 2800 1900 5 10 0 0 0 0 1
+pintype=pas
+T 2445 1895 5 10 1 1 0 6 1
+pinlabel=BOOT2
+T 2800 1900 5 10 0 0 0 0 1
+pinseq=23
+T 2595 1945 5 10 1 1 0 0 1
+pinnumber=17
+}
+P 2800 4000 2500 4000 1 0 0
+{
+T 2800 4000 5 10 0 0 0 0 1
+pintype=in
+T 2445 3995 5 10 1 1 0 6 1
+pinlabel=VOSNS
+T 2595 4045 5 10 1 1 0 0 1
+pinnumber=9
+T 2800 4000 5 10 0 0 0 0 1
+pinseq=13
+}
+P 2800 4300 2500 4300 1 0 0
+{
+T 2800 4300 5 10 0 0 0 0 1
+pintype=in
+T 2445 4295 5 10 1 1 0 6 1
+pinlabel=VISNS
+T 2595 4345 5 10 1 1 0 0 1
+pinnumber=28
+T 2800 4300 5 10 0 0 0 0 1
+pinseq=11
+}
+P 2800 3400 2500 3400 1 0 0
+{
+T 2800 3400 5 10 0 0 0 0 1
+pintype=out
+T 2445 3395 5 10 1 1 0 6 1
+pinlabel=HDRV1
+T 2595 3445 5 10 1 1 0 0 1
+pinnumber=24
+T 2800 3400 5 10 0 0 0 0 1
+pinseq=17
+}
+P 2800 3700 2500 3700 1 0 0
+{
+T 2800 3700 5 10 0 0 0 0 1
+pintype=pas
+T 2445 3695 5 10 1 1 0 6 1
+pinlabel=SW1
+T 2800 3700 5 10 0 0 0 0 1
+pinseq=15
+T 2595 3745 5 10 1 1 0 0 1
+pinnumber=25
+}
+T 1000 5200 8 10 0 1 0 0 1
+numslots=0
+P 1400 0 1400 300 1 0 0
+{
+T 1400 0 5 10 0 0 0 0 1
+pintype=pwr
+T 1400 355 5 10 1 1 90 0 1
+pinlabel=PAD_GND
+T 1350 205 5 10 1 1 90 6 1
+pinnumber=29
+T 1400 0 5 10 0 0 0 0 1
+pinseq=29
+}
+T 5500 3300 8 10 0 1 0 0 1
+footprint=QFN28_4_5_EP
diff --git a/motors/symbols/SI864x.sym b/motors/symbols/SI864x.sym
new file mode 100644
index 0000000..0dc3603
--- /dev/null
+++ b/motors/symbols/SI864x.sym
@@ -0,0 +1,186 @@
+v 20130925 2
+B 300 0 1700 2400 3 0 0 0 -1 -1 0 -1 -1 -1 -1 -1
+P 0 2200 300 2200 1 0 0
+{
+T 0 2200 5 10 0 0 0 0 1
+pintype=pwr
+T 355 2195 5 10 1 1 0 0 1
+pinlabel=VDD1
+T 205 2245 5 10 1 1 0 6 1
+pinnumber=1
+T 0 2200 5 10 0 0 0 0 1
+pinseq=1
+}
+P 0 1900 300 1900 1 0 0
+{
+T 0 1900 5 10 0 0 0 0 1
+pintype=pwr
+T 355 1895 5 10 1 1 0 0 1
+pinlabel=GND1-1
+T 205 1945 5 10 1 1 0 6 1
+pinnumber=2
+T 0 1900 5 10 0 0 0 0 1
+pinseq=2
+}
+P 0 1600 300 1600 1 0 0
+{
+T 0 1600 5 10 0 0 0 0 1
+pintype=pwr
+T 355 1595 5 10 1 1 0 0 1
+pinlabel=GND1-2
+T 205 1645 5 10 1 1 0 6 1
+pinnumber=8
+T 0 1600 5 10 0 0 0 0 1
+pinseq=3
+}
+P 0 1300 300 1300 1 0 0
+{
+T 0 1300 5 10 0 0 0 0 1
+pintype=in
+T 355 1295 5 10 1 1 0 0 1
+pinlabel=EN1
+T 205 1345 5 10 1 1 0 6 1
+pinnumber=7
+T 0 1300 5 10 0 0 0 0 1
+pinseq=4
+}
+P 2300 2200 2000 2200 1 0 0
+{
+T 2300 2200 5 10 0 0 0 0 1
+pintype=pwr
+T 1945 2195 5 10 1 1 0 6 1
+pinlabel=VDD2
+T 2095 2245 5 10 1 1 0 0 1
+pinnumber=16
+T 2300 2200 5 10 0 0 0 0 1
+pinseq=9
+}
+P 2300 1900 2000 1900 1 0 0
+{
+T 2300 1900 5 10 0 0 0 0 1
+pintype=pwr
+T 1945 1895 5 10 1 1 0 6 1
+pinlabel=GND2-1
+T 2095 1945 5 10 1 1 0 0 1
+pinnumber=15
+T 2300 1900 5 10 0 0 0 0 1
+pinseq=10
+}
+P 2300 1600 2000 1600 1 0 0
+{
+T 2300 1600 5 10 0 0 0 0 1
+pintype=pwr
+T 1945 1595 5 10 1 1 0 6 1
+pinlabel=GND2-2
+T 2095 1645 5 10 1 1 0 0 1
+pinnumber=9
+T 2300 1600 5 10 0 0 0 0 1
+pinseq=11
+}
+P 2300 1300 2000 1300 1 0 0
+{
+T 2300 1300 5 10 0 0 0 0 1
+pintype=in
+T 1945 1295 5 10 1 1 0 6 1
+pinlabel=EN2
+T 2095 1345 5 10 1 1 0 0 1
+pinnumber=10
+T 2300 1300 5 10 0 0 0 0 1
+pinseq=12
+}
+P 0 1000 300 1000 1 0 0
+{
+T 0 1000 5 10 0 0 0 0 1
+pintype=io
+T 355 995 5 10 1 1 0 0 1
+pinlabel=A1
+T 205 1045 5 10 1 1 0 6 1
+pinnumber=3
+T 0 1000 5 10 0 0 0 0 1
+pinseq=5
+}
+P 0 700 300 700 1 0 0
+{
+T 0 700 5 10 0 0 0 0 1
+pintype=io
+T 355 695 5 10 1 1 0 0 1
+pinlabel=A2
+T 205 745 5 10 1 1 0 6 1
+pinnumber=4
+T 0 700 5 10 0 0 0 0 1
+pinseq=6
+}
+P 0 400 300 400 1 0 0
+{
+T 0 400 5 10 0 0 0 0 1
+pintype=io
+T 355 395 5 10 1 1 0 0 1
+pinlabel=A3
+T 205 445 5 10 1 1 0 6 1
+pinnumber=5
+T 0 400 5 10 0 0 0 0 1
+pinseq=7
+}
+P 0 100 300 100 1 0 0
+{
+T 0 100 5 10 0 0 0 0 1
+pintype=io
+T 355 95 5 10 1 1 0 0 1
+pinlabel=A4
+T 205 145 5 10 1 1 0 6 1
+pinnumber=6
+T 0 100 5 10 0 0 0 0 1
+pinseq=8
+}
+P 2300 1000 2000 1000 1 0 0
+{
+T 2300 1000 5 10 0 0 0 0 1
+pintype=io
+T 1945 995 5 10 1 1 0 6 1
+pinlabel=B1
+T 2095 1045 5 10 1 1 0 0 1
+pinnumber=14
+T 2300 1000 5 10 0 0 0 0 1
+pinseq=13
+}
+P 2300 700 2000 700 1 0 0
+{
+T 2300 700 5 10 0 0 0 0 1
+pintype=io
+T 1945 695 5 10 1 1 0 6 1
+pinlabel=B2
+T 2095 745 5 10 1 1 0 0 1
+pinnumber=13
+T 2300 700 5 10 0 0 0 0 1
+pinseq=14
+}
+P 2300 400 2000 400 1 0 0
+{
+T 2300 400 5 10 0 0 0 0 1
+pintype=io
+T 1945 395 5 10 1 1 0 6 1
+pinlabel=B3
+T 2095 445 5 10 1 1 0 0 1
+pinnumber=12
+T 2300 400 5 10 0 0 0 0 1
+pinseq=15
+}
+P 2300 100 2000 100 1 0 0
+{
+T 2300 100 5 10 0 0 0 0 1
+pintype=io
+T 1945 95 5 10 1 1 0 6 1
+pinlabel=B4
+T 2095 145 5 10 1 1 0 0 1
+pinnumber=11
+T 2300 100 5 10 0 0 0 0 1
+pinseq=16
+}
+T 500 2400 8 10 1 1 0 0 1
+device=SI864x
+T 1500 2400 8 10 1 1 0 0 1
+refdes=U?
+T 1700 3000 8 10 0 1 0 0 1
+footprint=SO16W
+T 2400 3100 8 10 0 1 0 0 1
+numslots=0
diff --git a/motors/symbols/inverter.sym b/motors/symbols/inverter.sym
new file mode 100644
index 0000000..93b50c1
--- /dev/null
+++ b/motors/symbols/inverter.sym
@@ -0,0 +1,63 @@
+v 20130925 2
+L 700 0 700 600 3 0 0 0 -1 -1
+L 700 600 1200 300 3 0 0 0 -1 -1
+L 1200 300 700 0 3 0 0 0 -1 -1
+V 1250 300 50 6 0 0 0 -1 -1 0 -1 -1 -1 -1 -1
+P 400 300 700 300 1 0 0
+{
+T 600 350 5 8 1 1 0 6 1
+pinnumber=2
+T 600 250 5 8 0 1 0 8 1
+pinseq=1
+T 750 300 9 8 0 1 0 0 1
+pinlabel=A
+T 750 300 5 8 0 1 0 2 1
+pintype=in
+}
+P 1600 300 1300 300 1 0 0
+{
+T 1400 350 5 8 1 1 0 0 1
+pinnumber=4
+T 1400 250 5 8 0 1 0 2 1
+pinseq=2
+T 1150 300 9 8 0 1 0 6 1
+pinlabel=Y
+T 1150 300 5 8 0 1 0 8 1
+pintype=out
+}
+T 700 1000 5 10 0 0 0 0 1
+numslots=0
+T 700 800 5 10 0 0 0 0 1
+device=INVERTER
+L 790 360 790 160 3 0 0 0 -1 -1
+L 790 160 850 200 3 0 0 0 -1 -1
+L 790 360 850 400 3 0 0 0 -1 -1
+L 790 160 730 120 3 0 0 0 -1 -1
+L 850 200 850 400 3 0 0 0 -1 -1
+L 850 400 920 440 3 0 0 0 -1 -1
+T 1200 600 8 10 1 1 0 0 1
+refdes=U?
+T 700 3200 5 10 0 0 0 0 1
+footprint=SOT25
+P 400 0 700 0 1 0 0
+{
+T 400 0 5 10 0 0 0 0 1
+pintype=pwr
+T -45 -5 5 10 1 1 0 0 1
+pinlabel=GND
+T 605 45 5 10 1 1 0 6 1
+pinnumber=3
+T 400 0 5 10 0 0 0 0 1
+pinseq=3
+}
+P 400 600 700 600 1 0 0
+{
+T 400 600 5 10 0 0 0 0 1
+pintype=pwr
+T -45 595 5 10 1 1 0 0 1
+pinlabel=VCC
+T 605 645 5 10 1 1 0 6 1
+pinnumber=5
+T 400 600 5 10 0 0 0 0 1
+pinseq=4
+}
diff --git a/motors/symbols/usb-a.sym b/motors/symbols/usb-a.sym
new file mode 100644
index 0000000..b15d512
--- /dev/null
+++ b/motors/symbols/usb-a.sym
@@ -0,0 +1,65 @@
+v 20130925 2
+B 400 0 1300 1000 3 0 0 0 -1 -1 0 -1 -1 -1 -1 -1
+T 400 1000 8 10 1 1 0 0 1
+device=USB
+T 400 1000 8 10 0 1 0 0 1
+description=USB A Connector
+T 1000 1000 8 10 1 1 0 0 1
+refdes=CONN?
+T 400 800 8 10 0 1 0 0 1
+numslots=0
+P 100 800 400 800 1 0 0
+{
+T 100 800 5 10 0 0 0 0 1
+pintype=pwr
+T 455 795 5 10 1 1 0 0 1
+pinlabel=VBUS
+T 305 845 5 10 1 1 0 6 1
+pinnumber=1
+T 100 800 5 10 0 0 0 0 1
+pinseq=0
+}
+P 100 500 400 500 1 0 0
+{
+T 100 500 5 10 0 0 0 0 1
+pintype=pwr
+T 455 495 5 10 1 1 0 0 1
+pinlabel=GND
+T 305 545 5 10 1 1 0 6 1
+pinnumber=4
+T 100 500 5 10 0 0 0 0 1
+pinseq=0
+}
+P 100 200 400 200 1 0 0
+{
+T 100 200 5 10 0 0 0 0 1
+pintype=pwr
+T 455 195 5 10 1 1 0 0 1
+pinlabel=SHIELD
+T 305 245 5 10 1 1 0 6 1
+pinnumber=5
+T 100 200 5 10 0 0 0 0 1
+pinseq=0
+}
+P 2000 700 1700 700 1 0 0
+{
+T 2000 700 5 10 0 0 0 0 1
+pintype=io
+T 1645 695 5 10 1 1 0 6 1
+pinlabel=D+
+T 1795 745 5 10 1 1 0 0 1
+pinnumber=3
+T 2000 700 5 10 0 0 0 0 1
+pinseq=0
+}
+P 2000 300 1700 300 1 0 0
+{
+T 2000 300 5 10 0 0 0 0 1
+pintype=io
+T 1645 295 5 10 1 1 0 6 1
+pinlabel=D-
+T 1795 345 5 10 1 1 0 0 1
+pinnumber=2
+T 2000 300 5 10 0 0 0 0 1
+pinseq=0
+}
diff --git a/motors/uart_schematic/check_refdes.rb b/motors/uart_schematic/check_refdes.rb
new file mode 120000
index 0000000..cc807ce
--- /dev/null
+++ b/motors/uart_schematic/check_refdes.rb
@@ -0,0 +1 @@
+../big_schematic/check_refdes.rb
\ No newline at end of file
diff --git a/motors/uart_schematic/gafrc b/motors/uart_schematic/gafrc
new file mode 100644
index 0000000..c1bfff0
--- /dev/null
+++ b/motors/uart_schematic/gafrc
@@ -0,0 +1,2 @@
+(component-library "../symbols" "Custom Symbols")
+(source-library "..")
diff --git a/motors/uart_schematic/gschem_file.rb b/motors/uart_schematic/gschem_file.rb
new file mode 120000
index 0000000..9f1da4c
--- /dev/null
+++ b/motors/uart_schematic/gschem_file.rb
@@ -0,0 +1 @@
+../big_schematic/gschem_file.rb
\ No newline at end of file
diff --git a/motors/uart_schematic/gschemrc b/motors/uart_schematic/gschemrc
new file mode 100644
index 0000000..fcf437d
--- /dev/null
+++ b/motors/uart_schematic/gschemrc
@@ -0,0 +1,3 @@
+(load (string-append geda-data-path "/scheme/auto-uref.scm")) ; load the autonumbering script
+(add-hook! add-component-hook auto-uref)       ; autonumber when adding a component
+(add-hook! copy-component-hook auto-uref)      ; autonumber when copying a component
diff --git a/motors/uart_schematic/ordering.rb b/motors/uart_schematic/ordering.rb
new file mode 120000
index 0000000..48325a4
--- /dev/null
+++ b/motors/uart_schematic/ordering.rb
@@ -0,0 +1 @@
+../big_schematic/ordering.rb
\ No newline at end of file
diff --git a/motors/uart_schematic/packages b/motors/uart_schematic/packages
new file mode 120000
index 0000000..a16c405
--- /dev/null
+++ b/motors/uart_schematic/packages
@@ -0,0 +1 @@
+../packages
\ No newline at end of file
diff --git a/motors/uart_schematic/parts.rb b/motors/uart_schematic/parts.rb
new file mode 120000
index 0000000..99f7624
--- /dev/null
+++ b/motors/uart_schematic/parts.rb
@@ -0,0 +1 @@
+../big_schematic/parts.rb
\ No newline at end of file
diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart-20190115.zip b/motors/uart_schematic/shipped_files/uart-20190115/uart-20190115.zip
new file mode 100644
index 0000000..e7a7030
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart-20190115.zip
Binary files differ
diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.bottom.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.bottom.gbr
new file mode 100644
index 0000000..165825d
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.bottom.gbr
@@ -0,0 +1,1147 @@
+G04 start of page 5 for group 3 idx 3 *

+G04 Title: uart, bottom *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNBOTTOM*%

+%ADD135C,0.0380*%

+%ADD134C,0.0906*%

+%ADD133C,0.0354*%

+%ADD132C,0.0118*%

+%ADD131C,0.1285*%

+%ADD130C,0.0433*%

+%ADD129C,0.0400*%

+%ADD128C,0.0118*%

+%ADD127C,0.0350*%

+%ADD126C,0.0200*%

+%ADD125C,0.0240*%

+%ADD124C,0.0450*%

+%ADD123C,0.0360*%

+%ADD122R,0.0240X0.0240*%

+%ADD121R,0.0512X0.0512*%

+%ADD120R,0.1004X0.1004*%

+%ADD119R,0.0700X0.0700*%

+%ADD118R,0.0095X0.0095*%

+%ADD117R,0.0528X0.0528*%

+%ADD116R,0.0177X0.0177*%

+%ADD115R,0.0295X0.0295*%

+%ADD114R,0.0200X0.0200*%

+%ADD113C,0.0600*%

+%ADD112C,0.1063*%

+%ADD111C,0.0551*%

+%ADD110C,0.0256*%

+%ADD109C,0.1800*%

+%ADD108C,0.0630*%

+%ADD107C,0.0650*%

+%ADD106C,0.0001*%

+%ADD105C,0.0057*%

+%ADD104C,0.0060*%

+%ADD103C,0.0150*%

+%ADD102C,0.0100*%

+%ADD101C,0.0250*%

+G54D101*X466500Y307500D02*Y298500D01*

+X471000Y294000D02*X466500Y298500D01*

+X471000Y294000D02*X476500D01*

+X466500Y307500D02*X462500Y311500D01*

+X463500Y310500D02*X476000Y323000D01*

+X487000D01*

+X496000Y332000D01*

+X554500Y329780D02*X548000Y323280D01*

+Y318559D01*

+Y313441D02*Y308720D01*

+X554500Y302220D01*

+X528500Y329780D02*X522000Y323280D01*

+Y318559D01*

+Y313441D02*Y308720D01*

+G54D102*X516500Y325000D02*X522500Y331000D01*

+G54D101*X522000Y308720D02*X528500Y302220D01*

+G54D102*X516500Y304500D02*Y325000D01*

+G54D101*X410000Y329780D02*X403500Y323280D01*

+Y318559D01*

+Y313441D02*Y308720D01*

+X410000Y302220D01*

+X354500Y329780D02*X348000Y323280D01*

+Y318559D01*

+Y313441D02*Y308720D01*

+X354500Y302220D01*

+G54D102*X427000Y326500D02*X420000D01*

+X326224Y321776D02*X336000Y312000D01*

+X323075Y314425D02*X331000Y306500D01*

+X319925Y307075D02*X321000Y306000D01*

+G54D101*X299000Y329780D02*X292500Y323280D01*

+X243500Y329780D02*X237000Y323280D01*

+Y318559D01*

+Y313441D02*Y308720D01*

+X243500Y302220D01*

+G54D102*X288500Y330000D02*Y302500D01*

+G54D101*X292500Y323280D02*Y318559D01*

+Y313441D02*Y308720D01*

+X299000Y302220D01*

+X188000Y329780D02*X181500Y323280D01*

+Y318559D01*

+Y313441D02*Y308720D01*

+X188000Y302220D01*

+G54D103*X210000Y294000D02*X213500Y297500D01*

+Y314000D01*

+G54D102*X278000Y305500D02*X271000Y298500D01*

+X288500Y302500D02*X295500Y295500D01*

+G54D101*X658500Y283630D02*Y278500D01*

+X658000Y278000D01*

+X653500Y277500D02*Y278500D01*

+X642000Y270000D02*X656130D01*

+X658500Y272370D01*

+X649000Y277500D02*X646500Y275000D01*

+X653500Y278500D02*X650500Y281500D01*

+X647500D01*

+X644500Y278500D01*

+G54D103*X637890Y283020D02*X645020D01*

+X647500Y285500D01*

+G54D102*X640448Y285579D02*X643079D01*

+X646000Y288500D01*

+X640448Y287547D02*X642547D01*

+X646500Y291500D01*

+X646000Y288500D02*X649000D01*

+X650000Y287500D01*

+G54D103*X646500Y291441D02*X650882D01*

+X651441Y292000D01*

+G54D102*X640448Y293453D02*Y291484D01*

+X637693D01*

+X636709Y290500D01*

+X640448Y289516D02*X642016D01*

+X643000Y290500D01*

+Y294000D01*

+X650000Y287500D02*X664500D01*

+X673000Y286000D02*X667000Y292000D01*

+X656500D01*

+X664500Y287500D02*X667000Y285000D01*

+X675000Y286500D02*X664000Y297500D01*

+X667000Y303000D02*X681000Y289000D01*

+X664000Y297500D02*X656559D01*

+X675000Y286500D02*Y257000D01*

+X673000Y286000D02*Y257500D01*

+X681000Y252500D02*Y289000D01*

+X667000Y285000D02*Y257500D01*

+X675000Y257000D02*X654500Y236500D01*

+X668000Y245500D02*X674000D01*

+X681000Y252500D01*

+X654000Y238500D02*X673000Y257500D01*

+X667000D02*X651500Y242000D01*

+X635921Y297980D02*Y301421D01*

+X633953Y297980D02*Y307488D01*

+X633941Y307500D01*

+X631984Y297980D02*Y308516D01*

+X633941Y307500D02*Y312000D01*

+X631984Y308516D02*X630500Y310000D01*

+X633941Y312000D02*X633500Y312441D01*

+Y317559D02*X639500D01*

+X635921Y301421D02*X639059Y304559D01*

+Y312000D01*

+X639500Y312441D01*

+X637890Y297980D02*X637980D01*

+X643000Y294000D02*X645500Y296500D01*

+X640448Y295421D02*X643000Y297972D01*

+Y298500D01*

+X644000Y299500D01*

+X645500Y296500D02*X646500D01*

+G54D103*X650441D01*

+X651441Y297500D01*

+G54D102*X644000Y299500D02*X647559D01*

+X651059Y303000D01*

+X667000D01*

+X637980Y297980D02*X643000Y303000D01*

+X645941D01*

+X643000D02*Y306441D01*

+X644500Y307941D01*

+X639500Y312441D02*X643882D01*

+X644500Y313059D01*

+X630016Y279484D02*X632000Y277500D01*

+G54D103*Y272000D02*Y277000D01*

+X628500Y274059D02*Y276500D01*

+X627000Y278000D01*

+G54D102*X628047Y279047D02*X627000Y278000D01*

+G54D103*X628941Y268941D02*X632000Y272000D01*

+G54D102*X631984Y280016D02*X635000Y277000D01*

+X632000Y277500D02*Y277000D01*

+X635921Y281079D02*X638500Y278500D01*

+X640500D01*

+G54D101*X644500D02*X640500D01*

+G54D102*X633953Y280547D02*X640500Y274000D01*

+X635000Y277000D02*Y276000D01*

+G54D101*Y259500D01*

+X640500Y274000D02*Y271500D01*

+X642000Y270000D01*

+X646500Y275000D02*X644500D01*

+G54D103*X623000Y268941D02*X628941D01*

+G54D101*X619000Y277500D02*Y255500D01*

+X628500Y246000D01*

+G54D103*X619000Y277910D02*Y277500D01*

+G54D102*X621000Y234000D02*X623500Y236500D01*

+G54D101*X635000Y259500D02*X648500Y246000D01*

+G54D102*X623500Y236500D02*X654500D01*

+X621000Y238500D02*X654000D01*

+X651500Y242000D02*X591500D01*

+X562500Y271000D01*

+G54D101*X593500Y283500D02*Y277500D01*

+Y283500D02*X598500Y288500D01*

+X613000D01*

+G54D102*X614000D02*X613000D01*

+G54D101*X605000Y282870D02*X607130Y285000D01*

+X618000D01*

+X616500Y280500D02*X613059D01*

+X612500Y279941D01*

+G54D102*X635921Y283020D02*Y281079D01*

+X633953Y283020D02*Y280547D01*

+X631984Y283020D02*Y280016D01*

+X626079Y283020D02*Y281579D01*

+X623000Y278500D01*

+Y274059D01*

+G54D103*X624110Y283020D02*X619000Y277910D01*

+G54D102*X630016Y283020D02*Y279484D01*

+X628047Y283020D02*Y279047D01*

+G54D103*X630016Y283016D02*Y285776D01*

+X631000Y286760D01*

+G54D102*X621552Y289516D02*X617484D01*

+X616500Y290500D01*

+X621552Y287547D02*X614953D01*

+X621552Y285579D02*X618579D01*

+X618000Y285000D01*

+X620016Y291484D02*X621552D01*

+X614953Y287547D02*X614000Y288500D01*

+X617059Y294441D02*X620016Y291484D01*

+X613059Y294441D02*X617059D01*

+G54D101*X605000Y294130D02*X598630D01*

+X598000Y293500D01*

+G54D102*X596000Y306500D02*Y312500D01*

+X609000Y299941D02*X610500Y298441D01*

+Y297000D01*

+X613059Y294441D01*

+X608500Y305059D02*X613382D01*

+X613441Y305000D01*

+X614500Y299559D02*X617559D01*

+X613441Y312000D02*X616941Y315500D01*

+X621552Y293453D02*Y297948D01*

+X622000Y300500D02*Y306000D01*

+X622500Y306500D01*

+X622059Y324000D02*X622500Y323559D01*

+Y320000D01*

+X621552Y297948D02*X618559Y300941D01*

+X617559Y299559D02*X618750Y300750D01*

+X624110Y297980D02*Y298390D01*

+X622000Y300500D01*

+X626079Y301921D02*X625000Y303000D01*

+X618559Y300941D02*Y307059D01*

+X628047Y304453D02*X625500Y307000D01*

+X618559Y307059D02*X622500Y311000D01*

+X625500Y307000D02*Y312559D01*

+X622559Y315500D01*

+X628000Y308000D02*Y315941D01*

+X627000Y316941D01*

+X626079Y297980D02*Y301921D01*

+X628047Y297980D02*Y304453D01*

+X630016Y297980D02*Y305984D01*

+X616941Y315500D02*Y324441D01*

+X620500Y328000D01*

+X624500D01*

+X627000Y325500D01*

+X630016Y305984D02*X628000Y308000D01*

+X630500Y310000D02*Y321043D01*

+X632957Y323500D01*

+X627000Y322059D02*Y325500D01*

+X640043Y323500D02*Y324457D01*

+X636500Y328000D01*

+X629500D01*

+X627000Y325500D01*

+X613441Y305059D02*Y312000D01*

+X591000Y306500D02*Y310000D01*

+X589000Y312000D01*

+X563000D01*

+X561000Y310000D01*

+Y305500D01*

+Y306500D02*Y297559D01*

+X566000Y306500D02*Y297559D01*

+X566059Y297500D01*

+X559000Y340500D02*Y319000D01*

+X562000Y316000D01*

+X561000Y297500D02*Y297000D01*

+X571000Y306500D02*Y301500D01*

+X572500Y300000D01*

+Y296000D01*

+X576000Y306500D02*Y297000D01*

+X581000Y306500D02*Y298500D01*

+X586000Y306500D02*Y300500D01*

+G54D101*X679890Y374000D02*Y338610D01*

+X680500Y338000D01*

+X666110Y374000D02*Y338610D01*

+X665500Y338000D01*

+G54D103*X649500Y365000D02*X647000Y362500D01*

+Y356500D01*

+X641941D02*Y362559D01*

+G54D102*X636500Y356500D02*X641941D01*

+G54D103*Y362559D02*X639500Y365000D01*

+G54D102*X647000Y356500D02*Y352000D01*

+X646500Y351500D01*

+X629500Y365000D02*X621846Y357346D01*

+X619224D01*

+X619500Y365000D02*X616075Y361575D01*

+Y357346D01*

+X609500Y365000D02*X612925Y361575D01*

+X589000Y370500D02*X632500D01*

+X634500Y368500D01*

+Y358500D01*

+X612925Y361575D02*Y357346D01*

+X599500Y365000D02*X607154Y357346D01*

+X609776D01*

+X634500Y358500D02*X636500Y356500D01*

+G54D104*X592500Y359200D02*Y357000D01*

+X593000Y356500D01*

+X593500Y355000D02*X599500D01*

+X603500Y351000D01*

+X593000Y356500D02*X603929D01*

+X609776Y350654D01*

+X603500Y351000D02*Y349000D01*

+X605000Y347500D01*

+X598500Y344000D02*X600500Y346000D01*

+X601000Y344500D02*X600000Y343500D01*

+X605000Y347500D02*X612000D01*

+X612925Y348425D01*

+Y350654D01*

+X600500Y346000D02*X613000D01*

+X614500Y344500D02*X601000D01*

+X613000Y346000D02*X616075Y349075D01*

+X619224Y349224D02*X614500Y344500D01*

+X616075Y349075D02*Y350654D01*

+X619224D02*Y349224D01*

+G54D101*X502000Y365000D02*Y343500D01*

+X513500Y332000D01*

+G54D102*X522500Y331000D02*Y333500D01*

+X527000Y338000D01*

+Y346000D01*

+X510500Y362500D01*

+Y368500D01*

+X503500Y375500D01*

+G54D101*X578559Y369669D02*Y356677D01*

+X582890Y352346D01*

+X573441Y369669D02*Y356677D01*

+X569110Y352346D01*

+G54D102*X584300Y367000D02*X585500D01*

+G54D104*X588000Y363000D02*X584400D01*

+X584300Y363100D01*

+X588000Y359000D02*X584500D01*

+X584300Y359200D01*

+G54D102*X561000Y374000D02*Y342500D01*

+G54D104*X591000D02*Y349500D01*

+X586000Y342500D02*Y347500D01*

+X597500Y337500D02*X598500Y338500D01*

+Y344000D01*

+Y330000D02*X587500D01*

+X582500Y335000D01*

+X591000Y349500D02*X591500Y350000D01*

+X586000Y347500D02*X593500Y355000D01*

+X581000Y344500D02*X593000Y356500D01*

+G54D102*X596000Y342500D02*Y351000D01*

+G54D104*X600000Y343500D02*Y331500D01*

+X598500Y330000D01*

+G54D102*X596000Y351000D02*X595000Y352000D01*

+G54D104*X581000Y342500D02*Y344500D01*

+X578500Y337500D02*X597500D01*

+X576000Y342500D02*Y340000D01*

+X578500Y337500D01*

+X582500Y335000D02*X575500D01*

+X571000Y339500D01*

+Y342500D01*

+G54D102*X566000D02*Y347000D01*

+X564500Y348500D01*

+X561000Y342500D02*X559000Y340500D01*

+X585500Y367000D02*X589000Y370500D01*

+G54D101*X582890Y374000D02*X578559Y369669D01*

+X569110Y374000D02*X573441Y369669D01*

+G54D102*X561000Y374000D02*X566000Y379000D01*

+X585500D01*

+X589000Y375500D01*

+Y370500D01*

+X503500Y375500D02*X432500D01*

+X561000Y297559D02*X560941Y297500D01*

+X561000Y297000D02*X547000Y283000D01*

+X569000Y297500D02*X566000D01*

+X572500Y296000D02*X557500Y281000D01*

+X576000Y297000D02*X557500Y278500D01*

+X581000Y298500D02*X558500Y276000D01*

+X586000Y300500D02*X559000Y273500D01*

+X558500Y276000D02*X491500D01*

+X557500Y278500D02*X489500D01*

+X510500Y281000D02*X534500D01*

+X557500D02*X534500D01*

+X547000Y283000D02*X531500D01*

+X528500Y286000D01*

+X559000Y273500D02*X493500D01*

+X562500Y271000D02*X495000D01*

+X483000Y282500D02*X490500Y290000D01*

+X483000Y278500D02*Y282500D01*

+X490500Y290000D02*X501500D01*

+X510500Y281000D01*

+X528500Y286000D02*Y292500D01*

+X516500Y304500D01*

+X489500Y274000D02*X491500Y276000D01*

+X494500Y286500D02*X494000D01*

+X463500Y243500D03*

+X457500Y250000D02*X455000D01*

+X467500Y243500D02*Y241000D01*

+X493500Y273500D02*X463500Y243500D01*

+X449500Y240000D02*X451000D01*

+X495000Y271000D02*X467500Y243500D01*

+Y241000D02*X463000Y236500D01*

+X447000D01*

+X429000Y254500D01*

+X494000Y286500D02*X457500Y250000D01*

+X451000Y240000D02*X489500Y278500D01*

+X461000Y272000D02*X462000Y273000D01*

+X477500D01*

+X483000Y278500D01*

+G54D103*X258000Y365000D02*Y373441D01*

+X252941Y373500D02*X249500D01*

+X258000D02*Y383500D01*

+G54D102*X248000Y365000D02*X240500Y357500D01*

+G54D103*X197441Y373500D02*X194000D01*

+G54D102*X198500Y358000D02*X207000D01*

+X208925Y356075D01*

+Y353346D01*

+X194154D02*X205776D01*

+G54D103*X202500Y373500D02*Y383500D01*

+G54D102*X192500Y365000D02*Y364000D01*

+X198500Y358000D01*

+X182500Y365000D02*X194154Y353346D01*

+X215224Y346654D02*X216654D01*

+X220500Y339000D02*X230500Y349000D01*

+X219000Y341000D02*X229000Y351000D01*

+X217000Y343000D02*X227000Y353000D01*

+X216654Y346654D02*X225000Y355000D01*

+X212075Y344425D02*X213500Y343000D01*

+X219378Y357500D02*X215224Y353346D01*

+G54D103*X225500Y322000D02*X242000Y338500D01*

+X246000D01*

+X263000Y309000D02*Y338500D01*

+X274000Y314500D02*Y338500D01*

+G54D102*X230500Y349000D02*X269500D01*

+X229000Y351000D02*X273000D01*

+X212075Y346654D02*Y344425D01*

+X208925Y346654D02*Y343575D01*

+Y343500D02*Y342575D01*

+X210500Y341000D01*

+X205776Y346654D02*Y341724D01*

+X208500Y339000D01*

+X213500Y343000D02*X217000D01*

+X219000Y341000D02*X210500D01*

+X220500Y339000D02*X208500D01*

+X212000Y353500D02*Y358500D01*

+X213000Y359500D01*

+G54D103*X202500Y365000D02*Y373441D01*

+G54D102*X238000Y365000D02*X233000Y359500D01*

+X213000D01*

+X240500Y357500D02*X219378D01*

+G54D103*X424500Y365000D02*Y373441D01*

+X419441Y373500D02*X416000D01*

+X363941D02*X360500D01*

+G54D102*X414500Y365000D02*Y360000D01*

+X412500Y358000D01*

+X404500Y360500D02*X409276Y355724D01*

+X412500Y358000D02*Y351000D01*

+X409276Y355724D02*Y351346D01*

+X422500Y331500D02*X412425Y341575D01*

+Y344654D01*

+X420000Y326500D02*X409276Y337224D01*

+Y344654D01*

+X371500Y272000D02*X461000D01*

+X476000Y277500D02*X427000Y326500D01*

+G54D103*X308441Y373500D02*X305000D01*

+G54D102*X303500Y365000D02*X310500Y358000D01*

+X318500D01*

+X319925Y356575D01*

+G54D103*X313500Y365000D02*Y383500D01*

+G54D102*X319925Y356575D02*Y353346D01*

+X323000Y356500D02*Y353000D01*

+X293500Y365000D02*X305154Y353346D01*

+X269500Y349000D02*X278000Y340500D01*

+X273000Y351000D02*X280500Y343500D01*

+X289500Y353000D02*X295500Y347000D01*

+X294500Y355000D02*X304500Y345000D01*

+X305154Y353346D02*X316776D01*

+X347346D02*X326224D01*

+X342000Y358000D02*X324500D01*

+X323000Y356500D01*

+G54D103*X424500Y383500D02*X171000D01*

+G54D102*X227000Y353000D02*X289500D01*

+X225000Y355000D02*X294500D01*

+X341000Y281000D02*X336000Y286000D01*

+X326224Y346654D02*Y321776D01*

+X323075Y346654D02*Y314425D01*

+X295500Y347000D02*Y337000D01*

+X288500Y330000D01*

+X316776Y346654D02*Y291276D01*

+X304500Y345000D02*Y291000D01*

+X349000Y365000D02*X342000Y358000D01*

+X359000Y365000D02*X347346Y353346D01*

+G54D103*X369000Y365000D02*Y383500D01*

+X424500Y373500D02*Y383500D01*

+G54D102*X432500Y375500D02*X424500Y383500D01*

+G54D103*X162500Y365000D02*Y291500D01*

+X181000Y273000D01*

+X154500Y243500D02*Y367000D01*

+X171000Y383500D01*

+X205000Y314000D02*Y257750D01*

+X210000D02*Y294000D01*

+X221000Y285500D02*X215000Y279500D01*

+X220000Y257750D02*Y275500D01*

+X225500Y281000D01*

+X225000Y257750D02*Y271000D01*

+X221000Y314000D02*Y285500D01*

+X225500Y281000D02*Y322000D01*

+X225000Y271000D02*X263000Y309000D01*

+X230000Y270500D02*X274000Y314500D01*

+G54D102*X246000Y277500D02*Y270059D01*

+G54D103*X230000Y257750D02*Y270500D01*

+G54D102*X246000Y264941D02*Y261500D01*

+X271000Y298500D02*Y268000D01*

+G54D103*X181000Y273000D02*X194500D01*

+X200000Y267500D01*

+Y257750D01*

+X195000D02*X191750D01*

+X191500Y258000D01*

+X215000Y279500D02*Y257500D01*

+G54D102*Y237250D02*Y243500D01*

+G54D103*X195000Y237250D02*X191750D01*

+X191500Y237000D01*

+G54D102*X200000Y237250D02*Y231000D01*

+X205000Y237250D02*Y243500D01*

+X210000Y237250D02*Y231000D01*

+X220000Y237250D02*Y231000D01*

+X225000Y237250D02*Y243500D01*

+G54D103*X188000Y210000D02*X154500Y243500D01*

+G54D102*X404500Y365000D02*Y360500D01*

+X386000Y217500D02*Y224941D01*

+Y230059D02*Y233500D01*

+X366000Y277500D02*X371500Y272000D01*

+X476000Y217500D02*X470000Y211500D01*

+X465000D01*

+X461000Y215500D01*

+Y219000D01*

+X466000Y217500D02*X450000Y233500D01*

+X436000D01*

+X461000Y219000D02*X455500Y224500D01*

+X432500D01*

+X436000Y233500D02*X407500Y262000D01*

+X432500Y224500D02*X401500Y255500D01*

+X426000Y217500D02*X398500Y245000D01*

+X416000Y217500D02*X392000Y241500D01*

+G54D103*X386000Y217500D02*X378500Y210000D01*

+G54D102*X407500Y262000D02*X351000D01*

+X401500Y255500D02*X346000D01*

+X351000Y262000D02*X341000Y272000D01*

+Y281000D01*

+X346000Y255500D02*X331000Y270500D01*

+X336000Y312000D02*Y286000D01*

+X331000Y270500D02*Y306500D01*

+X398500Y245000D02*X343500D01*

+X392000Y241500D02*X337500D01*

+X337000Y242000D01*

+X311000Y285500D02*Y238000D01*

+X321000Y246500D02*X326000Y241500D01*

+G54D103*X378500Y210000D02*X188000D01*

+G54D102*X230000Y237250D02*X296250D01*

+X306000Y247000D01*

+X281000Y284000D02*Y268000D01*

+X346000Y217500D02*X329500Y234000D01*

+Y240500D01*

+X319925Y346654D02*Y307075D01*

+X321000Y306000D02*Y246500D01*

+X316776Y291276D02*X311000Y285500D01*

+X295500Y295500D02*Y287000D01*

+X304500Y291000D02*X301000Y287500D01*

+X278000Y340500D02*Y305500D01*

+X280500Y343500D02*Y284500D01*

+X281000Y284000D01*

+X295500Y287000D02*X291000Y282500D01*

+Y268000D01*

+X301000Y287500D02*Y268000D01*

+X306000Y247000D02*Y277500D01*

+X311000Y238000D02*X321000Y228000D01*

+Y214500D01*

+X323500Y212000D01*

+X326000Y241500D02*Y217500D01*

+X323500Y212000D02*X330500D01*

+X336000Y217500D01*

+X346000D02*X345500D01*

+X356000D02*X339000Y234500D01*

+G54D105*X666000Y313130D02*X666710Y312420D01*

+X668840D01*

+X669550Y313130D01*

+Y314550D01*

+X666000Y318100D02*X669550Y314550D01*

+X666000Y318100D02*X669550D01*

+X671254Y317390D02*X671964Y318100D01*

+X671254Y313130D02*Y317390D01*

+Y313130D02*X671964Y312420D01*

+X673384D01*

+X674094Y313130D01*

+Y317390D01*

+X673384Y318100D02*X674094Y317390D01*

+X671964Y318100D02*X673384D01*

+X671254Y316680D02*X674094Y313840D01*

+X675798Y313556D02*X676934Y312420D01*

+Y318100D01*

+X675798D02*X677928D01*

+X680342D02*X682472Y315260D01*

+Y313130D02*Y315260D01*

+X681762Y312420D02*X682472Y313130D01*

+X680342Y312420D02*X681762D01*

+X679632Y313130D02*X680342Y312420D01*

+X679632Y313130D02*Y314550D01*

+X680342Y315260D01*

+X682472D01*

+X684176Y317390D02*X684886Y318100D01*

+X684176Y313130D02*Y317390D01*

+Y313130D02*X684886Y312420D01*

+X686306D01*

+X687016Y313130D01*

+Y317390D01*

+X686306Y318100D02*X687016Y317390D01*

+X684886Y318100D02*X686306D01*

+X684176Y316680D02*X687016Y313840D01*

+X688720Y313556D02*X689856Y312420D01*

+Y318100D01*

+X688720D02*X690850D01*

+X692554Y313556D02*X693690Y312420D01*

+Y318100D01*

+X692554D02*X694684D01*

+X696388Y312420D02*X699228D01*

+X696388D02*Y315260D01*

+X697098Y314550D01*

+X698518D01*

+X699228Y315260D01*

+Y317390D01*

+X698518Y318100D02*X699228Y317390D01*

+X697098Y318100D02*X698518D01*

+X696388Y317390D02*X697098Y318100D01*

+G54D106*G36*

+X646250Y368250D02*Y361750D01*

+X652750D01*

+Y368250D01*

+X646250D01*

+G37*

+G54D107*X639500Y365000D03*

+G54D108*X666110Y374000D03*

+X679890D03*

+X666110Y352346D03*

+X679890D03*

+G54D107*X629500Y365000D03*

+X619500D03*

+G54D109*X701500Y380000D03*

+G54D110*X631000Y290500D03*

+Y286760D03*

+Y294240D03*

+X636709Y290500D03*

+X625291D03*

+G54D109*X701500Y212000D03*

+G54D107*X609500Y365000D03*

+G54D106*G36*

+X525250Y368250D02*Y361750D01*

+X531750D01*

+Y368250D01*

+X525250D01*

+G37*

+G54D107*X518500Y365000D03*

+G54D106*G36*

+X550750Y368250D02*Y361750D01*

+X557250D01*

+Y368250D01*

+X550750D01*

+G37*

+G54D107*X544000Y365000D03*

+X599500D03*

+G54D108*X569110Y374000D03*

+X582890D03*

+Y352346D03*

+X569110D03*

+G54D111*X554500Y329780D03*

+Y312063D03*

+X528500D03*

+X554500Y302220D03*

+G54D112*X543831Y290134D03*

+G54D111*X528500Y302220D03*

+G54D112*X517831Y290134D03*

+G54D111*X554500Y319937D03*

+G54D112*X543831Y341866D03*

+G54D111*X528500Y329780D03*

+Y319937D03*

+G54D112*X517831Y341866D03*

+G54D106*G36*

+X243000Y220500D02*Y214500D01*

+X249000D01*

+Y220500D01*

+X243000D01*

+G37*

+G54D113*X256000Y217500D03*

+X266000D03*

+X276000D03*

+X286000D03*

+X296000D03*

+X306000D03*

+X316000D03*

+X326000D03*

+X336000D03*

+X346000D03*

+X356000D03*

+X366000D03*

+X376000D03*

+X386000D03*

+X396000D03*

+X406000D03*

+X416000D03*

+X406000Y277500D03*

+X396000D03*

+X386000D03*

+X376000D03*

+X366000D03*

+X356000D03*

+X346000D03*

+X336000D03*

+X326000D03*

+X316000D03*

+X306000D03*

+X296000D03*

+X286000D03*

+X276000D03*

+X266000D03*

+X256000D03*

+X246000D03*

+X426000Y217500D03*

+X436000D03*

+X446000D03*

+X456000D03*

+X466000D03*

+X476000D03*

+Y277500D03*

+X466000D03*

+X456000D03*

+X446000D03*

+X436000D03*

+X426000D03*

+X416000D03*

+G54D111*X410000Y329780D03*

+G54D112*X399331Y341866D03*

+G54D111*X410000Y319937D03*

+Y312063D03*

+Y302220D03*

+G54D112*X399331Y290134D03*

+G54D106*G36*

+X447750Y368250D02*Y361750D01*

+X454250D01*

+Y368250D01*

+X447750D01*

+G37*

+G54D107*X441000Y365000D03*

+G54D106*G36*

+X421250Y368250D02*Y361750D01*

+X427750D01*

+Y368250D01*

+X421250D01*

+G37*

+G54D107*X414500Y365000D03*

+G54D106*G36*

+X473250Y368250D02*Y361750D01*

+X479750D01*

+Y368250D01*

+X473250D01*

+G37*

+G54D107*X466500Y365000D03*

+G54D106*G36*

+X498750Y368250D02*Y361750D01*

+X505250D01*

+Y368250D01*

+X498750D01*

+G37*

+G54D107*X492000Y365000D03*

+X404500D03*

+X394500D03*

+X384500D03*

+G54D106*G36*

+X365750Y368250D02*Y361750D01*

+X372250D01*

+Y368250D01*

+X365750D01*

+G37*

+G54D107*X359000Y365000D03*

+X349000D03*

+X339000D03*

+X329000D03*

+G54D111*X354500Y329780D03*

+G54D112*X343831Y341866D03*

+G54D106*G36*

+X310250Y368250D02*Y361750D01*

+X316750D01*

+Y368250D01*

+X310250D01*

+G37*

+G54D107*X303500Y365000D03*

+X293500D03*

+X283500D03*

+X273500D03*

+G54D106*G36*

+X254750Y368250D02*Y361750D01*

+X261250D01*

+Y368250D01*

+X254750D01*

+G37*

+G54D107*X248000Y365000D03*

+X238000D03*

+X228000D03*

+X218000D03*

+G54D106*G36*

+X199250Y368250D02*Y361750D01*

+X205750D01*

+Y368250D01*

+X199250D01*

+G37*

+G54D107*X192500Y365000D03*

+X182500D03*

+X172500D03*

+X162500D03*

+G54D109*X141000Y380000D03*

+G54D111*X354500Y319937D03*

+X299000D03*

+Y312063D03*

+Y302220D03*

+G54D112*X288331Y290134D03*

+G54D111*X354500Y312063D03*

+Y302220D03*

+G54D112*X343831Y290134D03*

+G54D111*X299000Y329780D03*

+G54D112*X288331Y341866D03*

+G54D111*X243500Y329780D03*

+Y319937D03*

+Y312063D03*

+Y302220D03*

+X188000D03*

+G54D112*X232831Y341866D03*

+G54D111*X188000Y329780D03*

+Y319937D03*

+Y312063D03*

+G54D112*X177331Y341866D03*

+X232831Y290134D03*

+X177331D03*

+G54D109*X141000Y212000D03*

+G54D114*X596000Y309500D02*Y303500D01*

+X591000Y309500D02*Y303500D01*

+X586000Y309500D02*Y303500D01*

+X581000Y309500D02*Y303500D01*

+X576000Y309500D02*Y303500D01*

+X571000Y309500D02*Y303500D01*

+X566000Y309500D02*Y303500D01*

+G54D115*X560941Y297992D02*Y297008D01*

+X566059Y297992D02*Y297008D01*

+G54D114*X561000Y309500D02*Y303500D01*

+G54D115*X521508Y313441D02*X522492D01*

+X547508D02*X548492D01*

+X424559Y373992D02*Y373008D01*

+X419441Y373992D02*Y373008D01*

+G54D116*X409276Y345539D02*Y343768D01*

+Y352232D02*Y350461D01*

+X412425Y352232D02*Y350461D01*

+X415575Y352232D02*Y350461D01*

+X418724Y352232D02*Y350461D01*

+X412425Y345539D02*Y343768D01*

+X415575Y345539D02*Y343768D01*

+X418724Y345539D02*Y343768D01*

+G54D115*X403008Y318559D02*X403992D01*

+X521508D02*X522492D01*

+X547508D02*X548492D01*

+X369059Y373992D02*Y373008D01*

+X363941Y373992D02*Y373008D01*

+G54D116*X205776Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X208925Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X212075Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X215224Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+G54D115*X202559Y373992D02*Y373008D01*

+X197441Y373992D02*Y373008D01*

+X403008Y313441D02*X403992D01*

+X347508D02*X348492D01*

+X292008D02*X292992D01*

+X236508D02*X237492D01*

+X347508Y318559D02*X348492D01*

+X292008D02*X292992D01*

+X236508D02*X237492D01*

+X181008D02*X181992D01*

+X181008Y313441D02*X181992D01*

+G54D116*X316776Y354232D02*Y352461D01*

+X319925Y354232D02*Y352461D01*

+X323075Y354232D02*Y352461D01*

+X326224Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X316776Y347539D02*Y345768D01*

+X319925Y347539D02*Y345768D01*

+X323075Y347539D02*Y345768D01*

+G54D115*X313659Y374092D02*Y373108D01*

+X308541Y374092D02*Y373108D01*

+X258059Y373992D02*Y373008D01*

+X252941Y373992D02*Y373008D01*

+X245508Y270059D02*X246492D01*

+X245508Y264941D02*X246492D01*

+X385508Y224941D02*X386492D01*

+X385508Y230059D02*X386492D01*

+G54D114*X230000Y240500D02*Y234000D01*

+X225000Y240500D02*Y234000D01*

+X220000Y240500D02*Y234000D01*

+X215000Y240500D02*Y234000D01*

+X210000Y240500D02*Y234000D01*

+X205000Y240500D02*Y234000D01*

+X200000Y240500D02*Y234000D01*

+X195000Y240500D02*Y234000D01*

+Y261000D02*Y254500D01*

+X200000Y261000D02*Y254500D01*

+X205000Y261000D02*Y254500D01*

+X210000Y261000D02*Y254500D01*

+X215000Y261000D02*Y254500D01*

+X220000Y261000D02*Y254500D01*

+X225000Y261000D02*Y254500D01*

+X230000Y261000D02*Y254500D01*

+G54D117*X657594Y272370D02*X659406D01*

+G54D115*X644008Y269941D02*X644992D01*

+X644008Y275059D02*X644992D01*

+X622508Y274059D02*X623492D01*

+X622508Y268941D02*X623492D01*

+X628008Y274059D02*X628992D01*

+X628008Y268941D02*X628992D01*

+X614008Y299559D02*X614992D01*

+X614008Y294441D02*X614992D01*

+X608008Y299941D02*X608992D01*

+X608008Y305059D02*X608992D01*

+X613441Y305492D02*Y304508D01*

+X616941Y315992D02*Y315008D01*

+G54D117*X604094Y294130D02*X605906D01*

+G54D115*X622059Y315992D02*Y315008D01*

+X616941Y324492D02*Y323508D01*

+X622059Y324492D02*Y323508D01*

+X612008Y285059D02*X612992D01*

+G54D117*X604094Y282870D02*X605906D01*

+G54D115*X612008Y279941D02*X612992D01*

+X618559Y305492D02*Y304508D01*

+G54D118*X624110Y298688D02*Y297272D01*

+Y283728D02*Y282312D01*

+X620843Y285579D02*X622260D01*

+X620843Y287547D02*X622260D01*

+X620843Y289516D02*X622260D01*

+X620843Y291484D02*X622260D01*

+X620843Y293453D02*X622260D01*

+X620843Y295421D02*X622260D01*

+G54D115*X651059Y303492D02*Y302508D01*

+X646008Y296559D02*X646992D01*

+G54D119*X665500Y339300D02*Y336700D01*

+X680500Y339300D02*Y336700D01*

+G54D115*X641941Y356992D02*Y356008D01*

+X647059Y356992D02*Y356008D01*

+G54D118*X626079Y298688D02*Y297272D01*

+X628047Y298688D02*Y297272D01*

+X630016Y298688D02*Y297272D01*

+X631984Y298688D02*Y297272D01*

+X633953Y298688D02*Y297272D01*

+X635921Y298688D02*Y297272D01*

+X637890Y298688D02*Y297272D01*

+X639740Y295421D02*X641157D01*

+X639740Y293453D02*X641157D01*

+X639740Y291484D02*X641157D01*

+X639740Y289516D02*X641157D01*

+X639740Y287547D02*X641157D01*

+X639740Y285579D02*X641157D01*

+X637890Y283728D02*Y282312D01*

+X635921Y283728D02*Y282312D01*

+X633953Y283728D02*Y282312D01*

+X631984Y283728D02*Y282312D01*

+X630016Y283728D02*Y282312D01*

+X628047Y283728D02*Y282312D01*

+X626079Y283728D02*Y282312D01*

+G54D120*X629032Y290500D02*X632969D01*

+G54D117*X657594Y283630D02*X659406D01*

+G54D115*X651441Y297992D02*Y297008D01*

+X656559Y297992D02*Y297008D01*

+X651441Y292492D02*Y291508D01*

+X656559Y292492D02*Y291508D01*

+X646008Y291441D02*X646992D01*

+G54D121*X640043Y323893D02*Y323107D01*

+X632957Y323893D02*Y323107D01*

+G54D115*X634941Y307992D02*Y307008D01*

+X633508Y312441D02*X634492D01*

+X633508Y317559D02*X634492D01*

+X626508Y322059D02*X627492D01*

+X626508Y316941D02*X627492D01*

+X645941Y303492D02*Y302508D01*

+X644508Y307941D02*X645492D01*

+X644508Y313059D02*X645492D01*

+X640059Y307992D02*Y307008D01*

+X639508Y317559D02*X640492D01*

+X639508Y312441D02*X640492D01*

+G54D122*X591700Y367000D02*X593300D01*

+X591700Y359200D02*X593300D01*

+X583500D02*X585100D01*

+X583500Y363100D02*X585100D01*

+X583500Y367000D02*X585100D01*

+G54D115*X573441Y366992D02*Y366008D01*

+X578559Y366992D02*Y366008D01*

+X573441Y359492D02*Y358508D01*

+X578559Y359492D02*Y358508D01*

+G54D114*X586000Y345500D02*Y339500D01*

+X591000Y345500D02*Y339500D01*

+X596000Y345500D02*Y339500D01*

+G54D116*X619224Y358232D02*Y356461D01*

+Y351539D02*Y349768D01*

+X616075Y358232D02*Y356461D01*

+Y351539D02*Y349768D01*

+X612925Y358232D02*Y356461D01*

+X609776Y358232D02*Y356461D01*

+X612925Y351539D02*Y349768D01*

+X609776Y351539D02*Y349768D01*

+G54D114*X561000Y345500D02*Y339500D01*

+X566000Y345500D02*Y339500D01*

+X571000Y345500D02*Y339500D01*

+X576000Y345500D02*Y339500D01*

+X581000Y345500D02*Y339500D01*

+G54D123*X628500Y246000D03*

+X653500Y277500D03*

+X648500Y246000D03*

+X658000Y278000D03*

+X649000Y277500D03*

+X668000Y245500D03*

+X680500Y244000D03*

+Y237500D03*

+X662500Y232000D03*

+X655000D03*

+X599500D03*

+X607500D03*

+X691500Y237500D03*

+Y244000D03*

+X686000Y231000D03*

+X598000Y293500D03*

+X569000Y297500D03*

+X575500Y285000D03*

+X621000Y234000D03*

+Y238500D03*

+X594000Y245500D03*

+G54D124*X587000Y264500D03*

+Y254500D03*

+X583000Y259500D03*

+G54D123*X562000Y316000D03*

+X532500Y288000D03*

+X593500Y277500D03*

+X627000Y278000D03*

+X616500Y280500D03*

+Y290500D03*

+X625000Y303000D03*

+X622500Y306500D03*

+X647500Y285500D03*

+X637500Y303000D03*

+X622500Y311000D03*

+Y320000D03*

+X627000Y325500D03*

+G54D124*X596000Y320000D03*

+G54D123*Y312500D03*

+X570500Y244000D03*

+X581500Y237500D03*

+Y244000D03*

+X576000Y231000D03*

+X570500Y237500D03*

+X539000Y244000D03*

+Y237500D03*

+X518500D03*

+Y244000D03*

+X513000Y231000D03*

+X507500Y237500D03*

+X550000D03*

+X544500Y231000D03*

+X550000Y244000D03*

+X507500D03*

+X449500Y313500D03*

+G54D113*X462500Y311500D03*

+X442000Y326000D03*

+G54D124*X496000Y332000D03*

+X246000Y338500D03*

+X274000D03*

+X263000D03*

+G54D123*X422500Y331500D03*

+X416000Y373500D03*

+X313500Y323500D03*

+G54D113*X513500Y332000D03*

+G54D123*X569000Y328500D03*

+G54D125*X576000Y322500D03*

+G54D124*X568500Y323500D03*

+G54D113*X563500Y334500D03*

+X554500Y339000D03*

+G54D123*X583000Y328500D03*

+G54D124*X583500Y323500D03*

+X596500Y333500D03*

+X589000D03*

+Y326000D03*

+X596500D03*

+G54D123*X573500Y348500D03*

+X564500D03*

+X578000Y349000D03*

+G54D125*X591500Y350000D03*

+G54D123*X646500Y351500D03*

+X595000Y352000D03*

+G54D125*X588000Y363000D03*

+Y359000D03*

+G54D113*X606000Y381500D03*

+X600500Y386500D03*

+X595000Y381500D03*

+X589500Y386500D03*

+G54D123*X360500Y373500D03*

+X305000D03*

+X249500D03*

+X194000D03*

+X278500Y380000D03*

+X271000Y268000D03*

+X281000D03*

+X291000D03*

+X301000D03*

+G54D124*X492500Y294000D03*

+X485000D03*

+X476500D03*

+X471000D03*

+G54D123*X494500Y286500D03*

+X415500D03*

+G54D124*X483000Y323000D03*

+G54D113*X502000Y315000D03*

+X498000Y257000D03*

+G54D123*X246000Y261500D03*

+X429000Y254500D03*

+G54D113*X498000Y264000D03*

+G54D123*X463500Y243500D03*

+X489500Y274000D03*

+X464500Y264000D03*

+X465500Y270000D03*

+X449500Y240000D03*

+X455000Y250000D03*

+G54D124*X191500Y258000D03*

+Y237000D03*

+X205000Y314000D03*

+X213500D03*

+X221000D03*

+G54D123*X386000Y233500D03*

+X376500Y306500D03*

+X225000Y243500D03*

+X215000D03*

+X205000D03*

+X220000Y231000D03*

+X210000D03*

+X200000D03*

+X329500Y240500D03*

+X339000Y234500D03*

+X337000Y242000D03*

+X343500Y245000D03*

+G54D126*G54D101*G54D126*G54D101*G54D126*G54D127*G54D101*G54D126*G54D127*G54D126*G54D128*G54D101*G54D127*G54D126*G54D101*G54D126*G54D128*G54D126*G54D128*G54D127*G54D126*G54D101*G54D126*G54D101*G54D127*G54D126*G54D127*G54D126*G54D101*G54D126*G54D129*G54D130*G54D129*G54D131*G54D132*G54D131*G54D129*G54D130*G54D133*G54D134*G54D133*G54D134*G54D133*G54D134*G54D133*G54D134*G54D135*G54D133*G54D134*G54D133*G54D134*G54D129*G54D133*G54D134*G54D129*G54D131*G54D133*G54D134*G54D133*G54D134*G54D133*G54D134*G54D133*G54D134*G54D133*G54D134*G54D131*M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.bottommask.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.bottommask.gbr
new file mode 100644
index 0000000..87209a8
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.bottommask.gbr
@@ -0,0 +1,408 @@
+G04 start of page 9 for group -4062 idx -4062 *

+G04 Title: uart, soldermask *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNBOTTOMMASK*%

+%ADD184R,0.0572X0.0572*%

+%ADD183R,0.1042X0.1042*%

+%ADD182R,0.0840X0.0840*%

+%ADD181R,0.0132X0.0132*%

+%ADD180R,0.0614X0.0614*%

+%ADD179R,0.0260X0.0260*%

+%ADD178R,0.0355X0.0355*%

+%ADD177R,0.0300X0.0300*%

+%ADD176C,0.0660*%

+%ADD175C,0.1161*%

+%ADD174C,0.0650*%

+%ADD173C,0.1850*%

+%ADD172C,0.0728*%

+%ADD171C,0.0710*%

+%ADD170C,0.0001*%

+G54D170*G36*

+X645950Y368550D02*Y361450D01*

+X653050D01*

+Y368550D01*

+X645950D01*

+G37*

+G54D171*X639500Y365000D03*

+G54D172*X666110Y374000D03*

+X679890D03*

+X666110Y352346D03*

+X679890D03*

+G54D171*X629500Y365000D03*

+X619500D03*

+G54D173*X701500Y380000D03*

+Y212000D03*

+G54D171*X609500Y365000D03*

+G54D170*G36*

+X524950Y368550D02*Y361450D01*

+X532050D01*

+Y368550D01*

+X524950D01*

+G37*

+G54D171*X518500Y365000D03*

+G54D170*G36*

+X550450Y368550D02*Y361450D01*

+X557550D01*

+Y368550D01*

+X550450D01*

+G37*

+G54D171*X544000Y365000D03*

+X599500D03*

+G54D172*X569110Y374000D03*

+X582890D03*

+Y352346D03*

+X569110D03*

+G54D174*X554500Y329780D03*

+Y312063D03*

+X528500D03*

+X554500Y302220D03*

+G54D175*X543831Y290134D03*

+G54D174*X528500Y302220D03*

+G54D175*X517831Y290134D03*

+G54D174*X554500Y319937D03*

+G54D175*X543831Y341866D03*

+G54D174*X528500Y329780D03*

+Y319937D03*

+G54D175*X517831Y341866D03*

+G54D170*G36*

+X242700Y220800D02*Y214200D01*

+X249300D01*

+Y220800D01*

+X242700D01*

+G37*

+G54D176*X256000Y217500D03*

+X266000D03*

+X276000D03*

+X286000D03*

+X296000D03*

+X306000D03*

+X316000D03*

+X326000D03*

+X336000D03*

+X346000D03*

+X356000D03*

+X366000D03*

+X376000D03*

+X386000D03*

+X396000D03*

+X406000D03*

+X416000D03*

+X406000Y277500D03*

+X396000D03*

+X386000D03*

+X376000D03*

+X366000D03*

+X356000D03*

+X346000D03*

+X336000D03*

+X326000D03*

+X316000D03*

+X306000D03*

+X296000D03*

+X286000D03*

+X276000D03*

+X266000D03*

+X256000D03*

+X246000D03*

+X426000Y217500D03*

+X436000D03*

+X446000D03*

+X456000D03*

+X466000D03*

+X476000D03*

+Y277500D03*

+X466000D03*

+X456000D03*

+X446000D03*

+X436000D03*

+X426000D03*

+X416000D03*

+G54D174*X410000Y329780D03*

+G54D175*X399331Y341866D03*

+G54D174*X410000Y319937D03*

+Y312063D03*

+Y302220D03*

+G54D175*X399331Y290134D03*

+G54D170*G36*

+X447450Y368550D02*Y361450D01*

+X454550D01*

+Y368550D01*

+X447450D01*

+G37*

+G54D171*X441000Y365000D03*

+G54D170*G36*

+X420950Y368550D02*Y361450D01*

+X428050D01*

+Y368550D01*

+X420950D01*

+G37*

+G54D171*X414500Y365000D03*

+G54D170*G36*

+X472950Y368550D02*Y361450D01*

+X480050D01*

+Y368550D01*

+X472950D01*

+G37*

+G54D171*X466500Y365000D03*

+G54D170*G36*

+X498450Y368550D02*Y361450D01*

+X505550D01*

+Y368550D01*

+X498450D01*

+G37*

+G54D171*X492000Y365000D03*

+X404500D03*

+X394500D03*

+X384500D03*

+G54D170*G36*

+X365450Y368550D02*Y361450D01*

+X372550D01*

+Y368550D01*

+X365450D01*

+G37*

+G54D171*X359000Y365000D03*

+X349000D03*

+X339000D03*

+X329000D03*

+G54D174*X354500Y329780D03*

+G54D175*X343831Y341866D03*

+G54D170*G36*

+X309950Y368550D02*Y361450D01*

+X317050D01*

+Y368550D01*

+X309950D01*

+G37*

+G54D171*X303500Y365000D03*

+X293500D03*

+X283500D03*

+X273500D03*

+G54D170*G36*

+X254450Y368550D02*Y361450D01*

+X261550D01*

+Y368550D01*

+X254450D01*

+G37*

+G54D171*X248000Y365000D03*

+X238000D03*

+X228000D03*

+X218000D03*

+G54D170*G36*

+X198950Y368550D02*Y361450D01*

+X206050D01*

+Y368550D01*

+X198950D01*

+G37*

+G54D171*X192500Y365000D03*

+X182500D03*

+X172500D03*

+X162500D03*

+G54D173*X141000Y380000D03*

+G54D174*X354500Y319937D03*

+X299000D03*

+Y312063D03*

+Y302220D03*

+G54D175*X288331Y290134D03*

+G54D174*X354500Y312063D03*

+Y302220D03*

+G54D175*X343831Y290134D03*

+G54D174*X299000Y329780D03*

+G54D175*X288331Y341866D03*

+G54D174*X243500Y329780D03*

+Y319937D03*

+Y312063D03*

+Y302220D03*

+X188000D03*

+G54D175*X232831Y341866D03*

+G54D174*X188000Y329780D03*

+Y319937D03*

+Y312063D03*

+G54D175*X177331Y341866D03*

+X232831Y290134D03*

+X177331D03*

+G54D173*X141000Y212000D03*

+G54D177*X596000Y309500D02*Y303500D01*

+X591000Y309500D02*Y303500D01*

+X586000Y309500D02*Y303500D01*

+X581000Y309500D02*Y303500D01*

+X576000Y309500D02*Y303500D01*

+X571000Y309500D02*Y303500D01*

+X566000Y309500D02*Y303500D01*

+G54D178*X560941Y297992D02*Y297008D01*

+X566059Y297992D02*Y297008D01*

+G54D177*X561000Y309500D02*Y303500D01*

+G54D178*X521508Y313441D02*X522492D01*

+X547508D02*X548492D01*

+X424559Y373992D02*Y373008D01*

+X419441Y373992D02*Y373008D01*

+G54D179*X409276Y345539D02*Y343768D01*

+Y352232D02*Y350461D01*

+X412425Y352232D02*Y350461D01*

+X415575Y352232D02*Y350461D01*

+X418724Y352232D02*Y350461D01*

+X412425Y345539D02*Y343768D01*

+X415575Y345539D02*Y343768D01*

+X418724Y345539D02*Y343768D01*

+G54D178*X403008Y318559D02*X403992D01*

+X521508D02*X522492D01*

+X547508D02*X548492D01*

+X369059Y373992D02*Y373008D01*

+X363941Y373992D02*Y373008D01*

+G54D179*X205776Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X208925Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X212075Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X215224Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+G54D178*X202559Y373992D02*Y373008D01*

+X197441Y373992D02*Y373008D01*

+X403008Y313441D02*X403992D01*

+X347508D02*X348492D01*

+X292008D02*X292992D01*

+X236508D02*X237492D01*

+X347508Y318559D02*X348492D01*

+X292008D02*X292992D01*

+X236508D02*X237492D01*

+X181008D02*X181992D01*

+X181008Y313441D02*X181992D01*

+G54D179*X316776Y354232D02*Y352461D01*

+X319925Y354232D02*Y352461D01*

+X323075Y354232D02*Y352461D01*

+X326224Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X316776Y347539D02*Y345768D01*

+X319925Y347539D02*Y345768D01*

+X323075Y347539D02*Y345768D01*

+G54D178*X313659Y374092D02*Y373108D01*

+X308541Y374092D02*Y373108D01*

+X258059Y373992D02*Y373008D01*

+X252941Y373992D02*Y373008D01*

+X245508Y270059D02*X246492D01*

+X245508Y264941D02*X246492D01*

+X385508Y224941D02*X386492D01*

+X385508Y230059D02*X386492D01*

+G54D177*X230000Y240500D02*Y234000D01*

+X225000Y240500D02*Y234000D01*

+X220000Y240500D02*Y234000D01*

+X215000Y240500D02*Y234000D01*

+X210000Y240500D02*Y234000D01*

+X205000Y240500D02*Y234000D01*

+X200000Y240500D02*Y234000D01*

+X195000Y240500D02*Y234000D01*

+Y261000D02*Y254500D01*

+X200000Y261000D02*Y254500D01*

+X205000Y261000D02*Y254500D01*

+X210000Y261000D02*Y254500D01*

+X215000Y261000D02*Y254500D01*

+X220000Y261000D02*Y254500D01*

+X225000Y261000D02*Y254500D01*

+X230000Y261000D02*Y254500D01*

+G54D180*X657594Y272370D02*X659406D01*

+G54D178*X644008Y269941D02*X644992D01*

+X644008Y275059D02*X644992D01*

+X622508Y274059D02*X623492D01*

+X622508Y268941D02*X623492D01*

+X628008Y274059D02*X628992D01*

+X628008Y268941D02*X628992D01*

+X614008Y299559D02*X614992D01*

+X614008Y294441D02*X614992D01*

+X608008Y299941D02*X608992D01*

+X608008Y305059D02*X608992D01*

+X613441Y305492D02*Y304508D01*

+X616941Y315992D02*Y315008D01*

+G54D180*X604094Y294130D02*X605906D01*

+G54D178*X622059Y315992D02*Y315008D01*

+X616941Y324492D02*Y323508D01*

+X622059Y324492D02*Y323508D01*

+X612008Y285059D02*X612992D01*

+G54D180*X604094Y282870D02*X605906D01*

+G54D178*X612008Y279941D02*X612992D01*

+X618559Y305492D02*Y304508D01*

+G54D181*X624110Y298688D02*Y297272D01*

+Y283728D02*Y282312D01*

+X620843Y285579D02*X622260D01*

+X620843Y287547D02*X622260D01*

+X620843Y289516D02*X622260D01*

+X620843Y291484D02*X622260D01*

+X620843Y293453D02*X622260D01*

+X620843Y295421D02*X622260D01*

+G54D178*X651059Y303492D02*Y302508D01*

+X646008Y296559D02*X646992D01*

+G54D182*X665500Y339300D02*Y336700D01*

+X680500Y339300D02*Y336700D01*

+G54D178*X641941Y356992D02*Y356008D01*

+X647059Y356992D02*Y356008D01*

+G54D181*X626079Y298688D02*Y297272D01*

+X628047Y298688D02*Y297272D01*

+X630016Y298688D02*Y297272D01*

+X631984Y298688D02*Y297272D01*

+X633953Y298688D02*Y297272D01*

+X635921Y298688D02*Y297272D01*

+X637890Y298688D02*Y297272D01*

+X639740Y295421D02*X641157D01*

+X639740Y293453D02*X641157D01*

+X639740Y291484D02*X641157D01*

+X639740Y289516D02*X641157D01*

+X639740Y287547D02*X641157D01*

+X639740Y285579D02*X641157D01*

+X637890Y283728D02*Y282312D01*

+X635921Y283728D02*Y282312D01*

+X633953Y283728D02*Y282312D01*

+X631984Y283728D02*Y282312D01*

+X630016Y283728D02*Y282312D01*

+X628047Y283728D02*Y282312D01*

+X626079Y283728D02*Y282312D01*

+G54D183*X629032Y290500D02*X632969D01*

+G54D180*X657594Y283630D02*X659406D01*

+G54D178*X651441Y297992D02*Y297008D01*

+X656559Y297992D02*Y297008D01*

+X651441Y292492D02*Y291508D01*

+X656559Y292492D02*Y291508D01*

+X646008Y291441D02*X646992D01*

+G54D184*X640043Y323893D02*Y323107D01*

+X632957Y323893D02*Y323107D01*

+G54D178*X634941Y307992D02*Y307008D01*

+X633508Y312441D02*X634492D01*

+X633508Y317559D02*X634492D01*

+X626508Y322059D02*X627492D01*

+X626508Y316941D02*X627492D01*

+X645941Y303492D02*Y302508D01*

+X644508Y307941D02*X645492D01*

+X644508Y313059D02*X645492D01*

+X640059Y307992D02*Y307008D01*

+X639508Y317559D02*X640492D01*

+X639508Y312441D02*X640492D01*

+G54D177*X591700Y367000D02*X593300D01*

+X591700Y359200D02*X593300D01*

+X583500D02*X585100D01*

+X583500Y363100D02*X585100D01*

+X583500Y367000D02*X585100D01*

+G54D178*X573441Y366992D02*Y366008D01*

+X578559Y366992D02*Y366008D01*

+X573441Y359492D02*Y358508D01*

+X578559Y359492D02*Y358508D01*

+G54D177*X586000Y345500D02*Y339500D01*

+X591000Y345500D02*Y339500D01*

+X596000Y345500D02*Y339500D01*

+G54D179*X619224Y358232D02*Y356461D01*

+Y351539D02*Y349768D01*

+X616075Y358232D02*Y356461D01*

+Y351539D02*Y349768D01*

+X612925Y358232D02*Y356461D01*

+X609776Y358232D02*Y356461D01*

+X612925Y351539D02*Y349768D01*

+X609776Y351539D02*Y349768D01*

+G54D177*X561000Y345500D02*Y339500D01*

+X566000Y345500D02*Y339500D01*

+X571000Y345500D02*Y339500D01*

+X576000Y345500D02*Y339500D01*

+X581000Y345500D02*Y339500D01*

+M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.bottompaste.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.bottompaste.gbr
new file mode 100644
index 0000000..71db06a
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.bottompaste.gbr
@@ -0,0 +1,199 @@
+G04 start of page 13 for group -4014 idx -4014 *

+G04 Title: uart, bottompaste *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNBOTTOMPASTE*%

+%ADD216R,0.0177X0.0177*%

+%ADD215R,0.0200X0.0200*%

+%ADD214R,0.0240X0.0240*%

+%ADD213R,0.0700X0.0700*%

+%ADD212R,0.0512X0.0512*%

+%ADD211R,0.1004X0.1004*%

+%ADD210R,0.0095X0.0095*%

+%ADD209R,0.0528X0.0528*%

+%ADD208R,0.0295X0.0295*%

+G54D208*X614008Y299559D02*X614992D01*

+X614008Y294441D02*X614992D01*

+X608008Y299941D02*X608992D01*

+X608008Y305059D02*X608992D01*

+X618559Y305492D02*Y304508D01*

+X613441Y305492D02*Y304508D01*

+X612008Y285059D02*X612992D01*

+X612008Y279941D02*X612992D01*

+G54D209*X604094Y294130D02*X605906D01*

+X604094Y282870D02*X605906D01*

+G54D208*X644008Y269941D02*X644992D01*

+X644008Y275059D02*X644992D01*

+G54D209*X657594Y283630D02*X659406D01*

+X657594Y272370D02*X659406D01*

+G54D210*X624110Y298688D02*Y297272D01*

+X626079Y298688D02*Y297272D01*

+X628047Y298688D02*Y297272D01*

+X630016Y298688D02*Y297272D01*

+X631984Y298688D02*Y297272D01*

+X633953Y298688D02*Y297272D01*

+X635921Y298688D02*Y297272D01*

+X637890Y298688D02*Y297272D01*

+X639740Y295421D02*X641157D01*

+X639740Y293453D02*X641157D01*

+X639740Y291484D02*X641157D01*

+X639740Y289516D02*X641157D01*

+X639740Y287547D02*X641157D01*

+X639740Y285579D02*X641157D01*

+X637890Y283728D02*Y282312D01*

+X635921Y283728D02*Y282312D01*

+X633953Y283728D02*Y282312D01*

+X631984Y283728D02*Y282312D01*

+X630016Y283728D02*Y282312D01*

+X628047Y283728D02*Y282312D01*

+X626079Y283728D02*Y282312D01*

+X624110Y283728D02*Y282312D01*

+X620843Y285579D02*X622260D01*

+X620843Y287547D02*X622260D01*

+X620843Y289516D02*X622260D01*

+X620843Y291484D02*X622260D01*

+X620843Y293453D02*X622260D01*

+X620843Y295421D02*X622260D01*

+G54D211*X629032Y290500D02*X632969D01*

+G54D208*X622508Y274059D02*X623492D01*

+X622508Y268941D02*X623492D01*

+X628008Y274059D02*X628992D01*

+X628008Y268941D02*X628992D01*

+X616941Y315992D02*Y315008D01*

+X622059Y315992D02*Y315008D01*

+X616941Y324492D02*Y323508D01*

+X622059Y324492D02*Y323508D01*

+X651441Y297992D02*Y297008D01*

+X656559Y297992D02*Y297008D01*

+X651441Y292492D02*Y291508D01*

+X656559Y292492D02*Y291508D01*

+X646008Y296559D02*X646992D01*

+X646008Y291441D02*X646992D01*

+X651059Y303492D02*Y302508D01*

+X645941Y303492D02*Y302508D01*

+G54D212*X640043Y323893D02*Y323107D01*

+X632957Y323893D02*Y323107D01*

+G54D208*X626508Y322059D02*X627492D01*

+X626508Y316941D02*X627492D01*

+X644508Y307941D02*X645492D01*

+X644508Y313059D02*X645492D01*

+X634941Y307992D02*Y307008D01*

+X640059Y307992D02*Y307008D01*

+X633508Y312441D02*X634492D01*

+X633508Y317559D02*X634492D01*

+X639508D02*X640492D01*

+X639508Y312441D02*X640492D01*

+X385508Y224941D02*X386492D01*

+X385508Y230059D02*X386492D01*

+X245508Y270059D02*X246492D01*

+X245508Y264941D02*X246492D01*

+G54D213*X665500Y339300D02*Y336700D01*

+X680500Y339300D02*Y336700D01*

+G54D214*X591700Y367000D02*X593300D01*

+X591700Y359200D02*X593300D01*

+X583500D02*X585100D01*

+X583500Y363100D02*X585100D01*

+X583500Y367000D02*X585100D01*

+G54D208*X641941Y356992D02*Y356008D01*

+X647059Y356992D02*Y356008D01*

+G54D215*X561000Y345500D02*Y339500D01*

+X566000Y345500D02*Y339500D01*

+X571000Y345500D02*Y339500D01*

+X576000Y345500D02*Y339500D01*

+X581000Y345500D02*Y339500D01*

+X586000Y345500D02*Y339500D01*

+X591000Y345500D02*Y339500D01*

+X596000Y345500D02*Y339500D01*

+Y309500D02*Y303500D01*

+X591000Y309500D02*Y303500D01*

+X586000Y309500D02*Y303500D01*

+X581000Y309500D02*Y303500D01*

+X576000Y309500D02*Y303500D01*

+X571000Y309500D02*Y303500D01*

+X566000Y309500D02*Y303500D01*

+X561000Y309500D02*Y303500D01*

+X230000Y240500D02*Y234000D01*

+X225000Y240500D02*Y234000D01*

+X220000Y240500D02*Y234000D01*

+X215000Y240500D02*Y234000D01*

+X210000Y240500D02*Y234000D01*

+X205000Y240500D02*Y234000D01*

+X200000Y240500D02*Y234000D01*

+X195000Y240500D02*Y234000D01*

+Y261000D02*Y254500D01*

+X200000Y261000D02*Y254500D01*

+X205000Y261000D02*Y254500D01*

+X210000Y261000D02*Y254500D01*

+X215000Y261000D02*Y254500D01*

+X220000Y261000D02*Y254500D01*

+X225000Y261000D02*Y254500D01*

+X230000Y261000D02*Y254500D01*

+G54D208*X424559Y373992D02*Y373008D01*

+X419441Y373992D02*Y373008D01*

+X369059Y373992D02*Y373008D01*

+X363941Y373992D02*Y373008D01*

+X403008Y318559D02*X403992D01*

+X403008Y313441D02*X403992D01*

+G54D216*X409276Y345539D02*Y343768D01*

+Y352232D02*Y350461D01*

+X412425Y345539D02*Y343768D01*

+Y352232D02*Y350461D01*

+X415575Y345539D02*Y343768D01*

+Y352232D02*Y350461D01*

+X418724Y345539D02*Y343768D01*

+Y352232D02*Y350461D01*

+X316776Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X319925Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X323075Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X326224Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X205776Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X208925Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X212075Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X215224Y347539D02*Y345768D01*

+Y354232D02*Y352461D01*

+X619224Y358232D02*Y356461D01*

+Y351539D02*Y349768D01*

+X616075Y358232D02*Y356461D01*

+Y351539D02*Y349768D01*

+X612925Y358232D02*Y356461D01*

+Y351539D02*Y349768D01*

+X609776Y358232D02*Y356461D01*

+Y351539D02*Y349768D01*

+G54D208*X573441Y366992D02*Y366008D01*

+X578559Y366992D02*Y366008D01*

+X573441Y359492D02*Y358508D01*

+X578559Y359492D02*Y358508D01*

+X521508Y318559D02*X522492D01*

+X521508Y313441D02*X522492D01*

+X547508Y318559D02*X548492D01*

+X547508Y313441D02*X548492D01*

+X313659Y374092D02*Y373108D01*

+X308541Y374092D02*Y373108D01*

+X258059Y373992D02*Y373008D01*

+X252941Y373992D02*Y373008D01*

+X202559Y373992D02*Y373008D01*

+X197441Y373992D02*Y373008D01*

+X347508Y318559D02*X348492D01*

+X347508Y313441D02*X348492D01*

+X292008Y318559D02*X292992D01*

+X292008Y313441D02*X292992D01*

+X236508Y318559D02*X237492D01*

+X236508Y313441D02*X237492D01*

+X181008Y318559D02*X181992D01*

+X181008Y313441D02*X181992D01*

+X560941Y297992D02*Y297008D01*

+X566059Y297992D02*Y297008D01*

+M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.bottomsilk.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.bottomsilk.gbr
new file mode 100644
index 0000000..e69267b
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.bottomsilk.gbr
@@ -0,0 +1,1364 @@
+G04 start of page 11 for group -4078 idx -4078 *

+G04 Title: uart, bottomsilk *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNBOTTOMSILK*%

+%ADD193C,0.0150*%

+%ADD192C,0.0110*%

+%ADD191C,0.0080*%

+%ADD190C,0.0100*%

+G54D190*X646500Y288500D02*X647500D01*

+X650500Y285500D01*

+X611500Y297000D02*X611000Y296500D01*

+Y292000D01*

+X643500Y318000D02*X645000D01*

+X631000Y315000D02*X629500Y313500D01*

+G54D191*X630000Y212970D02*X630490Y212480D01*

+X631960D01*

+X632450Y212970D01*

+Y213950D01*

+X630000Y216400D02*X632450Y213950D01*

+X630000Y216400D02*X632450D01*

+X633626Y215910D02*X634116Y216400D01*

+X633626Y212970D02*Y215910D01*

+Y212970D02*X634116Y212480D01*

+X635096D01*

+X635586Y212970D01*

+Y215910D01*

+X635096Y216400D02*X635586Y215910D01*

+X634116Y216400D02*X635096D01*

+X633626Y215420D02*X635586Y213460D01*

+X636762Y213264D02*X637546Y212480D01*

+Y216400D01*

+X636762D02*X638232D01*

+X639898D02*X641368Y214440D01*

+Y212970D02*Y214440D01*

+X640878Y212480D02*X641368Y212970D01*

+X639898Y212480D02*X640878D01*

+X639408Y212970D02*X639898Y212480D01*

+X639408Y212970D02*Y213950D01*

+X639898Y214440D01*

+X641368D01*

+X642544Y215910D02*X643034Y216400D01*

+X642544Y212970D02*Y215910D01*

+Y212970D02*X643034Y212480D01*

+X644014D01*

+X644504Y212970D01*

+Y215910D01*

+X644014Y216400D02*X644504Y215910D01*

+X643034Y216400D02*X644014D01*

+X642544Y215420D02*X644504Y213460D01*

+X645680Y213264D02*X646464Y212480D01*

+Y216400D01*

+X645680D02*X647150D01*

+X648326Y213264D02*X649110Y212480D01*

+Y216400D01*

+X648326D02*X649796D01*

+X650972Y212480D02*X652932D01*

+X650972D02*Y214440D01*

+X651462Y213950D01*

+X652442D01*

+X652932Y214440D01*

+Y215910D01*

+X652442Y216400D02*X652932Y215910D01*

+X651462Y216400D02*X652442D01*

+X650972Y215910D02*X651462Y216400D01*

+X632500Y218480D02*Y222400D01*

+Y218480D02*X634460D01*

+X632500Y220244D02*X633970D01*

+X635636Y218480D02*X637596D01*

+X638086Y218970D01*

+Y219950D01*

+X637596Y220440D02*X638086Y219950D01*

+X636126Y220440D02*X637596D01*

+X636126Y218480D02*Y222400D01*

+X636910Y220440D02*X638086Y222400D01*

+X639948D02*X641222D01*

+X639262Y221714D02*X639948Y222400D01*

+X639262Y219166D02*Y221714D01*

+Y219166D02*X639948Y218480D01*

+X641222D01*

+X644652Y222400D02*X646122Y220440D01*

+Y218970D02*Y220440D01*

+X645632Y218480D02*X646122Y218970D01*

+X644652Y218480D02*X645632D01*

+X644162Y218970D02*X644652Y218480D01*

+X644162Y218970D02*Y219950D01*

+X644652Y220440D01*

+X646122D01*

+X647788Y222400D02*X649748Y218480D01*

+X647298D02*X649748D01*

+X650924Y219264D02*X651708Y218480D01*

+Y222400D01*

+X650924D02*X652394D01*

+X616460Y223480D02*X616950Y223970D01*

+X614990Y223480D02*X616460D01*

+X614500Y223970D02*X614990Y223480D01*

+X614500Y223970D02*Y224950D01*

+X614990Y225440D01*

+X616460D01*

+X616950Y225930D01*

+Y226910D01*

+X616460Y227400D02*X616950Y226910D01*

+X614990Y227400D02*X616460D01*

+X614500Y226910D02*X614990Y227400D01*

+X618616Y225930D02*Y228870D01*

+X618126Y225440D02*X618616Y225930D01*

+X619106Y225440D01*

+X620086D01*

+X620576Y225930D01*

+Y226910D01*

+X620086Y227400D02*X620576Y226910D01*

+X619106Y227400D02*X620086D01*

+X618616Y226910D02*X619106Y227400D01*

+X623222Y225440D02*X623712Y225930D01*

+X622242Y225440D02*X623222D01*

+X621752Y225930D02*X622242Y225440D01*

+X621752Y225930D02*Y226910D01*

+X622242Y227400D01*

+X623712Y225440D02*Y226910D01*

+X624202Y227400D01*

+X622242D02*X623222D01*

+X623712Y226910D01*

+X625868Y225930D02*Y227400D01*

+Y225930D02*X626358Y225440D01*

+X627338D01*

+X625378D02*X625868Y225930D01*

+X629004Y223480D02*Y226910D01*

+X629494Y227400D01*

+X628514Y224950D02*X629494D01*

+X631944Y225440D02*X632434Y225930D01*

+X630964Y225440D02*X631944D01*

+X630474Y225930D02*X630964Y225440D01*

+X630474Y225930D02*Y226910D01*

+X630964Y227400D01*

+X632434Y225440D02*Y226910D01*

+X632924Y227400D01*

+X630964D02*X631944D01*

+X632434Y226910D01*

+X634590Y225930D02*Y227400D01*

+Y225930D02*X635080Y225440D01*

+X635570D01*

+X636060Y225930D01*

+Y227400D01*

+X634100Y225440D02*X634590Y225930D01*

+X639000Y223480D02*X640960D01*

+X641450Y223970D01*

+Y224950D01*

+X640960Y225440D02*X641450Y224950D01*

+X639490Y225440D02*X640960D01*

+X639490Y223480D02*Y227400D01*

+X640274Y225440D02*X641450Y227400D01*

+X642626Y225930D02*Y226910D01*

+Y225930D02*X643116Y225440D01*

+X644096D01*

+X644586Y225930D01*

+Y226910D01*

+X644096Y227400D02*X644586Y226910D01*

+X643116Y227400D02*X644096D01*

+X642626Y226910D02*X643116Y227400D01*

+X645762Y223480D02*Y227400D01*

+Y226910D02*X646252Y227400D01*

+X647232D01*

+X647722Y226910D01*

+Y225930D02*Y226910D01*

+X647232Y225440D02*X647722Y225930D01*

+X646252Y225440D02*X647232D01*

+X645762Y225930D02*X646252Y225440D01*

+X648898Y225930D02*Y226910D01*

+Y225930D02*X649388Y225440D01*

+X650368D01*

+X650858Y225930D01*

+Y226910D01*

+X650368Y227400D02*X650858Y226910D01*

+X649388Y227400D02*X650368D01*

+X648898Y226910D02*X649388Y227400D01*

+X652524Y223480D02*Y226910D01*

+X653014Y227400D01*

+X652034Y224950D02*X653014D01*

+X653994Y224460D02*Y224558D01*

+Y225930D02*Y227400D01*

+X655464Y225440D02*X656934D01*

+X654974Y225930D02*X655464Y225440D01*

+X654974Y225930D02*Y226910D01*

+X655464Y227400D01*

+X656934D01*

+X658600D02*X660070D01*

+X660560Y226910D01*

+X660070Y226420D02*X660560Y226910D01*

+X658600Y226420D02*X660070D01*

+X658110Y225930D02*X658600Y226420D01*

+X658110Y225930D02*X658600Y225440D01*

+X660070D01*

+X660560Y225930D01*

+X658110Y226910D02*X658600Y227400D01*

+X550000Y216980D02*Y220410D01*

+X550490Y220900D01*

+X551470D01*

+X551960Y220410D01*

+Y216980D02*Y220410D01*

+X553136Y217960D02*Y220900D01*

+Y217960D02*X553822Y216980D01*

+X554900D01*

+X555586Y217960D01*

+Y220900D01*

+X553136Y218940D02*X555586D01*

+X556762Y216980D02*X558722D01*

+X559212Y217470D01*

+Y218450D01*

+X558722Y218940D02*X559212Y218450D01*

+X557252Y218940D02*X558722D01*

+X557252Y216980D02*Y220900D01*

+X558036Y218940D02*X559212Y220900D01*

+X560388Y216980D02*X562348D01*

+X561368D02*Y220900D01*

+X565974D02*X567248D01*

+X565288Y220214D02*X565974Y220900D01*

+X565288Y217666D02*Y220214D01*

+Y217666D02*X565974Y216980D01*

+X567248D01*

+X569894Y218940D02*X570384Y219430D01*

+X568914Y218940D02*X569894D01*

+X568424Y219430D02*X568914Y218940D01*

+X568424Y219430D02*Y220410D01*

+X568914Y220900D01*

+X570384Y218940D02*Y220410D01*

+X570874Y220900D01*

+X568914D02*X569894D01*

+X570384Y220410D01*

+X572540Y219430D02*Y220900D01*

+Y219430D02*X573030Y218940D01*

+X573520D01*

+X574010Y219430D01*

+Y220900D01*

+Y219430D02*X574500Y218940D01*

+X574990D01*

+X575480Y219430D01*

+Y220900D01*

+X572050Y218940D02*X572540Y219430D01*

+X577146Y220900D02*X578616D01*

+X576656Y220410D02*X577146Y220900D01*

+X576656Y219430D02*Y220410D01*

+Y219430D02*X577146Y218940D01*

+X578126D01*

+X578616Y219430D01*

+X576656Y219920D02*X578616D01*

+Y219430D02*Y219920D01*

+X580282Y219430D02*Y220900D01*

+Y219430D02*X580772Y218940D01*

+X581752D01*

+X579792D02*X580282Y219430D01*

+X584398Y218940D02*X584888Y219430D01*

+X583418Y218940D02*X584398D01*

+X582928Y219430D02*X583418Y218940D01*

+X582928Y219430D02*Y220410D01*

+X583418Y220900D01*

+X584888Y218940D02*Y220410D01*

+X585378Y220900D01*

+X583418D02*X584398D01*

+X584888Y220410D01*

+X588318Y220900D02*X590278D01*

+X590768Y220410D01*

+Y219234D02*Y220410D01*

+X590278Y218744D02*X590768Y219234D01*

+X588808Y218744D02*X590278D01*

+X588808Y216980D02*Y220900D01*

+X588318Y216980D02*X590278D01*

+X590768Y217470D01*

+Y218254D01*

+X590278Y218744D02*X590768Y218254D01*

+X591944Y219430D02*Y220410D01*

+Y219430D02*X592434Y218940D01*

+X593414D01*

+X593904Y219430D01*

+Y220410D01*

+X593414Y220900D02*X593904Y220410D01*

+X592434Y220900D02*X593414D01*

+X591944Y220410D02*X592434Y220900D01*

+X596550Y218940D02*X597040Y219430D01*

+X595570Y218940D02*X596550D01*

+X595080Y219430D02*X595570Y218940D01*

+X595080Y219430D02*Y220410D01*

+X595570Y220900D01*

+X597040Y218940D02*Y220410D01*

+X597530Y220900D01*

+X595570D02*X596550D01*

+X597040Y220410D01*

+X599196Y219430D02*Y220900D01*

+Y219430D02*X599686Y218940D01*

+X600666D01*

+X598706D02*X599196Y219430D01*

+X603802Y216980D02*Y220900D01*

+X603312D02*X603802Y220410D01*

+X602332Y220900D02*X603312D01*

+X601842Y220410D02*X602332Y220900D01*

+X601842Y219430D02*Y220410D01*

+Y219430D02*X602332Y218940D01*

+X603312D01*

+X603802Y219430D01*

+G54D190*X193000Y232000D02*X232000D01*

+X193000Y263000D02*Y232000D01*

+Y263000D02*X232000D01*

+Y245000D02*Y232000D01*

+Y263000D02*Y250000D01*

+G75*G03X232000Y245000I0J-2500D01*G01*

+G54D191*X663028Y284496D02*Y271504D01*

+X653972Y284496D02*Y271504D01*

+G54D192*Y272882D03*

+X663028D03*

+G54D191*X664000Y345750D02*X682000D01*

+X664000Y330250D02*X682000D01*

+G54D193*X665500Y344500D02*Y345250D01*

+X666500Y344500D02*Y345250D01*

+X665500Y344500D02*X666500D01*

+X665500Y330750D02*Y331500D01*

+X666500Y330750D02*Y331500D01*

+X665500D02*X666500D01*

+G54D191*X609528Y294996D02*Y282004D01*

+X600472Y294996D02*Y282004D01*

+G54D192*Y283382D03*

+X609528D03*

+G54D190*X619174Y280643D02*X642826D01*

+X619174Y300357D02*Y280643D01*

+Y300357D02*X642826D01*

+Y280643D01*

+X619174Y300359D02*X617674Y301859D01*

+G54D191*X636107Y326255D02*X636893D01*

+X636107Y320745D02*X636893D01*

+G54D190*X581500Y369000D02*X595400D01*

+Y357200D01*

+X581500D02*X595400D01*

+X581500Y369000D02*Y357200D01*

+X559000Y347500D02*X598000D01*

+Y301500D01*

+X559000D02*X598000D01*

+X559000Y347500D02*Y327000D01*

+Y322000D02*Y301500D01*

+Y322000D02*G75*G03X559000Y327000I0J2500D01*G01*

+G54D191*X249650Y262550D02*Y263850D01*

+X250350Y261850D02*X249650Y262550D01*

+X250350Y261850D02*X252950D01*

+X253650Y262550D01*

+Y263850D01*

+X252850Y265050D02*X253650Y265850D01*

+X249650D02*X253650D01*

+X249650Y265050D02*Y266550D01*

+X250150Y267750D02*X249650Y268250D01*

+X250150Y267750D02*X253150D01*

+X253650Y268250D01*

+Y269250D01*

+X253150Y269750D01*

+X250150D02*X253150D01*

+X249650Y269250D02*X250150Y269750D01*

+X249650Y268250D02*Y269250D01*

+X250650Y267750D02*X252650Y269750D01*

+X252850Y270950D02*X253650Y271750D01*

+X249650D02*X253650D01*

+X249650Y270950D02*Y272450D01*

+X390150Y224550D02*Y225850D01*

+X390850Y223850D02*X390150Y224550D01*

+X390850Y223850D02*X393450D01*

+X394150Y224550D01*

+Y225850D01*

+X393350Y227050D02*X394150Y227850D01*

+X390150D02*X394150D01*

+X390150Y227050D02*Y228550D01*

+X390650Y229750D02*X390150Y230250D01*

+X390650Y229750D02*X393650D01*

+X394150Y230250D01*

+Y231250D01*

+X393650Y231750D01*

+X390650D02*X393650D01*

+X390150Y231250D02*X390650Y231750D01*

+X390150Y230250D02*Y231250D01*

+X391150Y229750D02*X393150Y231750D01*

+X393650Y232950D02*X394150Y233450D01*

+Y234950D01*

+X393650Y235450D01*

+X392650D02*X393650D01*

+X390150Y232950D02*X392650Y235450D01*

+X390150Y232950D02*Y235450D01*

+X234500Y242000D02*Y245500D01*

+X235000Y246000D01*

+X236000D01*

+X236500Y245500D01*

+Y242000D02*Y245500D01*

+X237700Y242500D02*X238200Y242000D01*

+X239200D01*

+X239700Y242500D01*

+X239200Y246000D02*X239700Y245500D01*

+X238200Y246000D02*X239200D01*

+X237700Y245500D02*X238200Y246000D01*

+Y243800D02*X239200D01*

+X239700Y242500D02*Y243300D01*

+Y244300D02*Y245500D01*

+Y244300D02*X239200Y243800D01*

+X239700Y243300D02*X239200Y243800D01*

+X240900Y245500D02*X241400Y246000D01*

+X240900Y242500D02*Y245500D01*

+Y242500D02*X241400Y242000D01*

+X242400D01*

+X242900Y242500D01*

+Y245500D01*

+X242400Y246000D02*X242900Y245500D01*

+X241400Y246000D02*X242400D01*

+X240900Y245000D02*X242900Y243000D01*

+X244100Y242500D02*X244600Y242000D01*

+X246100D01*

+X246600Y242500D01*

+Y243500D01*

+X244100Y246000D02*X246600Y243500D01*

+X244100Y246000D02*X246600D01*

+X417550Y381850D02*X418850D01*

+X416850Y381150D02*X417550Y381850D01*

+X416850Y378550D02*Y381150D01*

+Y378550D02*X417550Y377850D01*

+X418850D01*

+X420050Y378350D02*X420550Y377850D01*

+X421550D01*

+X422050Y378350D01*

+X421550Y381850D02*X422050Y381350D01*

+X420550Y381850D02*X421550D01*

+X420050Y381350D02*X420550Y381850D01*

+Y379650D02*X421550D01*

+X422050Y378350D02*Y379150D01*

+Y380150D02*Y381350D01*

+Y380150D02*X421550Y379650D01*

+X422050Y379150D02*X421550Y379650D01*

+X423250Y378650D02*X424050Y377850D01*

+Y381850D01*

+X423250D02*X424750D01*

+X426450D02*X427950Y379850D01*

+Y378350D02*Y379850D01*

+X427450Y377850D02*X427950Y378350D01*

+X426450Y377850D02*X427450D01*

+X425950Y378350D02*X426450Y377850D01*

+X425950Y378350D02*Y379350D01*

+X426450Y379850D01*

+X427950D01*

+X361050Y381850D02*X362350D01*

+X360350Y381150D02*X361050Y381850D01*

+X360350Y378550D02*Y381150D01*

+Y378550D02*X361050Y377850D01*

+X362350D01*

+X363550Y378350D02*X364050Y377850D01*

+X365050D01*

+X365550Y378350D01*

+X365050Y381850D02*X365550Y381350D01*

+X364050Y381850D02*X365050D01*

+X363550Y381350D02*X364050Y381850D01*

+Y379650D02*X365050D01*

+X365550Y378350D02*Y379150D01*

+Y380150D02*Y381350D01*

+Y380150D02*X365050Y379650D01*

+X365550Y379150D02*X365050Y379650D01*

+X366750Y378650D02*X367550Y377850D01*

+Y381850D01*

+X366750D02*X368250D01*

+X369450Y381350D02*X369950Y381850D01*

+X369450Y380550D02*Y381350D01*

+Y380550D02*X370150Y379850D01*

+X370750D01*

+X371450Y380550D01*

+Y381350D01*

+X370950Y381850D02*X371450Y381350D01*

+X369950Y381850D02*X370950D01*

+X369450Y379150D02*X370150Y379850D01*

+X369450Y378350D02*Y379150D01*

+Y378350D02*X369950Y377850D01*

+X370950D01*

+X371450Y378350D01*

+Y379150D01*

+X370750Y379850D02*X371450Y379150D01*

+X305950Y381750D02*X307250D01*

+X305250Y381050D02*X305950Y381750D01*

+X305250Y378450D02*Y381050D01*

+Y378450D02*X305950Y377750D01*

+X307250D01*

+X308450Y378250D02*X308950Y377750D01*

+X309950D01*

+X310450Y378250D01*

+X309950Y381750D02*X310450Y381250D01*

+X308950Y381750D02*X309950D01*

+X308450Y381250D02*X308950Y381750D01*

+Y379550D02*X309950D01*

+X310450Y378250D02*Y379050D01*

+Y380050D02*Y381250D01*

+Y380050D02*X309950Y379550D01*

+X310450Y379050D02*X309950Y379550D01*

+X311650Y378550D02*X312450Y377750D01*

+Y381750D01*

+X311650D02*X313150D01*

+X314850D02*X316850Y377750D01*

+X314350D02*X316850D01*

+X250550Y381850D02*X251850D01*

+X249850Y381150D02*X250550Y381850D01*

+X249850Y378550D02*Y381150D01*

+Y378550D02*X250550Y377850D01*

+X251850D01*

+X253050Y378350D02*X253550Y377850D01*

+X254550D01*

+X255050Y378350D01*

+X254550Y381850D02*X255050Y381350D01*

+X253550Y381850D02*X254550D01*

+X253050Y381350D02*X253550Y381850D01*

+Y379650D02*X254550D01*

+X255050Y378350D02*Y379150D01*

+Y380150D02*Y381350D01*

+Y380150D02*X254550Y379650D01*

+X255050Y379150D02*X254550Y379650D01*

+X256250Y378650D02*X257050Y377850D01*

+Y381850D01*

+X256250D02*X257750D01*

+X260450Y377850D02*X260950Y378350D01*

+X259450Y377850D02*X260450D01*

+X258950Y378350D02*X259450Y377850D01*

+X258950Y378350D02*Y381350D01*

+X259450Y381850D01*

+X260450Y379650D02*X260950Y380150D01*

+X258950Y379650D02*X260450D01*

+X259450Y381850D02*X260450D01*

+X260950Y381350D01*

+Y380150D02*Y381350D01*

+X193550Y381850D02*X194850D01*

+X192850Y381150D02*X193550Y381850D01*

+X192850Y378550D02*Y381150D01*

+Y378550D02*X193550Y377850D01*

+X194850D01*

+X196050Y378350D02*X196550Y377850D01*

+X197550D01*

+X198050Y378350D01*

+X197550Y381850D02*X198050Y381350D01*

+X196550Y381850D02*X197550D01*

+X196050Y381350D02*X196550Y381850D01*

+Y379650D02*X197550D01*

+X198050Y378350D02*Y379150D01*

+Y380150D02*Y381350D01*

+Y380150D02*X197550Y379650D01*

+X198050Y379150D02*X197550Y379650D01*

+X199250Y378650D02*X200050Y377850D01*

+Y381850D01*

+X199250D02*X200750D01*

+X201950Y377850D02*X203950D01*

+X201950D02*Y379850D01*

+X202450Y379350D01*

+X203450D01*

+X203950Y379850D01*

+Y381350D01*

+X203450Y381850D02*X203950Y381350D01*

+X202450Y381850D02*X203450D01*

+X201950Y381350D02*X202450Y381850D01*

+X204500Y339000D02*X206500D01*

+X207000Y339500D01*

+Y340500D01*

+X206500Y341000D02*X207000Y340500D01*

+X205000Y341000D02*X206500D01*

+X205000Y339000D02*Y343000D01*

+X205800Y341000D02*X207000Y343000D01*

+X208200Y339800D02*X209000Y339000D01*

+Y343000D01*

+X208200D02*X209700D01*

+X210900Y342500D02*X211400Y343000D01*

+X210900Y339500D02*Y342500D01*

+Y339500D02*X211400Y339000D01*

+X212400D01*

+X212900Y339500D01*

+Y342500D01*

+X212400Y343000D02*X212900Y342500D01*

+X211400Y343000D02*X212400D01*

+X210900Y342000D02*X212900Y340000D01*

+X214100Y339800D02*X214900Y339000D01*

+Y343000D01*

+X214100D02*X215600D01*

+X284650Y311550D02*Y312850D01*

+X285350Y310850D02*X284650Y311550D01*

+X285350Y310850D02*X287950D01*

+X288650Y311550D01*

+Y312850D01*

+X288150Y314050D02*X288650Y314550D01*

+Y315550D01*

+X288150Y316050D01*

+X284650Y315550D02*X285150Y316050D01*

+X284650Y314550D02*Y315550D01*

+X285150Y314050D02*X284650Y314550D01*

+X286850D02*Y315550D01*

+X287350Y316050D02*X288150D01*

+X285150D02*X286350D01*

+X286850Y315550D01*

+X287350Y316050D02*X286850Y315550D01*

+X285150Y317250D02*X284650Y317750D01*

+X285150Y317250D02*X288150D01*

+X288650Y317750D01*

+Y318750D01*

+X288150Y319250D01*

+X285150D02*X288150D01*

+X284650Y318750D02*X285150Y319250D01*

+X284650Y317750D02*Y318750D01*

+X285650Y317250D02*X287650Y319250D01*

+X285150Y320450D02*X284650Y320950D01*

+X285150Y320450D02*X285950D01*

+X286650Y321150D01*

+Y321750D01*

+X285950Y322450D01*

+X285150D02*X285950D01*

+X284650Y321950D02*X285150Y322450D01*

+X284650Y320950D02*Y321950D01*

+X287350Y320450D02*X286650Y321150D01*

+X287350Y320450D02*X288150D01*

+X288650Y320950D01*

+Y321950D01*

+X288150Y322450D01*

+X287350D02*X288150D01*

+X286650Y321750D02*X287350Y322450D01*

+X229150Y312050D02*Y313350D01*

+X229850Y311350D02*X229150Y312050D01*

+X229850Y311350D02*X232450D01*

+X233150Y312050D01*

+Y313350D01*

+X232650Y314550D02*X233150Y315050D01*

+Y316050D01*

+X232650Y316550D01*

+X229150Y316050D02*X229650Y316550D01*

+X229150Y315050D02*Y316050D01*

+X229650Y314550D02*X229150Y315050D01*

+X231350D02*Y316050D01*

+X231850Y316550D02*X232650D01*

+X229650D02*X230850D01*

+X231350Y316050D01*

+X231850Y316550D02*X231350Y316050D01*

+X229650Y317750D02*X229150Y318250D01*

+X229650Y317750D02*X232650D01*

+X233150Y318250D01*

+Y319250D01*

+X232650Y319750D01*

+X229650D02*X232650D01*

+X229150Y319250D02*X229650Y319750D01*

+X229150Y318250D02*Y319250D01*

+X230150Y317750D02*X232150Y319750D01*

+X229150Y321450D02*X233150Y323450D01*

+Y320950D02*Y323450D01*

+X173650Y311550D02*Y312850D01*

+X174350Y310850D02*X173650Y311550D01*

+X174350Y310850D02*X176950D01*

+X177650Y311550D01*

+Y312850D01*

+X177150Y314050D02*X177650Y314550D01*

+Y315550D01*

+X177150Y316050D01*

+X173650Y315550D02*X174150Y316050D01*

+X173650Y314550D02*Y315550D01*

+X174150Y314050D02*X173650Y314550D01*

+X175850D02*Y315550D01*

+X176350Y316050D02*X177150D01*

+X174150D02*X175350D01*

+X175850Y315550D01*

+X176350Y316050D02*X175850Y315550D01*

+X174150Y317250D02*X173650Y317750D01*

+X174150Y317250D02*X177150D01*

+X177650Y317750D01*

+Y318750D01*

+X177150Y319250D01*

+X174150D02*X177150D01*

+X173650Y318750D02*X174150Y319250D01*

+X173650Y317750D02*Y318750D01*

+X174650Y317250D02*X176650Y319250D01*

+X177650Y321950D02*X177150Y322450D01*

+X177650Y320950D02*Y321950D01*

+X177150Y320450D02*X177650Y320950D01*

+X174150Y320450D02*X177150D01*

+X174150D02*X173650Y320950D01*

+X175850Y321950D02*X175350Y322450D01*

+X175850Y320450D02*Y321950D01*

+X173650Y320950D02*Y321950D01*

+X174150Y322450D01*

+X175350D01*

+X558050Y293850D02*X559350D01*

+X557350Y293150D02*X558050Y293850D01*

+X557350Y290550D02*Y293150D01*

+Y290550D02*X558050Y289850D01*

+X559350D01*

+X560550Y290350D02*X561050Y289850D01*

+X562550D01*

+X563050Y290350D01*

+Y291350D01*

+X560550Y293850D02*X563050Y291350D01*

+X560550Y293850D02*X563050D01*

+X564250Y293350D02*X564750Y293850D01*

+X564250Y290350D02*Y293350D01*

+Y290350D02*X564750Y289850D01*

+X565750D01*

+X566250Y290350D01*

+Y293350D01*

+X565750Y293850D02*X566250Y293350D01*

+X564750Y293850D02*X565750D01*

+X564250Y292850D02*X566250Y290850D01*

+X567450Y290650D02*X568250Y289850D01*

+Y293850D01*

+X567450D02*X568950D01*

+X394650Y311050D02*Y312350D01*

+X395350Y310350D02*X394650Y311050D01*

+X395350Y310350D02*X397950D01*

+X398650Y311050D01*

+Y312350D01*

+X398150Y313550D02*X398650Y314050D01*

+Y315050D01*

+X398150Y315550D01*

+X394650Y315050D02*X395150Y315550D01*

+X394650Y314050D02*Y315050D01*

+X395150Y313550D02*X394650Y314050D01*

+X396850D02*Y315050D01*

+X397350Y315550D02*X398150D01*

+X395150D02*X396350D01*

+X396850Y315050D01*

+X397350Y315550D02*X396850Y315050D01*

+X397850Y316750D02*X398650Y317550D01*

+X394650D02*X398650D01*

+X394650Y316750D02*Y318250D01*

+X395150Y319450D02*X394650Y319950D01*

+X395150Y319450D02*X398150D01*

+X398650Y319950D01*

+Y320950D01*

+X398150Y321450D01*

+X395150D02*X398150D01*

+X394650Y320950D02*X395150Y321450D01*

+X394650Y319950D02*Y320950D01*

+X395650Y319450D02*X397650Y321450D01*

+X314000Y338000D02*X316000D01*

+X316500Y338500D01*

+Y339500D01*

+X316000Y340000D02*X316500Y339500D01*

+X314500Y340000D02*X316000D01*

+X314500Y338000D02*Y342000D01*

+X315300Y340000D02*X316500Y342000D01*

+X317700Y338800D02*X318500Y338000D01*

+Y342000D01*

+X317700D02*X319200D01*

+X320400Y341500D02*X320900Y342000D01*

+X320400Y338500D02*Y341500D01*

+Y338500D02*X320900Y338000D01*

+X321900D01*

+X322400Y338500D01*

+Y341500D01*

+X321900Y342000D02*X322400Y341500D01*

+X320900Y342000D02*X321900D01*

+X320400Y341000D02*X322400Y339000D01*

+X323600Y338500D02*X324100Y338000D01*

+X325600D01*

+X326100Y338500D01*

+Y339500D01*

+X323600Y342000D02*X326100Y339500D01*

+X323600Y342000D02*X326100D01*

+X339650Y311550D02*Y312850D01*

+X340350Y310850D02*X339650Y311550D01*

+X340350Y310850D02*X342950D01*

+X343650Y311550D01*

+Y312850D01*

+X343150Y314050D02*X343650Y314550D01*

+Y315550D01*

+X343150Y316050D01*

+X339650Y315550D02*X340150Y316050D01*

+X339650Y314550D02*Y315550D01*

+X340150Y314050D02*X339650Y314550D01*

+X341850D02*Y315550D01*

+X342350Y316050D02*X343150D01*

+X340150D02*X341350D01*

+X341850Y315550D01*

+X342350Y316050D02*X341850Y315550D01*

+X340150Y317250D02*X339650Y317750D01*

+X340150Y317250D02*X343150D01*

+X343650Y317750D01*

+Y318750D01*

+X343150Y319250D01*

+X340150D02*X343150D01*

+X339650Y318750D02*X340150Y319250D01*

+X339650Y317750D02*Y318750D01*

+X340650Y317250D02*X342650Y319250D01*

+X339650Y320950D02*X341650Y322450D01*

+X343150D01*

+X343650Y321950D02*X343150Y322450D01*

+X343650Y320950D02*Y321950D01*

+X343150Y320450D02*X343650Y320950D01*

+X342150Y320450D02*X343150D01*

+X342150D02*X341650Y320950D01*

+Y322450D01*

+X666000Y274500D02*Y278500D01*

+X667300Y274500D02*X668000Y275200D01*

+Y277800D01*

+X667300Y278500D02*X668000Y277800D01*

+X665500Y278500D02*X667300D01*

+X665500Y274500D02*X667300D01*

+X669200Y275000D02*X669700Y274500D01*

+X670700D01*

+X671200Y275000D01*

+X670700Y278500D02*X671200Y278000D01*

+X669700Y278500D02*X670700D01*

+X669200Y278000D02*X669700Y278500D01*

+Y276300D02*X670700D01*

+X671200Y275000D02*Y275800D01*

+Y276800D02*Y278000D01*

+Y276800D02*X670700Y276300D01*

+X671200Y275800D02*X670700Y276300D01*

+X609650Y268550D02*Y269850D01*

+X610350Y267850D02*X609650Y268550D01*

+X610350Y267850D02*X612950D01*

+X613650Y268550D01*

+Y269850D01*

+X612850Y271050D02*X613650Y271850D01*

+X609650D02*X613650D01*

+X609650Y271050D02*Y272550D01*

+X611150Y273750D02*X613650Y275750D01*

+X611150Y273750D02*Y276250D01*

+X609650Y275750D02*X613650D01*

+X594500Y284000D02*X598500D01*

+Y285300D02*X597800Y286000D01*

+X595200D02*X597800D01*

+X594500Y285300D02*X595200Y286000D01*

+X594500Y283500D02*Y285300D01*

+X598500Y283500D02*Y285300D01*

+X598000Y287200D02*X598500Y287700D01*

+Y289200D01*

+X598000Y289700D01*

+X597000D02*X598000D01*

+X594500Y287200D02*X597000Y289700D01*

+X594500Y287200D02*Y289700D01*

+X631500Y284000D02*Y287500D01*

+X632000Y288000D01*

+X633000D01*

+X633500Y287500D01*

+Y284000D02*Y287500D01*

+X634700Y284800D02*X635500Y284000D01*

+Y288000D01*

+X634700D02*X636200D01*

+X648650Y277550D02*Y278850D01*

+X649350Y276850D02*X648650Y277550D01*

+X649350Y276850D02*X651950D01*

+X652650Y277550D01*

+Y278850D01*

+X651850Y280050D02*X652650Y280850D01*

+X648650D02*X652650D01*

+X648650Y280050D02*Y281550D01*

+X652650Y284250D02*X652150Y284750D01*

+X652650Y283250D02*Y284250D01*

+X652150Y282750D02*X652650Y283250D01*

+X649150Y282750D02*X652150D01*

+X649150D02*X648650Y283250D01*

+X650850Y284250D02*X650350Y284750D01*

+X650850Y282750D02*Y284250D01*

+X648650Y283250D02*Y284250D01*

+X649150Y284750D01*

+X650350D01*

+X642150Y259550D02*Y260850D01*

+X642850Y258850D02*X642150Y259550D01*

+X642850Y258850D02*X645450D01*

+X646150Y259550D01*

+Y260850D01*

+X645350Y262050D02*X646150Y262850D01*

+X642150D02*X646150D01*

+X642150Y262050D02*Y263550D01*

+X646150Y264750D02*Y266750D01*

+X644150Y264750D02*X646150D01*

+X644150D02*X644650Y265250D01*

+Y266250D01*

+X644150Y266750D01*

+X642650D02*X644150D01*

+X642150Y266250D02*X642650Y266750D01*

+X642150Y265250D02*Y266250D01*

+X642650Y264750D02*X642150Y265250D01*

+X620150Y261050D02*Y262350D01*

+X620850Y260350D02*X620150Y261050D01*

+X620850Y260350D02*X623450D01*

+X624150Y261050D01*

+Y262350D01*

+X620150Y264050D02*X622150Y265550D01*

+X623650D01*

+X624150Y265050D02*X623650Y265550D01*

+X624150Y264050D02*Y265050D01*

+X623650Y263550D02*X624150Y264050D01*

+X622650Y263550D02*X623650D01*

+X622650D02*X622150Y264050D01*

+Y265550D01*

+X626650Y258050D02*Y259350D01*

+X627350Y257350D02*X626650Y258050D01*

+X627350Y257350D02*X629950D01*

+X630650Y258050D01*

+Y259350D01*

+X629850Y260550D02*X630650Y261350D01*

+X626650D02*X630650D01*

+X626650Y260550D02*Y262050D01*

+X630150Y263250D02*X630650Y263750D01*

+Y264750D01*

+X630150Y265250D01*

+X626650Y264750D02*X627150Y265250D01*

+X626650Y263750D02*Y264750D01*

+X627150Y263250D02*X626650Y263750D01*

+X628850D02*Y264750D01*

+X629350Y265250D02*X630150D01*

+X627150D02*X628350D01*

+X628850Y264750D01*

+X629350Y265250D02*X628850Y264750D01*

+X614380Y287350D02*Y288890D01*

+X613995Y289275D01*

+X613225D02*X613995D01*

+X612840Y288890D02*X613225Y289275D01*

+X612840Y287735D02*Y288890D01*

+X611300Y287735D02*X614380D01*

+X612840Y288351D02*X611300Y289275D01*

+X614380Y290199D02*Y291739D01*

+X612840Y290199D02*X614380D01*

+X612840D02*X613225Y290584D01*

+Y291354D01*

+X612840Y291739D01*

+X611685D02*X612840D01*

+X611300Y291354D02*X611685Y291739D01*

+X611300Y290584D02*Y291354D01*

+X611685Y290199D02*X611300Y290584D01*

+X605150Y299850D02*Y301850D01*

+X604650Y302350D01*

+X603650D02*X604650D01*

+X603150Y301850D02*X603650Y302350D01*

+X603150Y300350D02*Y301850D01*

+X601150Y300350D02*X605150D01*

+X603150Y301150D02*X601150Y302350D01*

+X604650Y303550D02*X605150Y304050D01*

+Y305050D01*

+X604650Y305550D01*

+X601150Y305050D02*X601650Y305550D01*

+X601150Y304050D02*Y305050D01*

+X601650Y303550D02*X601150Y304050D01*

+X603350D02*Y305050D01*

+X603850Y305550D02*X604650D01*

+X601650D02*X602850D01*

+X603350Y305050D01*

+X603850Y305550D02*X603350Y305050D01*

+X644550Y326350D02*X645850D01*

+X643850Y325650D02*X644550Y326350D01*

+X643850Y323050D02*Y325650D01*

+Y323050D02*X644550Y322350D01*

+X645850D01*

+X647050Y323150D02*X647850Y322350D01*

+Y326350D01*

+X647050D02*X648550D01*

+X649750Y323150D02*X650550Y322350D01*

+Y326350D01*

+X649750D02*X651250D01*

+X651890Y308850D02*Y310370D01*

+X651510Y310750D01*

+X650750D02*X651510D01*

+X650370Y310370D02*X650750Y310750D01*

+X650370Y309230D02*Y310370D01*

+X648850Y309230D02*X651890D01*

+X650370Y309838D02*X648850Y310750D01*

+X649990Y311662D02*X651890Y313182D01*

+X649990Y311662D02*Y313562D01*

+X648850Y313182D02*X651890D01*

+X645350Y316620D02*X646890D01*

+X647275Y317005D01*

+Y317775D01*

+X646890Y318160D02*X647275Y317775D01*

+X645735Y318160D02*X646890D01*

+X645735Y316620D02*Y319700D01*

+X646351Y318160D02*X647275Y319700D01*

+X648199Y317236D02*X648815Y316620D01*

+Y319700D01*

+X648199D02*X649354D01*

+X650278Y319315D02*X650663Y319700D01*

+X650278Y317005D02*Y319315D01*

+Y317005D02*X650663Y316620D01*

+X651433D01*

+X651818Y317005D01*

+Y319315D01*

+X651433Y319700D02*X651818Y319315D01*

+X650663Y319700D02*X651433D01*

+X650278Y318930D02*X651818Y317390D01*

+X615389Y311200D02*X616390D01*

+X614850Y310661D02*X615389Y311200D01*

+X614850Y308659D02*Y310661D01*

+Y308659D02*X615389Y308120D01*

+X616390D01*

+X617314Y310815D02*X617699Y311200D01*

+X617314Y310199D02*Y310815D01*

+Y310199D02*X617853Y309660D01*

+X618315D01*

+X618854Y310199D01*

+Y310815D01*

+X618469Y311200D02*X618854Y310815D01*

+X617699Y311200D02*X618469D01*

+X617314Y309121D02*X617853Y309660D01*

+X617314Y308505D02*Y309121D01*

+Y308505D02*X617699Y308120D01*

+X618469D01*

+X618854Y308505D01*

+Y309121D01*

+X618315Y309660D02*X618854Y309121D01*

+X608350Y314120D02*X609890D01*

+X610275Y314505D01*

+Y315275D01*

+X609890Y315660D02*X610275Y315275D01*

+X608735Y315660D02*X609890D01*

+X608735Y314120D02*Y317200D01*

+X609351Y315660D02*X610275Y317200D01*

+X611199Y314505D02*X611584Y314120D01*

+X612739D01*

+X613124Y314505D01*

+Y315275D01*

+X611199Y317200D02*X613124Y315275D01*

+X611199Y317200D02*X613124D01*

+X608850Y322350D02*X610850D01*

+X611350Y322850D01*

+Y323850D01*

+X610850Y324350D02*X611350Y323850D01*

+X609350Y324350D02*X610850D01*

+X609350Y322350D02*Y326350D01*

+X610150Y324350D02*X611350Y326350D01*

+X612550Y323150D02*X613350Y322350D01*

+Y326350D01*

+X612550D02*X614050D01*

+X626882Y309150D02*X627870D01*

+X626350Y308618D02*X626882Y309150D01*

+X626350Y306642D02*Y308618D01*

+Y306642D02*X626882Y306110D01*

+X627870D01*

+X628782Y306718D02*X629390Y306110D01*

+Y309150D01*

+X628782D02*X629922D01*

+X630834Y308770D02*X631214Y309150D01*

+X630834Y308162D02*Y308770D01*

+Y308162D02*X631366Y307630D01*

+X631822D01*

+X632354Y308162D01*

+Y308770D01*

+X631974Y309150D02*X632354Y308770D01*

+X631214Y309150D02*X631974D01*

+X630834Y307098D02*X631366Y307630D01*

+X630834Y306490D02*Y307098D01*

+Y306490D02*X631214Y306110D01*

+X631974D01*

+X632354Y306490D01*

+Y307098D01*

+X631822Y307630D02*X632354Y307098D01*

+X624889Y313200D02*X625890D01*

+X624350Y312661D02*X624889Y313200D01*

+X624350Y310659D02*Y312661D01*

+Y310659D02*X624889Y310120D01*

+X625890D01*

+X626814Y310736D02*X627430Y310120D01*

+Y313200D01*

+X626814D02*X627969D01*

+X629278D02*X630818Y310120D01*

+X628893D02*X630818D01*

+X660350Y295850D02*X662350D01*

+X662850Y296350D01*

+Y297350D01*

+X662350Y297850D02*X662850Y297350D01*

+X660850Y297850D02*X662350D01*

+X660850Y295850D02*Y299850D01*

+X661650Y297850D02*X662850Y299850D01*

+X664550D02*X666050Y297850D01*

+Y296350D02*Y297850D01*

+X665550Y295850D02*X666050Y296350D01*

+X664550Y295850D02*X665550D01*

+X664050Y296350D02*X664550Y295850D01*

+X664050Y296350D02*Y297350D01*

+X664550Y297850D01*

+X666050D01*

+X659850Y289850D02*X661850D01*

+X662350Y290350D01*

+Y291350D01*

+X661850Y291850D02*X662350Y291350D01*

+X660350Y291850D02*X661850D01*

+X660350Y289850D02*Y293850D01*

+X661150Y291850D02*X662350Y293850D01*

+X663550Y293350D02*X664050Y293850D01*

+X663550Y292550D02*Y293350D01*

+Y292550D02*X664250Y291850D01*

+X664850D01*

+X665550Y292550D01*

+Y293350D01*

+X665050Y293850D02*X665550Y293350D01*

+X664050Y293850D02*X665050D01*

+X663550Y291150D02*X664250Y291850D01*

+X663550Y290350D02*Y291150D01*

+Y290350D02*X664050Y289850D01*

+X665050D01*

+X665550Y290350D01*

+Y291150D01*

+X664850Y291850D02*X665550Y291150D01*

+X654350Y302850D02*X656350D01*

+X656850Y303350D01*

+Y304350D01*

+X656350Y304850D02*X656850Y304350D01*

+X654850Y304850D02*X656350D01*

+X654850Y302850D02*Y306850D01*

+X655650Y304850D02*X656850Y306850D01*

+X659550Y302850D02*X660050Y303350D01*

+X658550Y302850D02*X659550D01*

+X658050Y303350D02*X658550Y302850D01*

+X658050Y303350D02*Y306350D01*

+X658550Y306850D01*

+X659550Y304650D02*X660050Y305150D01*

+X658050Y304650D02*X659550D01*

+X658550Y306850D02*X659550D01*

+X660050Y306350D01*

+Y305150D02*Y306350D01*

+X671500Y324500D02*Y328500D01*

+X672800Y324500D02*X673500Y325200D01*

+Y327800D01*

+X672800Y328500D02*X673500Y327800D01*

+X671000Y328500D02*X672800D01*

+X671000Y324500D02*X672800D01*

+X674700Y325300D02*X675500Y324500D01*

+Y328500D01*

+X674700D02*X676200D01*

+X588500Y370000D02*Y373500D01*

+X589000Y374000D01*

+X590000D01*

+X590500Y373500D01*

+Y370000D02*Y373500D01*

+X591700Y370500D02*X592200Y370000D01*

+X593700D01*

+X594200Y370500D01*

+Y371500D01*

+X591700Y374000D02*X594200Y371500D01*

+X591700Y374000D02*X594200D01*

+X595400Y373500D02*X595900Y374000D01*

+X595400Y370500D02*Y373500D01*

+Y370500D02*X595900Y370000D01*

+X596900D01*

+X597400Y370500D01*

+Y373500D01*

+X596900Y374000D02*X597400Y373500D01*

+X595900Y374000D02*X596900D01*

+X595400Y373000D02*X597400Y371000D01*

+X598600Y370500D02*X599100Y370000D01*

+X600600D01*

+X601100Y370500D01*

+Y371500D01*

+X598600Y374000D02*X601100Y371500D01*

+X598600Y374000D02*X601100D01*

+X624650Y328550D02*Y329850D01*

+X625350Y327850D02*X624650Y328550D01*

+X625350Y327850D02*X627950D01*

+X628650Y328550D01*

+Y329850D01*

+X627850Y331050D02*X628650Y331850D01*

+X624650D02*X628650D01*

+X624650Y331050D02*Y332550D01*

+X625150Y333750D02*X624650Y334250D01*

+X625150Y333750D02*X628150D01*

+X628650Y334250D01*

+Y335250D01*

+X628150Y335750D01*

+X625150D02*X628150D01*

+X624650Y335250D02*X625150Y335750D01*

+X624650Y334250D02*Y335250D01*

+X625650Y333750D02*X627650Y335750D01*

+X631550Y352850D02*X632850D01*

+X630850Y352150D02*X631550Y352850D01*

+X630850Y349550D02*Y352150D01*

+Y349550D02*X631550Y348850D01*

+X632850D01*

+X634050Y349350D02*X634550Y348850D01*

+X636050D01*

+X636550Y349350D01*

+Y350350D01*

+X634050Y352850D02*X636550Y350350D01*

+X634050Y352850D02*X636550D01*

+X637750Y352350D02*X638250Y352850D01*

+X637750Y349350D02*Y352350D01*

+Y349350D02*X638250Y348850D01*

+X639250D01*

+X639750Y349350D01*

+Y352350D01*

+X639250Y352850D02*X639750Y352350D01*

+X638250Y352850D02*X639250D01*

+X637750Y351850D02*X639750Y349850D01*

+X640950Y349350D02*X641450Y348850D01*

+X642950D01*

+X643450Y349350D01*

+Y350350D01*

+X640950Y352850D02*X643450Y350350D01*

+X640950Y352850D02*X643450D01*

+X601000Y331000D02*Y334500D01*

+X601500Y335000D01*

+X602500D01*

+X603000Y334500D01*

+Y331000D02*Y334500D01*

+X604200Y331500D02*X604700Y331000D01*

+X606200D01*

+X606700Y331500D01*

+Y332500D01*

+X604200Y335000D02*X606700Y332500D01*

+X604200Y335000D02*X606700D01*

+X607900Y334500D02*X608400Y335000D01*

+X607900Y331500D02*Y334500D01*

+Y331500D02*X608400Y331000D01*

+X609400D01*

+X609900Y331500D01*

+Y334500D01*

+X609400Y335000D02*X609900Y334500D01*

+X608400Y335000D02*X609400D01*

+X607900Y334000D02*X609900Y332000D01*

+X611100Y331800D02*X611900Y331000D01*

+Y335000D01*

+X611100D02*X612600D01*

+X559550Y368350D02*X560850D01*

+X558850Y367650D02*X559550Y368350D01*

+X558850Y365050D02*Y367650D01*

+Y365050D02*X559550Y364350D01*

+X560850D01*

+X562050Y364850D02*X562550Y364350D01*

+X563550D01*

+X564050Y364850D01*

+X563550Y368350D02*X564050Y367850D01*

+X562550Y368350D02*X563550D01*

+X562050Y367850D02*X562550Y368350D01*

+Y366150D02*X563550D01*

+X564050Y364850D02*Y365650D01*

+Y366650D02*Y367850D01*

+Y366650D02*X563550Y366150D01*

+X564050Y365650D02*X563550Y366150D01*

+X565250Y365150D02*X566050Y364350D01*

+Y368350D01*

+X565250D02*X566750D01*

+X567950Y366850D02*X569950Y364350D01*

+X567950Y366850D02*X570450D01*

+X569950Y364350D02*Y368350D01*

+X560050Y361350D02*X561350D01*

+X559350Y360650D02*X560050Y361350D01*

+X559350Y358050D02*Y360650D01*

+Y358050D02*X560050Y357350D01*

+X561350D01*

+X562550Y357850D02*X563050Y357350D01*

+X564050D01*

+X564550Y357850D01*

+X564050Y361350D02*X564550Y360850D01*

+X563050Y361350D02*X564050D01*

+X562550Y360850D02*X563050Y361350D01*

+Y359150D02*X564050D01*

+X564550Y357850D02*Y358650D01*

+Y359650D02*Y360850D01*

+Y359650D02*X564050Y359150D01*

+X564550Y358650D02*X564050Y359150D01*

+X565750Y358150D02*X566550Y357350D01*

+Y361350D01*

+X565750D02*X567250D01*

+X568450Y357850D02*X568950Y357350D01*

+X569950D01*

+X570450Y357850D01*

+X569950Y361350D02*X570450Y360850D01*

+X568950Y361350D02*X569950D01*

+X568450Y360850D02*X568950Y361350D01*

+Y359150D02*X569950D01*

+X570450Y357850D02*Y358650D01*

+Y359650D02*Y360850D01*

+Y359650D02*X569950Y359150D01*

+X570450Y358650D02*X569950Y359150D01*

+X609000Y342500D02*X611000D01*

+X611500Y343000D01*

+Y344000D01*

+X611000Y344500D02*X611500Y344000D01*

+X609500Y344500D02*X611000D01*

+X609500Y342500D02*Y346500D01*

+X610300Y344500D02*X611500Y346500D01*

+X612700Y343000D02*X613200Y342500D01*

+X614700D01*

+X615200Y343000D01*

+Y344000D01*

+X612700Y346500D02*X615200Y344000D01*

+X612700Y346500D02*X615200D01*

+X616400Y346000D02*X616900Y346500D01*

+X616400Y343000D02*Y346000D01*

+Y343000D02*X616900Y342500D01*

+X617900D01*

+X618400Y343000D01*

+Y346000D01*

+X617900Y346500D02*X618400Y346000D01*

+X616900Y346500D02*X617900D01*

+X616400Y345500D02*X618400Y343500D01*

+X619600Y343300D02*X620400Y342500D01*

+Y346500D01*

+X619600D02*X621100D01*

+X514150Y311550D02*Y312850D01*

+X514850Y310850D02*X514150Y311550D01*

+X514850Y310850D02*X517450D01*

+X518150Y311550D01*

+Y312850D01*

+X517650Y314050D02*X518150Y314550D01*

+Y315550D01*

+X517650Y316050D01*

+X514150Y315550D02*X514650Y316050D01*

+X514150Y314550D02*Y315550D01*

+X514650Y314050D02*X514150Y314550D01*

+X516350D02*Y315550D01*

+X516850Y316050D02*X517650D01*

+X514650D02*X515850D01*

+X516350Y315550D01*

+X516850Y316050D02*X516350Y315550D01*

+X517350Y317250D02*X518150Y318050D01*

+X514150D02*X518150D01*

+X514150Y317250D02*Y318750D01*

+X517650Y319950D02*X518150Y320450D01*

+Y321950D01*

+X517650Y322450D01*

+X516650D02*X517650D01*

+X514150Y319950D02*X516650Y322450D01*

+X514150Y319950D02*Y322450D01*

+X540150Y311550D02*Y312850D01*

+X540850Y310850D02*X540150Y311550D01*

+X540850Y310850D02*X543450D01*

+X544150Y311550D01*

+Y312850D01*

+X543650Y314050D02*X544150Y314550D01*

+Y315550D01*

+X543650Y316050D01*

+X540150Y315550D02*X540650Y316050D01*

+X540150Y314550D02*Y315550D01*

+X540650Y314050D02*X540150Y314550D01*

+X542350D02*Y315550D01*

+X542850Y316050D02*X543650D01*

+X540650D02*X541850D01*

+X542350Y315550D01*

+X542850Y316050D02*X542350Y315550D01*

+X543350Y317250D02*X544150Y318050D01*

+X540150D02*X544150D01*

+X540150Y317250D02*Y318750D01*

+X543350Y319950D02*X544150Y320750D01*

+X540150D02*X544150D01*

+X540150Y319950D02*Y321450D01*

+X407500Y337000D02*X409500D01*

+X410000Y337500D01*

+Y338500D01*

+X409500Y339000D02*X410000Y338500D01*

+X408000Y339000D02*X409500D01*

+X408000Y337000D02*Y341000D01*

+X408800Y339000D02*X410000Y341000D01*

+X411200Y337800D02*X412000Y337000D01*

+Y341000D01*

+X411200D02*X412700D01*

+X413900Y340500D02*X414400Y341000D01*

+X413900Y337500D02*Y340500D01*

+Y337500D02*X414400Y337000D01*

+X415400D01*

+X415900Y337500D01*

+Y340500D01*

+X415400Y341000D02*X415900Y340500D01*

+X414400Y341000D02*X415400D01*

+X413900Y340000D02*X415900Y338000D01*

+X417100Y337500D02*X417600Y337000D01*

+X418600D01*

+X419100Y337500D01*

+X418600Y341000D02*X419100Y340500D01*

+X417600Y341000D02*X418600D01*

+X417100Y340500D02*X417600Y341000D01*

+Y338800D02*X418600D01*

+X419100Y337500D02*Y338300D01*

+Y339300D02*Y340500D01*

+Y339300D02*X418600Y338800D01*

+X419100Y338300D02*X418600Y338800D01*

+M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.fab.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.fab.gbr
new file mode 100644
index 0000000..33cff1e
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.fab.gbr
@@ -0,0 +1,2672 @@
+G04 start of page 14 for group -3984 idx -3984 *

+G04 Title: uart, fab *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNFAB*%

+%ADD220C,0.0100*%

+%ADD219C,0.0075*%

+%ADD218C,0.0060*%

+%ADD217R,0.0080X0.0080*%

+G54D217*X700700Y380000D02*G75*G03X702300Y380000I800J0D01*G01*

+G75*G03X700700Y380000I-800J0D01*G01*

+X699100D02*G75*G03X703900Y380000I2400J0D01*G01*

+G75*G03X699100Y380000I-2400J0D01*G01*

+X140200D02*G75*G03X141800Y380000I800J0D01*G01*

+G75*G03X140200Y380000I-800J0D01*G01*

+X138600D02*G75*G03X143400Y380000I2400J0D01*G01*

+G75*G03X138600Y380000I-2400J0D01*G01*

+X700700Y212000D02*G75*G03X702300Y212000I800J0D01*G01*

+G75*G03X700700Y212000I-800J0D01*G01*

+X699100D02*G75*G03X703900Y212000I2400J0D01*G01*

+G75*G03X699100Y212000I-2400J0D01*G01*

+X140200D02*G75*G03X141800Y212000I800J0D01*G01*

+G75*G03X140200Y212000I-800J0D01*G01*

+X138600D02*G75*G03X143400Y212000I2400J0D01*G01*

+G75*G03X138600Y212000I-2400J0D01*G01*

+X14200Y511250D02*G75*G03X15800Y511250I800J0D01*G01*

+G75*G03X14200Y511250I-800J0D01*G01*

+X12600D02*G75*G03X17400Y511250I2400J0D01*G01*

+G75*G03X12600Y511250I-2400J0D01*G01*

+G54D218*X135000Y513500D02*X136500Y510500D01*

+X138000Y513500D01*

+X136500Y510500D02*Y507500D01*

+X139800Y510800D02*X142050D01*

+X139800Y507500D02*X142800D01*

+X139800Y513500D02*Y507500D01*

+Y513500D02*X142800D01*

+X147600D02*X148350Y512750D01*

+X145350Y513500D02*X147600D01*

+X144600Y512750D02*X145350Y513500D01*

+X144600Y512750D02*Y511250D01*

+X145350Y510500D01*

+X147600D01*

+X148350Y509750D01*

+Y508250D01*

+X147600Y507500D02*X148350Y508250D01*

+X145350Y507500D02*X147600D01*

+X144600Y508250D02*X145350Y507500D01*

+X98000Y509750D02*X101000Y513500D01*

+X98000Y509750D02*X101750D01*

+X101000Y513500D02*Y507500D01*

+X45000Y508250D02*X45750Y507500D01*

+X45000Y512750D02*Y508250D01*

+Y512750D02*X45750Y513500D01*

+X47250D01*

+X48000Y512750D01*

+Y508250D01*

+X47250Y507500D02*X48000Y508250D01*

+X45750Y507500D02*X47250D01*

+X45000Y509000D02*X48000Y512000D01*

+X49800Y507500D02*X50550D01*

+X52350Y512300D02*X53550Y513500D01*

+Y507500D01*

+X52350D02*X54600D01*

+X56400Y512750D02*X57150Y513500D01*

+X59400D01*

+X60150Y512750D01*

+Y511250D01*

+X56400Y507500D02*X60150Y511250D01*

+X56400Y507500D02*X60150D01*

+X62700D02*X64950Y510500D01*

+Y512750D02*Y510500D01*

+X64200Y513500D02*X64950Y512750D01*

+X62700Y513500D02*X64200D01*

+X61950Y512750D02*X62700Y513500D01*

+X61950Y512750D02*Y511250D01*

+X62700Y510500D01*

+X64950D01*

+X541431Y344266D02*X546231Y339466D01*

+X541431D02*X546231Y344266D01*

+X542231Y343466D02*X545431D01*

+X542231D02*Y340266D01*

+X545431D01*

+Y343466D02*Y340266D01*

+X541431Y292534D02*X546231Y287734D01*

+X541431D02*X546231Y292534D01*

+X542231Y291734D02*X545431D01*

+X542231D02*Y288534D01*

+X545431D01*

+Y291734D02*Y288534D01*

+X515431Y344266D02*X520231Y339466D01*

+X515431D02*X520231Y344266D01*

+X516231Y343466D02*X519431D01*

+X516231D02*Y340266D01*

+X519431D01*

+Y343466D02*Y340266D01*

+X515431Y292534D02*X520231Y287734D01*

+X515431D02*X520231Y292534D01*

+X516231Y291734D02*X519431D01*

+X516231D02*Y288534D01*

+X519431D01*

+Y291734D02*Y288534D01*

+X396931Y344266D02*X401731Y339466D01*

+X396931D02*X401731Y344266D01*

+X397731Y343466D02*X400931D01*

+X397731D02*Y340266D01*

+X400931D01*

+Y343466D02*Y340266D01*

+X396931Y292534D02*X401731Y287734D01*

+X396931D02*X401731Y292534D01*

+X397731Y291734D02*X400931D01*

+X397731D02*Y288534D01*

+X400931D01*

+Y291734D02*Y288534D01*

+X341431Y344266D02*X346231Y339466D01*

+X341431D02*X346231Y344266D01*

+X342231Y343466D02*X345431D01*

+X342231D02*Y340266D01*

+X345431D01*

+Y343466D02*Y340266D01*

+X341431Y292534D02*X346231Y287734D01*

+X341431D02*X346231Y292534D01*

+X342231Y291734D02*X345431D01*

+X342231D02*Y288534D01*

+X345431D01*

+Y291734D02*Y288534D01*

+X285931Y344266D02*X290731Y339466D01*

+X285931D02*X290731Y344266D01*

+X286731Y343466D02*X289931D01*

+X286731D02*Y340266D01*

+X289931D01*

+Y343466D02*Y340266D01*

+X285931Y292534D02*X290731Y287734D01*

+X285931D02*X290731Y292534D01*

+X286731Y291734D02*X289931D01*

+X286731D02*Y288534D01*

+X289931D01*

+Y291734D02*Y288534D01*

+X230431Y344266D02*X235231Y339466D01*

+X230431D02*X235231Y344266D01*

+X231231Y343466D02*X234431D01*

+X231231D02*Y340266D01*

+X234431D01*

+Y343466D02*Y340266D01*

+X230431Y292534D02*X235231Y287734D01*

+X230431D02*X235231Y292534D01*

+X231231Y291734D02*X234431D01*

+X231231D02*Y288534D01*

+X234431D01*

+Y291734D02*Y288534D01*

+X174931Y344266D02*X179731Y339466D01*

+X174931D02*X179731Y344266D01*

+X175731Y343466D02*X178931D01*

+X175731D02*Y340266D01*

+X178931D01*

+Y343466D02*Y340266D01*

+X174931Y292534D02*X179731Y287734D01*

+X174931D02*X179731Y292534D01*

+X175731Y291734D02*X178931D01*

+X175731D02*Y288534D01*

+X178931D01*

+Y291734D02*Y288534D01*

+X12600Y528650D02*X17400Y523850D01*

+X12600D02*X17400Y528650D01*

+X13400Y527850D02*X16600D01*

+X13400D02*Y524650D01*

+X16600D01*

+Y527850D02*Y524650D01*

+X135000Y528500D02*X136500Y525500D01*

+X138000Y528500D01*

+X136500Y525500D02*Y522500D01*

+X139800Y525800D02*X142050D01*

+X139800Y522500D02*X142800D01*

+X139800Y528500D02*Y522500D01*

+Y528500D02*X142800D01*

+X147600D02*X148350Y527750D01*

+X145350Y528500D02*X147600D01*

+X144600Y527750D02*X145350Y528500D01*

+X144600Y527750D02*Y526250D01*

+X145350Y525500D01*

+X147600D01*

+X148350Y524750D01*

+Y523250D01*

+X147600Y522500D02*X148350Y523250D01*

+X145350Y522500D02*X147600D01*

+X144600Y523250D02*X145350Y522500D01*

+X98000Y527300D02*X99200Y528500D01*

+Y522500D01*

+X98000D02*X100250D01*

+X102050Y524750D02*X105050Y528500D01*

+X102050Y524750D02*X105800D01*

+X105050Y528500D02*Y522500D01*

+X45000Y523250D02*X45750Y522500D01*

+X45000Y527750D02*Y523250D01*

+Y527750D02*X45750Y528500D01*

+X47250D01*

+X48000Y527750D01*

+Y523250D01*

+X47250Y522500D02*X48000Y523250D01*

+X45750Y522500D02*X47250D01*

+X45000Y524000D02*X48000Y527000D01*

+X49800Y522500D02*X50550D01*

+X52350Y523250D02*X53100Y522500D01*

+X52350Y527750D02*Y523250D01*

+Y527750D02*X53100Y528500D01*

+X54600D01*

+X55350Y527750D01*

+Y523250D01*

+X54600Y522500D02*X55350Y523250D01*

+X53100Y522500D02*X54600D01*

+X52350Y524000D02*X55350Y527000D01*

+X57900Y522500D02*X60150Y525500D01*

+Y527750D02*Y525500D01*

+X59400Y528500D02*X60150Y527750D01*

+X57900Y528500D02*X59400D01*

+X57150Y527750D02*X57900Y528500D01*

+X57150Y527750D02*Y526250D01*

+X57900Y525500D01*

+X60150D01*

+X61950Y527300D02*X63150Y528500D01*

+Y522500D01*

+X61950D02*X64200D01*

+X666110Y377200D02*Y370800D01*

+X662910Y374000D02*X669310D01*

+X664510Y375600D02*X667710D01*

+X664510D02*Y372400D01*

+X667710D01*

+Y375600D02*Y372400D01*

+X679890Y377200D02*Y370800D01*

+X676690Y374000D02*X683090D01*

+X678290Y375600D02*X681490D01*

+X678290D02*Y372400D01*

+X681490D01*

+Y375600D02*Y372400D01*

+X666110Y355546D02*Y349146D01*

+X662910Y352346D02*X669310D01*

+X664510Y353946D02*X667710D01*

+X664510D02*Y350746D01*

+X667710D01*

+Y353946D02*Y350746D01*

+X679890Y355546D02*Y349146D01*

+X676690Y352346D02*X683090D01*

+X678290Y353946D02*X681490D01*

+X678290D02*Y350746D01*

+X681490D01*

+Y353946D02*Y350746D01*

+X569110Y377200D02*Y370800D01*

+X565910Y374000D02*X572310D01*

+X567510Y375600D02*X570710D01*

+X567510D02*Y372400D01*

+X570710D01*

+Y375600D02*Y372400D01*

+X582890Y377200D02*Y370800D01*

+X579690Y374000D02*X586090D01*

+X581290Y375600D02*X584490D01*

+X581290D02*Y372400D01*

+X584490D01*

+Y375600D02*Y372400D01*

+X569110Y355546D02*Y349146D01*

+X565910Y352346D02*X572310D01*

+X567510Y353946D02*X570710D01*

+X567510D02*Y350746D01*

+X570710D01*

+Y353946D02*Y350746D01*

+X582890Y355546D02*Y349146D01*

+X579690Y352346D02*X586090D01*

+X581290Y353946D02*X584490D01*

+X581290D02*Y350746D01*

+X584490D01*

+Y353946D02*Y350746D01*

+X15000Y544450D02*Y538050D01*

+X11800Y541250D02*X18200D01*

+X13400Y542850D02*X16600D01*

+X13400D02*Y539650D01*

+X16600D01*

+Y542850D02*Y539650D01*

+X135000Y543500D02*X136500Y540500D01*

+X138000Y543500D01*

+X136500Y540500D02*Y537500D01*

+X139800Y540800D02*X142050D01*

+X139800Y537500D02*X142800D01*

+X139800Y543500D02*Y537500D01*

+Y543500D02*X142800D01*

+X147600D02*X148350Y542750D01*

+X145350Y543500D02*X147600D01*

+X144600Y542750D02*X145350Y543500D01*

+X144600Y542750D02*Y541250D01*

+X145350Y540500D01*

+X147600D01*

+X148350Y539750D01*

+Y538250D01*

+X147600Y537500D02*X148350Y538250D01*

+X145350Y537500D02*X147600D01*

+X144600Y538250D02*X145350Y537500D01*

+X98000Y538250D02*X98750Y537500D01*

+X98000Y539450D02*Y538250D01*

+Y539450D02*X99050Y540500D01*

+X99950D01*

+X101000Y539450D01*

+Y538250D01*

+X100250Y537500D02*X101000Y538250D01*

+X98750Y537500D02*X100250D01*

+X98000Y541550D02*X99050Y540500D01*

+X98000Y542750D02*Y541550D01*

+Y542750D02*X98750Y543500D01*

+X100250D01*

+X101000Y542750D01*

+Y541550D01*

+X99950Y540500D02*X101000Y541550D01*

+X45000Y538250D02*X45750Y537500D01*

+X45000Y542750D02*Y538250D01*

+Y542750D02*X45750Y543500D01*

+X47250D01*

+X48000Y542750D01*

+Y538250D01*

+X47250Y537500D02*X48000Y538250D01*

+X45750Y537500D02*X47250D01*

+X45000Y539000D02*X48000Y542000D01*

+X49800Y537500D02*X50550D01*

+X52350Y538250D02*X53100Y537500D01*

+X52350Y542750D02*Y538250D01*

+Y542750D02*X53100Y543500D01*

+X54600D01*

+X55350Y542750D01*

+Y538250D01*

+X54600Y537500D02*X55350Y538250D01*

+X53100Y537500D02*X54600D01*

+X52350Y539000D02*X55350Y542000D01*

+X57150Y539750D02*X60150Y543500D01*

+X57150Y539750D02*X60900D01*

+X60150Y543500D02*Y537500D01*

+X62700Y542750D02*X63450Y543500D01*

+X64950D01*

+X65700Y542750D01*

+X64950Y537500D02*X65700Y538250D01*

+X63450Y537500D02*X64950D01*

+X62700Y538250D02*X63450Y537500D01*

+Y540800D02*X64950D01*

+X65700Y542750D02*Y541550D01*

+Y540050D02*Y538250D01*

+Y540050D02*X64950Y540800D01*

+X65700Y541550D02*X64950Y540800D01*

+X649500Y365000D02*Y361800D01*

+Y365000D02*X652273Y366600D01*

+X649500Y365000D02*X646727Y366600D01*

+X647900Y365000D02*G75*G03X651100Y365000I1600J0D01*G01*

+G75*G03X647900Y365000I-1600J0D01*G01*

+X639500D02*Y361800D01*

+Y365000D02*X642273Y366600D01*

+X639500Y365000D02*X636727Y366600D01*

+X637900Y365000D02*G75*G03X641100Y365000I1600J0D01*G01*

+G75*G03X637900Y365000I-1600J0D01*G01*

+X629500D02*Y361800D01*

+Y365000D02*X632273Y366600D01*

+X629500Y365000D02*X626727Y366600D01*

+X627900Y365000D02*G75*G03X631100Y365000I1600J0D01*G01*

+G75*G03X627900Y365000I-1600J0D01*G01*

+X619500D02*Y361800D01*

+Y365000D02*X622273Y366600D01*

+X619500Y365000D02*X616727Y366600D01*

+X617900Y365000D02*G75*G03X621100Y365000I1600J0D01*G01*

+G75*G03X617900Y365000I-1600J0D01*G01*

+X609500D02*Y361800D01*

+Y365000D02*X612273Y366600D01*

+X609500Y365000D02*X606727Y366600D01*

+X607900Y365000D02*G75*G03X611100Y365000I1600J0D01*G01*

+G75*G03X607900Y365000I-1600J0D01*G01*

+X599500D02*Y361800D01*

+Y365000D02*X602273Y366600D01*

+X599500Y365000D02*X596727Y366600D01*

+X597900Y365000D02*G75*G03X601100Y365000I1600J0D01*G01*

+G75*G03X597900Y365000I-1600J0D01*G01*

+X528500D02*Y361800D01*

+Y365000D02*X531273Y366600D01*

+X528500Y365000D02*X525727Y366600D01*

+X526900Y365000D02*G75*G03X530100Y365000I1600J0D01*G01*

+G75*G03X526900Y365000I-1600J0D01*G01*

+X518500D02*Y361800D01*

+Y365000D02*X521273Y366600D01*

+X518500Y365000D02*X515727Y366600D01*

+X516900Y365000D02*G75*G03X520100Y365000I1600J0D01*G01*

+G75*G03X516900Y365000I-1600J0D01*G01*

+X554000D02*Y361800D01*

+Y365000D02*X556773Y366600D01*

+X554000Y365000D02*X551227Y366600D01*

+X552400Y365000D02*G75*G03X555600Y365000I1600J0D01*G01*

+G75*G03X552400Y365000I-1600J0D01*G01*

+X544000D02*Y361800D01*

+Y365000D02*X546773Y366600D01*

+X544000Y365000D02*X541227Y366600D01*

+X542400Y365000D02*G75*G03X545600Y365000I1600J0D01*G01*

+G75*G03X542400Y365000I-1600J0D01*G01*

+X451000D02*Y361800D01*

+Y365000D02*X453773Y366600D01*

+X451000Y365000D02*X448227Y366600D01*

+X449400Y365000D02*G75*G03X452600Y365000I1600J0D01*G01*

+G75*G03X449400Y365000I-1600J0D01*G01*

+X441000D02*Y361800D01*

+Y365000D02*X443773Y366600D01*

+X441000Y365000D02*X438227Y366600D01*

+X439400Y365000D02*G75*G03X442600Y365000I1600J0D01*G01*

+G75*G03X439400Y365000I-1600J0D01*G01*

+X476500D02*Y361800D01*

+Y365000D02*X479273Y366600D01*

+X476500Y365000D02*X473727Y366600D01*

+X474900Y365000D02*G75*G03X478100Y365000I1600J0D01*G01*

+G75*G03X474900Y365000I-1600J0D01*G01*

+X466500D02*Y361800D01*

+Y365000D02*X469273Y366600D01*

+X466500Y365000D02*X463727Y366600D01*

+X464900Y365000D02*G75*G03X468100Y365000I1600J0D01*G01*

+G75*G03X464900Y365000I-1600J0D01*G01*

+X502000D02*Y361800D01*

+Y365000D02*X504773Y366600D01*

+X502000Y365000D02*X499227Y366600D01*

+X500400Y365000D02*G75*G03X503600Y365000I1600J0D01*G01*

+G75*G03X500400Y365000I-1600J0D01*G01*

+X492000D02*Y361800D01*

+Y365000D02*X494773Y366600D01*

+X492000Y365000D02*X489227Y366600D01*

+X490400Y365000D02*G75*G03X493600Y365000I1600J0D01*G01*

+G75*G03X490400Y365000I-1600J0D01*G01*

+X424500D02*Y361800D01*

+Y365000D02*X427273Y366600D01*

+X424500Y365000D02*X421727Y366600D01*

+X422900Y365000D02*G75*G03X426100Y365000I1600J0D01*G01*

+G75*G03X422900Y365000I-1600J0D01*G01*

+X414500D02*Y361800D01*

+Y365000D02*X417273Y366600D01*

+X414500Y365000D02*X411727Y366600D01*

+X412900Y365000D02*G75*G03X416100Y365000I1600J0D01*G01*

+G75*G03X412900Y365000I-1600J0D01*G01*

+X404500D02*Y361800D01*

+Y365000D02*X407273Y366600D01*

+X404500Y365000D02*X401727Y366600D01*

+X402900Y365000D02*G75*G03X406100Y365000I1600J0D01*G01*

+G75*G03X402900Y365000I-1600J0D01*G01*

+X394500D02*Y361800D01*

+Y365000D02*X397273Y366600D01*

+X394500Y365000D02*X391727Y366600D01*

+X392900Y365000D02*G75*G03X396100Y365000I1600J0D01*G01*

+G75*G03X392900Y365000I-1600J0D01*G01*

+X384500D02*Y361800D01*

+Y365000D02*X387273Y366600D01*

+X384500Y365000D02*X381727Y366600D01*

+X382900Y365000D02*G75*G03X386100Y365000I1600J0D01*G01*

+G75*G03X382900Y365000I-1600J0D01*G01*

+X369000D02*Y361800D01*

+Y365000D02*X371773Y366600D01*

+X369000Y365000D02*X366227Y366600D01*

+X367400Y365000D02*G75*G03X370600Y365000I1600J0D01*G01*

+G75*G03X367400Y365000I-1600J0D01*G01*

+X359000D02*Y361800D01*

+Y365000D02*X361773Y366600D01*

+X359000Y365000D02*X356227Y366600D01*

+X357400Y365000D02*G75*G03X360600Y365000I1600J0D01*G01*

+G75*G03X357400Y365000I-1600J0D01*G01*

+X349000D02*Y361800D01*

+Y365000D02*X351773Y366600D01*

+X349000Y365000D02*X346227Y366600D01*

+X347400Y365000D02*G75*G03X350600Y365000I1600J0D01*G01*

+G75*G03X347400Y365000I-1600J0D01*G01*

+X339000D02*Y361800D01*

+Y365000D02*X341773Y366600D01*

+X339000Y365000D02*X336227Y366600D01*

+X337400Y365000D02*G75*G03X340600Y365000I1600J0D01*G01*

+G75*G03X337400Y365000I-1600J0D01*G01*

+X329000D02*Y361800D01*

+Y365000D02*X331773Y366600D01*

+X329000Y365000D02*X326227Y366600D01*

+X327400Y365000D02*G75*G03X330600Y365000I1600J0D01*G01*

+G75*G03X327400Y365000I-1600J0D01*G01*

+X313500D02*Y361800D01*

+Y365000D02*X316273Y366600D01*

+X313500Y365000D02*X310727Y366600D01*

+X311900Y365000D02*G75*G03X315100Y365000I1600J0D01*G01*

+G75*G03X311900Y365000I-1600J0D01*G01*

+X303500D02*Y361800D01*

+Y365000D02*X306273Y366600D01*

+X303500Y365000D02*X300727Y366600D01*

+X301900Y365000D02*G75*G03X305100Y365000I1600J0D01*G01*

+G75*G03X301900Y365000I-1600J0D01*G01*

+X293500D02*Y361800D01*

+Y365000D02*X296273Y366600D01*

+X293500Y365000D02*X290727Y366600D01*

+X291900Y365000D02*G75*G03X295100Y365000I1600J0D01*G01*

+G75*G03X291900Y365000I-1600J0D01*G01*

+X283500D02*Y361800D01*

+Y365000D02*X286273Y366600D01*

+X283500Y365000D02*X280727Y366600D01*

+X281900Y365000D02*G75*G03X285100Y365000I1600J0D01*G01*

+G75*G03X281900Y365000I-1600J0D01*G01*

+X273500D02*Y361800D01*

+Y365000D02*X276273Y366600D01*

+X273500Y365000D02*X270727Y366600D01*

+X271900Y365000D02*G75*G03X275100Y365000I1600J0D01*G01*

+G75*G03X271900Y365000I-1600J0D01*G01*

+X258000D02*Y361800D01*

+Y365000D02*X260773Y366600D01*

+X258000Y365000D02*X255227Y366600D01*

+X256400Y365000D02*G75*G03X259600Y365000I1600J0D01*G01*

+G75*G03X256400Y365000I-1600J0D01*G01*

+X248000D02*Y361800D01*

+Y365000D02*X250773Y366600D01*

+X248000Y365000D02*X245227Y366600D01*

+X246400Y365000D02*G75*G03X249600Y365000I1600J0D01*G01*

+G75*G03X246400Y365000I-1600J0D01*G01*

+X238000D02*Y361800D01*

+Y365000D02*X240773Y366600D01*

+X238000Y365000D02*X235227Y366600D01*

+X236400Y365000D02*G75*G03X239600Y365000I1600J0D01*G01*

+G75*G03X236400Y365000I-1600J0D01*G01*

+X228000D02*Y361800D01*

+Y365000D02*X230773Y366600D01*

+X228000Y365000D02*X225227Y366600D01*

+X226400Y365000D02*G75*G03X229600Y365000I1600J0D01*G01*

+G75*G03X226400Y365000I-1600J0D01*G01*

+X218000D02*Y361800D01*

+Y365000D02*X220773Y366600D01*

+X218000Y365000D02*X215227Y366600D01*

+X216400Y365000D02*G75*G03X219600Y365000I1600J0D01*G01*

+G75*G03X216400Y365000I-1600J0D01*G01*

+X202500D02*Y361800D01*

+Y365000D02*X205273Y366600D01*

+X202500Y365000D02*X199727Y366600D01*

+X200900Y365000D02*G75*G03X204100Y365000I1600J0D01*G01*

+G75*G03X200900Y365000I-1600J0D01*G01*

+X192500D02*Y361800D01*

+Y365000D02*X195273Y366600D01*

+X192500Y365000D02*X189727Y366600D01*

+X190900Y365000D02*G75*G03X194100Y365000I1600J0D01*G01*

+G75*G03X190900Y365000I-1600J0D01*G01*

+X182500D02*Y361800D01*

+Y365000D02*X185273Y366600D01*

+X182500Y365000D02*X179727Y366600D01*

+X180900Y365000D02*G75*G03X184100Y365000I1600J0D01*G01*

+G75*G03X180900Y365000I-1600J0D01*G01*

+X172500D02*Y361800D01*

+Y365000D02*X175273Y366600D01*

+X172500Y365000D02*X169727Y366600D01*

+X170900Y365000D02*G75*G03X174100Y365000I1600J0D01*G01*

+G75*G03X170900Y365000I-1600J0D01*G01*

+X162500D02*Y361800D01*

+Y365000D02*X165273Y366600D01*

+X162500Y365000D02*X159727Y366600D01*

+X160900Y365000D02*G75*G03X164100Y365000I1600J0D01*G01*

+G75*G03X160900Y365000I-1600J0D01*G01*

+X15000Y556250D02*Y553050D01*

+Y556250D02*X17773Y557850D01*

+X15000Y556250D02*X12227Y557850D01*

+X13400Y556250D02*G75*G03X16600Y556250I1600J0D01*G01*

+G75*G03X13400Y556250I-1600J0D01*G01*

+X135000Y558500D02*X136500Y555500D01*

+X138000Y558500D01*

+X136500Y555500D02*Y552500D01*

+X139800Y555800D02*X142050D01*

+X139800Y552500D02*X142800D01*

+X139800Y558500D02*Y552500D01*

+Y558500D02*X142800D01*

+X147600D02*X148350Y557750D01*

+X145350Y558500D02*X147600D01*

+X144600Y557750D02*X145350Y558500D01*

+X144600Y557750D02*Y556250D01*

+X145350Y555500D01*

+X147600D01*

+X148350Y554750D01*

+Y553250D01*

+X147600Y552500D02*X148350Y553250D01*

+X145350Y552500D02*X147600D01*

+X144600Y553250D02*X145350Y552500D01*

+X98000Y554750D02*X101000Y558500D01*

+X98000Y554750D02*X101750D01*

+X101000Y558500D02*Y552500D01*

+X103550Y557300D02*X104750Y558500D01*

+Y552500D01*

+X103550D02*X105800D01*

+X45000Y553250D02*X45750Y552500D01*

+X45000Y557750D02*Y553250D01*

+Y557750D02*X45750Y558500D01*

+X47250D01*

+X48000Y557750D01*

+Y553250D01*

+X47250Y552500D02*X48000Y553250D01*

+X45750Y552500D02*X47250D01*

+X45000Y554000D02*X48000Y557000D01*

+X49800Y552500D02*X50550D01*

+X52350Y553250D02*X53100Y552500D01*

+X52350Y557750D02*Y553250D01*

+Y557750D02*X53100Y558500D01*

+X54600D01*

+X55350Y557750D01*

+Y553250D01*

+X54600Y552500D02*X55350Y553250D01*

+X53100Y552500D02*X54600D01*

+X52350Y554000D02*X55350Y557000D01*

+X57150Y554750D02*X60150Y558500D01*

+X57150Y554750D02*X60900D01*

+X60150Y558500D02*Y552500D01*

+X62700Y553250D02*X63450Y552500D01*

+X62700Y557750D02*Y553250D01*

+Y557750D02*X63450Y558500D01*

+X64950D01*

+X65700Y557750D01*

+Y553250D01*

+X64950Y552500D02*X65700Y553250D01*

+X63450Y552500D02*X64950D01*

+X62700Y554000D02*X65700Y557000D01*

+X244400Y219100D02*X247600D01*

+X244400D02*Y215900D01*

+X247600D01*

+Y219100D02*Y215900D01*

+X254400Y219100D02*X257600D01*

+X254400D02*Y215900D01*

+X257600D01*

+Y219100D02*Y215900D01*

+X264400Y219100D02*X267600D01*

+X264400D02*Y215900D01*

+X267600D01*

+Y219100D02*Y215900D01*

+X274400Y219100D02*X277600D01*

+X274400D02*Y215900D01*

+X277600D01*

+Y219100D02*Y215900D01*

+X284400Y219100D02*X287600D01*

+X284400D02*Y215900D01*

+X287600D01*

+Y219100D02*Y215900D01*

+X294400Y219100D02*X297600D01*

+X294400D02*Y215900D01*

+X297600D01*

+Y219100D02*Y215900D01*

+X304400Y219100D02*X307600D01*

+X304400D02*Y215900D01*

+X307600D01*

+Y219100D02*Y215900D01*

+X314400Y219100D02*X317600D01*

+X314400D02*Y215900D01*

+X317600D01*

+Y219100D02*Y215900D01*

+X324400Y219100D02*X327600D01*

+X324400D02*Y215900D01*

+X327600D01*

+Y219100D02*Y215900D01*

+X334400Y219100D02*X337600D01*

+X334400D02*Y215900D01*

+X337600D01*

+Y219100D02*Y215900D01*

+X344400Y219100D02*X347600D01*

+X344400D02*Y215900D01*

+X347600D01*

+Y219100D02*Y215900D01*

+X354400Y219100D02*X357600D01*

+X354400D02*Y215900D01*

+X357600D01*

+Y219100D02*Y215900D01*

+X364400Y219100D02*X367600D01*

+X364400D02*Y215900D01*

+X367600D01*

+Y219100D02*Y215900D01*

+X374400Y219100D02*X377600D01*

+X374400D02*Y215900D01*

+X377600D01*

+Y219100D02*Y215900D01*

+X384400Y219100D02*X387600D01*

+X384400D02*Y215900D01*

+X387600D01*

+Y219100D02*Y215900D01*

+X394400Y219100D02*X397600D01*

+X394400D02*Y215900D01*

+X397600D01*

+Y219100D02*Y215900D01*

+X404400Y219100D02*X407600D01*

+X404400D02*Y215900D01*

+X407600D01*

+Y219100D02*Y215900D01*

+X414400Y219100D02*X417600D01*

+X414400D02*Y215900D01*

+X417600D01*

+Y219100D02*Y215900D01*

+X424400Y219100D02*X427600D01*

+X424400D02*Y215900D01*

+X427600D01*

+Y219100D02*Y215900D01*

+X434400Y219100D02*X437600D01*

+X434400D02*Y215900D01*

+X437600D01*

+Y219100D02*Y215900D01*

+X444400Y219100D02*X447600D01*

+X444400D02*Y215900D01*

+X447600D01*

+Y219100D02*Y215900D01*

+X454400Y219100D02*X457600D01*

+X454400D02*Y215900D01*

+X457600D01*

+Y219100D02*Y215900D01*

+X464400Y219100D02*X467600D01*

+X464400D02*Y215900D01*

+X467600D01*

+Y219100D02*Y215900D01*

+X474400Y219100D02*X477600D01*

+X474400D02*Y215900D01*

+X477600D01*

+Y219100D02*Y215900D01*

+X474400Y279100D02*X477600D01*

+X474400D02*Y275900D01*

+X477600D01*

+Y279100D02*Y275900D01*

+X464400Y279100D02*X467600D01*

+X464400D02*Y275900D01*

+X467600D01*

+Y279100D02*Y275900D01*

+X454400Y279100D02*X457600D01*

+X454400D02*Y275900D01*

+X457600D01*

+Y279100D02*Y275900D01*

+X444400Y279100D02*X447600D01*

+X444400D02*Y275900D01*

+X447600D01*

+Y279100D02*Y275900D01*

+X434400Y279100D02*X437600D01*

+X434400D02*Y275900D01*

+X437600D01*

+Y279100D02*Y275900D01*

+X424400Y279100D02*X427600D01*

+X424400D02*Y275900D01*

+X427600D01*

+Y279100D02*Y275900D01*

+X414400Y279100D02*X417600D01*

+X414400D02*Y275900D01*

+X417600D01*

+Y279100D02*Y275900D01*

+X404400Y279100D02*X407600D01*

+X404400D02*Y275900D01*

+X407600D01*

+Y279100D02*Y275900D01*

+X394400Y279100D02*X397600D01*

+X394400D02*Y275900D01*

+X397600D01*

+Y279100D02*Y275900D01*

+X384400Y279100D02*X387600D01*

+X384400D02*Y275900D01*

+X387600D01*

+Y279100D02*Y275900D01*

+X374400Y279100D02*X377600D01*

+X374400D02*Y275900D01*

+X377600D01*

+Y279100D02*Y275900D01*

+X364400Y279100D02*X367600D01*

+X364400D02*Y275900D01*

+X367600D01*

+Y279100D02*Y275900D01*

+X354400Y279100D02*X357600D01*

+X354400D02*Y275900D01*

+X357600D01*

+Y279100D02*Y275900D01*

+X344400Y279100D02*X347600D01*

+X344400D02*Y275900D01*

+X347600D01*

+Y279100D02*Y275900D01*

+X334400Y279100D02*X337600D01*

+X334400D02*Y275900D01*

+X337600D01*

+Y279100D02*Y275900D01*

+X324400Y279100D02*X327600D01*

+X324400D02*Y275900D01*

+X327600D01*

+Y279100D02*Y275900D01*

+X314400Y279100D02*X317600D01*

+X314400D02*Y275900D01*

+X317600D01*

+Y279100D02*Y275900D01*

+X304400Y279100D02*X307600D01*

+X304400D02*Y275900D01*

+X307600D01*

+Y279100D02*Y275900D01*

+X294400Y279100D02*X297600D01*

+X294400D02*Y275900D01*

+X297600D01*

+Y279100D02*Y275900D01*

+X284400Y279100D02*X287600D01*

+X284400D02*Y275900D01*

+X287600D01*

+Y279100D02*Y275900D01*

+X274400Y279100D02*X277600D01*

+X274400D02*Y275900D01*

+X277600D01*

+Y279100D02*Y275900D01*

+X264400Y279100D02*X267600D01*

+X264400D02*Y275900D01*

+X267600D01*

+Y279100D02*Y275900D01*

+X254400Y279100D02*X257600D01*

+X254400D02*Y275900D01*

+X257600D01*

+Y279100D02*Y275900D01*

+X244400Y279100D02*X247600D01*

+X244400D02*Y275900D01*

+X247600D01*

+Y279100D02*Y275900D01*

+X13400Y572850D02*X16600D01*

+X13400D02*Y569650D01*

+X16600D01*

+Y572850D02*Y569650D01*

+X135000Y573500D02*X136500Y570500D01*

+X138000Y573500D01*

+X136500Y570500D02*Y567500D01*

+X139800Y570800D02*X142050D01*

+X139800Y567500D02*X142800D01*

+X139800Y573500D02*Y567500D01*

+Y573500D02*X142800D01*

+X147600D02*X148350Y572750D01*

+X145350Y573500D02*X147600D01*

+X144600Y572750D02*X145350Y573500D01*

+X144600Y572750D02*Y571250D01*

+X145350Y570500D01*

+X147600D01*

+X148350Y569750D01*

+Y568250D01*

+X147600Y567500D02*X148350Y568250D01*

+X145350Y567500D02*X147600D01*

+X144600Y568250D02*X145350Y567500D01*

+X98000Y569750D02*X101000Y573500D01*

+X98000Y569750D02*X101750D01*

+X101000Y573500D02*Y567500D01*

+X103550Y568250D02*X104300Y567500D01*

+X103550Y569450D02*Y568250D01*

+Y569450D02*X104600Y570500D01*

+X105500D01*

+X106550Y569450D01*

+Y568250D01*

+X105800Y567500D02*X106550Y568250D01*

+X104300Y567500D02*X105800D01*

+X103550Y571550D02*X104600Y570500D01*

+X103550Y572750D02*Y571550D01*

+Y572750D02*X104300Y573500D01*

+X105800D01*

+X106550Y572750D01*

+Y571550D01*

+X105500Y570500D02*X106550Y571550D01*

+X45000Y568250D02*X45750Y567500D01*

+X45000Y572750D02*Y568250D01*

+Y572750D02*X45750Y573500D01*

+X47250D01*

+X48000Y572750D01*

+Y568250D01*

+X47250Y567500D02*X48000Y568250D01*

+X45750Y567500D02*X47250D01*

+X45000Y569000D02*X48000Y572000D01*

+X49800Y567500D02*X50550D01*

+X52350Y568250D02*X53100Y567500D01*

+X52350Y572750D02*Y568250D01*

+Y572750D02*X53100Y573500D01*

+X54600D01*

+X55350Y572750D01*

+Y568250D01*

+X54600Y567500D02*X55350Y568250D01*

+X53100Y567500D02*X54600D01*

+X52350Y569000D02*X55350Y572000D01*

+X57150Y572750D02*X57900Y573500D01*

+X59400D01*

+X60150Y572750D01*

+X59400Y567500D02*X60150Y568250D01*

+X57900Y567500D02*X59400D01*

+X57150Y568250D02*X57900Y567500D01*

+Y570800D02*X59400D01*

+X60150Y572750D02*Y571550D01*

+Y570050D02*Y568250D01*

+Y570050D02*X59400Y570800D01*

+X60150Y571550D02*X59400Y570800D01*

+X61950Y568250D02*X62700Y567500D01*

+X61950Y569450D02*Y568250D01*

+Y569450D02*X63000Y570500D01*

+X63900D01*

+X64950Y569450D01*

+Y568250D01*

+X64200Y567500D02*X64950Y568250D01*

+X62700Y567500D02*X64200D01*

+X61950Y571550D02*X63000Y570500D01*

+X61950Y572750D02*Y571550D01*

+Y572750D02*X62700Y573500D01*

+X64200D01*

+X64950Y572750D01*

+Y571550D01*

+X63900Y570500D02*X64950Y571550D01*

+X461700Y311500D02*G75*G03X463300Y311500I800J0D01*G01*

+G75*G03X461700Y311500I-800J0D01*G01*

+X441200Y326000D02*G75*G03X442800Y326000I800J0D01*G01*

+G75*G03X441200Y326000I-800J0D01*G01*

+X512700Y332000D02*G75*G03X514300Y332000I800J0D01*G01*

+G75*G03X512700Y332000I-800J0D01*G01*

+X605200Y381500D02*G75*G03X606800Y381500I800J0D01*G01*

+G75*G03X605200Y381500I-800J0D01*G01*

+X599700Y386500D02*G75*G03X601300Y386500I800J0D01*G01*

+G75*G03X599700Y386500I-800J0D01*G01*

+X594200Y381500D02*G75*G03X595800Y381500I800J0D01*G01*

+G75*G03X594200Y381500I-800J0D01*G01*

+X588700Y386500D02*G75*G03X590300Y386500I800J0D01*G01*

+G75*G03X588700Y386500I-800J0D01*G01*

+X562700Y334500D02*G75*G03X564300Y334500I800J0D01*G01*

+G75*G03X562700Y334500I-800J0D01*G01*

+X553700Y339000D02*G75*G03X555300Y339000I800J0D01*G01*

+G75*G03X553700Y339000I-800J0D01*G01*

+X497200Y264000D02*G75*G03X498800Y264000I800J0D01*G01*

+G75*G03X497200Y264000I-800J0D01*G01*

+Y257000D02*G75*G03X498800Y257000I800J0D01*G01*

+G75*G03X497200Y257000I-800J0D01*G01*

+X501200Y315000D02*G75*G03X502800Y315000I800J0D01*G01*

+G75*G03X501200Y315000I-800J0D01*G01*

+X553700Y329780D02*G75*G03X555300Y329780I800J0D01*G01*

+G75*G03X553700Y329780I-800J0D01*G01*

+Y319937D02*G75*G03X555300Y319937I800J0D01*G01*

+G75*G03X553700Y319937I-800J0D01*G01*

+Y312063D02*G75*G03X555300Y312063I800J0D01*G01*

+G75*G03X553700Y312063I-800J0D01*G01*

+Y302220D02*G75*G03X555300Y302220I800J0D01*G01*

+G75*G03X553700Y302220I-800J0D01*G01*

+X527700Y329780D02*G75*G03X529300Y329780I800J0D01*G01*

+G75*G03X527700Y329780I-800J0D01*G01*

+Y319937D02*G75*G03X529300Y319937I800J0D01*G01*

+G75*G03X527700Y319937I-800J0D01*G01*

+Y312063D02*G75*G03X529300Y312063I800J0D01*G01*

+G75*G03X527700Y312063I-800J0D01*G01*

+Y302220D02*G75*G03X529300Y302220I800J0D01*G01*

+G75*G03X527700Y302220I-800J0D01*G01*

+X409200Y329780D02*G75*G03X410800Y329780I800J0D01*G01*

+G75*G03X409200Y329780I-800J0D01*G01*

+Y319937D02*G75*G03X410800Y319937I800J0D01*G01*

+G75*G03X409200Y319937I-800J0D01*G01*

+Y312063D02*G75*G03X410800Y312063I800J0D01*G01*

+G75*G03X409200Y312063I-800J0D01*G01*

+Y302220D02*G75*G03X410800Y302220I800J0D01*G01*

+G75*G03X409200Y302220I-800J0D01*G01*

+X353700Y329780D02*G75*G03X355300Y329780I800J0D01*G01*

+G75*G03X353700Y329780I-800J0D01*G01*

+Y319937D02*G75*G03X355300Y319937I800J0D01*G01*

+G75*G03X353700Y319937I-800J0D01*G01*

+Y312063D02*G75*G03X355300Y312063I800J0D01*G01*

+G75*G03X353700Y312063I-800J0D01*G01*

+Y302220D02*G75*G03X355300Y302220I800J0D01*G01*

+G75*G03X353700Y302220I-800J0D01*G01*

+X298200Y329780D02*G75*G03X299800Y329780I800J0D01*G01*

+G75*G03X298200Y329780I-800J0D01*G01*

+Y319937D02*G75*G03X299800Y319937I800J0D01*G01*

+G75*G03X298200Y319937I-800J0D01*G01*

+Y312063D02*G75*G03X299800Y312063I800J0D01*G01*

+G75*G03X298200Y312063I-800J0D01*G01*

+Y302220D02*G75*G03X299800Y302220I800J0D01*G01*

+G75*G03X298200Y302220I-800J0D01*G01*

+X242700Y329780D02*G75*G03X244300Y329780I800J0D01*G01*

+G75*G03X242700Y329780I-800J0D01*G01*

+Y319937D02*G75*G03X244300Y319937I800J0D01*G01*

+G75*G03X242700Y319937I-800J0D01*G01*

+Y312063D02*G75*G03X244300Y312063I800J0D01*G01*

+G75*G03X242700Y312063I-800J0D01*G01*

+Y302220D02*G75*G03X244300Y302220I800J0D01*G01*

+G75*G03X242700Y302220I-800J0D01*G01*

+X187200Y329780D02*G75*G03X188800Y329780I800J0D01*G01*

+G75*G03X187200Y329780I-800J0D01*G01*

+Y319937D02*G75*G03X188800Y319937I800J0D01*G01*

+G75*G03X187200Y319937I-800J0D01*G01*

+Y312063D02*G75*G03X188800Y312063I800J0D01*G01*

+G75*G03X187200Y312063I-800J0D01*G01*

+Y302220D02*G75*G03X188800Y302220I800J0D01*G01*

+G75*G03X187200Y302220I-800J0D01*G01*

+X14200Y586250D02*G75*G03X15800Y586250I800J0D01*G01*

+G75*G03X14200Y586250I-800J0D01*G01*

+X135000Y588500D02*X136500Y585500D01*

+X138000Y588500D01*

+X136500Y585500D02*Y582500D01*

+X139800Y585800D02*X142050D01*

+X139800Y582500D02*X142800D01*

+X139800Y588500D02*Y582500D01*

+Y588500D02*X142800D01*

+X147600D02*X148350Y587750D01*

+X145350Y588500D02*X147600D01*

+X144600Y587750D02*X145350Y588500D01*

+X144600Y587750D02*Y586250D01*

+X145350Y585500D01*

+X147600D01*

+X148350Y584750D01*

+Y583250D01*

+X147600Y582500D02*X148350Y583250D01*

+X145350Y582500D02*X147600D01*

+X144600Y583250D02*X145350Y582500D01*

+X98000Y584750D02*X101000Y588500D01*

+X98000Y584750D02*X101750D01*

+X101000Y588500D02*Y582500D01*

+X103550Y583250D02*X104300Y582500D01*

+X103550Y587750D02*Y583250D01*

+Y587750D02*X104300Y588500D01*

+X105800D01*

+X106550Y587750D01*

+Y583250D01*

+X105800Y582500D02*X106550Y583250D01*

+X104300Y582500D02*X105800D01*

+X103550Y584000D02*X106550Y587000D01*

+X45000Y583250D02*X45750Y582500D01*

+X45000Y587750D02*Y583250D01*

+Y587750D02*X45750Y588500D01*

+X47250D01*

+X48000Y587750D01*

+Y583250D01*

+X47250Y582500D02*X48000Y583250D01*

+X45750Y582500D02*X47250D01*

+X45000Y584000D02*X48000Y587000D01*

+X49800Y582500D02*X50550D01*

+X52350Y583250D02*X53100Y582500D01*

+X52350Y587750D02*Y583250D01*

+Y587750D02*X53100Y588500D01*

+X54600D01*

+X55350Y587750D01*

+Y583250D01*

+X54600Y582500D02*X55350Y583250D01*

+X53100Y582500D02*X54600D01*

+X52350Y584000D02*X55350Y587000D01*

+X57150Y587750D02*X57900Y588500D01*

+X59400D01*

+X60150Y587750D01*

+X59400Y582500D02*X60150Y583250D01*

+X57900Y582500D02*X59400D01*

+X57150Y583250D02*X57900Y582500D01*

+Y585800D02*X59400D01*

+X60150Y587750D02*Y586550D01*

+Y585050D02*Y583250D01*

+Y585050D02*X59400Y585800D01*

+X60150Y586550D02*X59400Y585800D01*

+X61950Y588500D02*X64950D01*

+X61950D02*Y585500D01*

+X62700Y586250D01*

+X64200D01*

+X64950Y585500D01*

+Y583250D01*

+X64200Y582500D02*X64950Y583250D01*

+X62700Y582500D02*X64200D01*

+X61950Y583250D02*X62700Y582500D01*

+X491300Y295200D02*X493700Y292800D01*

+X491300D02*X493700Y295200D01*

+X483800D02*X486200Y292800D01*

+X483800D02*X486200Y295200D01*

+X475300D02*X477700Y292800D01*

+X475300D02*X477700Y295200D01*

+X469800D02*X472200Y292800D01*

+X469800D02*X472200Y295200D01*

+X481800Y324200D02*X484200Y321800D01*

+X481800D02*X484200Y324200D01*

+X494800Y333200D02*X497200Y330800D01*

+X494800D02*X497200Y333200D01*

+X585800Y265700D02*X588200Y263300D01*

+X585800D02*X588200Y265700D01*

+X585800Y255700D02*X588200Y253300D01*

+X585800D02*X588200Y255700D01*

+X581800Y260700D02*X584200Y258300D01*

+X581800D02*X584200Y260700D01*

+X582300Y324700D02*X584700Y322300D01*

+X582300D02*X584700Y324700D01*

+X567300D02*X569700Y322300D01*

+X567300D02*X569700Y324700D01*

+X595300Y334700D02*X597700Y332300D01*

+X595300D02*X597700Y334700D01*

+X587800D02*X590200Y332300D01*

+X587800D02*X590200Y334700D01*

+X587800Y327200D02*X590200Y324800D01*

+X587800D02*X590200Y327200D01*

+X595300D02*X597700Y324800D01*

+X595300D02*X597700Y327200D01*

+X594800Y321200D02*X597200Y318800D01*

+X594800D02*X597200Y321200D01*

+X190300Y259200D02*X192700Y256800D01*

+X190300D02*X192700Y259200D01*

+X190300Y238200D02*X192700Y235800D01*

+X190300D02*X192700Y238200D01*

+X244800Y339700D02*X247200Y337300D01*

+X244800D02*X247200Y339700D01*

+X272800D02*X275200Y337300D01*

+X272800D02*X275200Y339700D01*

+X261800D02*X264200Y337300D01*

+X261800D02*X264200Y339700D01*

+X203800Y315200D02*X206200Y312800D01*

+X203800D02*X206200Y315200D01*

+X212300D02*X214700Y312800D01*

+X212300D02*X214700Y315200D01*

+X219800D02*X222200Y312800D01*

+X219800D02*X222200Y315200D01*

+X13800Y602450D02*X16200Y600050D01*

+X13800D02*X16200Y602450D01*

+X135000Y603500D02*X136500Y600500D01*

+X138000Y603500D01*

+X136500Y600500D02*Y597500D01*

+X139800Y600800D02*X142050D01*

+X139800Y597500D02*X142800D01*

+X139800Y603500D02*Y597500D01*

+Y603500D02*X142800D01*

+X147600D02*X148350Y602750D01*

+X145350Y603500D02*X147600D01*

+X144600Y602750D02*X145350Y603500D01*

+X144600Y602750D02*Y601250D01*

+X145350Y600500D01*

+X147600D01*

+X148350Y599750D01*

+Y598250D01*

+X147600Y597500D02*X148350Y598250D01*

+X145350Y597500D02*X147600D01*

+X144600Y598250D02*X145350Y597500D01*

+X98000Y602750D02*X98750Y603500D01*

+X101000D01*

+X101750Y602750D01*

+Y601250D01*

+X98000Y597500D02*X101750Y601250D01*

+X98000Y597500D02*X101750D01*

+X103550Y599750D02*X106550Y603500D01*

+X103550Y599750D02*X107300D01*

+X106550Y603500D02*Y597500D01*

+X45000Y598250D02*X45750Y597500D01*

+X45000Y602750D02*Y598250D01*

+Y602750D02*X45750Y603500D01*

+X47250D01*

+X48000Y602750D01*

+Y598250D01*

+X47250Y597500D02*X48000Y598250D01*

+X45750Y597500D02*X47250D01*

+X45000Y599000D02*X48000Y602000D01*

+X49800Y597500D02*X50550D01*

+X52350Y598250D02*X53100Y597500D01*

+X52350Y602750D02*Y598250D01*

+Y602750D02*X53100Y603500D01*

+X54600D01*

+X55350Y602750D01*

+Y598250D01*

+X54600Y597500D02*X55350Y598250D01*

+X53100Y597500D02*X54600D01*

+X52350Y599000D02*X55350Y602000D01*

+X57150Y602750D02*X57900Y603500D01*

+X60150D01*

+X60900Y602750D01*

+Y601250D01*

+X57150Y597500D02*X60900Y601250D01*

+X57150Y597500D02*X60900D01*

+X62700Y603500D02*X65700D01*

+X62700D02*Y600500D01*

+X63450Y601250D01*

+X64950D01*

+X65700Y600500D01*

+Y598250D01*

+X64950Y597500D02*X65700Y598250D01*

+X63450Y597500D02*X64950D01*

+X62700Y598250D02*X63450Y597500D01*

+X628500Y247600D02*Y244400D01*

+X626900Y246000D02*X630100D01*

+X653500Y279100D02*Y275900D01*

+X651900Y277500D02*X655100D01*

+X593500Y279100D02*Y275900D01*

+X591900Y277500D02*X595100D01*

+X648500Y247600D02*Y244400D01*

+X646900Y246000D02*X650100D01*

+X627000Y279600D02*Y276400D01*

+X625400Y278000D02*X628600D01*

+X658000Y279600D02*Y276400D01*

+X656400Y278000D02*X659600D01*

+X616500Y282100D02*Y278900D01*

+X614900Y280500D02*X618100D01*

+X616500Y292100D02*Y288900D01*

+X614900Y290500D02*X618100D01*

+X598000Y295100D02*Y291900D01*

+X596400Y293500D02*X599600D01*

+X649000Y279100D02*Y275900D01*

+X647400Y277500D02*X650600D01*

+X647500Y287100D02*Y283900D01*

+X645900Y285500D02*X649100D01*

+X621000Y235600D02*Y232400D01*

+X619400Y234000D02*X622600D01*

+X621000Y240100D02*Y236900D01*

+X619400Y238500D02*X622600D01*

+X637500Y304600D02*Y301400D01*

+X635900Y303000D02*X639100D01*

+X625000Y304600D02*Y301400D01*

+X623400Y303000D02*X626600D01*

+X622500Y308100D02*Y304900D01*

+X620900Y306500D02*X624100D01*

+X622500Y312600D02*Y309400D01*

+X620900Y311000D02*X624100D01*

+X622500Y321600D02*Y318400D01*

+X620900Y320000D02*X624100D01*

+X627000Y327100D02*Y323900D01*

+X625400Y325500D02*X628600D01*

+X594000Y247100D02*Y243900D01*

+X592400Y245500D02*X595600D01*

+X668000Y247100D02*Y243900D01*

+X666400Y245500D02*X669600D01*

+X449500Y315100D02*Y311900D01*

+X447900Y313500D02*X451100D01*

+X570500Y245600D02*Y242400D01*

+X568900Y244000D02*X572100D01*

+X581500Y239100D02*Y235900D01*

+X579900Y237500D02*X583100D01*

+X581500Y245600D02*Y242400D01*

+X579900Y244000D02*X583100D01*

+X576000Y232600D02*Y229400D01*

+X574400Y231000D02*X577600D01*

+X570500Y239100D02*Y235900D01*

+X568900Y237500D02*X572100D01*

+X539000Y245600D02*Y242400D01*

+X537400Y244000D02*X540600D01*

+X550000Y239100D02*Y235900D01*

+X548400Y237500D02*X551600D01*

+X550000Y245600D02*Y242400D01*

+X548400Y244000D02*X551600D01*

+X544500Y232600D02*Y229400D01*

+X542900Y231000D02*X546100D01*

+X539000Y239100D02*Y235900D01*

+X537400Y237500D02*X540600D01*

+X507500Y245600D02*Y242400D01*

+X505900Y244000D02*X509100D01*

+X518500Y239100D02*Y235900D01*

+X516900Y237500D02*X520100D01*

+X518500Y245600D02*Y242400D01*

+X516900Y244000D02*X520100D01*

+X513000Y232600D02*Y229400D01*

+X511400Y231000D02*X514600D01*

+X507500Y239100D02*Y235900D01*

+X505900Y237500D02*X509100D01*

+X680500Y245600D02*Y242400D01*

+X678900Y244000D02*X682100D01*

+X691500Y239100D02*Y235900D01*

+X689900Y237500D02*X693100D01*

+X691500Y245600D02*Y242400D01*

+X689900Y244000D02*X693100D01*

+X686000Y232600D02*Y229400D01*

+X684400Y231000D02*X687600D01*

+X680500Y239100D02*Y235900D01*

+X678900Y237500D02*X682100D01*

+X662500Y233600D02*Y230400D01*

+X660900Y232000D02*X664100D01*

+X655000Y233600D02*Y230400D01*

+X653400Y232000D02*X656600D01*

+X599500Y233600D02*Y230400D01*

+X597900Y232000D02*X601100D01*

+X607500Y233600D02*Y230400D01*

+X605900Y232000D02*X609100D01*

+X569000Y330100D02*Y326900D01*

+X567400Y328500D02*X570600D01*

+X583000Y330100D02*Y326900D01*

+X581400Y328500D02*X584600D01*

+X573500Y350100D02*Y346900D01*

+X571900Y348500D02*X575100D01*

+X578000Y350600D02*Y347400D01*

+X576400Y349000D02*X579600D01*

+X646500Y353100D02*Y349900D01*

+X644900Y351500D02*X648100D01*

+X595000Y353600D02*Y350400D01*

+X593400Y352000D02*X596600D01*

+X564500Y350100D02*Y346900D01*

+X562900Y348500D02*X566100D01*

+X596000Y314100D02*Y310900D01*

+X594400Y312500D02*X597600D01*

+X569000Y299100D02*Y295900D01*

+X567400Y297500D02*X570600D01*

+X575500Y286600D02*Y283400D01*

+X573900Y285000D02*X577100D01*

+X562000Y317600D02*Y314400D01*

+X560400Y316000D02*X563600D01*

+X416000Y375100D02*Y371900D01*

+X414400Y373500D02*X417600D01*

+X360500Y375100D02*Y371900D01*

+X358900Y373500D02*X362100D01*

+X305000Y375100D02*Y371900D01*

+X303400Y373500D02*X306600D01*

+X249500Y375100D02*Y371900D01*

+X247900Y373500D02*X251100D01*

+X194000Y375100D02*Y371900D01*

+X192400Y373500D02*X195600D01*

+X386000Y235100D02*Y231900D01*

+X384400Y233500D02*X387600D01*

+X246000Y263100D02*Y259900D01*

+X244400Y261500D02*X247600D01*

+X278500Y381600D02*Y378400D01*

+X276900Y380000D02*X280100D01*

+X225000Y245100D02*Y241900D01*

+X223400Y243500D02*X226600D01*

+X220000Y232600D02*Y229400D01*

+X218400Y231000D02*X221600D01*

+X215000Y245100D02*Y241900D01*

+X213400Y243500D02*X216600D01*

+X210000Y232600D02*Y229400D01*

+X208400Y231000D02*X211600D01*

+X205000Y245100D02*Y241900D01*

+X203400Y243500D02*X206600D01*

+X200000Y232600D02*Y229400D01*

+X198400Y231000D02*X201600D01*

+X494500Y288100D02*Y284900D01*

+X492900Y286500D02*X496100D01*

+X463500Y245100D02*Y241900D01*

+X461900Y243500D02*X465100D01*

+X449500Y241600D02*Y238400D01*

+X447900Y240000D02*X451100D01*

+X455000Y251600D02*Y248400D01*

+X453400Y250000D02*X456600D01*

+X489500Y275600D02*Y272400D01*

+X487900Y274000D02*X491100D01*

+X429000Y256100D02*Y252900D01*

+X427400Y254500D02*X430600D01*

+X464500Y265600D02*Y262400D01*

+X462900Y264000D02*X466100D01*

+X465500Y271600D02*Y268400D01*

+X463900Y270000D02*X467100D01*

+X422500Y333100D02*Y329900D01*

+X420900Y331500D02*X424100D01*

+X415500Y288100D02*Y284900D01*

+X413900Y286500D02*X417100D01*

+X532500Y289600D02*Y286400D01*

+X530900Y288000D02*X534100D01*

+X376500Y308100D02*Y304900D01*

+X374900Y306500D02*X378100D01*

+X313500Y325100D02*Y321900D01*

+X311900Y323500D02*X315100D01*

+X329500Y242100D02*Y238900D01*

+X327900Y240500D02*X331100D01*

+X339000Y236100D02*Y232900D01*

+X337400Y234500D02*X340600D01*

+X271000Y269600D02*Y266400D01*

+X269400Y268000D02*X272600D01*

+X281000Y269600D02*Y266400D01*

+X279400Y268000D02*X282600D01*

+X337000Y243600D02*Y240400D01*

+X335400Y242000D02*X338600D01*

+X343500Y246600D02*Y243400D01*

+X341900Y245000D02*X345100D01*

+X291000Y269600D02*Y266400D01*

+X289400Y268000D02*X292600D01*

+X301000Y269600D02*Y266400D01*

+X299400Y268000D02*X302600D01*

+X15000Y617850D02*Y614650D01*

+X13400Y616250D02*X16600D01*

+X135000Y618500D02*X136500Y615500D01*

+X138000Y618500D01*

+X136500Y615500D02*Y612500D01*

+X139800Y615800D02*X142050D01*

+X139800Y612500D02*X142800D01*

+X139800Y618500D02*Y612500D01*

+Y618500D02*X142800D01*

+X147600D02*X148350Y617750D01*

+X145350Y618500D02*X147600D01*

+X144600Y617750D02*X145350Y618500D01*

+X144600Y617750D02*Y616250D01*

+X145350Y615500D01*

+X147600D01*

+X148350Y614750D01*

+Y613250D01*

+X147600Y612500D02*X148350Y613250D01*

+X145350Y612500D02*X147600D01*

+X144600Y613250D02*X145350Y612500D01*

+X98750D02*X101000Y615500D01*

+Y617750D02*Y615500D01*

+X100250Y618500D02*X101000Y617750D01*

+X98750Y618500D02*X100250D01*

+X98000Y617750D02*X98750Y618500D01*

+X98000Y617750D02*Y616250D01*

+X98750Y615500D01*

+X101000D01*

+X102800Y617750D02*X103550Y618500D01*

+X105800D01*

+X106550Y617750D01*

+Y616250D01*

+X102800Y612500D02*X106550Y616250D01*

+X102800Y612500D02*X106550D01*

+X45000Y613250D02*X45750Y612500D01*

+X45000Y617750D02*Y613250D01*

+Y617750D02*X45750Y618500D01*

+X47250D01*

+X48000Y617750D01*

+Y613250D01*

+X47250Y612500D02*X48000Y613250D01*

+X45750Y612500D02*X47250D01*

+X45000Y614000D02*X48000Y617000D01*

+X49800Y612500D02*X50550D01*

+X52350Y613250D02*X53100Y612500D01*

+X52350Y617750D02*Y613250D01*

+Y617750D02*X53100Y618500D01*

+X54600D01*

+X55350Y617750D01*

+Y613250D01*

+X54600Y612500D02*X55350Y613250D01*

+X53100Y612500D02*X54600D01*

+X52350Y614000D02*X55350Y617000D01*

+X57150Y617750D02*X57900Y618500D01*

+X60150D01*

+X60900Y617750D01*

+Y616250D01*

+X57150Y612500D02*X60900Y616250D01*

+X57150Y612500D02*X60900D01*

+X62700Y613250D02*X63450Y612500D01*

+X62700Y617750D02*Y613250D01*

+Y617750D02*X63450Y618500D01*

+X64950D01*

+X65700Y617750D01*

+Y613250D01*

+X64950Y612500D02*X65700Y613250D01*

+X63450Y612500D02*X64950D01*

+X62700Y614000D02*X65700Y617000D01*

+X576000Y322500D02*Y320900D01*

+Y322500D02*X577387Y323300D01*

+X576000Y322500D02*X574613Y323300D01*

+X591500Y350000D02*Y348400D01*

+Y350000D02*X592887Y350800D01*

+X591500Y350000D02*X590113Y350800D01*

+X588000Y363000D02*Y361400D01*

+Y363000D02*X589387Y363800D01*

+X588000Y363000D02*X586613Y363800D01*

+X588000Y359000D02*Y357400D01*

+Y359000D02*X589387Y359800D01*

+X588000Y359000D02*X586613Y359800D01*

+X631000Y290500D02*Y288900D01*

+Y290500D02*X632387Y291300D01*

+X631000Y290500D02*X629613Y291300D01*

+X631000Y286760D02*Y285160D01*

+Y286760D02*X632387Y287560D01*

+X631000Y286760D02*X629613Y287560D01*

+X631000Y294240D02*Y292640D01*

+Y294240D02*X632387Y295040D01*

+X631000Y294240D02*X629613Y295040D01*

+X636709Y290500D02*Y288900D01*

+Y290500D02*X638095Y291300D01*

+X636709Y290500D02*X635322Y291300D01*

+X625291Y290500D02*Y288900D01*

+Y290500D02*X626678Y291300D01*

+X625291Y290500D02*X623905Y291300D01*

+X15000Y631250D02*Y629650D01*

+Y631250D02*X16387Y632050D01*

+X15000Y631250D02*X13613Y632050D01*

+X135000Y633500D02*X136500Y630500D01*

+X138000Y633500D01*

+X136500Y630500D02*Y627500D01*

+X139800Y630800D02*X142050D01*

+X139800Y627500D02*X142800D01*

+X139800Y633500D02*Y627500D01*

+Y633500D02*X142800D01*

+X147600D02*X148350Y632750D01*

+X145350Y633500D02*X147600D01*

+X144600Y632750D02*X145350Y633500D01*

+X144600Y632750D02*Y631250D01*

+X145350Y630500D01*

+X147600D01*

+X148350Y629750D01*

+Y628250D01*

+X147600Y627500D02*X148350Y628250D01*

+X145350Y627500D02*X147600D01*

+X144600Y628250D02*X145350Y627500D01*

+X98750D02*X101000Y630500D01*

+Y632750D02*Y630500D01*

+X100250Y633500D02*X101000Y632750D01*

+X98750Y633500D02*X100250D01*

+X98000Y632750D02*X98750Y633500D01*

+X98000Y632750D02*Y631250D01*

+X98750Y630500D01*

+X101000D01*

+X45000Y628250D02*X45750Y627500D01*

+X45000Y632750D02*Y628250D01*

+Y632750D02*X45750Y633500D01*

+X47250D01*

+X48000Y632750D01*

+Y628250D01*

+X47250Y627500D02*X48000Y628250D01*

+X45750Y627500D02*X47250D01*

+X45000Y629000D02*X48000Y632000D01*

+X49800Y627500D02*X50550D01*

+X52350Y628250D02*X53100Y627500D01*

+X52350Y632750D02*Y628250D01*

+Y632750D02*X53100Y633500D01*

+X54600D01*

+X55350Y632750D01*

+Y628250D01*

+X54600Y627500D02*X55350Y628250D01*

+X53100Y627500D02*X54600D01*

+X52350Y629000D02*X55350Y632000D01*

+X57150Y632300D02*X58350Y633500D01*

+Y627500D01*

+X57150D02*X59400D01*

+X61200Y632750D02*X61950Y633500D01*

+X64200D01*

+X64950Y632750D01*

+Y631250D01*

+X61200Y627500D02*X64950Y631250D01*

+X61200Y627500D02*X64950D01*

+X3000Y648500D02*X3750Y647750D01*

+X750Y648500D02*X3000D01*

+X0Y647750D02*X750Y648500D01*

+X0Y647750D02*Y646250D01*

+X750Y645500D01*

+X3000D01*

+X3750Y644750D01*

+Y643250D01*

+X3000Y642500D02*X3750Y643250D01*

+X750Y642500D02*X3000D01*

+X0Y643250D02*X750Y642500D01*

+X5550Y645500D02*Y643250D01*

+X6300Y642500D01*

+X8550Y645500D02*Y641000D01*

+X7800Y640250D02*X8550Y641000D01*

+X6300Y640250D02*X7800D01*

+X5550Y641000D02*X6300Y640250D01*

+Y642500D02*X7800D01*

+X8550Y643250D01*

+X11100Y644750D02*Y642500D01*

+Y644750D02*X11850Y645500D01*

+X12600D01*

+X13350Y644750D01*

+Y642500D01*

+Y644750D02*X14100Y645500D01*

+X14850D01*

+X15600Y644750D01*

+Y642500D01*

+X10350Y645500D02*X11100Y644750D01*

+X17400Y648500D02*Y642500D01*

+Y643250D02*X18150Y642500D01*

+X19650D01*

+X20400Y643250D01*

+Y644750D02*Y643250D01*

+X19650Y645500D02*X20400Y644750D01*

+X18150Y645500D02*X19650D01*

+X17400Y644750D02*X18150Y645500D01*

+X22200Y644750D02*Y643250D01*

+Y644750D02*X22950Y645500D01*

+X24450D01*

+X25200Y644750D01*

+Y643250D01*

+X24450Y642500D02*X25200Y643250D01*

+X22950Y642500D02*X24450D01*

+X22200Y643250D02*X22950Y642500D01*

+X27000Y648500D02*Y643250D01*

+X27750Y642500D01*

+X0Y639250D02*X29250D01*

+X41750Y648500D02*Y642500D01*

+X43700Y648500D02*X44750Y647450D01*

+Y643550D01*

+X43700Y642500D02*X44750Y643550D01*

+X41000Y642500D02*X43700D01*

+X41000Y648500D02*X43700D01*

+G54D219*X46550Y647000D02*Y646850D01*

+G54D218*Y644750D02*Y642500D01*

+X50300Y645500D02*X51050Y644750D01*

+X48800Y645500D02*X50300D01*

+X48050Y644750D02*X48800Y645500D01*

+X48050Y644750D02*Y643250D01*

+X48800Y642500D01*

+X51050Y645500D02*Y643250D01*

+X51800Y642500D01*

+X48800D02*X50300D01*

+X51050Y643250D01*

+X54350Y644750D02*Y642500D01*

+Y644750D02*X55100Y645500D01*

+X55850D01*

+X56600Y644750D01*

+Y642500D01*

+Y644750D02*X57350Y645500D01*

+X58100D01*

+X58850Y644750D01*

+Y642500D01*

+X53600Y645500D02*X54350Y644750D01*

+X60650Y642500D02*X61400D01*

+X65900Y643250D02*X66650Y642500D01*

+X65900Y647750D02*X66650Y648500D01*

+X65900Y647750D02*Y643250D01*

+X68450Y648500D02*X69950D01*

+X69200D02*Y642500D01*

+X68450D02*X69950D01*

+X72500Y644750D02*Y642500D01*

+Y644750D02*X73250Y645500D01*

+X74000D01*

+X74750Y644750D01*

+Y642500D01*

+X71750Y645500D02*X72500Y644750D01*

+X77300Y645500D02*X79550D01*

+X76550Y644750D02*X77300Y645500D01*

+X76550Y644750D02*Y643250D01*

+X77300Y642500D01*

+X79550D01*

+X81350Y648500D02*Y642500D01*

+Y644750D02*X82100Y645500D01*

+X83600D01*

+X84350Y644750D01*

+Y642500D01*

+X86150Y648500D02*X86900Y647750D01*

+Y643250D01*

+X86150Y642500D02*X86900Y643250D01*

+X41000Y639250D02*X88700D01*

+X96050Y642500D02*X98000D01*

+X95000Y643550D02*X96050Y642500D01*

+X95000Y647450D02*Y643550D01*

+Y647450D02*X96050Y648500D01*

+X98000D01*

+X99800Y644750D02*Y643250D01*

+Y644750D02*X100550Y645500D01*

+X102050D01*

+X102800Y644750D01*

+Y643250D01*

+X102050Y642500D02*X102800Y643250D01*

+X100550Y642500D02*X102050D01*

+X99800Y643250D02*X100550Y642500D01*

+X104600Y645500D02*Y643250D01*

+X105350Y642500D01*

+X106850D01*

+X107600Y643250D01*

+Y645500D02*Y643250D01*

+X110150Y644750D02*Y642500D01*

+Y644750D02*X110900Y645500D01*

+X111650D01*

+X112400Y644750D01*

+Y642500D01*

+X109400Y645500D02*X110150Y644750D01*

+X114950Y648500D02*Y643250D01*

+X115700Y642500D01*

+X114200Y646250D02*X115700D01*

+X95000Y639250D02*X117200D01*

+X130750Y648500D02*Y642500D01*

+X130000Y648500D02*X133000D01*

+X133750Y647750D01*

+Y646250D01*

+X133000Y645500D02*X133750Y646250D01*

+X130750Y645500D02*X133000D01*

+X135550Y648500D02*Y643250D01*

+X136300Y642500D01*

+X140050Y645500D02*X140800Y644750D01*

+X138550Y645500D02*X140050D01*

+X137800Y644750D02*X138550Y645500D01*

+X137800Y644750D02*Y643250D01*

+X138550Y642500D01*

+X140800Y645500D02*Y643250D01*

+X141550Y642500D01*

+X138550D02*X140050D01*

+X140800Y643250D01*

+X144100Y648500D02*Y643250D01*

+X144850Y642500D01*

+X143350Y646250D02*X144850D01*

+X147100Y642500D02*X149350D01*

+X146350Y643250D02*X147100Y642500D01*

+X146350Y644750D02*Y643250D01*

+Y644750D02*X147100Y645500D01*

+X148600D01*

+X149350Y644750D01*

+X146350Y644000D02*X149350D01*

+Y644750D02*Y644000D01*

+X154150Y648500D02*Y642500D01*

+X153400D02*X154150Y643250D01*

+X151900Y642500D02*X153400D01*

+X151150Y643250D02*X151900Y642500D01*

+X151150Y644750D02*Y643250D01*

+Y644750D02*X151900Y645500D01*

+X153400D01*

+X154150Y644750D01*

+X157450Y645500D02*Y644750D01*

+Y643250D02*Y642500D01*

+X155950Y647750D02*Y647000D01*

+Y647750D02*X156700Y648500D01*

+X158200D01*

+X158950Y647750D01*

+Y647000D01*

+X157450Y645500D02*X158950Y647000D01*

+X130000Y639250D02*X160750D01*

+X0Y663500D02*X3000D01*

+X1500D02*Y657500D01*

+X4800Y663500D02*Y657500D01*

+Y659750D02*X5550Y660500D01*

+X7050D01*

+X7800Y659750D01*

+Y657500D01*

+X10350D02*X12600D01*

+X9600Y658250D02*X10350Y657500D01*

+X9600Y659750D02*Y658250D01*

+Y659750D02*X10350Y660500D01*

+X11850D01*

+X12600Y659750D01*

+X9600Y659000D02*X12600D01*

+Y659750D02*Y659000D01*

+X15150Y659750D02*Y657500D01*

+Y659750D02*X15900Y660500D01*

+X17400D01*

+X14400D02*X15150Y659750D01*

+X19950Y657500D02*X22200D01*

+X19200Y658250D02*X19950Y657500D01*

+X19200Y659750D02*Y658250D01*

+Y659750D02*X19950Y660500D01*

+X21450D01*

+X22200Y659750D01*

+X19200Y659000D02*X22200D01*

+Y659750D02*Y659000D01*

+X28950Y660500D02*X29700Y659750D01*

+X27450Y660500D02*X28950D01*

+X26700Y659750D02*X27450Y660500D01*

+X26700Y659750D02*Y658250D01*

+X27450Y657500D01*

+X29700Y660500D02*Y658250D01*

+X30450Y657500D01*

+X27450D02*X28950D01*

+X29700Y658250D01*

+X33000Y659750D02*Y657500D01*

+Y659750D02*X33750Y660500D01*

+X35250D01*

+X32250D02*X33000Y659750D01*

+X37800Y657500D02*X40050D01*

+X37050Y658250D02*X37800Y657500D01*

+X37050Y659750D02*Y658250D01*

+Y659750D02*X37800Y660500D01*

+X39300D01*

+X40050Y659750D01*

+X37050Y659000D02*X40050D01*

+Y659750D02*Y659000D01*

+X45300Y657500D02*X47550Y660500D01*

+Y662750D02*Y660500D01*

+X46800Y663500D02*X47550Y662750D01*

+X45300Y663500D02*X46800D01*

+X44550Y662750D02*X45300Y663500D01*

+X44550Y662750D02*Y661250D01*

+X45300Y660500D01*

+X47550D01*

+X55050Y663500D02*Y657500D01*

+X54300D02*X55050Y658250D01*

+X52800Y657500D02*X54300D01*

+X52050Y658250D02*X52800Y657500D01*

+X52050Y659750D02*Y658250D01*

+Y659750D02*X52800Y660500D01*

+X54300D01*

+X55050Y659750D01*

+G54D219*X56850Y662000D02*Y661850D01*

+G54D218*Y659750D02*Y657500D01*

+X59100Y662750D02*Y657500D01*

+Y662750D02*X59850Y663500D01*

+X60600D01*

+X58350Y660500D02*X59850D01*

+X62850Y662750D02*Y657500D01*

+Y662750D02*X63600Y663500D01*

+X64350D01*

+X62100Y660500D02*X63600D01*

+X66600Y657500D02*X68850D01*

+X65850Y658250D02*X66600Y657500D01*

+X65850Y659750D02*Y658250D01*

+Y659750D02*X66600Y660500D01*

+X68100D01*

+X68850Y659750D01*

+X65850Y659000D02*X68850D01*

+Y659750D02*Y659000D01*

+X71400Y659750D02*Y657500D01*

+Y659750D02*X72150Y660500D01*

+X73650D01*

+X70650D02*X71400Y659750D01*

+X76200Y657500D02*X78450D01*

+X75450Y658250D02*X76200Y657500D01*

+X75450Y659750D02*Y658250D01*

+Y659750D02*X76200Y660500D01*

+X77700D01*

+X78450Y659750D01*

+X75450Y659000D02*X78450D01*

+Y659750D02*Y659000D01*

+X81000Y659750D02*Y657500D01*

+Y659750D02*X81750Y660500D01*

+X82500D01*

+X83250Y659750D01*

+Y657500D01*

+X80250Y660500D02*X81000Y659750D01*

+X85800Y663500D02*Y658250D01*

+X86550Y657500D01*

+X85050Y661250D02*X86550D01*

+X93750Y663500D02*Y657500D01*

+X93000D02*X93750Y658250D01*

+X91500Y657500D02*X93000D01*

+X90750Y658250D02*X91500Y657500D01*

+X90750Y659750D02*Y658250D01*

+Y659750D02*X91500Y660500D01*

+X93000D01*

+X93750Y659750D01*

+X96300D02*Y657500D01*

+Y659750D02*X97050Y660500D01*

+X98550D01*

+X95550D02*X96300Y659750D01*

+G54D219*X100350Y662000D02*Y661850D01*

+G54D218*Y659750D02*Y657500D01*

+X101850Y663500D02*Y658250D01*

+X102600Y657500D01*

+X104100Y663500D02*Y658250D01*

+X104850Y657500D01*

+X109800D02*X112050D01*

+X112800Y658250D01*

+X112050Y659000D02*X112800Y658250D01*

+X109800Y659000D02*X112050D01*

+X109050Y659750D02*X109800Y659000D01*

+X109050Y659750D02*X109800Y660500D01*

+X112050D01*

+X112800Y659750D01*

+X109050Y658250D02*X109800Y657500D01*

+G54D219*X114600Y662000D02*Y661850D01*

+G54D218*Y659750D02*Y657500D01*

+X116100Y660500D02*X119100D01*

+X116100Y657500D02*X119100Y660500D01*

+X116100Y657500D02*X119100D01*

+X121650D02*X123900D01*

+X120900Y658250D02*X121650Y657500D01*

+X120900Y659750D02*Y658250D01*

+Y659750D02*X121650Y660500D01*

+X123150D01*

+X123900Y659750D01*

+X120900Y659000D02*X123900D01*

+Y659750D02*Y659000D01*

+X126450Y657500D02*X128700D01*

+X129450Y658250D01*

+X128700Y659000D02*X129450Y658250D01*

+X126450Y659000D02*X128700D01*

+X125700Y659750D02*X126450Y659000D01*

+X125700Y659750D02*X126450Y660500D01*

+X128700D01*

+X129450Y659750D01*

+X125700Y658250D02*X126450Y657500D01*

+X133950Y660500D02*Y658250D01*

+X134700Y657500D01*

+X136200D01*

+X136950Y658250D01*

+Y660500D02*Y658250D01*

+X139500Y657500D02*X141750D01*

+X142500Y658250D01*

+X141750Y659000D02*X142500Y658250D01*

+X139500Y659000D02*X141750D01*

+X138750Y659750D02*X139500Y659000D01*

+X138750Y659750D02*X139500Y660500D01*

+X141750D01*

+X142500Y659750D01*

+X138750Y658250D02*X139500Y657500D01*

+X145050D02*X147300D01*

+X144300Y658250D02*X145050Y657500D01*

+X144300Y659750D02*Y658250D01*

+Y659750D02*X145050Y660500D01*

+X146550D01*

+X147300Y659750D01*

+X144300Y659000D02*X147300D01*

+Y659750D02*Y659000D01*

+X152100Y663500D02*Y657500D01*

+X151350D02*X152100Y658250D01*

+X149850Y657500D02*X151350D01*

+X149100Y658250D02*X149850Y657500D01*

+X149100Y659750D02*Y658250D01*

+Y659750D02*X149850Y660500D01*

+X151350D01*

+X152100Y659750D01*

+G54D219*X156600Y662000D02*Y661850D01*

+G54D218*Y659750D02*Y657500D01*

+X158850Y659750D02*Y657500D01*

+Y659750D02*X159600Y660500D01*

+X160350D01*

+X161100Y659750D01*

+Y657500D01*

+X158100Y660500D02*X158850Y659750D01*

+X166350Y663500D02*Y658250D01*

+X167100Y657500D01*

+X165600Y661250D02*X167100D01*

+X168600Y663500D02*Y657500D01*

+Y659750D02*X169350Y660500D01*

+X170850D01*

+X171600Y659750D01*

+Y657500D01*

+G54D219*X173400Y662000D02*Y661850D01*

+G54D218*Y659750D02*Y657500D01*

+X175650D02*X177900D01*

+X178650Y658250D01*

+X177900Y659000D02*X178650Y658250D01*

+X175650Y659000D02*X177900D01*

+X174900Y659750D02*X175650Y659000D01*

+X174900Y659750D02*X175650Y660500D01*

+X177900D01*

+X178650Y659750D01*

+X174900Y658250D02*X175650Y657500D01*

+X183150Y663500D02*Y658250D01*

+X183900Y657500D01*

+X187650Y660500D02*X188400Y659750D01*

+X186150Y660500D02*X187650D01*

+X185400Y659750D02*X186150Y660500D01*

+X185400Y659750D02*Y658250D01*

+X186150Y657500D01*

+X188400Y660500D02*Y658250D01*

+X189150Y657500D01*

+X186150D02*X187650D01*

+X188400Y658250D01*

+X190950Y660500D02*Y658250D01*

+X191700Y657500D01*

+X193950Y660500D02*Y656000D01*

+X193200Y655250D02*X193950Y656000D01*

+X191700Y655250D02*X193200D01*

+X190950Y656000D02*X191700Y655250D01*

+Y657500D02*X193200D01*

+X193950Y658250D01*

+X195750Y659750D02*Y658250D01*

+Y659750D02*X196500Y660500D01*

+X198000D01*

+X198750Y659750D01*

+Y658250D01*

+X198000Y657500D02*X198750Y658250D01*

+X196500Y657500D02*X198000D01*

+X195750Y658250D02*X196500Y657500D01*

+X200550Y660500D02*Y658250D01*

+X201300Y657500D01*

+X202800D01*

+X203550Y658250D01*

+Y660500D02*Y658250D01*

+X206100Y663500D02*Y658250D01*

+X206850Y657500D01*

+X205350Y661250D02*X206850D01*

+X208350Y656000D02*X209850Y657500D01*

+X214350Y662750D02*X215100Y663500D01*

+X217350D01*

+X218100Y662750D01*

+Y661250D01*

+X214350Y657500D02*X218100Y661250D01*

+X214350Y657500D02*X218100D01*

+X219900Y658250D02*X220650Y657500D01*

+X219900Y659450D02*Y658250D01*

+Y659450D02*X220950Y660500D01*

+X221850D01*

+X222900Y659450D01*

+Y658250D01*

+X222150Y657500D02*X222900Y658250D01*

+X220650Y657500D02*X222150D01*

+X219900Y661550D02*X220950Y660500D01*

+X219900Y662750D02*Y661550D01*

+Y662750D02*X220650Y663500D01*

+X222150D01*

+X222900Y662750D01*

+Y661550D01*

+X221850Y660500D02*X222900Y661550D01*

+X224700Y658250D02*X225450Y657500D01*

+X224700Y662750D02*Y658250D01*

+Y662750D02*X225450Y663500D01*

+X226950D01*

+X227700Y662750D01*

+Y658250D01*

+X226950Y657500D02*X227700Y658250D01*

+X225450Y657500D02*X226950D01*

+X224700Y659000D02*X227700Y662000D01*

+X232200Y663500D02*Y657500D01*

+Y659750D02*X232950Y660500D01*

+X234450D01*

+X235200Y659750D01*

+Y657500D01*

+X237000Y659750D02*Y658250D01*

+Y659750D02*X237750Y660500D01*

+X239250D01*

+X240000Y659750D01*

+Y658250D01*

+X239250Y657500D02*X240000Y658250D01*

+X237750Y657500D02*X239250D01*

+X237000Y658250D02*X237750Y657500D01*

+X241800Y663500D02*Y658250D01*

+X242550Y657500D01*

+X244800D02*X247050D01*

+X244050Y658250D02*X244800Y657500D01*

+X244050Y659750D02*Y658250D01*

+Y659750D02*X244800Y660500D01*

+X246300D01*

+X247050Y659750D01*

+X244050Y659000D02*X247050D01*

+Y659750D02*Y659000D01*

+X249600Y657500D02*X251850D01*

+X252600Y658250D01*

+X251850Y659000D02*X252600Y658250D01*

+X249600Y659000D02*X251850D01*

+X248850Y659750D02*X249600Y659000D01*

+X248850Y659750D02*X249600Y660500D01*

+X251850D01*

+X252600Y659750D01*

+X248850Y658250D02*X249600Y657500D01*

+X257850Y663500D02*Y658250D01*

+X258600Y657500D01*

+X257100Y661250D02*X258600D01*

+X260100Y659750D02*Y658250D01*

+Y659750D02*X260850Y660500D01*

+X262350D01*

+X263100Y659750D01*

+Y658250D01*

+X262350Y657500D02*X263100Y658250D01*

+X260850Y657500D02*X262350D01*

+X260100Y658250D02*X260850Y657500D01*

+X265650Y663500D02*Y658250D01*

+X266400Y657500D01*

+X264900Y661250D02*X266400D01*

+X270150Y660500D02*X270900Y659750D01*

+X268650Y660500D02*X270150D01*

+X267900Y659750D02*X268650Y660500D01*

+X267900Y659750D02*Y658250D01*

+X268650Y657500D01*

+X270900Y660500D02*Y658250D01*

+X271650Y657500D01*

+X268650D02*X270150D01*

+X270900Y658250D01*

+X273450Y663500D02*Y658250D01*

+X274200Y657500D01*

+G54D220*X714000Y390000D02*Y202000D01*

+X131000Y392500D02*X711500D01*

+X131000Y199500D02*X711500D01*

+X128500Y390000D02*Y202000D01*

+X711500Y392500D02*G75*G02X714000Y390000I0J-2500D01*G01*

+Y202000D02*G75*G02X711500Y199500I-2500J0D01*G01*

+X128500Y390000D02*G75*G02X131000Y392500I2500J0D01*G01*

+Y199500D02*G75*G02X128500Y202000I0J2500D01*G01*

+G54D218*X363675Y-9500D02*X366675D01*

+X367425Y-8750D01*

+Y-6950D02*Y-8750D01*

+X366675Y-6200D02*X367425Y-6950D01*

+X364425Y-6200D02*X366675D01*

+X364425Y-3500D02*Y-9500D01*

+X363675Y-3500D02*X366675D01*

+X367425Y-4250D01*

+Y-5450D01*

+X366675Y-6200D02*X367425Y-5450D01*

+X369225Y-7250D02*Y-8750D01*

+Y-7250D02*X369975Y-6500D01*

+X371475D01*

+X372225Y-7250D01*

+Y-8750D01*

+X371475Y-9500D02*X372225Y-8750D01*

+X369975Y-9500D02*X371475D01*

+X369225Y-8750D02*X369975Y-9500D01*

+X376275Y-6500D02*X377025Y-7250D01*

+X374775Y-6500D02*X376275D01*

+X374025Y-7250D02*X374775Y-6500D01*

+X374025Y-7250D02*Y-8750D01*

+X374775Y-9500D01*

+X377025Y-6500D02*Y-8750D01*

+X377775Y-9500D01*

+X374775D02*X376275D01*

+X377025Y-8750D01*

+X380325Y-7250D02*Y-9500D01*

+Y-7250D02*X381075Y-6500D01*

+X382575D01*

+X379575D02*X380325Y-7250D01*

+X387375Y-3500D02*Y-9500D01*

+X386625D02*X387375Y-8750D01*

+X385125Y-9500D02*X386625D01*

+X384375Y-8750D02*X385125Y-9500D01*

+X384375Y-7250D02*Y-8750D01*

+Y-7250D02*X385125Y-6500D01*

+X386625D01*

+X387375Y-7250D01*

+X391875D02*Y-8750D01*

+Y-7250D02*X392625Y-6500D01*

+X394125D01*

+X394875Y-7250D01*

+Y-8750D01*

+X394125Y-9500D02*X394875Y-8750D01*

+X392625Y-9500D02*X394125D01*

+X391875Y-8750D02*X392625Y-9500D01*

+X396675Y-6500D02*Y-8750D01*

+X397425Y-9500D01*

+X398925D01*

+X399675Y-8750D01*

+Y-6500D02*Y-8750D01*

+X402225Y-3500D02*Y-8750D01*

+X402975Y-9500D01*

+X401475Y-5750D02*X402975D01*

+X404475Y-3500D02*Y-8750D01*

+X405225Y-9500D01*

+G54D219*X406725Y-5000D02*Y-5150D01*

+G54D218*Y-7250D02*Y-9500D01*

+X408975Y-7250D02*Y-9500D01*

+Y-7250D02*X409725Y-6500D01*

+X410475D01*

+X411225Y-7250D01*

+Y-9500D01*

+X408225Y-6500D02*X408975Y-7250D01*

+X413775Y-9500D02*X416025D01*

+X413025Y-8750D02*X413775Y-9500D01*

+X413025Y-7250D02*Y-8750D01*

+Y-7250D02*X413775Y-6500D01*

+X415275D01*

+X416025Y-7250D01*

+X413025Y-8000D02*X416025D01*

+Y-7250D02*Y-8000D01*

+G54D219*X420525Y-5000D02*Y-5150D01*

+G54D218*Y-7250D02*Y-9500D01*

+X422775D02*X425025D01*

+X425775Y-8750D01*

+X425025Y-8000D02*X425775Y-8750D01*

+X422775Y-8000D02*X425025D01*

+X422025Y-7250D02*X422775Y-8000D01*

+X422025Y-7250D02*X422775Y-6500D01*

+X425025D01*

+X425775Y-7250D01*

+X422025Y-8750D02*X422775Y-9500D01*

+X431025Y-3500D02*Y-8750D01*

+X431775Y-9500D01*

+X430275Y-5750D02*X431775D01*

+X433275Y-3500D02*Y-9500D01*

+Y-7250D02*X434025Y-6500D01*

+X435525D01*

+X436275Y-7250D01*

+Y-9500D01*

+X438825D02*X441075D01*

+X438075Y-8750D02*X438825Y-9500D01*

+X438075Y-7250D02*Y-8750D01*

+Y-7250D02*X438825Y-6500D01*

+X440325D01*

+X441075Y-7250D01*

+X438075Y-8000D02*X441075D01*

+Y-7250D02*Y-8000D01*

+X446325Y-6500D02*X448575D01*

+X445575Y-7250D02*X446325Y-6500D01*

+X445575Y-7250D02*Y-8750D01*

+X446325Y-9500D01*

+X448575D01*

+X451125D02*X453375D01*

+X450375Y-8750D02*X451125Y-9500D01*

+X450375Y-7250D02*Y-8750D01*

+Y-7250D02*X451125Y-6500D01*

+X452625D01*

+X453375Y-7250D01*

+X450375Y-8000D02*X453375D01*

+Y-7250D02*Y-8000D01*

+X455925Y-7250D02*Y-9500D01*

+Y-7250D02*X456675Y-6500D01*

+X457425D01*

+X458175Y-7250D01*

+Y-9500D01*

+X455175Y-6500D02*X455925Y-7250D01*

+X460725Y-3500D02*Y-8750D01*

+X461475Y-9500D01*

+X459975Y-5750D02*X461475D01*

+X463725Y-9500D02*X465975D01*

+X462975Y-8750D02*X463725Y-9500D01*

+X462975Y-7250D02*Y-8750D01*

+Y-7250D02*X463725Y-6500D01*

+X465225D01*

+X465975Y-7250D01*

+X462975Y-8000D02*X465975D01*

+Y-7250D02*Y-8000D01*

+X468525Y-7250D02*Y-9500D01*

+Y-7250D02*X469275Y-6500D01*

+X470775D01*

+X467775D02*X468525Y-7250D01*

+X472575Y-3500D02*Y-8750D01*

+X473325Y-9500D01*

+G54D219*X474825Y-5000D02*Y-5150D01*

+G54D218*Y-7250D02*Y-9500D01*

+X477075Y-7250D02*Y-9500D01*

+Y-7250D02*X477825Y-6500D01*

+X478575D01*

+X479325Y-7250D01*

+Y-9500D01*

+X476325Y-6500D02*X477075Y-7250D01*

+X481875Y-9500D02*X484125D01*

+X481125Y-8750D02*X481875Y-9500D01*

+X481125Y-7250D02*Y-8750D01*

+Y-7250D02*X481875Y-6500D01*

+X483375D01*

+X484125Y-7250D01*

+X481125Y-8000D02*X484125D01*

+Y-7250D02*Y-8000D01*

+X488625Y-7250D02*Y-8750D01*

+Y-7250D02*X489375Y-6500D01*

+X490875D01*

+X491625Y-7250D01*

+Y-8750D01*

+X490875Y-9500D02*X491625Y-8750D01*

+X489375Y-9500D02*X490875D01*

+X488625Y-8750D02*X489375Y-9500D01*

+X494175Y-4250D02*Y-9500D01*

+Y-4250D02*X494925Y-3500D01*

+X495675D01*

+X493425Y-6500D02*X494925D01*

+X500625Y-3500D02*Y-8750D01*

+X501375Y-9500D01*

+X499875Y-5750D02*X501375D01*

+X502875Y-3500D02*Y-9500D01*

+Y-7250D02*X503625Y-6500D01*

+X505125D01*

+X505875Y-7250D01*

+Y-9500D01*

+G54D219*X507675Y-5000D02*Y-5150D01*

+G54D218*Y-7250D02*Y-9500D01*

+X509925D02*X512175D01*

+X512925Y-8750D01*

+X512175Y-8000D02*X512925Y-8750D01*

+X509925Y-8000D02*X512175D01*

+X509175Y-7250D02*X509925Y-8000D01*

+X509175Y-7250D02*X509925Y-6500D01*

+X512175D01*

+X512925Y-7250D01*

+X509175Y-8750D02*X509925Y-9500D01*

+X518175Y-7250D02*Y-11750D01*

+X517425Y-6500D02*X518175Y-7250D01*

+X518925Y-6500D01*

+X520425D01*

+X521175Y-7250D01*

+Y-8750D01*

+X520425Y-9500D02*X521175Y-8750D01*

+X518925Y-9500D02*X520425D01*

+X518175Y-8750D02*X518925Y-9500D01*

+X525225Y-6500D02*X525975Y-7250D01*

+X523725Y-6500D02*X525225D01*

+X522975Y-7250D02*X523725Y-6500D01*

+X522975Y-7250D02*Y-8750D01*

+X523725Y-9500D01*

+X525975Y-6500D02*Y-8750D01*

+X526725Y-9500D01*

+X523725D02*X525225D01*

+X525975Y-8750D01*

+X529275Y-3500D02*Y-8750D01*

+X530025Y-9500D01*

+X528525Y-5750D02*X530025D01*

+X531525Y-3500D02*Y-9500D01*

+Y-7250D02*X532275Y-6500D01*

+X533775D01*

+X534525Y-7250D01*

+Y-9500D01*

+X200750Y528500D02*Y522500D01*

+X202700Y528500D02*X203750Y527450D01*

+Y523550D01*

+X202700Y522500D02*X203750Y523550D01*

+X200000Y522500D02*X202700D01*

+X200000Y528500D02*X202700D01*

+X207800Y525500D02*X208550Y524750D01*

+X206300Y525500D02*X207800D01*

+X205550Y524750D02*X206300Y525500D01*

+X205550Y524750D02*Y523250D01*

+X206300Y522500D01*

+X208550Y525500D02*Y523250D01*

+X209300Y522500D01*

+X206300D02*X207800D01*

+X208550Y523250D01*

+X211850Y528500D02*Y523250D01*

+X212600Y522500D01*

+X211100Y526250D02*X212600D01*

+X214850Y522500D02*X217100D01*

+X214100Y523250D02*X214850Y522500D01*

+X214100Y524750D02*Y523250D01*

+Y524750D02*X214850Y525500D01*

+X216350D01*

+X217100Y524750D01*

+X214100Y524000D02*X217100D01*

+Y524750D02*Y524000D01*

+X218900Y526250D02*X219650D01*

+X218900Y524750D02*X219650D01*

+X224150Y528500D02*Y525500D01*

+X224900Y522500D01*

+X226400Y525500D01*

+X227900Y522500D01*

+X228650Y525500D01*

+Y528500D02*Y525500D01*

+X231200Y522500D02*X233450D01*

+X230450Y523250D02*X231200Y522500D01*

+X230450Y524750D02*Y523250D01*

+Y524750D02*X231200Y525500D01*

+X232700D01*

+X233450Y524750D01*

+X230450Y524000D02*X233450D01*

+Y524750D02*Y524000D01*

+X238250Y528500D02*Y522500D01*

+X237500D02*X238250Y523250D01*

+X236000Y522500D02*X237500D01*

+X235250Y523250D02*X236000Y522500D01*

+X235250Y524750D02*Y523250D01*

+Y524750D02*X236000Y525500D01*

+X237500D01*

+X238250Y524750D01*

+X242750Y527300D02*X243950Y528500D01*

+Y522500D01*

+X242750D02*X245000D01*

+X249050Y528500D02*X249800Y527750D01*

+X247550Y528500D02*X249050D01*

+X246800Y527750D02*X247550Y528500D01*

+X246800Y527750D02*Y523250D01*

+X247550Y522500D01*

+X249050Y525800D02*X249800Y525050D01*

+X246800Y525800D02*X249050D01*

+X247550Y522500D02*X249050D01*

+X249800Y523250D01*

+Y525050D02*Y523250D01*

+X255350Y528500D02*X256550D01*

+Y523250D01*

+X255800Y522500D02*X256550Y523250D01*

+X255050Y522500D02*X255800D01*

+X254300Y523250D02*X255050Y522500D01*

+X254300Y524000D02*Y523250D01*

+X260600Y525500D02*X261350Y524750D01*

+X259100Y525500D02*X260600D01*

+X258350Y524750D02*X259100Y525500D01*

+X258350Y524750D02*Y523250D01*

+X259100Y522500D01*

+X261350Y525500D02*Y523250D01*

+X262100Y522500D01*

+X259100D02*X260600D01*

+X261350Y523250D01*

+X264650Y524750D02*Y522500D01*

+Y524750D02*X265400Y525500D01*

+X266150D01*

+X266900Y524750D01*

+Y522500D01*

+X263900Y525500D02*X264650Y524750D01*

+X271400Y527750D02*X272150Y528500D01*

+X274400D01*

+X275150Y527750D01*

+Y526250D01*

+X271400Y522500D02*X275150Y526250D01*

+X271400Y522500D02*X275150D01*

+X276950Y523250D02*X277700Y522500D01*

+X276950Y527750D02*Y523250D01*

+Y527750D02*X277700Y528500D01*

+X279200D01*

+X279950Y527750D01*

+Y523250D01*

+X279200Y522500D02*X279950Y523250D01*

+X277700Y522500D02*X279200D01*

+X276950Y524000D02*X279950Y527000D01*

+X281750Y527300D02*X282950Y528500D01*

+Y522500D01*

+X281750D02*X284000D01*

+X286550D02*X288800Y525500D01*

+Y527750D02*Y525500D01*

+X288050Y528500D02*X288800Y527750D01*

+X286550Y528500D02*X288050D01*

+X285800Y527750D02*X286550Y528500D01*

+X285800Y527750D02*Y526250D01*

+X286550Y525500D01*

+X288800D01*

+X293300Y523250D02*X294050Y522500D01*

+X293300Y527750D02*Y523250D01*

+Y527750D02*X294050Y528500D01*

+X295550D01*

+X296300Y527750D01*

+Y523250D01*

+X295550Y522500D02*X296300Y523250D01*

+X294050Y522500D02*X295550D01*

+X293300Y524000D02*X296300Y527000D01*

+X298850Y522500D02*X301850Y528500D01*

+X298100D02*X301850D01*

+X303650Y526250D02*X304400D01*

+X303650Y524750D02*X304400D01*

+X306200Y528500D02*X309200D01*

+X306200D02*Y525500D01*

+X306950Y526250D01*

+X308450D01*

+X309200Y525500D01*

+Y523250D01*

+X308450Y522500D02*X309200Y523250D01*

+X306950Y522500D02*X308450D01*

+X306200Y523250D02*X306950Y522500D01*

+X311000Y523250D02*X311750Y522500D01*

+X311000Y527750D02*Y523250D01*

+Y527750D02*X311750Y528500D01*

+X313250D01*

+X314000Y527750D01*

+Y523250D01*

+X313250Y522500D02*X314000Y523250D01*

+X311750Y522500D02*X313250D01*

+X311000Y524000D02*X314000Y527000D01*

+X315800Y526250D02*X316550D01*

+X315800Y524750D02*X316550D01*

+X318350Y527750D02*X319100Y528500D01*

+X320600D01*

+X321350Y527750D01*

+X320600Y522500D02*X321350Y523250D01*

+X319100Y522500D02*X320600D01*

+X318350Y523250D02*X319100Y522500D01*

+Y525800D02*X320600D01*

+X321350Y527750D02*Y526550D01*

+Y525050D02*Y523250D01*

+Y525050D02*X320600Y525800D01*

+X321350Y526550D02*X320600Y525800D01*

+X323150Y524750D02*X326150Y528500D01*

+X323150Y524750D02*X326900D01*

+X326150Y528500D02*Y522500D01*

+X331400Y527000D02*Y522500D01*

+Y527000D02*X332450Y528500D01*

+X334100D01*

+X335150Y527000D01*

+Y522500D01*

+X331400Y525500D02*X335150D01*

+X336950Y528500D02*Y522500D01*

+Y528500D02*X339200Y525500D01*

+X341450Y528500D01*

+Y522500D01*

+X348950Y528500D02*X349700Y527750D01*

+X346700Y528500D02*X348950D01*

+X345950Y527750D02*X346700Y528500D01*

+X345950Y527750D02*Y523250D01*

+X346700Y522500D01*

+X348950D01*

+X349700Y523250D01*

+Y524750D02*Y523250D01*

+X348950Y525500D02*X349700Y524750D01*

+X347450Y525500D02*X348950D01*

+X351500Y528500D02*Y522500D01*

+Y528500D02*X353750Y525500D01*

+X356000Y528500D01*

+Y522500D01*

+X357800Y528500D02*X360800D01*

+X359300D02*Y522500D01*

+X365300Y528500D02*Y523250D01*

+X366050Y522500D01*

+X367550D01*

+X368300Y523250D01*

+Y528500D02*Y523250D01*

+X370100Y528500D02*X373100D01*

+X371600D02*Y522500D01*

+X375950D02*X377900D01*

+X374900Y523550D02*X375950Y522500D01*

+X374900Y527450D02*Y523550D01*

+Y527450D02*X375950Y528500D01*

+X377900D01*

+X200000Y542000D02*Y537500D01*

+Y542000D02*X201050Y543500D01*

+X202700D01*

+X203750Y542000D01*

+Y537500D01*

+X200000Y540500D02*X203750D01*

+X205550D02*Y538250D01*

+X206300Y537500D01*

+X207800D01*

+X208550Y538250D01*

+Y540500D02*Y538250D01*

+X211100Y543500D02*Y538250D01*

+X211850Y537500D01*

+X210350Y541250D02*X211850D01*

+X213350Y543500D02*Y537500D01*

+Y539750D02*X214100Y540500D01*

+X215600D01*

+X216350Y539750D01*

+Y537500D01*

+X218150Y539750D02*Y538250D01*

+Y539750D02*X218900Y540500D01*

+X220400D01*

+X221150Y539750D01*

+Y538250D01*

+X220400Y537500D02*X221150Y538250D01*

+X218900Y537500D02*X220400D01*

+X218150Y538250D02*X218900Y537500D01*

+X223700Y539750D02*Y537500D01*

+Y539750D02*X224450Y540500D01*

+X225950D01*

+X222950D02*X223700Y539750D01*

+X227750Y541250D02*X228500D01*

+X227750Y539750D02*X228500D01*

+X233000Y537500D02*X236000D01*

+X236750Y538250D01*

+Y540050D02*Y538250D01*

+X236000Y540800D02*X236750Y540050D01*

+X233750Y540800D02*X236000D01*

+X233750Y543500D02*Y537500D01*

+X233000Y543500D02*X236000D01*

+X236750Y542750D01*

+Y541550D01*

+X236000Y540800D02*X236750Y541550D01*

+X239300Y539750D02*Y537500D01*

+Y539750D02*X240050Y540500D01*

+X241550D01*

+X238550D02*X239300Y539750D01*

+G54D219*X243350Y542000D02*Y541850D01*

+G54D218*Y539750D02*Y537500D01*

+X247100Y540500D02*X247850Y539750D01*

+X245600Y540500D02*X247100D01*

+X244850Y539750D02*X245600Y540500D01*

+X244850Y539750D02*Y538250D01*

+X245600Y537500D01*

+X247850Y540500D02*Y538250D01*

+X248600Y537500D01*

+X245600D02*X247100D01*

+X247850Y538250D01*

+X251150Y539750D02*Y537500D01*

+Y539750D02*X251900Y540500D01*

+X252650D01*

+X253400Y539750D01*

+Y537500D01*

+X250400Y540500D02*X251150Y539750D01*

+X260900Y543500D02*X261650Y542750D01*

+X258650Y543500D02*X260900D01*

+X257900Y542750D02*X258650Y543500D01*

+X257900Y542750D02*Y541250D01*

+X258650Y540500D01*

+X260900D01*

+X261650Y539750D01*

+Y538250D01*

+X260900Y537500D02*X261650Y538250D01*

+X258650Y537500D02*X260900D01*

+X257900Y538250D02*X258650Y537500D01*

+G54D219*X263450Y542000D02*Y541850D01*

+G54D218*Y539750D02*Y537500D01*

+X264950Y543500D02*Y538250D01*

+X265700Y537500D01*

+X267200Y540500D02*X268700Y537500D01*

+X270200Y540500D02*X268700Y537500D01*

+X272750D02*X275000D01*

+X272000Y538250D02*X272750Y537500D01*

+X272000Y539750D02*Y538250D01*

+Y539750D02*X272750Y540500D01*

+X274250D01*

+X275000Y539750D01*

+X272000Y539000D02*X275000D01*

+Y539750D02*Y539000D01*

+X277550Y539750D02*Y537500D01*

+Y539750D02*X278300Y540500D01*

+X279800D01*

+X276800D02*X277550Y539750D01*

+X282350D02*Y537500D01*

+Y539750D02*X283100Y540500D01*

+X283850D01*

+X284600Y539750D01*

+Y537500D01*

+Y539750D02*X285350Y540500D01*

+X286100D01*

+X286850Y539750D01*

+Y537500D01*

+X281600Y540500D02*X282350Y539750D01*

+X290900Y540500D02*X291650Y539750D01*

+X289400Y540500D02*X290900D01*

+X288650Y539750D02*X289400Y540500D01*

+X288650Y539750D02*Y538250D01*

+X289400Y537500D01*

+X291650Y540500D02*Y538250D01*

+X292400Y537500D01*

+X289400D02*X290900D01*

+X291650Y538250D01*

+X294950Y539750D02*Y537500D01*

+Y539750D02*X295700Y540500D01*

+X296450D01*

+X297200Y539750D01*

+Y537500D01*

+X294200Y540500D02*X294950Y539750D01*

+X200000Y558500D02*X203000D01*

+X201500D02*Y552500D01*

+G54D219*X204800Y557000D02*Y556850D01*

+G54D218*Y554750D02*Y552500D01*

+X207050Y558500D02*Y553250D01*

+X207800Y552500D01*

+X206300Y556250D02*X207800D01*

+X209300Y558500D02*Y553250D01*

+X210050Y552500D01*

+X212300D02*X214550D01*

+X211550Y553250D02*X212300Y552500D01*

+X211550Y554750D02*Y553250D01*

+Y554750D02*X212300Y555500D01*

+X213800D01*

+X214550Y554750D01*

+X211550Y554000D02*X214550D01*

+Y554750D02*Y554000D01*

+X216350Y556250D02*X217100D01*

+X216350Y554750D02*X217100D01*

+X221600Y555500D02*Y553250D01*

+X222350Y552500D01*

+X223850D01*

+X224600Y553250D01*

+Y555500D02*Y553250D01*

+X228650Y555500D02*X229400Y554750D01*

+X227150Y555500D02*X228650D01*

+X226400Y554750D02*X227150Y555500D01*

+X226400Y554750D02*Y553250D01*

+X227150Y552500D01*

+X229400Y555500D02*Y553250D01*

+X230150Y552500D01*

+X227150D02*X228650D01*

+X229400Y553250D01*

+X232700Y554750D02*Y552500D01*

+Y554750D02*X233450Y555500D01*

+X234950D01*

+X231950D02*X232700Y554750D01*

+X237500Y558500D02*Y553250D01*

+X238250Y552500D01*

+X236750Y556250D02*X238250D01*

+X242450Y555500D02*X245450D01*

+X249950Y558500D02*Y552500D01*

+Y558500D02*X252950D01*

+X249950Y555800D02*X252200D01*

+X257000Y555500D02*X257750Y554750D01*

+X255500Y555500D02*X257000D01*

+X254750Y554750D02*X255500Y555500D01*

+X254750Y554750D02*Y553250D01*

+X255500Y552500D01*

+X257750Y555500D02*Y553250D01*

+X258500Y552500D01*

+X255500D02*X257000D01*

+X257750Y553250D01*

+X260300Y558500D02*Y552500D01*

+Y553250D02*X261050Y552500D01*

+X262550D01*

+X263300Y553250D01*

+Y554750D02*Y553250D01*

+X262550Y555500D02*X263300Y554750D01*

+X261050Y555500D02*X262550D01*

+X260300Y554750D02*X261050Y555500D01*

+X265850Y554750D02*Y552500D01*

+Y554750D02*X266600Y555500D01*

+X268100D01*

+X265100D02*X265850Y554750D01*

+G54D219*X269900Y557000D02*Y556850D01*

+G54D218*Y554750D02*Y552500D01*

+X272150Y555500D02*X274400D01*

+X271400Y554750D02*X272150Y555500D01*

+X271400Y554750D02*Y553250D01*

+X272150Y552500D01*

+X274400D01*

+X278450Y555500D02*X279200Y554750D01*

+X276950Y555500D02*X278450D01*

+X276200Y554750D02*X276950Y555500D01*

+X276200Y554750D02*Y553250D01*

+X276950Y552500D01*

+X279200Y555500D02*Y553250D01*

+X279950Y552500D01*

+X276950D02*X278450D01*

+X279200Y553250D01*

+X282500Y558500D02*Y553250D01*

+X283250Y552500D01*

+X281750Y556250D02*X283250D01*

+G54D219*X284750Y557000D02*Y556850D01*

+G54D218*Y554750D02*Y552500D01*

+X286250Y554750D02*Y553250D01*

+Y554750D02*X287000Y555500D01*

+X288500D01*

+X289250Y554750D01*

+Y553250D01*

+X288500Y552500D02*X289250Y553250D01*

+X287000Y552500D02*X288500D01*

+X286250Y553250D02*X287000Y552500D01*

+X291800Y554750D02*Y552500D01*

+Y554750D02*X292550Y555500D01*

+X293300D01*

+X294050Y554750D01*

+Y552500D01*

+X291050Y555500D02*X291800Y554750D01*

+X299300Y558500D02*Y552500D01*

+X301250Y558500D02*X302300Y557450D01*

+Y553550D01*

+X301250Y552500D02*X302300Y553550D01*

+X298550Y552500D02*X301250D01*

+X298550Y558500D02*X301250D01*

+X304850Y554750D02*Y552500D01*

+Y554750D02*X305600Y555500D01*

+X307100D01*

+X304100D02*X304850Y554750D01*

+X311150Y555500D02*X311900Y554750D01*

+X309650Y555500D02*X311150D01*

+X308900Y554750D02*X309650Y555500D01*

+X308900Y554750D02*Y553250D01*

+X309650Y552500D01*

+X311900Y555500D02*Y553250D01*

+X312650Y552500D01*

+X309650D02*X311150D01*

+X311900Y553250D01*

+X314450Y555500D02*Y553250D01*

+X315200Y552500D01*

+X315950D01*

+X316700Y553250D01*

+Y555500D02*Y553250D01*

+X317450Y552500D01*

+X318200D01*

+X318950Y553250D01*

+Y555500D02*Y553250D01*

+G54D219*X320750Y557000D02*Y556850D01*

+G54D218*Y554750D02*Y552500D01*

+X323000Y554750D02*Y552500D01*

+Y554750D02*X323750Y555500D01*

+X324500D01*

+X325250Y554750D01*

+Y552500D01*

+X322250Y555500D02*X323000Y554750D01*

+X329300Y555500D02*X330050Y554750D01*

+X327800Y555500D02*X329300D01*

+X327050Y554750D02*X327800Y555500D01*

+X327050Y554750D02*Y553250D01*

+X327800Y552500D01*

+X329300D01*

+X330050Y553250D01*

+X327050Y551000D02*X327800Y550250D01*

+X329300D01*

+X330050Y551000D01*

+Y555500D02*Y551000D01*

+M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.group1.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.group1.gbr
new file mode 100644
index 0000000..64d27bb
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.group1.gbr
@@ -0,0 +1,17163 @@
+G04 start of page 3 for group 1 idx 1 *

+G04 Title: uart, signal2 *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNGROUP1*%

+%ADD74C,0.0380*%

+%ADD73C,0.0906*%

+%ADD72C,0.0354*%

+%ADD71C,0.0118*%

+%ADD70C,0.1285*%

+%ADD69C,0.0433*%

+%ADD68C,0.0400*%

+%ADD67C,0.0118*%

+%ADD66C,0.0350*%

+%ADD65C,0.0250*%

+%ADD64C,0.0200*%

+%ADD63C,0.0240*%

+%ADD62C,0.0450*%

+%ADD61C,0.0360*%

+%ADD60C,0.0600*%

+%ADD59C,0.1063*%

+%ADD58C,0.0551*%

+%ADD57C,0.0256*%

+%ADD56C,0.1800*%

+%ADD55C,0.0630*%

+%ADD54C,0.0650*%

+%ADD53C,0.0001*%

+G54D53*G36*

+X586304Y390000D02*X587556D01*

+X587142Y389746D01*

+X586663Y389337D01*

+X586304Y388917D01*

+Y390000D01*

+G37*

+G36*

+X701500Y320500D02*X666104D01*

+Y348185D01*

+X666110Y348184D01*

+X666761Y348235D01*

+X667396Y348388D01*

+X668000Y348638D01*

+X668557Y348979D01*

+X669054Y349403D01*

+X669478Y349900D01*

+X669819Y350457D01*

+X670069Y351060D01*

+X670221Y351695D01*

+X670260Y352346D01*

+X670221Y352998D01*

+X670069Y353633D01*

+X669819Y354236D01*

+X669478Y354793D01*

+X669054Y355290D01*

+X668557Y355714D01*

+X668000Y356055D01*

+X667396Y356305D01*

+X666761Y356458D01*

+X666110Y356509D01*

+X666104Y356508D01*

+Y369838D01*

+X666110Y369838D01*

+X666761Y369889D01*

+X667396Y370041D01*

+X668000Y370291D01*

+X668557Y370633D01*

+X669054Y371057D01*

+X669478Y371553D01*

+X669819Y372110D01*

+X670069Y372714D01*

+X670221Y373349D01*

+X670260Y374000D01*

+X670221Y374651D01*

+X670069Y375286D01*

+X669819Y375890D01*

+X669478Y376447D01*

+X669054Y376943D01*

+X668557Y377367D01*

+X668000Y377709D01*

+X667396Y377959D01*

+X666761Y378111D01*

+X666110Y378162D01*

+X666104Y378162D01*

+Y390000D01*

+X701108D01*

+X699931Y389907D01*

+X698400Y389540D01*

+X696946Y388938D01*

+X695604Y388115D01*

+X694407Y387093D01*

+X693385Y385896D01*

+X692562Y384554D01*

+X691960Y383100D01*

+X691593Y381569D01*

+X691469Y380000D01*

+X691593Y378431D01*

+X691960Y376900D01*

+X692562Y375446D01*

+X693385Y374104D01*

+X694407Y372907D01*

+X695604Y371885D01*

+X696946Y371062D01*

+X698400Y370460D01*

+X699931Y370093D01*

+X701500Y369969D01*

+Y320500D01*

+G37*

+G36*

+X666104D02*X662500D01*

+Y340000D01*

+X646496D01*

+Y348993D01*

+X646500Y348992D01*

+X646892Y349023D01*

+X647275Y349115D01*

+X647638Y349266D01*

+X647974Y349471D01*

+X648273Y349727D01*

+X648529Y350026D01*

+X648734Y350362D01*

+X648885Y350725D01*

+X648977Y351108D01*

+X649000Y351500D01*

+X648977Y351892D01*

+X648885Y352275D01*

+X648734Y352638D01*

+X648529Y352974D01*

+X648273Y353273D01*

+X647974Y353529D01*

+X647638Y353734D01*

+X647275Y353885D01*

+X646892Y353977D01*

+X646500Y354008D01*

+X646496Y354007D01*

+Y360251D01*

+X652985Y360264D01*

+X653215Y360319D01*

+X653433Y360409D01*

+X653634Y360533D01*

+X653814Y360686D01*

+X653967Y360866D01*

+X654091Y361067D01*

+X654181Y361285D01*

+X654236Y361515D01*

+X654250Y361750D01*

+X654236Y368485D01*

+X654181Y368715D01*

+X654091Y368933D01*

+X653967Y369134D01*

+X653814Y369314D01*

+X653634Y369467D01*

+X653433Y369591D01*

+X653215Y369681D01*

+X652985Y369736D01*

+X652750Y369750D01*

+X646496Y369737D01*

+Y390000D01*

+X666104D01*

+Y378162D01*

+X665459Y378111D01*

+X664824Y377959D01*

+X664221Y377709D01*

+X663664Y377367D01*

+X663167Y376943D01*

+X662743Y376447D01*

+X662402Y375890D01*

+X662152Y375286D01*

+X661999Y374651D01*

+X661948Y374000D01*

+X661999Y373349D01*

+X662152Y372714D01*

+X662402Y372110D01*

+X662743Y371553D01*

+X663167Y371057D01*

+X663664Y370633D01*

+X664221Y370291D01*

+X664824Y370041D01*

+X665459Y369889D01*

+X666104Y369838D01*

+Y356508D01*

+X665459Y356458D01*

+X664824Y356305D01*

+X664221Y356055D01*

+X663664Y355714D01*

+X663167Y355290D01*

+X662743Y354793D01*

+X662402Y354236D01*

+X662152Y353633D01*

+X661999Y352998D01*

+X661948Y352346D01*

+X661999Y351695D01*

+X662152Y351060D01*

+X662402Y350457D01*

+X662743Y349900D01*

+X663167Y349403D01*

+X663664Y348979D01*

+X664221Y348638D01*

+X664824Y348388D01*

+X665459Y348235D01*

+X666104Y348185D01*

+Y320500D01*

+G37*

+G36*

+X593597Y324518D02*X593863Y324084D01*

+X594195Y323695D01*

+X594584Y323363D01*

+X595020Y323095D01*

+X595493Y322900D01*

+X595990Y322780D01*

+X596500Y322740D01*

+X597010Y322780D01*

+X597507Y322900D01*

+X597980Y323095D01*

+X598416Y323363D01*

+X598805Y323695D01*

+X599137Y324084D01*

+X599405Y324520D01*

+X599500Y324750D01*

+Y305500D01*

+X593597Y299597D01*

+Y324518D01*

+G37*

+G36*

+Y332018D02*X593863Y331584D01*

+X594195Y331195D01*

+X594584Y330863D01*

+X595020Y330595D01*

+X595493Y330400D01*

+X595990Y330280D01*

+X596500Y330240D01*

+X597010Y330280D01*

+X597507Y330400D01*

+X597980Y330595D01*

+X598416Y330863D01*

+X598805Y331195D01*

+X599137Y331584D01*

+X599405Y332020D01*

+X599500Y332250D01*

+Y327250D01*

+X599405Y327480D01*

+X599137Y327916D01*

+X598805Y328305D01*

+X598416Y328637D01*

+X597980Y328905D01*

+X597507Y329100D01*

+X597010Y329220D01*

+X596500Y329260D01*

+X595990Y329220D01*

+X595493Y329100D01*

+X595020Y328905D01*

+X594584Y328637D01*

+X594195Y328305D01*

+X593863Y327916D01*

+X593597Y327482D01*

+Y332018D01*

+G37*

+G36*

+X646496Y340000D02*X639493D01*

+Y360236D01*

+X639500Y360235D01*

+X640245Y360294D01*

+X640972Y360469D01*

+X641663Y360755D01*

+X642301Y361145D01*

+X642869Y361631D01*

+X643355Y362199D01*

+X643745Y362837D01*

+X644031Y363528D01*

+X644206Y364255D01*

+X644250Y365000D01*

+X644206Y365745D01*

+X644031Y366472D01*

+X643745Y367163D01*

+X643355Y367801D01*

+X642869Y368369D01*

+X642301Y368855D01*

+X641663Y369245D01*

+X640972Y369531D01*

+X640245Y369706D01*

+X639500Y369765D01*

+X639493Y369764D01*

+Y390000D01*

+X646496D01*

+Y369737D01*

+X646015Y369736D01*

+X645785Y369681D01*

+X645567Y369591D01*

+X645366Y369467D01*

+X645186Y369314D01*

+X645033Y369134D01*

+X644909Y368933D01*

+X644819Y368715D01*

+X644764Y368485D01*

+X644750Y368250D01*

+X644764Y361515D01*

+X644819Y361285D01*

+X644909Y361067D01*

+X645033Y360866D01*

+X645186Y360686D01*

+X645366Y360533D01*

+X645567Y360409D01*

+X645785Y360319D01*

+X646015Y360264D01*

+X646250Y360250D01*

+X646496Y360251D01*

+Y354007D01*

+X646108Y353977D01*

+X645725Y353885D01*

+X645362Y353734D01*

+X645026Y353529D01*

+X644727Y353273D01*

+X644471Y352974D01*

+X644266Y352638D01*

+X644115Y352275D01*

+X644023Y351892D01*

+X643992Y351500D01*

+X644023Y351108D01*

+X644115Y350725D01*

+X644266Y350362D01*

+X644471Y350026D01*

+X644727Y349727D01*

+X645026Y349471D01*

+X645362Y349266D01*

+X645725Y349115D01*

+X646108Y349023D01*

+X646496Y348993D01*

+Y340000D01*

+G37*

+G36*

+X639493D02*X629493D01*

+Y360236D01*

+X629500Y360235D01*

+X630245Y360294D01*

+X630972Y360469D01*

+X631663Y360755D01*

+X632301Y361145D01*

+X632869Y361631D01*

+X633355Y362199D01*

+X633745Y362837D01*

+X634031Y363528D01*

+X634206Y364255D01*

+X634250Y365000D01*

+X634206Y365745D01*

+X634031Y366472D01*

+X633745Y367163D01*

+X633355Y367801D01*

+X632869Y368369D01*

+X632301Y368855D01*

+X631663Y369245D01*

+X630972Y369531D01*

+X630245Y369706D01*

+X629500Y369765D01*

+X629493Y369764D01*

+Y390000D01*

+X639493D01*

+Y369764D01*

+X638755Y369706D01*

+X638028Y369531D01*

+X637337Y369245D01*

+X636699Y368855D01*

+X636131Y368369D01*

+X635645Y367801D01*

+X635255Y367163D01*

+X634969Y366472D01*

+X634794Y365745D01*

+X634735Y365000D01*

+X634794Y364255D01*

+X634969Y363528D01*

+X635255Y362837D01*

+X635645Y362199D01*

+X636131Y361631D01*

+X636699Y361145D01*

+X637337Y360755D01*

+X638028Y360469D01*

+X638755Y360294D01*

+X639493Y360236D01*

+Y340000D01*

+G37*

+G36*

+X629493D02*X619493D01*

+Y360236D01*

+X619500Y360235D01*

+X620245Y360294D01*

+X620972Y360469D01*

+X621663Y360755D01*

+X622301Y361145D01*

+X622869Y361631D01*

+X623355Y362199D01*

+X623745Y362837D01*

+X624031Y363528D01*

+X624206Y364255D01*

+X624250Y365000D01*

+X624206Y365745D01*

+X624031Y366472D01*

+X623745Y367163D01*

+X623355Y367801D01*

+X622869Y368369D01*

+X622301Y368855D01*

+X621663Y369245D01*

+X620972Y369531D01*

+X620245Y369706D01*

+X619500Y369765D01*

+X619493Y369764D01*

+Y390000D01*

+X629493D01*

+Y369764D01*

+X628755Y369706D01*

+X628028Y369531D01*

+X627337Y369245D01*

+X626699Y368855D01*

+X626131Y368369D01*

+X625645Y367801D01*

+X625255Y367163D01*

+X624969Y366472D01*

+X624794Y365745D01*

+X624735Y365000D01*

+X624794Y364255D01*

+X624969Y363528D01*

+X625255Y362837D01*

+X625645Y362199D01*

+X626131Y361631D01*

+X626699Y361145D01*

+X627337Y360755D01*

+X628028Y360469D01*

+X628755Y360294D01*

+X629493Y360236D01*

+Y340000D01*

+G37*

+G36*

+X619493D02*X609493D01*

+Y360236D01*

+X609500Y360235D01*

+X610245Y360294D01*

+X610972Y360469D01*

+X611663Y360755D01*

+X612301Y361145D01*

+X612869Y361631D01*

+X613355Y362199D01*

+X613745Y362837D01*

+X614031Y363528D01*

+X614206Y364255D01*

+X614250Y365000D01*

+X614206Y365745D01*

+X614031Y366472D01*

+X613745Y367163D01*

+X613355Y367801D01*

+X612869Y368369D01*

+X612301Y368855D01*

+X611663Y369245D01*

+X610972Y369531D01*

+X610245Y369706D01*

+X609500Y369765D01*

+X609493Y369764D01*

+Y379544D01*

+X609575Y379678D01*

+X609816Y380260D01*

+X609963Y380872D01*

+X610000Y381500D01*

+X609963Y382128D01*

+X609816Y382740D01*

+X609575Y383322D01*

+X609493Y383456D01*

+Y390000D01*

+X619493D01*

+Y369764D01*

+X618755Y369706D01*

+X618028Y369531D01*

+X617337Y369245D01*

+X616699Y368855D01*

+X616131Y368369D01*

+X615645Y367801D01*

+X615255Y367163D01*

+X614969Y366472D01*

+X614794Y365745D01*

+X614735Y365000D01*

+X614794Y364255D01*

+X614969Y363528D01*

+X615255Y362837D01*

+X615645Y362199D01*

+X616131Y361631D01*

+X616699Y361145D01*

+X617337Y360755D01*

+X618028Y360469D01*

+X618755Y360294D01*

+X619493Y360236D01*

+Y340000D01*

+G37*

+G36*

+X609493Y383456D02*X609246Y383858D01*

+X608837Y384337D01*

+X608358Y384746D01*

+X607822Y385075D01*

+X607240Y385316D01*

+X606628Y385463D01*

+X606000Y385512D01*

+X605372Y385463D01*

+X604760Y385316D01*

+X604252Y385105D01*

+X604316Y385260D01*

+X604463Y385872D01*

+X604500Y386500D01*

+X604463Y387128D01*

+X604316Y387740D01*

+X604075Y388322D01*

+X603746Y388858D01*

+X603337Y389337D01*

+X602858Y389746D01*

+X602444Y390000D01*

+X609493D01*

+Y383456D01*

+G37*

+G36*

+Y340000D02*X606500D01*

+X599734Y333234D01*

+X599750Y333500D01*

+X599720Y334010D01*

+X599600Y334507D01*

+X599493Y334768D01*

+Y360236D01*

+X599500Y360235D01*

+X600245Y360294D01*

+X600972Y360469D01*

+X601663Y360755D01*

+X602301Y361145D01*

+X602869Y361631D01*

+X603355Y362199D01*

+X603745Y362837D01*

+X604031Y363528D01*

+X604206Y364255D01*

+X604250Y365000D01*

+X604206Y365745D01*

+X604031Y366472D01*

+X603745Y367163D01*

+X603355Y367801D01*

+X602869Y368369D01*

+X602301Y368855D01*

+X601663Y369245D01*

+X600972Y369531D01*

+X600245Y369706D01*

+X599500Y369765D01*

+X599493Y369764D01*

+Y382628D01*

+X599872Y382537D01*

+X600500Y382488D01*

+X601128Y382537D01*

+X601740Y382684D01*

+X602248Y382895D01*

+X602184Y382740D01*

+X602037Y382128D01*

+X601988Y381500D01*

+X602037Y380872D01*

+X602184Y380260D01*

+X602425Y379678D01*

+X602754Y379142D01*

+X603163Y378663D01*

+X603642Y378254D01*

+X604178Y377925D01*

+X604760Y377684D01*

+X605372Y377537D01*

+X606000Y377488D01*

+X606628Y377537D01*

+X607240Y377684D01*

+X607822Y377925D01*

+X608358Y378254D01*

+X608837Y378663D01*

+X609246Y379142D01*

+X609493Y379544D01*

+Y369764D01*

+X608755Y369706D01*

+X608028Y369531D01*

+X607337Y369245D01*

+X606699Y368855D01*

+X606131Y368369D01*

+X605645Y367801D01*

+X605255Y367163D01*

+X604969Y366472D01*

+X604794Y365745D01*

+X604735Y365000D01*

+X604794Y364255D01*

+X604969Y363528D01*

+X605255Y362837D01*

+X605645Y362199D01*

+X606131Y361631D01*

+X606699Y361145D01*

+X607337Y360755D01*

+X608028Y360469D01*

+X608755Y360294D01*

+X609493Y360236D01*

+Y340000D01*

+G37*

+G36*

+X599493Y334768D02*X599405Y334980D01*

+X599137Y335416D01*

+X598805Y335805D01*

+X598416Y336137D01*

+X597980Y336405D01*

+X597507Y336600D01*

+X597010Y336720D01*

+X596500Y336760D01*

+X595990Y336720D01*

+X595493Y336600D01*

+X595020Y336405D01*

+X594584Y336137D01*

+X594195Y335805D01*

+X593863Y335416D01*

+X593597Y334982D01*

+Y349928D01*

+X593862Y349766D01*

+X594225Y349615D01*

+X594608Y349523D01*

+X595000Y349492D01*

+X595392Y349523D01*

+X595775Y349615D01*

+X596138Y349766D01*

+X596474Y349971D01*

+X596773Y350227D01*

+X597029Y350526D01*

+X597234Y350862D01*

+X597385Y351225D01*

+X597477Y351608D01*

+X597500Y352000D01*

+X597477Y352392D01*

+X597385Y352775D01*

+X597234Y353138D01*

+X597029Y353474D01*

+X596773Y353773D01*

+X596474Y354029D01*

+X596138Y354234D01*

+X595775Y354385D01*

+X595392Y354477D01*

+X595000Y354508D01*

+X594608Y354477D01*

+X594225Y354385D01*

+X593862Y354234D01*

+X593597Y354072D01*

+Y377752D01*

+X593760Y377684D01*

+X594372Y377537D01*

+X595000Y377488D01*

+X595628Y377537D01*

+X596240Y377684D01*

+X596822Y377925D01*

+X597358Y378254D01*

+X597837Y378663D01*

+X598246Y379142D01*

+X598575Y379678D01*

+X598816Y380260D01*

+X598963Y380872D01*

+X599000Y381500D01*

+X598963Y382128D01*

+X598816Y382740D01*

+X598752Y382895D01*

+X599260Y382684D01*

+X599493Y382628D01*

+Y369764D01*

+X598755Y369706D01*

+X598028Y369531D01*

+X597337Y369245D01*

+X596699Y368855D01*

+X596131Y368369D01*

+X595645Y367801D01*

+X595255Y367163D01*

+X594969Y366472D01*

+X594794Y365745D01*

+X594735Y365000D01*

+X594794Y364255D01*

+X594969Y363528D01*

+X595255Y362837D01*

+X595645Y362199D01*

+X596131Y361631D01*

+X596699Y361145D01*

+X597337Y360755D01*

+X598028Y360469D01*

+X598755Y360294D01*

+X599493Y360236D01*

+Y334768D01*

+G37*

+G36*

+X593597Y334982D02*X593595Y334980D01*

+X593400Y334507D01*

+X593280Y334010D01*

+X593240Y333500D01*

+X593280Y332990D01*

+X593400Y332493D01*

+X593595Y332020D01*

+X593597Y332018D01*

+Y327482D01*

+X593595Y327480D01*

+X593400Y327007D01*

+X593280Y326510D01*

+X593240Y326000D01*

+X593280Y325490D01*

+X593400Y324993D01*

+X593595Y324520D01*

+X593597Y324518D01*

+Y299597D01*

+X591000Y297000D01*

+Y277598D01*

+X590992Y277500D01*

+X591000Y277402D01*

+Y269000D01*

+X586304D01*

+Y321855D01*

+X586405Y322020D01*

+X586600Y322493D01*

+X586720Y322990D01*

+X586750Y323500D01*

+X586741Y323656D01*

+X587084Y323363D01*

+X587520Y323095D01*

+X587993Y322900D01*

+X588490Y322780D01*

+X589000Y322740D01*

+X589510Y322780D01*

+X590007Y322900D01*

+X590480Y323095D01*

+X590916Y323363D01*

+X591305Y323695D01*

+X591637Y324084D01*

+X591905Y324520D01*

+X592100Y324993D01*

+X592220Y325490D01*

+X592250Y326000D01*

+X592220Y326510D01*

+X592100Y327007D01*

+X591905Y327480D01*

+X591637Y327916D01*

+X591305Y328305D01*

+X590916Y328637D01*

+X590480Y328905D01*

+X590007Y329100D01*

+X589510Y329220D01*

+X589000Y329260D01*

+X588490Y329220D01*

+X587993Y329100D01*

+X587520Y328905D01*

+X587084Y328637D01*

+X586695Y328305D01*

+X586363Y327916D01*

+X586304Y327820D01*

+Y331680D01*

+X586363Y331584D01*

+X586695Y331195D01*

+X587084Y330863D01*

+X587520Y330595D01*

+X587993Y330400D01*

+X588490Y330280D01*

+X589000Y330240D01*

+X589510Y330280D01*

+X590007Y330400D01*

+X590480Y330595D01*

+X590916Y330863D01*

+X591305Y331195D01*

+X591637Y331584D01*

+X591905Y332020D01*

+X592100Y332493D01*

+X592220Y332990D01*

+X592250Y333500D01*

+X592220Y334010D01*

+X592100Y334507D01*

+X591905Y334980D01*

+X591637Y335416D01*

+X591305Y335805D01*

+X590916Y336137D01*

+X590480Y336405D01*

+X590007Y336600D01*

+X589510Y336720D01*

+X589000Y336760D01*

+X588490Y336720D01*

+X587993Y336600D01*

+X587520Y336405D01*

+X587084Y336137D01*

+X586695Y335805D01*

+X586363Y335416D01*

+X586304Y335320D01*

+Y350117D01*

+X586351Y350143D01*

+X586413Y350192D01*

+X586466Y350250D01*

+X586508Y350316D01*

+X586685Y350659D01*

+X586826Y351018D01*

+X586932Y351390D01*

+X587004Y351769D01*

+X587039Y352153D01*

+Y352540D01*

+X587004Y352924D01*

+X586932Y353303D01*

+X586826Y353675D01*

+X586685Y354034D01*

+X586512Y354379D01*

+X586469Y354446D01*

+X586415Y354504D01*

+X586353Y354553D01*

+X586304Y354580D01*

+Y358389D01*

+X586390Y358180D01*

+X586538Y357938D01*

+X586723Y357723D01*

+X586938Y357538D01*

+X587180Y357390D01*

+X587442Y357282D01*

+X587717Y357216D01*

+X588000Y357193D01*

+X588283Y357216D01*

+X588558Y357282D01*

+X588820Y357390D01*

+X589062Y357538D01*

+X589277Y357723D01*

+X589462Y357938D01*

+X589610Y358180D01*

+X589718Y358442D01*

+X589784Y358717D01*

+X589801Y359000D01*

+X589784Y359283D01*

+X589718Y359558D01*

+X589610Y359820D01*

+X589462Y360062D01*

+X589277Y360277D01*

+X589062Y360462D01*

+X588820Y360610D01*

+X588558Y360718D01*

+X588283Y360784D01*

+X588000Y360807D01*

+X587717Y360784D01*

+X587442Y360718D01*

+X587180Y360610D01*

+X586938Y360462D01*

+X586723Y360277D01*

+X586538Y360062D01*

+X586390Y359820D01*

+X586304Y359611D01*

+Y362389D01*

+X586390Y362180D01*

+X586538Y361938D01*

+X586723Y361723D01*

+X586938Y361538D01*

+X587180Y361390D01*

+X587442Y361282D01*

+X587717Y361216D01*

+X588000Y361193D01*

+X588283Y361216D01*

+X588558Y361282D01*

+X588820Y361390D01*

+X589062Y361538D01*

+X589277Y361723D01*

+X589462Y361938D01*

+X589610Y362180D01*

+X589718Y362442D01*

+X589784Y362717D01*

+X589801Y363000D01*

+X589784Y363283D01*

+X589718Y363558D01*

+X589610Y363820D01*

+X589462Y364062D01*

+X589277Y364277D01*

+X589062Y364462D01*

+X588820Y364610D01*

+X588558Y364718D01*

+X588283Y364784D01*

+X588000Y364807D01*

+X587717Y364784D01*

+X587442Y364718D01*

+X587180Y364610D01*

+X586938Y364462D01*

+X586723Y364277D01*

+X586538Y364062D01*

+X586390Y363820D01*

+X586304Y363611D01*

+Y371770D01*

+X586351Y371797D01*

+X586413Y371845D01*

+X586466Y371903D01*

+X586508Y371969D01*

+X586685Y372312D01*

+X586826Y372672D01*

+X586932Y373043D01*

+X587004Y373422D01*

+X587039Y373807D01*

+Y374193D01*

+X587004Y374578D01*

+X586932Y374957D01*

+X586826Y375328D01*

+X586685Y375688D01*

+X586512Y376033D01*

+X586469Y376099D01*

+X586415Y376157D01*

+X586353Y376206D01*

+X586304Y376234D01*

+Y384083D01*

+X586663Y383663D01*

+X587142Y383254D01*

+X587678Y382925D01*

+X588260Y382684D01*

+X588872Y382537D01*

+X589500Y382488D01*

+X590128Y382537D01*

+X590740Y382684D01*

+X591248Y382895D01*

+X591184Y382740D01*

+X591037Y382128D01*

+X590988Y381500D01*

+X591037Y380872D01*

+X591184Y380260D01*

+X591425Y379678D01*

+X591754Y379142D01*

+X592163Y378663D01*

+X592642Y378254D01*

+X593178Y377925D01*

+X593597Y377752D01*

+Y354072D01*

+X593526Y354029D01*

+X593227Y353773D01*

+X592971Y353474D01*

+X592766Y353138D01*

+X592615Y352775D01*

+X592523Y352392D01*

+X592492Y352000D01*

+X592523Y351608D01*

+X592558Y351464D01*

+X592320Y351610D01*

+X592058Y351718D01*

+X591783Y351784D01*

+X591500Y351807D01*

+X591217Y351784D01*

+X590942Y351718D01*

+X590680Y351610D01*

+X590438Y351462D01*

+X590223Y351277D01*

+X590038Y351062D01*

+X589890Y350820D01*

+X589782Y350558D01*

+X589716Y350283D01*

+X589693Y350000D01*

+X589716Y349717D01*

+X589782Y349442D01*

+X589890Y349180D01*

+X590038Y348938D01*

+X590223Y348723D01*

+X590438Y348538D01*

+X590680Y348390D01*

+X590942Y348282D01*

+X591217Y348216D01*

+X591500Y348193D01*

+X591783Y348216D01*

+X592058Y348282D01*

+X592320Y348390D01*

+X592562Y348538D01*

+X592777Y348723D01*

+X592962Y348938D01*

+X593110Y349180D01*

+X593218Y349442D01*

+X593284Y349717D01*

+X593301Y350000D01*

+X593291Y350172D01*

+X593526Y349971D01*

+X593597Y349928D01*

+Y334982D01*

+G37*

+G36*

+X586304Y327820D02*X586095Y327480D01*

+X585900Y327007D01*

+X585780Y326510D01*

+X585740Y326000D01*

+X585752Y325851D01*

+X585416Y326137D01*

+X584980Y326405D01*

+X584507Y326600D01*

+X584010Y326720D01*

+X583500Y326760D01*

+X582990Y326720D01*

+X582891Y326696D01*

+Y348197D01*

+X583083D01*

+X583467Y348233D01*

+X583847Y348304D01*

+X584218Y348410D01*

+X584578Y348551D01*

+X584923Y348724D01*

+X584989Y348768D01*

+X585047Y348821D01*

+X585096Y348884D01*

+X585135Y348953D01*

+X585162Y349027D01*

+X585177Y349105D01*

+X585180Y349184D01*

+X585171Y349263D01*

+X585149Y349339D01*

+X585116Y349411D01*

+X585072Y349477D01*

+X585018Y349535D01*

+X584956Y349584D01*

+X584887Y349623D01*

+X584812Y349650D01*

+X584735Y349665D01*

+X584656Y349668D01*

+X584577Y349659D01*

+X584501Y349637D01*

+X584429Y349603D01*

+X584169Y349469D01*

+X583897Y349362D01*

+X583615Y349282D01*

+X583328Y349227D01*

+X583036Y349200D01*

+X582891D01*

+Y355493D01*

+X583036D01*

+X583328Y355465D01*

+X583615Y355411D01*

+X583897Y355331D01*

+X584169Y355224D01*

+X584431Y355093D01*

+X584502Y355059D01*

+X584578Y355037D01*

+X584656Y355028D01*

+X584734Y355031D01*

+X584812Y355046D01*

+X584885Y355073D01*

+X584954Y355112D01*

+X585016Y355161D01*

+X585069Y355218D01*

+X585113Y355284D01*

+X585146Y355355D01*

+X585168Y355431D01*

+X585177Y355509D01*

+X585174Y355588D01*

+X585159Y355665D01*

+X585132Y355739D01*

+X585093Y355807D01*

+X585044Y355869D01*

+X584987Y355923D01*

+X584921Y355965D01*

+X584578Y356142D01*

+X584218Y356283D01*

+X583847Y356389D01*

+X583467Y356460D01*

+X583083Y356496D01*

+X582891D01*

+Y369850D01*

+X583083D01*

+X583467Y369886D01*

+X583847Y369958D01*

+X584218Y370064D01*

+X584578Y370204D01*

+X584923Y370377D01*

+X584989Y370421D01*

+X585047Y370475D01*

+X585096Y370537D01*

+X585135Y370606D01*

+X585162Y370681D01*

+X585177Y370758D01*

+X585180Y370838D01*

+X585171Y370916D01*

+X585149Y370993D01*

+X585116Y371064D01*

+X585072Y371130D01*

+X585018Y371188D01*

+X584956Y371237D01*

+X584887Y371276D01*

+X584812Y371303D01*

+X584735Y371319D01*

+X584656Y371322D01*

+X584577Y371312D01*

+X584501Y371291D01*

+X584429Y371256D01*

+X584169Y371122D01*

+X583897Y371016D01*

+X583615Y370935D01*

+X583328Y370881D01*

+X583036Y370854D01*

+X582891D01*

+Y377146D01*

+X583036D01*

+X583328Y377119D01*

+X583615Y377065D01*

+X583897Y376984D01*

+X584169Y376878D01*

+X584431Y376747D01*

+X584502Y376712D01*

+X584578Y376691D01*

+X584656Y376682D01*

+X584734Y376685D01*

+X584812Y376700D01*

+X584885Y376727D01*

+X584954Y376765D01*

+X585016Y376814D01*

+X585069Y376872D01*

+X585113Y376937D01*

+X585146Y377009D01*

+X585168Y377084D01*

+X585177Y377163D01*

+X585174Y377241D01*

+X585159Y377318D01*

+X585132Y377392D01*

+X585093Y377461D01*

+X585044Y377523D01*

+X584987Y377576D01*

+X584921Y377619D01*

+X584578Y377796D01*

+X584218Y377936D01*

+X583847Y378042D01*

+X583467Y378114D01*

+X583083Y378150D01*

+X582891D01*

+Y390000D01*

+X586304D01*

+Y388917D01*

+X586254Y388858D01*

+X585925Y388322D01*

+X585684Y387740D01*

+X585537Y387128D01*

+X585488Y386500D01*

+X585537Y385872D01*

+X585684Y385260D01*

+X585925Y384678D01*

+X586254Y384142D01*

+X586304Y384083D01*

+Y376234D01*

+X586283Y376245D01*

+X586209Y376272D01*

+X586131Y376288D01*

+X586052Y376291D01*

+X585973Y376281D01*

+X585897Y376260D01*

+X585825Y376226D01*

+X585759Y376182D01*

+X585701Y376129D01*

+X585652Y376066D01*

+X585614Y375997D01*

+X585586Y375923D01*

+X585571Y375845D01*

+X585568Y375766D01*

+X585577Y375687D01*

+X585599Y375611D01*

+X585633Y375540D01*

+X585768Y375280D01*

+X585874Y375007D01*

+X585955Y374726D01*

+X586009Y374438D01*

+X586036Y374146D01*

+Y373854D01*

+X586009Y373562D01*

+X585955Y373274D01*

+X585874Y372993D01*

+X585768Y372720D01*

+X585636Y372459D01*

+X585602Y372388D01*

+X585581Y372312D01*

+X585571Y372234D01*

+X585574Y372155D01*

+X585590Y372078D01*

+X585617Y372004D01*

+X585655Y371936D01*

+X585704Y371874D01*

+X585762Y371820D01*

+X585827Y371777D01*

+X585898Y371744D01*

+X585974Y371722D01*

+X586052Y371713D01*

+X586131Y371716D01*

+X586208Y371731D01*

+X586282Y371758D01*

+X586304Y371770D01*

+Y363611D01*

+X586282Y363558D01*

+X586216Y363283D01*

+X586193Y363000D01*

+X586216Y362717D01*

+X586282Y362442D01*

+X586304Y362389D01*

+Y359611D01*

+X586282Y359558D01*

+X586216Y359283D01*

+X586193Y359000D01*

+X586216Y358717D01*

+X586282Y358442D01*

+X586304Y358389D01*

+Y354580D01*

+X586283Y354591D01*

+X586209Y354619D01*

+X586131Y354634D01*

+X586052Y354637D01*

+X585973Y354628D01*

+X585897Y354606D01*

+X585825Y354573D01*

+X585759Y354529D01*

+X585701Y354475D01*

+X585652Y354413D01*

+X585614Y354344D01*

+X585586Y354269D01*

+X585571Y354191D01*

+X585568Y354112D01*

+X585577Y354034D01*

+X585599Y353957D01*

+X585633Y353886D01*

+X585768Y353626D01*

+X585874Y353353D01*

+X585955Y353072D01*

+X586009Y352784D01*

+X586036Y352493D01*

+Y352200D01*

+X586009Y351909D01*

+X585955Y351621D01*

+X585874Y351339D01*

+X585768Y351067D01*

+X585636Y350805D01*

+X585602Y350734D01*

+X585581Y350659D01*

+X585571Y350580D01*

+X585574Y350502D01*

+X585590Y350425D01*

+X585617Y350351D01*

+X585655Y350282D01*

+X585704Y350220D01*

+X585762Y350167D01*

+X585827Y350123D01*

+X585898Y350090D01*

+X585974Y350069D01*

+X586052Y350059D01*

+X586131Y350062D01*

+X586208Y350078D01*

+X586282Y350105D01*

+X586304Y350117D01*

+Y335320D01*

+X586095Y334980D01*

+X585900Y334507D01*

+X585780Y334010D01*

+X585740Y333500D01*

+X585780Y332990D01*

+X585900Y332493D01*

+X586095Y332020D01*

+X586304Y331680D01*

+Y327820D01*

+G37*

+G36*

+Y269000D02*X582891D01*

+Y320304D01*

+X582990Y320280D01*

+X583500Y320240D01*

+X584010Y320280D01*

+X584507Y320400D01*

+X584980Y320595D01*

+X585416Y320863D01*

+X585805Y321195D01*

+X586137Y321584D01*

+X586304Y321855D01*

+Y269000D01*

+G37*

+G36*

+X582891D02*X579476D01*

+Y350113D01*

+X579496Y350102D01*

+X579570Y350074D01*

+X579648Y350059D01*

+X579727Y350056D01*

+X579806Y350065D01*

+X579882Y350087D01*

+X579954Y350120D01*

+X580020Y350164D01*

+X580078Y350218D01*

+X580127Y350280D01*

+X580166Y350349D01*

+X580193Y350424D01*

+X580209Y350501D01*

+X580212Y350581D01*

+X580202Y350659D01*

+X580181Y350736D01*

+X580146Y350807D01*

+X580012Y351067D01*

+X579905Y351339D01*

+X579825Y351621D01*

+X579771Y351909D01*

+X579744Y352200D01*

+Y352493D01*

+X579771Y352784D01*

+X579825Y353072D01*

+X579905Y353353D01*

+X580012Y353626D01*

+X580143Y353888D01*

+X580177Y353959D01*

+X580199Y354034D01*

+X580208Y354112D01*

+X580205Y354191D01*

+X580190Y354268D01*

+X580163Y354342D01*

+X580124Y354411D01*

+X580076Y354473D01*

+X580018Y354526D01*

+X579953Y354570D01*

+X579881Y354603D01*

+X579805Y354624D01*

+X579727Y354634D01*

+X579649Y354631D01*

+X579571Y354615D01*

+X579498Y354588D01*

+X579476Y354576D01*

+Y371766D01*

+X579496Y371755D01*

+X579570Y371728D01*

+X579648Y371712D01*

+X579727Y371709D01*

+X579806Y371719D01*

+X579882Y371740D01*

+X579954Y371774D01*

+X580020Y371818D01*

+X580078Y371871D01*

+X580127Y371934D01*

+X580166Y372003D01*

+X580193Y372077D01*

+X580209Y372155D01*

+X580212Y372234D01*

+X580202Y372313D01*

+X580181Y372389D01*

+X580146Y372460D01*

+X580012Y372720D01*

+X579905Y372993D01*

+X579825Y373274D01*

+X579771Y373562D01*

+X579744Y373854D01*

+Y374146D01*

+X579771Y374438D01*

+X579825Y374726D01*

+X579905Y375007D01*

+X580012Y375280D01*

+X580143Y375541D01*

+X580177Y375612D01*

+X580199Y375688D01*

+X580208Y375766D01*

+X580205Y375845D01*

+X580190Y375922D01*

+X580163Y375996D01*

+X580124Y376064D01*

+X580076Y376126D01*

+X580018Y376180D01*

+X579953Y376223D01*

+X579881Y376256D01*

+X579805Y376278D01*

+X579727Y376287D01*

+X579649Y376284D01*

+X579571Y376269D01*

+X579498Y376242D01*

+X579476Y376230D01*

+Y390000D01*

+X582891D01*

+Y378150D01*

+X582697D01*

+X582312Y378114D01*

+X581933Y378042D01*

+X581562Y377936D01*

+X581202Y377796D01*

+X580857Y377623D01*

+X580791Y377579D01*

+X580733Y377525D01*

+X580684Y377463D01*

+X580645Y377394D01*

+X580618Y377319D01*

+X580602Y377242D01*

+X580599Y377162D01*

+X580608Y377084D01*

+X580630Y377007D01*

+X580663Y376936D01*

+X580707Y376870D01*

+X580761Y376812D01*

+X580823Y376763D01*

+X580893Y376724D01*

+X580967Y376697D01*

+X581045Y376681D01*

+X581124Y376678D01*

+X581203Y376688D01*

+X581279Y376709D01*

+X581350Y376744D01*

+X581610Y376878D01*

+X581883Y376984D01*

+X582164Y377065D01*

+X582452Y377119D01*

+X582743Y377146D01*

+X582891D01*

+Y370854D01*

+X582743D01*

+X582452Y370881D01*

+X582164Y370935D01*

+X581883Y371016D01*

+X581610Y371122D01*

+X581348Y371253D01*

+X581278Y371288D01*

+X581202Y371309D01*

+X581124Y371318D01*

+X581045Y371315D01*

+X580968Y371300D01*

+X580894Y371273D01*

+X580825Y371235D01*

+X580764Y371186D01*

+X580710Y371128D01*

+X580666Y371063D01*

+X580633Y370991D01*

+X580612Y370916D01*

+X580603Y370837D01*

+X580606Y370759D01*

+X580621Y370682D01*

+X580648Y370608D01*

+X580686Y370539D01*

+X580735Y370477D01*

+X580793Y370424D01*

+X580859Y370381D01*

+X581202Y370204D01*

+X581562Y370064D01*

+X581933Y369958D01*

+X582312Y369886D01*

+X582697Y369850D01*

+X582891D01*

+Y356496D01*

+X582697D01*

+X582312Y356460D01*

+X581933Y356389D01*

+X581562Y356283D01*

+X581202Y356142D01*

+X580857Y355969D01*

+X580791Y355925D01*

+X580733Y355872D01*

+X580684Y355809D01*

+X580645Y355740D01*

+X580618Y355666D01*

+X580602Y355588D01*

+X580599Y355509D01*

+X580608Y355430D01*

+X580630Y355354D01*

+X580663Y355282D01*

+X580707Y355216D01*

+X580761Y355158D01*

+X580823Y355109D01*

+X580893Y355070D01*

+X580967Y355043D01*

+X581045Y355028D01*

+X581124Y355025D01*

+X581203Y355034D01*

+X581279Y355056D01*

+X581350Y355090D01*

+X581610Y355224D01*

+X581883Y355331D01*

+X582164Y355411D01*

+X582452Y355465D01*

+X582743Y355493D01*

+X582891D01*

+Y349200D01*

+X582743D01*

+X582452Y349227D01*

+X582164Y349282D01*

+X581883Y349362D01*

+X581610Y349469D01*

+X581348Y349600D01*

+X581278Y349634D01*

+X581202Y349656D01*

+X581124Y349665D01*

+X581045Y349662D01*

+X580968Y349647D01*

+X580894Y349619D01*

+X580825Y349581D01*

+X580764Y349532D01*

+X580710Y349475D01*

+X580666Y349409D01*

+X580633Y349338D01*

+X580612Y349262D01*

+X580603Y349184D01*

+X580606Y349105D01*

+X580621Y349028D01*

+X580648Y348954D01*

+X580686Y348886D01*

+X580735Y348824D01*

+X580793Y348770D01*

+X580859Y348728D01*

+X581202Y348551D01*

+X581562Y348410D01*

+X581933Y348304D01*

+X582312Y348233D01*

+X582697Y348197D01*

+X582891D01*

+Y326696D01*

+X582493Y326600D01*

+X582020Y326405D01*

+X581584Y326137D01*

+X581195Y325805D01*

+X580863Y325416D01*

+X580595Y324980D01*

+X580400Y324507D01*

+X580280Y324010D01*

+X580240Y323500D01*

+X580280Y322990D01*

+X580400Y322493D01*

+X580595Y322020D01*

+X580863Y321584D01*

+X581195Y321195D01*

+X581584Y320863D01*

+X582020Y320595D01*

+X582493Y320400D01*

+X582891Y320304D01*

+Y269000D01*

+G37*

+G36*

+X579476D02*X575997D01*

+Y320694D01*

+X576000Y320693D01*

+X576283Y320716D01*

+X576558Y320782D01*

+X576820Y320890D01*

+X577062Y321038D01*

+X577277Y321223D01*

+X577462Y321438D01*

+X577610Y321680D01*

+X577718Y321942D01*

+X577784Y322217D01*

+X577801Y322500D01*

+X577784Y322783D01*

+X577718Y323058D01*

+X577610Y323320D01*

+X577462Y323562D01*

+X577277Y323777D01*

+X577062Y323962D01*

+X576820Y324110D01*

+X576558Y324218D01*

+X576283Y324284D01*

+X576000Y324307D01*

+X575997Y324306D01*

+Y390000D01*

+X579476D01*

+Y376230D01*

+X579429Y376203D01*

+X579367Y376155D01*

+X579313Y376097D01*

+X579271Y376031D01*

+X579094Y375688D01*

+X578954Y375328D01*

+X578847Y374957D01*

+X578776Y374578D01*

+X578740Y374193D01*

+Y373807D01*

+X578776Y373422D01*

+X578847Y373043D01*

+X578954Y372672D01*

+X579094Y372312D01*

+X579267Y371967D01*

+X579311Y371901D01*

+X579365Y371843D01*

+X579427Y371794D01*

+X579476Y371766D01*

+Y354576D01*

+X579429Y354550D01*

+X579367Y354501D01*

+X579313Y354443D01*

+X579271Y354377D01*

+X579094Y354034D01*

+X578954Y353675D01*

+X578847Y353303D01*

+X578776Y352924D01*

+X578740Y352540D01*

+Y352153D01*

+X578776Y351769D01*

+X578847Y351390D01*

+X578954Y351018D01*

+X579094Y350659D01*

+X579267Y350313D01*

+X579311Y350247D01*

+X579365Y350189D01*

+X579427Y350140D01*

+X579476Y350113D01*

+Y269000D01*

+G37*

+G36*

+X575997D02*X567626D01*

+Y320367D01*

+X567990Y320280D01*

+X568500Y320240D01*

+X569010Y320280D01*

+X569507Y320400D01*

+X569980Y320595D01*

+X570416Y320863D01*

+X570805Y321195D01*

+X571137Y321584D01*

+X571405Y322020D01*

+X571600Y322493D01*

+X571720Y322990D01*

+X571750Y323500D01*

+X571720Y324010D01*

+X571600Y324507D01*

+X571405Y324980D01*

+X571137Y325416D01*

+X570805Y325805D01*

+X570416Y326137D01*

+X569980Y326405D01*

+X569507Y326600D01*

+X569010Y326720D01*

+X568500Y326760D01*

+X567990Y326720D01*

+X567626Y326633D01*

+Y348470D01*

+X567824Y348388D01*

+X568459Y348235D01*

+X569110Y348184D01*

+X569761Y348235D01*

+X570396Y348388D01*

+X571000Y348638D01*

+X571557Y348979D01*

+X572054Y349403D01*

+X572478Y349900D01*

+X572819Y350457D01*

+X573069Y351060D01*

+X573221Y351695D01*

+X573260Y352346D01*

+X573221Y352998D01*

+X573069Y353633D01*

+X572819Y354236D01*

+X572478Y354793D01*

+X572054Y355290D01*

+X571557Y355714D01*

+X571000Y356055D01*

+X570396Y356305D01*

+X569761Y356458D01*

+X569110Y356509D01*

+X568459Y356458D01*

+X567824Y356305D01*

+X567626Y356223D01*

+Y370123D01*

+X567824Y370041D01*

+X568459Y369889D01*

+X569110Y369838D01*

+X569761Y369889D01*

+X570396Y370041D01*

+X571000Y370291D01*

+X571557Y370633D01*

+X572054Y371057D01*

+X572478Y371553D01*

+X572819Y372110D01*

+X573069Y372714D01*

+X573221Y373349D01*

+X573260Y374000D01*

+X573221Y374651D01*

+X573069Y375286D01*

+X572819Y375890D01*

+X572478Y376447D01*

+X572054Y376943D01*

+X571557Y377367D01*

+X571000Y377709D01*

+X570396Y377959D01*

+X569761Y378111D01*

+X569110Y378162D01*

+X568459Y378111D01*

+X567824Y377959D01*

+X567626Y377877D01*

+Y390000D01*

+X575997D01*

+Y324306D01*

+X575717Y324284D01*

+X575442Y324218D01*

+X575180Y324110D01*

+X574938Y323962D01*

+X574723Y323777D01*

+X574538Y323562D01*

+X574390Y323320D01*

+X574282Y323058D01*

+X574216Y322783D01*

+X574193Y322500D01*

+X574216Y322217D01*

+X574282Y321942D01*

+X574390Y321680D01*

+X574538Y321438D01*

+X574723Y321223D01*

+X574938Y321038D01*

+X575180Y320890D01*

+X575442Y320782D01*

+X575717Y320716D01*

+X575997Y320694D01*

+Y269000D01*

+G37*

+G36*

+X561996Y390000D02*X567626D01*

+Y377877D01*

+X567221Y377709D01*

+X566664Y377367D01*

+X566167Y376943D01*

+X565743Y376447D01*

+X565402Y375890D01*

+X565152Y375286D01*

+X564999Y374651D01*

+X564948Y374000D01*

+X564999Y373349D01*

+X565152Y372714D01*

+X565402Y372110D01*

+X565743Y371553D01*

+X566167Y371057D01*

+X566664Y370633D01*

+X567221Y370291D01*

+X567626Y370123D01*

+Y356223D01*

+X567221Y356055D01*

+X566664Y355714D01*

+X566167Y355290D01*

+X565743Y354793D01*

+X565402Y354236D01*

+X565152Y353633D01*

+X564999Y352998D01*

+X564948Y352346D01*

+X564999Y351695D01*

+X565152Y351060D01*

+X565219Y350899D01*

+X564892Y350977D01*

+X564500Y351008D01*

+X564108Y350977D01*

+X563725Y350885D01*

+X563362Y350734D01*

+X563026Y350529D01*

+X562727Y350273D01*

+X562471Y349974D01*

+X562266Y349638D01*

+X562115Y349275D01*

+X562023Y348892D01*

+X561996Y348549D01*

+Y390000D01*

+G37*

+G36*

+X567626Y269000D02*X561996D01*

+Y313493D01*

+X562000Y313492D01*

+X562392Y313523D01*

+X562775Y313615D01*

+X563138Y313766D01*

+X563474Y313971D01*

+X563773Y314227D01*

+X564029Y314526D01*

+X564234Y314862D01*

+X564385Y315225D01*

+X564477Y315608D01*

+X564500Y316000D01*

+X564477Y316392D01*

+X564385Y316775D01*

+X564234Y317138D01*

+X564029Y317474D01*

+X563773Y317773D01*

+X563474Y318029D01*

+X563138Y318234D01*

+X562775Y318385D01*

+X562392Y318477D01*

+X562000Y318508D01*

+X561996Y318507D01*

+Y330793D01*

+X562260Y330684D01*

+X562872Y330537D01*

+X563500Y330488D01*

+X564128Y330537D01*

+X564740Y330684D01*

+X565322Y330925D01*

+X565858Y331254D01*

+X566337Y331663D01*

+X566746Y332142D01*

+X567075Y332678D01*

+X567316Y333260D01*

+X567463Y333872D01*

+X567500Y334500D01*

+X567463Y335128D01*

+X567316Y335740D01*

+X567075Y336322D01*

+X566746Y336858D01*

+X566337Y337337D01*

+X565858Y337746D01*

+X565322Y338075D01*

+X564740Y338316D01*

+X564128Y338463D01*

+X563500Y338512D01*

+X562872Y338463D01*

+X562260Y338316D01*

+X561996Y338207D01*

+Y348451D01*

+X562023Y348108D01*

+X562115Y347725D01*

+X562266Y347362D01*

+X562471Y347026D01*

+X562727Y346727D01*

+X563026Y346471D01*

+X563362Y346266D01*

+X563725Y346115D01*

+X564108Y346023D01*

+X564500Y345992D01*

+X564892Y346023D01*

+X565275Y346115D01*

+X565638Y346266D01*

+X565974Y346471D01*

+X566273Y346727D01*

+X566529Y347026D01*

+X566734Y347362D01*

+X566885Y347725D01*

+X566977Y348108D01*

+X567000Y348500D01*

+X566983Y348783D01*

+X567221Y348638D01*

+X567626Y348470D01*

+Y326633D01*

+X567493Y326600D01*

+X567020Y326405D01*

+X566584Y326137D01*

+X566195Y325805D01*

+X565863Y325416D01*

+X565595Y324980D01*

+X565400Y324507D01*

+X565280Y324010D01*

+X565240Y323500D01*

+X565280Y322990D01*

+X565400Y322493D01*

+X565595Y322020D01*

+X565863Y321584D01*

+X566195Y321195D01*

+X566584Y320863D01*

+X567020Y320595D01*

+X567493Y320400D01*

+X567626Y320367D01*

+Y269000D01*

+G37*

+G36*

+X561996D02*X557573D01*

+Y300256D01*

+X557615Y300274D01*

+X557683Y300314D01*

+X557743Y300365D01*

+X557794Y300424D01*

+X557834Y300492D01*

+X557988Y300817D01*

+X558106Y301156D01*

+X558192Y301506D01*

+X558243Y301861D01*

+X558260Y302220D01*

+X558243Y302580D01*

+X558192Y302935D01*

+X558106Y303285D01*

+X557988Y303624D01*

+X557838Y303951D01*

+X557797Y304018D01*

+X557745Y304078D01*

+X557684Y304129D01*

+X557617Y304170D01*

+X557573Y304188D01*

+Y309889D01*

+X557857Y310353D01*

+X558083Y310899D01*

+X558221Y311474D01*

+X558256Y312063D01*

+X558221Y312652D01*

+X558083Y313227D01*

+X557857Y313773D01*

+X557573Y314237D01*

+Y317763D01*

+X557857Y318227D01*

+X558083Y318773D01*

+X558221Y319348D01*

+X558256Y319937D01*

+X558221Y320526D01*

+X558083Y321101D01*

+X557857Y321647D01*

+X557573Y322111D01*

+Y327606D01*

+X557857Y328069D01*

+X558083Y328615D01*

+X558221Y329190D01*

+X558256Y329780D01*

+X558221Y330369D01*

+X558083Y330944D01*

+X557857Y331490D01*

+X557573Y331953D01*

+Y336439D01*

+X557746Y336642D01*

+X558075Y337178D01*

+X558316Y337760D01*

+X558463Y338372D01*

+X558500Y339000D01*

+X558463Y339628D01*

+X558316Y340240D01*

+X558075Y340822D01*

+X557746Y341358D01*

+X557573Y341561D01*

+Y360285D01*

+X557715Y360319D01*

+X557933Y360409D01*

+X558134Y360533D01*

+X558314Y360686D01*

+X558467Y360866D01*

+X558591Y361067D01*

+X558681Y361285D01*

+X558736Y361515D01*

+X558750Y361750D01*

+X558736Y368485D01*

+X558681Y368715D01*

+X558591Y368933D01*

+X558467Y369134D01*

+X558314Y369314D01*

+X558134Y369467D01*

+X557933Y369591D01*

+X557715Y369681D01*

+X557573Y369715D01*

+Y390000D01*

+X561996D01*

+Y348549D01*

+X561992Y348500D01*

+X561996Y348451D01*

+Y338207D01*

+X561678Y338075D01*

+X561142Y337746D01*

+X560663Y337337D01*

+X560254Y336858D01*

+X559925Y336322D01*

+X559684Y335740D01*

+X559537Y335128D01*

+X559488Y334500D01*

+X559537Y333872D01*

+X559684Y333260D01*

+X559925Y332678D01*

+X560254Y332142D01*

+X560663Y331663D01*

+X561142Y331254D01*

+X561678Y330925D01*

+X561996Y330793D01*

+Y318507D01*

+X561608Y318477D01*

+X561225Y318385D01*

+X560862Y318234D01*

+X560526Y318029D01*

+X560227Y317773D01*

+X559971Y317474D01*

+X559766Y317138D01*

+X559615Y316775D01*

+X559523Y316392D01*

+X559492Y316000D01*

+X559523Y315608D01*

+X559615Y315225D01*

+X559766Y314862D01*

+X559971Y314526D01*

+X560227Y314227D01*

+X560526Y313971D01*

+X560862Y313766D01*

+X561225Y313615D01*

+X561608Y313523D01*

+X561996Y313493D01*

+Y269000D01*

+G37*

+G36*

+X557573Y369715D02*X557485Y369736D01*

+X557250Y369750D01*

+X554494Y369744D01*

+Y390000D01*

+X557573D01*

+Y369715D01*

+G37*

+G36*

+Y341561D02*X557337Y341837D01*

+X556858Y342246D01*

+X556322Y342575D01*

+X555740Y342816D01*

+X555128Y342963D01*

+X554500Y343012D01*

+X554494Y343012D01*

+Y360258D01*

+X557485Y360264D01*

+X557573Y360285D01*

+Y341561D01*

+G37*

+G36*

+Y331953D02*X557548Y331994D01*

+X557164Y332444D01*

+X556714Y332827D01*

+X556210Y333136D01*

+X555664Y333363D01*

+X555089Y333501D01*

+X554500Y333547D01*

+X554494Y333547D01*

+Y334988D01*

+X554500Y334988D01*

+X555128Y335037D01*

+X555740Y335184D01*

+X556322Y335425D01*

+X556858Y335754D01*

+X557337Y336163D01*

+X557573Y336439D01*

+Y331953D01*

+G37*

+G36*

+Y322111D02*X557548Y322151D01*

+X557164Y322601D01*

+X556714Y322985D01*

+X556210Y323294D01*

+X555664Y323520D01*

+X555089Y323658D01*

+X554500Y323704D01*

+X554494Y323704D01*

+Y326012D01*

+X554500Y326012D01*

+X555089Y326058D01*

+X555664Y326196D01*

+X556210Y326423D01*

+X556714Y326732D01*

+X557164Y327116D01*

+X557548Y327565D01*

+X557573Y327606D01*

+Y322111D01*

+G37*

+G36*

+Y314237D02*X557548Y314277D01*

+X557164Y314727D01*

+X556714Y315111D01*

+X556210Y315420D01*

+X555664Y315646D01*

+X555089Y315784D01*

+X554500Y315830D01*

+X554494Y315830D01*

+Y316170D01*

+X554500Y316170D01*

+X555089Y316216D01*

+X555664Y316354D01*

+X556210Y316580D01*

+X556714Y316889D01*

+X557164Y317273D01*

+X557548Y317723D01*

+X557573Y317763D01*

+Y314237D01*

+G37*

+G36*

+Y269000D02*X554494D01*

+Y298461D01*

+X554500Y298460D01*

+X554859Y298477D01*

+X555215Y298529D01*

+X555564Y298614D01*

+X555904Y298732D01*

+X556231Y298882D01*

+X556298Y298924D01*

+X556358Y298976D01*

+X556409Y299036D01*

+X556450Y299104D01*

+X556480Y299177D01*

+X556498Y299254D01*

+X556503Y299333D01*

+X556496Y299412D01*

+X556477Y299489D01*

+X556447Y299562D01*

+X556405Y299629D01*

+X556353Y299689D01*

+X556292Y299740D01*

+X556224Y299781D01*

+X556151Y299811D01*

+X556074Y299829D01*

+X555995Y299835D01*

+X555916Y299828D01*

+X555839Y299809D01*

+X555767Y299777D01*

+X555529Y299664D01*

+X555280Y299577D01*

+X555024Y299515D01*

+X554763Y299477D01*

+X554500Y299465D01*

+X554494Y299465D01*

+Y304976D01*

+X554500Y304976D01*

+X554763Y304964D01*

+X555024Y304926D01*

+X555280Y304864D01*

+X555529Y304777D01*

+X555768Y304667D01*

+X555840Y304635D01*

+X555917Y304616D01*

+X555995Y304610D01*

+X556073Y304615D01*

+X556150Y304633D01*

+X556223Y304663D01*

+X556290Y304703D01*

+X556351Y304754D01*

+X556402Y304813D01*

+X556444Y304880D01*

+X556474Y304953D01*

+X556493Y305029D01*

+X556500Y305108D01*

+X556494Y305186D01*

+X556477Y305263D01*

+X556447Y305336D01*

+X556406Y305403D01*

+X556356Y305463D01*

+X556296Y305515D01*

+X556229Y305555D01*

+X555904Y305709D01*

+X555564Y305827D01*

+X555215Y305912D01*

+X554859Y305963D01*

+X554500Y305981D01*

+X554494Y305980D01*

+Y308296D01*

+X554500Y308296D01*

+X555089Y308342D01*

+X555664Y308480D01*

+X556210Y308706D01*

+X556714Y309015D01*

+X557164Y309399D01*

+X557548Y309849D01*

+X557573Y309889D01*

+Y304188D01*

+X557543Y304200D01*

+X557466Y304218D01*

+X557387Y304224D01*

+X557308Y304217D01*

+X557231Y304198D01*

+X557158Y304167D01*

+X557091Y304125D01*

+X557031Y304073D01*

+X556980Y304013D01*

+X556939Y303945D01*

+X556909Y303872D01*

+X556892Y303794D01*

+X556886Y303715D01*

+X556893Y303637D01*

+X556912Y303560D01*

+X556944Y303487D01*

+X557057Y303249D01*

+X557143Y303000D01*

+X557206Y302744D01*

+X557243Y302484D01*

+X557256Y302220D01*

+X557243Y301957D01*

+X557206Y301696D01*

+X557143Y301440D01*

+X557057Y301192D01*

+X556947Y300952D01*

+X556915Y300880D01*

+X556896Y300804D01*

+X556889Y300726D01*

+X556895Y300647D01*

+X556913Y300570D01*

+X556942Y300497D01*

+X556983Y300430D01*

+X557033Y300370D01*

+X557093Y300318D01*

+X557160Y300277D01*

+X557232Y300246D01*

+X557309Y300227D01*

+X557387Y300220D01*

+X557466Y300226D01*

+X557542Y300244D01*

+X557573Y300256D01*

+Y269000D01*

+G37*

+G36*

+X551427Y317763D02*X551452Y317723D01*

+X551836Y317273D01*

+X552286Y316889D01*

+X552790Y316580D01*

+X553336Y316354D01*

+X553911Y316216D01*

+X554494Y316170D01*

+Y315830D01*

+X553911Y315784D01*

+X553336Y315646D01*

+X552790Y315420D01*

+X552286Y315111D01*

+X551836Y314727D01*

+X551452Y314277D01*

+X551427Y314237D01*

+Y317763D01*

+G37*

+G36*

+Y327606D02*X551452Y327565D01*

+X551836Y327116D01*

+X552286Y326732D01*

+X552790Y326423D01*

+X553336Y326196D01*

+X553911Y326058D01*

+X554494Y326012D01*

+Y323704D01*

+X553911Y323658D01*

+X553336Y323520D01*

+X552790Y323294D01*

+X552286Y322985D01*

+X551836Y322601D01*

+X551452Y322151D01*

+X551427Y322111D01*

+Y327606D01*

+G37*

+G36*

+Y336439D02*X551663Y336163D01*

+X552142Y335754D01*

+X552678Y335425D01*

+X553260Y335184D01*

+X553872Y335037D01*

+X554494Y334988D01*

+Y333547D01*

+X553911Y333501D01*

+X553336Y333363D01*

+X552790Y333136D01*

+X552286Y332827D01*

+X551836Y332444D01*

+X551452Y331994D01*

+X551427Y331953D01*

+Y336439D01*

+G37*

+G36*

+Y360251D02*X554494Y360258D01*

+Y343012D01*

+X553872Y342963D01*

+X553260Y342816D01*

+X552678Y342575D01*

+X552142Y342246D01*

+X551663Y341837D01*

+X551427Y341561D01*

+Y360251D01*

+G37*

+G36*

+Y390000D02*X554494D01*

+Y369744D01*

+X551427Y369738D01*

+Y390000D01*

+G37*

+G36*

+X554494Y269000D02*X551427D01*

+Y300253D01*

+X551457Y300241D01*

+X551534Y300223D01*

+X551613Y300217D01*

+X551692Y300224D01*

+X551769Y300243D01*

+X551842Y300274D01*

+X551909Y300316D01*

+X551969Y300368D01*

+X552020Y300428D01*

+X552061Y300496D01*

+X552091Y300569D01*

+X552108Y300647D01*

+X552114Y300726D01*

+X552107Y300804D01*

+X552088Y300881D01*

+X552056Y300954D01*

+X551943Y301192D01*

+X551857Y301440D01*

+X551794Y301696D01*

+X551757Y301957D01*

+X551744Y302220D01*

+X551757Y302484D01*

+X551794Y302744D01*

+X551857Y303000D01*

+X551943Y303249D01*

+X552053Y303489D01*

+X552085Y303561D01*

+X552104Y303637D01*

+X552111Y303715D01*

+X552105Y303794D01*

+X552087Y303871D01*

+X552058Y303944D01*

+X552017Y304011D01*

+X551967Y304071D01*

+X551907Y304123D01*

+X551840Y304164D01*

+X551768Y304195D01*

+X551691Y304214D01*

+X551613Y304220D01*

+X551534Y304215D01*

+X551458Y304197D01*

+X551427Y304185D01*

+Y309889D01*

+X551452Y309849D01*

+X551836Y309399D01*

+X552286Y309015D01*

+X552790Y308706D01*

+X553336Y308480D01*

+X553911Y308342D01*

+X554494Y308296D01*

+Y305980D01*

+X554141Y305963D01*

+X553785Y305912D01*

+X553436Y305827D01*

+X553096Y305709D01*

+X552769Y305559D01*

+X552702Y305517D01*

+X552642Y305465D01*

+X552591Y305405D01*

+X552550Y305337D01*

+X552520Y305264D01*

+X552502Y305186D01*

+X552497Y305108D01*

+X552504Y305029D01*

+X552523Y304952D01*

+X552553Y304879D01*

+X552595Y304812D01*

+X552647Y304752D01*

+X552708Y304701D01*

+X552776Y304660D01*

+X552849Y304630D01*

+X552926Y304612D01*

+X553005Y304606D01*

+X553084Y304613D01*

+X553161Y304632D01*

+X553233Y304664D01*

+X553471Y304777D01*

+X553720Y304864D01*

+X553976Y304926D01*

+X554237Y304964D01*

+X554494Y304976D01*

+Y299465D01*

+X554237Y299477D01*

+X553976Y299515D01*

+X553720Y299577D01*

+X553471Y299664D01*

+X553232Y299774D01*

+X553160Y299806D01*

+X553083Y299825D01*

+X553005Y299831D01*

+X552927Y299826D01*

+X552850Y299808D01*

+X552777Y299778D01*

+X552710Y299738D01*

+X552649Y299687D01*

+X552598Y299628D01*

+X552556Y299561D01*

+X552526Y299488D01*

+X552507Y299412D01*

+X552500Y299333D01*

+X552506Y299255D01*

+X552523Y299178D01*

+X552553Y299105D01*

+X552594Y299038D01*

+X552644Y298978D01*

+X552704Y298926D01*

+X552771Y298886D01*

+X553096Y298732D01*

+X553436Y298614D01*

+X553785Y298529D01*

+X554141Y298477D01*

+X554494Y298461D01*

+Y269000D01*

+G37*

+G36*

+X549115Y342407D02*X549125Y342331D01*

+X549146Y341866D01*

+X549125Y341401D01*

+X549115Y341326D01*

+Y342407D01*

+G37*

+G36*

+Y290674D02*X549125Y290599D01*

+X549146Y290134D01*

+X549125Y289669D01*

+X549115Y289593D01*

+Y290674D01*

+G37*

+G36*

+X551427Y269000D02*X549115D01*

+Y286683D01*

+X549298Y286961D01*

+X549555Y287452D01*

+X549767Y287963D01*

+X549935Y288491D01*

+X550055Y289032D01*

+X550127Y289581D01*

+X550152Y290134D01*

+X550127Y290687D01*

+X550055Y291236D01*

+X549935Y291777D01*

+X549767Y292304D01*

+X549555Y292816D01*

+X549298Y293306D01*

+X549115Y293592D01*

+Y338415D01*

+X549298Y338694D01*

+X549555Y339184D01*

+X549767Y339696D01*

+X549935Y340223D01*

+X550055Y340764D01*

+X550127Y341313D01*

+X550152Y341866D01*

+X550127Y342419D01*

+X550055Y342968D01*

+X549935Y343509D01*

+X549767Y344037D01*

+X549555Y344548D01*

+X549298Y345039D01*

+X549115Y345324D01*

+Y390000D01*

+X551427D01*

+Y369738D01*

+X550515Y369736D01*

+X550285Y369681D01*

+X550067Y369591D01*

+X549866Y369467D01*

+X549686Y369314D01*

+X549533Y369134D01*

+X549409Y368933D01*

+X549319Y368715D01*

+X549264Y368485D01*

+X549250Y368250D01*

+X549264Y361515D01*

+X549319Y361285D01*

+X549409Y361067D01*

+X549533Y360866D01*

+X549686Y360686D01*

+X549866Y360533D01*

+X550067Y360409D01*

+X550285Y360319D01*

+X550515Y360264D01*

+X550750Y360250D01*

+X551427Y360251D01*

+Y341561D01*

+X551254Y341358D01*

+X550925Y340822D01*

+X550684Y340240D01*

+X550537Y339628D01*

+X550488Y339000D01*

+X550537Y338372D01*

+X550684Y337760D01*

+X550925Y337178D01*

+X551254Y336642D01*

+X551427Y336439D01*

+Y331953D01*

+X551143Y331490D01*

+X550917Y330944D01*

+X550779Y330369D01*

+X550733Y329780D01*

+X550779Y329190D01*

+X550917Y328615D01*

+X551143Y328069D01*

+X551427Y327606D01*

+Y322111D01*

+X551143Y321647D01*

+X550917Y321101D01*

+X550779Y320526D01*

+X550733Y319937D01*

+X550779Y319348D01*

+X550917Y318773D01*

+X551143Y318227D01*

+X551427Y317763D01*

+Y314237D01*

+X551143Y313773D01*

+X550917Y313227D01*

+X550779Y312652D01*

+X550733Y312063D01*

+X550779Y311474D01*

+X550917Y310899D01*

+X551143Y310353D01*

+X551427Y309889D01*

+Y304185D01*

+X551385Y304167D01*

+X551317Y304127D01*

+X551257Y304076D01*

+X551206Y304017D01*

+X551166Y303949D01*

+X551012Y303624D01*

+X550894Y303285D01*

+X550808Y302935D01*

+X550757Y302580D01*

+X550740Y302220D01*

+X550757Y301861D01*

+X550808Y301506D01*

+X550894Y301156D01*

+X551012Y300817D01*

+X551162Y300490D01*

+X551203Y300422D01*

+X551255Y300363D01*

+X551316Y300312D01*

+X551383Y300271D01*

+X551427Y300253D01*

+Y269000D01*

+G37*

+G36*

+X549115D02*X543833D01*

+Y283813D01*

+X544384Y283837D01*

+X544933Y283910D01*

+X545473Y284030D01*

+X546001Y284197D01*

+X546513Y284410D01*

+X547003Y284667D01*

+X547470Y284965D01*

+X547531Y285016D01*

+X547584Y285075D01*

+X547626Y285142D01*

+X547658Y285215D01*

+X547677Y285292D01*

+X547685Y285372D01*

+X547680Y285451D01*

+X547662Y285528D01*

+X547633Y285602D01*

+X547593Y285671D01*

+X547542Y285732D01*

+X547482Y285785D01*

+X547415Y285827D01*

+X547342Y285859D01*

+X547265Y285878D01*

+X547186Y285886D01*

+X547106Y285881D01*

+X547029Y285863D01*

+X546955Y285834D01*

+X546887Y285792D01*

+X546498Y285537D01*

+X546086Y285321D01*

+X545656Y285142D01*

+X545212Y285002D01*

+X544757Y284900D01*

+X544296Y284839D01*

+X543833Y284819D01*

+Y295449D01*

+X544296Y295428D01*

+X544757Y295367D01*

+X545212Y295266D01*

+X545656Y295126D01*

+X546086Y294947D01*

+X546498Y294731D01*

+X546890Y294480D01*

+X546957Y294438D01*

+X547030Y294409D01*

+X547107Y294392D01*

+X547186Y294387D01*

+X547264Y294394D01*

+X547340Y294414D01*

+X547413Y294445D01*

+X547479Y294487D01*

+X547538Y294539D01*

+X547588Y294600D01*

+X547628Y294668D01*

+X547657Y294741D01*

+X547675Y294818D01*

+X547680Y294896D01*

+X547672Y294974D01*

+X547653Y295051D01*

+X547622Y295123D01*

+X547580Y295189D01*

+X547528Y295249D01*

+X547466Y295297D01*

+X547003Y295601D01*

+X546513Y295858D01*

+X546001Y296071D01*

+X545473Y296238D01*

+X544933Y296358D01*

+X544384Y296431D01*

+X543833Y296455D01*

+Y335545D01*

+X544384Y335569D01*

+X544933Y335642D01*

+X545473Y335762D01*

+X546001Y335929D01*

+X546513Y336142D01*

+X547003Y336399D01*

+X547470Y336698D01*

+X547531Y336748D01*

+X547584Y336807D01*

+X547626Y336875D01*

+X547658Y336948D01*

+X547677Y337025D01*

+X547685Y337104D01*

+X547680Y337183D01*

+X547662Y337261D01*

+X547633Y337335D01*

+X547593Y337403D01*

+X547542Y337464D01*

+X547482Y337517D01*

+X547415Y337559D01*

+X547342Y337591D01*

+X547265Y337611D01*

+X547186Y337618D01*

+X547106Y337613D01*

+X547029Y337596D01*

+X546955Y337566D01*

+X546887Y337524D01*

+X546498Y337269D01*

+X546086Y337053D01*

+X545656Y336874D01*

+X545212Y336734D01*

+X544757Y336633D01*

+X544296Y336572D01*

+X543833Y336551D01*

+Y347181D01*

+X544296Y347161D01*

+X544757Y347100D01*

+X545212Y346998D01*

+X545656Y346858D01*

+X546086Y346679D01*

+X546498Y346463D01*

+X546890Y346212D01*

+X546957Y346171D01*

+X547030Y346142D01*

+X547107Y346124D01*

+X547186Y346119D01*

+X547264Y346127D01*

+X547340Y346146D01*

+X547413Y346177D01*

+X547479Y346220D01*

+X547538Y346272D01*

+X547588Y346332D01*

+X547628Y346400D01*

+X547657Y346473D01*

+X547675Y346550D01*

+X547680Y346628D01*

+X547672Y346707D01*

+X547653Y346783D01*

+X547622Y346855D01*

+X547580Y346922D01*

+X547528Y346981D01*

+X547466Y347030D01*

+X547003Y347333D01*

+X546513Y347590D01*

+X546001Y347803D01*

+X545473Y347970D01*

+X544933Y348090D01*

+X544384Y348163D01*

+X543833Y348187D01*

+Y360248D01*

+X544000Y360235D01*

+X544745Y360294D01*

+X545472Y360469D01*

+X546163Y360755D01*

+X546801Y361145D01*

+X547369Y361631D01*

+X547855Y362199D01*

+X548245Y362837D01*

+X548531Y363528D01*

+X548706Y364255D01*

+X548750Y365000D01*

+X548706Y365745D01*

+X548531Y366472D01*

+X548245Y367163D01*

+X547855Y367801D01*

+X547369Y368369D01*

+X546801Y368855D01*

+X546163Y369245D01*

+X545472Y369531D01*

+X544745Y369706D01*

+X544000Y369765D01*

+X543833Y369752D01*

+Y390000D01*

+X549115D01*

+Y345324D01*

+X548999Y345505D01*

+X548949Y345567D01*

+X548889Y345619D01*

+X548822Y345662D01*

+X548749Y345693D01*

+X548672Y345713D01*

+X548593Y345720D01*

+X548514Y345715D01*

+X548436Y345698D01*

+X548362Y345668D01*

+X548294Y345628D01*

+X548233Y345577D01*

+X548180Y345518D01*

+X548138Y345450D01*

+X548106Y345377D01*

+X548086Y345300D01*

+X548079Y345221D01*

+X548084Y345142D01*

+X548101Y345064D01*

+X548131Y344990D01*

+X548172Y344923D01*

+X548428Y344534D01*

+X548644Y344121D01*

+X548822Y343691D01*

+X548963Y343247D01*

+X549064Y342793D01*

+X549115Y342407D01*

+Y341326D01*

+X549064Y340939D01*

+X548963Y340485D01*

+X548822Y340041D01*

+X548644Y339611D01*

+X548428Y339199D01*

+X548177Y338806D01*

+X548135Y338740D01*

+X548106Y338666D01*

+X548089Y338590D01*

+X548084Y338511D01*

+X548091Y338433D01*

+X548111Y338357D01*

+X548142Y338284D01*

+X548184Y338218D01*

+X548236Y338159D01*

+X548297Y338109D01*

+X548364Y338068D01*

+X548438Y338039D01*

+X548514Y338022D01*

+X548593Y338017D01*

+X548671Y338024D01*

+X548748Y338044D01*

+X548820Y338075D01*

+X548886Y338117D01*

+X548945Y338169D01*

+X548994Y338231D01*

+X549115Y338415D01*

+Y293592D01*

+X548999Y293773D01*

+X548949Y293834D01*

+X548889Y293887D01*

+X548822Y293929D01*

+X548749Y293961D01*

+X548672Y293981D01*

+X548593Y293988D01*

+X548514Y293983D01*

+X548436Y293966D01*

+X548362Y293936D01*

+X548294Y293896D01*

+X548233Y293845D01*

+X548180Y293785D01*

+X548138Y293718D01*

+X548106Y293645D01*

+X548086Y293568D01*

+X548079Y293489D01*

+X548084Y293410D01*

+X548101Y293332D01*

+X548131Y293258D01*

+X548172Y293191D01*

+X548428Y292801D01*

+X548644Y292389D01*

+X548822Y291959D01*

+X548963Y291515D01*

+X549064Y291061D01*

+X549115Y290674D01*

+Y289593D01*

+X549064Y289207D01*

+X548963Y288753D01*

+X548822Y288309D01*

+X548644Y287879D01*

+X548428Y287466D01*

+X548177Y287074D01*

+X548135Y287007D01*

+X548106Y286934D01*

+X548089Y286857D01*

+X548084Y286779D01*

+X548091Y286701D01*

+X548111Y286624D01*

+X548142Y286552D01*

+X548184Y286486D01*

+X548236Y286426D01*

+X548297Y286376D01*

+X548364Y286336D01*

+X548438Y286307D01*

+X548514Y286290D01*

+X548593Y286285D01*

+X548671Y286292D01*

+X548748Y286312D01*

+X548820Y286343D01*

+X548886Y286385D01*

+X548945Y286437D01*

+X548994Y286499D01*

+X549115Y286683D01*

+Y269000D01*

+G37*

+G36*

+X543833D02*X538546D01*

+Y286676D01*

+X538662Y286495D01*

+X538712Y286433D01*

+X538772Y286381D01*

+X538839Y286338D01*

+X538912Y286307D01*

+X538989Y286287D01*

+X539068Y286280D01*

+X539148Y286285D01*

+X539225Y286302D01*

+X539299Y286332D01*

+X539368Y286372D01*

+X539429Y286423D01*

+X539481Y286482D01*

+X539524Y286550D01*

+X539555Y286623D01*

+X539575Y286700D01*

+X539583Y286779D01*

+X539577Y286858D01*

+X539560Y286936D01*

+X539531Y287010D01*

+X539489Y287077D01*

+X539234Y287466D01*

+X539018Y287879D01*

+X538839Y288309D01*

+X538698Y288753D01*

+X538597Y289207D01*

+X538546Y289593D01*

+Y290674D01*

+X538597Y291061D01*

+X538698Y291515D01*

+X538839Y291959D01*

+X539018Y292389D01*

+X539234Y292801D01*

+X539485Y293194D01*

+X539526Y293260D01*

+X539555Y293334D01*

+X539572Y293410D01*

+X539577Y293489D01*

+X539570Y293567D01*

+X539551Y293643D01*

+X539519Y293716D01*

+X539477Y293782D01*

+X539425Y293841D01*

+X539365Y293891D01*

+X539297Y293932D01*

+X539224Y293961D01*

+X539147Y293978D01*

+X539068Y293983D01*

+X538990Y293976D01*

+X538914Y293956D01*

+X538842Y293925D01*

+X538775Y293883D01*

+X538716Y293831D01*

+X538667Y293769D01*

+X538546Y293585D01*

+Y338408D01*

+X538662Y338227D01*

+X538712Y338166D01*

+X538772Y338113D01*

+X538839Y338071D01*

+X538912Y338039D01*

+X538989Y338019D01*

+X539068Y338012D01*

+X539148Y338017D01*

+X539225Y338034D01*

+X539299Y338064D01*

+X539368Y338104D01*

+X539429Y338155D01*

+X539481Y338215D01*

+X539524Y338282D01*

+X539555Y338355D01*

+X539575Y338432D01*

+X539583Y338511D01*

+X539577Y338590D01*

+X539560Y338668D01*

+X539531Y338742D01*

+X539489Y338809D01*

+X539234Y339199D01*

+X539018Y339611D01*

+X538839Y340041D01*

+X538698Y340485D01*

+X538597Y340939D01*

+X538546Y341326D01*

+Y342407D01*

+X538597Y342793D01*

+X538698Y343247D01*

+X538839Y343691D01*

+X539018Y344121D01*

+X539234Y344534D01*

+X539485Y344926D01*

+X539526Y344993D01*

+X539555Y345066D01*

+X539572Y345143D01*

+X539577Y345221D01*

+X539570Y345299D01*

+X539551Y345376D01*

+X539519Y345448D01*

+X539477Y345514D01*

+X539425Y345574D01*

+X539365Y345624D01*

+X539297Y345664D01*

+X539224Y345693D01*

+X539147Y345710D01*

+X539068Y345715D01*

+X538990Y345708D01*

+X538914Y345688D01*

+X538842Y345657D01*

+X538775Y345615D01*

+X538716Y345563D01*

+X538667Y345501D01*

+X538546Y345317D01*

+Y390000D01*

+X543833D01*

+Y369752D01*

+X543255Y369706D01*

+X542528Y369531D01*

+X541837Y369245D01*

+X541199Y368855D01*

+X540631Y368369D01*

+X540145Y367801D01*

+X539755Y367163D01*

+X539469Y366472D01*

+X539294Y365745D01*

+X539235Y365000D01*

+X539294Y364255D01*

+X539469Y363528D01*

+X539755Y362837D01*

+X540145Y362199D01*

+X540631Y361631D01*

+X541199Y361145D01*

+X541837Y360755D01*

+X542528Y360469D01*

+X543255Y360294D01*

+X543833Y360248D01*

+Y348187D01*

+X543831Y348187D01*

+X543277Y348163D01*

+X542729Y348090D01*

+X542188Y347970D01*

+X541660Y347803D01*

+X541149Y347590D01*

+X540658Y347333D01*

+X540192Y347035D01*

+X540130Y346984D01*

+X540078Y346925D01*

+X540035Y346858D01*

+X540004Y346785D01*

+X539984Y346708D01*

+X539977Y346628D01*

+X539982Y346549D01*

+X539999Y346472D01*

+X540028Y346398D01*

+X540069Y346329D01*

+X540120Y346268D01*

+X540179Y346216D01*

+X540246Y346173D01*

+X540319Y346141D01*

+X540396Y346122D01*

+X540476Y346114D01*

+X540555Y346119D01*

+X540633Y346137D01*

+X540706Y346166D01*

+X540774Y346208D01*

+X541163Y346463D01*

+X541576Y346679D01*

+X542006Y346858D01*

+X542449Y346998D01*

+X542904Y347100D01*

+X543366Y347161D01*

+X543831Y347181D01*

+X543833Y347181D01*

+Y336551D01*

+X543831Y336551D01*

+X543366Y336572D01*

+X542904Y336633D01*

+X542449Y336734D01*

+X542006Y336874D01*

+X541576Y337053D01*

+X541163Y337269D01*

+X540771Y337520D01*

+X540704Y337562D01*

+X540631Y337591D01*

+X540554Y337608D01*

+X540476Y337613D01*

+X540397Y337606D01*

+X540321Y337586D01*

+X540249Y337555D01*

+X540182Y337513D01*

+X540123Y337461D01*

+X540073Y337400D01*

+X540033Y337332D01*

+X540004Y337259D01*

+X539987Y337182D01*

+X539982Y337104D01*

+X539989Y337026D01*

+X540009Y336949D01*

+X540040Y336877D01*

+X540082Y336811D01*

+X540134Y336751D01*

+X540195Y336703D01*

+X540658Y336399D01*

+X541149Y336142D01*

+X541660Y335929D01*

+X542188Y335762D01*

+X542729Y335642D01*

+X543277Y335569D01*

+X543831Y335545D01*

+X543833Y335545D01*

+Y296455D01*

+X543831Y296455D01*

+X543277Y296431D01*

+X542729Y296358D01*

+X542188Y296238D01*

+X541660Y296071D01*

+X541149Y295858D01*

+X540658Y295601D01*

+X540192Y295302D01*

+X540130Y295252D01*

+X540078Y295193D01*

+X540035Y295125D01*

+X540004Y295052D01*

+X539984Y294975D01*

+X539977Y294896D01*

+X539982Y294817D01*

+X539999Y294739D01*

+X540028Y294665D01*

+X540069Y294597D01*

+X540120Y294536D01*

+X540179Y294483D01*

+X540246Y294441D01*

+X540319Y294409D01*

+X540396Y294389D01*

+X540476Y294382D01*

+X540555Y294387D01*

+X540633Y294404D01*

+X540706Y294434D01*

+X540774Y294476D01*

+X541163Y294731D01*

+X541576Y294947D01*

+X542006Y295126D01*

+X542449Y295266D01*

+X542904Y295367D01*

+X543366Y295428D01*

+X543831Y295449D01*

+X543833Y295449D01*

+Y284819D01*

+X543831Y284819D01*

+X543366Y284839D01*

+X542904Y284900D01*

+X542449Y285002D01*

+X542006Y285142D01*

+X541576Y285321D01*

+X541163Y285537D01*

+X540771Y285788D01*

+X540704Y285829D01*

+X540631Y285858D01*

+X540554Y285876D01*

+X540476Y285881D01*

+X540397Y285873D01*

+X540321Y285854D01*

+X540249Y285823D01*

+X540182Y285780D01*

+X540123Y285728D01*

+X540073Y285668D01*

+X540033Y285600D01*

+X540004Y285527D01*

+X539987Y285450D01*

+X539982Y285372D01*

+X539989Y285293D01*

+X540009Y285217D01*

+X540040Y285145D01*

+X540082Y285078D01*

+X540134Y285019D01*

+X540195Y284970D01*

+X540658Y284667D01*

+X541149Y284410D01*

+X541660Y284197D01*

+X542188Y284030D01*

+X542729Y283910D01*

+X543277Y283837D01*

+X543831Y283813D01*

+X543833Y283813D01*

+Y269000D01*

+G37*

+G36*

+X538546Y341326D02*X538536Y341401D01*

+X538516Y341866D01*

+X538536Y342331D01*

+X538546Y342407D01*

+Y341326D01*

+G37*

+G36*

+Y289593D02*X538536Y289669D01*

+X538516Y290134D01*

+X538536Y290599D01*

+X538546Y290674D01*

+Y289593D01*

+G37*

+G36*

+Y269000D02*X531573D01*

+Y300256D01*

+X531615Y300274D01*

+X531683Y300314D01*

+X531743Y300365D01*

+X531794Y300424D01*

+X531834Y300492D01*

+X531988Y300817D01*

+X532106Y301156D01*

+X532192Y301506D01*

+X532243Y301861D01*

+X532260Y302220D01*

+X532243Y302580D01*

+X532192Y302935D01*

+X532106Y303285D01*

+X531988Y303624D01*

+X531838Y303951D01*

+X531797Y304018D01*

+X531745Y304078D01*

+X531684Y304129D01*

+X531617Y304170D01*

+X531573Y304188D01*

+Y309889D01*

+X531857Y310353D01*

+X532083Y310899D01*

+X532221Y311474D01*

+X532256Y312063D01*

+X532221Y312652D01*

+X532083Y313227D01*

+X531857Y313773D01*

+X531573Y314237D01*

+Y317763D01*

+X531857Y318227D01*

+X532083Y318773D01*

+X532221Y319348D01*

+X532256Y319937D01*

+X532221Y320526D01*

+X532083Y321101D01*

+X531857Y321647D01*

+X531573Y322111D01*

+Y327606D01*

+X531857Y328069D01*

+X532083Y328615D01*

+X532221Y329190D01*

+X532256Y329780D01*

+X532221Y330369D01*

+X532083Y330944D01*

+X531857Y331490D01*

+X531573Y331953D01*

+Y360263D01*

+X531985Y360264D01*

+X532215Y360319D01*

+X532433Y360409D01*

+X532634Y360533D01*

+X532814Y360686D01*

+X532967Y360866D01*

+X533091Y361067D01*

+X533181Y361285D01*

+X533236Y361515D01*

+X533250Y361750D01*

+X533236Y368485D01*

+X533181Y368715D01*

+X533091Y368933D01*

+X532967Y369134D01*

+X532814Y369314D01*

+X532634Y369467D01*

+X532433Y369591D01*

+X532215Y369681D01*

+X531985Y369736D01*

+X531750Y369750D01*

+X531573Y369750D01*

+Y390000D01*

+X538546D01*

+Y345317D01*

+X538363Y345039D01*

+X538107Y344548D01*

+X537894Y344037D01*

+X537727Y343509D01*

+X537607Y342968D01*

+X537534Y342419D01*

+X537510Y341866D01*

+X537534Y341313D01*

+X537607Y340764D01*

+X537727Y340223D01*

+X537894Y339696D01*

+X538107Y339184D01*

+X538363Y338694D01*

+X538546Y338408D01*

+Y293585D01*

+X538363Y293306D01*

+X538107Y292816D01*

+X537894Y292304D01*

+X537727Y291777D01*

+X537607Y291236D01*

+X537534Y290687D01*

+X537510Y290134D01*

+X537534Y289581D01*

+X537607Y289032D01*

+X537727Y288491D01*

+X537894Y287963D01*

+X538107Y287452D01*

+X538363Y286961D01*

+X538546Y286676D01*

+Y269000D01*

+G37*

+G36*

+X531573Y369750D02*X528494Y369743D01*

+Y390000D01*

+X531573D01*

+Y369750D01*

+G37*

+G36*

+Y331953D02*X531548Y331994D01*

+X531164Y332444D01*

+X530714Y332827D01*

+X530210Y333136D01*

+X529664Y333363D01*

+X529089Y333501D01*

+X528500Y333547D01*

+X528494Y333547D01*

+Y360257D01*

+X531573Y360263D01*

+Y331953D01*

+G37*

+G36*

+Y322111D02*X531548Y322151D01*

+X531164Y322601D01*

+X530714Y322985D01*

+X530210Y323294D01*

+X529664Y323520D01*

+X529089Y323658D01*

+X528500Y323704D01*

+X528494Y323704D01*

+Y326012D01*

+X528500Y326012D01*

+X529089Y326058D01*

+X529664Y326196D01*

+X530210Y326423D01*

+X530714Y326732D01*

+X531164Y327116D01*

+X531548Y327565D01*

+X531573Y327606D01*

+Y322111D01*

+G37*

+G36*

+Y314237D02*X531548Y314277D01*

+X531164Y314727D01*

+X530714Y315111D01*

+X530210Y315420D01*

+X529664Y315646D01*

+X529089Y315784D01*

+X528500Y315830D01*

+X528494Y315830D01*

+Y316170D01*

+X528500Y316170D01*

+X529089Y316216D01*

+X529664Y316354D01*

+X530210Y316580D01*

+X530714Y316889D01*

+X531164Y317273D01*

+X531548Y317723D01*

+X531573Y317763D01*

+Y314237D01*

+G37*

+G36*

+Y269000D02*X528494D01*

+Y298461D01*

+X528500Y298460D01*

+X528859Y298477D01*

+X529215Y298529D01*

+X529564Y298614D01*

+X529904Y298732D01*

+X530231Y298882D01*

+X530298Y298924D01*

+X530358Y298976D01*

+X530409Y299036D01*

+X530450Y299104D01*

+X530480Y299177D01*

+X530498Y299254D01*

+X530503Y299333D01*

+X530496Y299412D01*

+X530477Y299489D01*

+X530447Y299562D01*

+X530405Y299629D01*

+X530353Y299689D01*

+X530292Y299740D01*

+X530224Y299781D01*

+X530151Y299811D01*

+X530074Y299829D01*

+X529995Y299835D01*

+X529916Y299828D01*

+X529839Y299809D01*

+X529767Y299777D01*

+X529529Y299664D01*

+X529280Y299577D01*

+X529024Y299515D01*

+X528763Y299477D01*

+X528500Y299465D01*

+X528494Y299465D01*

+Y304976D01*

+X528500Y304976D01*

+X528763Y304964D01*

+X529024Y304926D01*

+X529280Y304864D01*

+X529529Y304777D01*

+X529768Y304667D01*

+X529840Y304635D01*

+X529917Y304616D01*

+X529995Y304610D01*

+X530073Y304615D01*

+X530150Y304633D01*

+X530223Y304663D01*

+X530290Y304703D01*

+X530351Y304754D01*

+X530402Y304813D01*

+X530444Y304880D01*

+X530474Y304953D01*

+X530493Y305029D01*

+X530500Y305108D01*

+X530494Y305186D01*

+X530477Y305263D01*

+X530447Y305336D01*

+X530406Y305403D01*

+X530356Y305463D01*

+X530296Y305515D01*

+X530229Y305555D01*

+X529904Y305709D01*

+X529564Y305827D01*

+X529215Y305912D01*

+X528859Y305963D01*

+X528500Y305981D01*

+X528494Y305980D01*

+Y308296D01*

+X528500Y308296D01*

+X529089Y308342D01*

+X529664Y308480D01*

+X530210Y308706D01*

+X530714Y309015D01*

+X531164Y309399D01*

+X531548Y309849D01*

+X531573Y309889D01*

+Y304188D01*

+X531543Y304200D01*

+X531466Y304218D01*

+X531387Y304224D01*

+X531308Y304217D01*

+X531231Y304198D01*

+X531158Y304167D01*

+X531091Y304125D01*

+X531031Y304073D01*

+X530980Y304013D01*

+X530939Y303945D01*

+X530909Y303872D01*

+X530892Y303794D01*

+X530886Y303715D01*

+X530893Y303637D01*

+X530912Y303560D01*

+X530944Y303487D01*

+X531057Y303249D01*

+X531143Y303000D01*

+X531206Y302744D01*

+X531243Y302484D01*

+X531256Y302220D01*

+X531243Y301957D01*

+X531206Y301696D01*

+X531143Y301440D01*

+X531057Y301192D01*

+X530947Y300952D01*

+X530915Y300880D01*

+X530896Y300804D01*

+X530889Y300726D01*

+X530895Y300647D01*

+X530913Y300570D01*

+X530942Y300497D01*

+X530983Y300430D01*

+X531033Y300370D01*

+X531093Y300318D01*

+X531160Y300277D01*

+X531232Y300246D01*

+X531309Y300227D01*

+X531387Y300220D01*

+X531466Y300226D01*

+X531542Y300244D01*

+X531573Y300256D01*

+Y269000D01*

+G37*

+G36*

+X525427Y317763D02*X525452Y317723D01*

+X525836Y317273D01*

+X526286Y316889D01*

+X526790Y316580D01*

+X527336Y316354D01*

+X527911Y316216D01*

+X528494Y316170D01*

+Y315830D01*

+X527911Y315784D01*

+X527336Y315646D01*

+X526790Y315420D01*

+X526286Y315111D01*

+X525836Y314727D01*

+X525452Y314277D01*

+X525427Y314237D01*

+Y317763D01*

+G37*

+G36*

+Y327606D02*X525452Y327565D01*

+X525836Y327116D01*

+X526286Y326732D01*

+X526790Y326423D01*

+X527336Y326196D01*

+X527911Y326058D01*

+X528494Y326012D01*

+Y323704D01*

+X527911Y323658D01*

+X527336Y323520D01*

+X526790Y323294D01*

+X526286Y322985D01*

+X525836Y322601D01*

+X525452Y322151D01*

+X525427Y322111D01*

+Y327606D01*

+G37*

+G36*

+Y360250D02*X528494Y360257D01*

+Y333547D01*

+X527911Y333501D01*

+X527336Y333363D01*

+X526790Y333136D01*

+X526286Y332827D01*

+X525836Y332444D01*

+X525452Y331994D01*

+X525427Y331953D01*

+Y360250D01*

+G37*

+G36*

+Y390000D02*X528494D01*

+Y369743D01*

+X525427Y369737D01*

+Y390000D01*

+G37*

+G36*

+X528494Y269000D02*X525427D01*

+Y300253D01*

+X525457Y300241D01*

+X525534Y300223D01*

+X525613Y300217D01*

+X525692Y300224D01*

+X525769Y300243D01*

+X525842Y300274D01*

+X525909Y300316D01*

+X525969Y300368D01*

+X526020Y300428D01*

+X526061Y300496D01*

+X526091Y300569D01*

+X526108Y300647D01*

+X526114Y300726D01*

+X526107Y300804D01*

+X526088Y300881D01*

+X526056Y300954D01*

+X525943Y301192D01*

+X525857Y301440D01*

+X525794Y301696D01*

+X525757Y301957D01*

+X525744Y302220D01*

+X525757Y302484D01*

+X525794Y302744D01*

+X525857Y303000D01*

+X525943Y303249D01*

+X526053Y303489D01*

+X526085Y303561D01*

+X526104Y303637D01*

+X526111Y303715D01*

+X526105Y303794D01*

+X526087Y303871D01*

+X526058Y303944D01*

+X526017Y304011D01*

+X525967Y304071D01*

+X525907Y304123D01*

+X525840Y304164D01*

+X525768Y304195D01*

+X525691Y304214D01*

+X525613Y304220D01*

+X525534Y304215D01*

+X525458Y304197D01*

+X525427Y304185D01*

+Y309889D01*

+X525452Y309849D01*

+X525836Y309399D01*

+X526286Y309015D01*

+X526790Y308706D01*

+X527336Y308480D01*

+X527911Y308342D01*

+X528494Y308296D01*

+Y305980D01*

+X528141Y305963D01*

+X527785Y305912D01*

+X527436Y305827D01*

+X527096Y305709D01*

+X526769Y305559D01*

+X526702Y305517D01*

+X526642Y305465D01*

+X526591Y305405D01*

+X526550Y305337D01*

+X526520Y305264D01*

+X526502Y305186D01*

+X526497Y305108D01*

+X526504Y305029D01*

+X526523Y304952D01*

+X526553Y304879D01*

+X526595Y304812D01*

+X526647Y304752D01*

+X526708Y304701D01*

+X526776Y304660D01*

+X526849Y304630D01*

+X526926Y304612D01*

+X527005Y304606D01*

+X527084Y304613D01*

+X527161Y304632D01*

+X527233Y304664D01*

+X527471Y304777D01*

+X527720Y304864D01*

+X527976Y304926D01*

+X528237Y304964D01*

+X528494Y304976D01*

+Y299465D01*

+X528237Y299477D01*

+X527976Y299515D01*

+X527720Y299577D01*

+X527471Y299664D01*

+X527232Y299774D01*

+X527160Y299806D01*

+X527083Y299825D01*

+X527005Y299831D01*

+X526927Y299826D01*

+X526850Y299808D01*

+X526777Y299778D01*

+X526710Y299738D01*

+X526649Y299687D01*

+X526598Y299628D01*

+X526556Y299561D01*

+X526526Y299488D01*

+X526507Y299412D01*

+X526500Y299333D01*

+X526506Y299255D01*

+X526523Y299178D01*

+X526553Y299105D01*

+X526594Y299038D01*

+X526644Y298978D01*

+X526704Y298926D01*

+X526771Y298886D01*

+X527096Y298732D01*

+X527436Y298614D01*

+X527785Y298529D01*

+X528141Y298477D01*

+X528494Y298461D01*

+Y269000D01*

+G37*

+G36*

+X523115Y342407D02*X523125Y342331D01*

+X523146Y341866D01*

+X523125Y341401D01*

+X523115Y341326D01*

+Y342407D01*

+G37*

+G36*

+Y290674D02*X523125Y290599D01*

+X523146Y290134D01*

+X523125Y289669D01*

+X523115Y289593D01*

+Y290674D01*

+G37*

+G36*

+X525427Y269000D02*X523115D01*

+Y286683D01*

+X523298Y286961D01*

+X523555Y287452D01*

+X523767Y287963D01*

+X523935Y288491D01*

+X524055Y289032D01*

+X524127Y289581D01*

+X524152Y290134D01*

+X524127Y290687D01*

+X524055Y291236D01*

+X523935Y291777D01*

+X523767Y292304D01*

+X523555Y292816D01*

+X523298Y293306D01*

+X523115Y293592D01*

+Y338415D01*

+X523298Y338694D01*

+X523555Y339184D01*

+X523767Y339696D01*

+X523935Y340223D01*

+X524055Y340764D01*

+X524127Y341313D01*

+X524152Y341866D01*

+X524127Y342419D01*

+X524055Y342968D01*

+X523935Y343509D01*

+X523767Y344037D01*

+X523555Y344548D01*

+X523298Y345039D01*

+X523115Y345324D01*

+Y363877D01*

+X523206Y364255D01*

+X523250Y365000D01*

+X523206Y365745D01*

+X523115Y366123D01*

+Y390000D01*

+X525427D01*

+Y369737D01*

+X525015Y369736D01*

+X524785Y369681D01*

+X524567Y369591D01*

+X524366Y369467D01*

+X524186Y369314D01*

+X524033Y369134D01*

+X523909Y368933D01*

+X523819Y368715D01*

+X523764Y368485D01*

+X523750Y368250D01*

+X523764Y361515D01*

+X523819Y361285D01*

+X523909Y361067D01*

+X524033Y360866D01*

+X524186Y360686D01*

+X524366Y360533D01*

+X524567Y360409D01*

+X524785Y360319D01*

+X525015Y360264D01*

+X525250Y360250D01*

+X525427Y360250D01*

+Y331953D01*

+X525143Y331490D01*

+X524917Y330944D01*

+X524779Y330369D01*

+X524733Y329780D01*

+X524779Y329190D01*

+X524917Y328615D01*

+X525143Y328069D01*

+X525427Y327606D01*

+Y322111D01*

+X525143Y321647D01*

+X524917Y321101D01*

+X524779Y320526D01*

+X524733Y319937D01*

+X524779Y319348D01*

+X524917Y318773D01*

+X525143Y318227D01*

+X525427Y317763D01*

+Y314237D01*

+X525143Y313773D01*

+X524917Y313227D01*

+X524779Y312652D01*

+X524733Y312063D01*

+X524779Y311474D01*

+X524917Y310899D01*

+X525143Y310353D01*

+X525427Y309889D01*

+Y304185D01*

+X525385Y304167D01*

+X525317Y304127D01*

+X525257Y304076D01*

+X525206Y304017D01*

+X525166Y303949D01*

+X525012Y303624D01*

+X524894Y303285D01*

+X524808Y302935D01*

+X524757Y302580D01*

+X524740Y302220D01*

+X524757Y301861D01*

+X524808Y301506D01*

+X524894Y301156D01*

+X525012Y300817D01*

+X525162Y300490D01*

+X525203Y300422D01*

+X525255Y300363D01*

+X525316Y300312D01*

+X525383Y300271D01*

+X525427Y300253D01*

+Y269000D01*

+G37*

+G36*

+X523115Y366123D02*X523031Y366472D01*

+X522745Y367163D01*

+X522355Y367801D01*

+X521869Y368369D01*

+X521301Y368855D01*

+X520663Y369245D01*

+X519972Y369531D01*

+X519245Y369706D01*

+X518500Y369765D01*

+X517833Y369712D01*

+Y390000D01*

+X523115D01*

+Y366123D01*

+G37*

+G36*

+Y269000D02*X517833D01*

+Y283813D01*

+X518384Y283837D01*

+X518933Y283910D01*

+X519473Y284030D01*

+X520001Y284197D01*

+X520513Y284410D01*

+X521003Y284667D01*

+X521470Y284965D01*

+X521531Y285016D01*

+X521584Y285075D01*

+X521626Y285142D01*

+X521658Y285215D01*

+X521677Y285292D01*

+X521685Y285372D01*

+X521680Y285451D01*

+X521662Y285528D01*

+X521633Y285602D01*

+X521593Y285671D01*

+X521542Y285732D01*

+X521482Y285785D01*

+X521415Y285827D01*

+X521342Y285859D01*

+X521265Y285878D01*

+X521186Y285886D01*

+X521106Y285881D01*

+X521029Y285863D01*

+X520955Y285834D01*

+X520887Y285792D01*

+X520498Y285537D01*

+X520086Y285321D01*

+X519656Y285142D01*

+X519212Y285002D01*

+X518757Y284900D01*

+X518296Y284839D01*

+X517833Y284819D01*

+Y295449D01*

+X518296Y295428D01*

+X518757Y295367D01*

+X519212Y295266D01*

+X519656Y295126D01*

+X520086Y294947D01*

+X520498Y294731D01*

+X520890Y294480D01*

+X520957Y294438D01*

+X521030Y294409D01*

+X521107Y294392D01*

+X521186Y294387D01*

+X521264Y294394D01*

+X521340Y294414D01*

+X521413Y294445D01*

+X521479Y294487D01*

+X521538Y294539D01*

+X521588Y294600D01*

+X521628Y294668D01*

+X521657Y294741D01*

+X521675Y294818D01*

+X521680Y294896D01*

+X521672Y294974D01*

+X521653Y295051D01*

+X521622Y295123D01*

+X521580Y295189D01*

+X521528Y295249D01*

+X521466Y295297D01*

+X521003Y295601D01*

+X520513Y295858D01*

+X520001Y296071D01*

+X519473Y296238D01*

+X518933Y296358D01*

+X518384Y296431D01*

+X517833Y296455D01*

+Y335545D01*

+X518384Y335569D01*

+X518933Y335642D01*

+X519473Y335762D01*

+X520001Y335929D01*

+X520513Y336142D01*

+X521003Y336399D01*

+X521470Y336698D01*

+X521531Y336748D01*

+X521584Y336807D01*

+X521626Y336875D01*

+X521658Y336948D01*

+X521677Y337025D01*

+X521685Y337104D01*

+X521680Y337183D01*

+X521662Y337261D01*

+X521633Y337335D01*

+X521593Y337403D01*

+X521542Y337464D01*

+X521482Y337517D01*

+X521415Y337559D01*

+X521342Y337591D01*

+X521265Y337611D01*

+X521186Y337618D01*

+X521106Y337613D01*

+X521029Y337596D01*

+X520955Y337566D01*

+X520887Y337524D01*

+X520498Y337269D01*

+X520086Y337053D01*

+X519656Y336874D01*

+X519212Y336734D01*

+X518757Y336633D01*

+X518296Y336572D01*

+X517833Y336551D01*

+Y347181D01*

+X518296Y347161D01*

+X518757Y347100D01*

+X519212Y346998D01*

+X519656Y346858D01*

+X520086Y346679D01*

+X520498Y346463D01*

+X520890Y346212D01*

+X520957Y346171D01*

+X521030Y346142D01*

+X521107Y346124D01*

+X521186Y346119D01*

+X521264Y346127D01*

+X521340Y346146D01*

+X521413Y346177D01*

+X521479Y346220D01*

+X521538Y346272D01*

+X521588Y346332D01*

+X521628Y346400D01*

+X521657Y346473D01*

+X521675Y346550D01*

+X521680Y346628D01*

+X521672Y346707D01*

+X521653Y346783D01*

+X521622Y346855D01*

+X521580Y346922D01*

+X521528Y346981D01*

+X521466Y347030D01*

+X521003Y347333D01*

+X520513Y347590D01*

+X520001Y347803D01*

+X519473Y347970D01*

+X518933Y348090D01*

+X518384Y348163D01*

+X517833Y348187D01*

+Y360288D01*

+X518500Y360235D01*

+X519245Y360294D01*

+X519972Y360469D01*

+X520663Y360755D01*

+X521301Y361145D01*

+X521869Y361631D01*

+X522355Y362199D01*

+X522745Y362837D01*

+X523031Y363528D01*

+X523115Y363877D01*

+Y345324D01*

+X522999Y345505D01*

+X522949Y345567D01*

+X522889Y345619D01*

+X522822Y345662D01*

+X522749Y345693D01*

+X522672Y345713D01*

+X522593Y345720D01*

+X522514Y345715D01*

+X522436Y345698D01*

+X522362Y345668D01*

+X522294Y345628D01*

+X522233Y345577D01*

+X522180Y345518D01*

+X522138Y345450D01*

+X522106Y345377D01*

+X522086Y345300D01*

+X522079Y345221D01*

+X522084Y345142D01*

+X522101Y345064D01*

+X522131Y344990D01*

+X522172Y344923D01*

+X522428Y344534D01*

+X522644Y344121D01*

+X522822Y343691D01*

+X522963Y343247D01*

+X523064Y342793D01*

+X523115Y342407D01*

+Y341326D01*

+X523064Y340939D01*

+X522963Y340485D01*

+X522822Y340041D01*

+X522644Y339611D01*

+X522428Y339199D01*

+X522177Y338806D01*

+X522135Y338740D01*

+X522106Y338666D01*

+X522089Y338590D01*

+X522084Y338511D01*

+X522091Y338433D01*

+X522111Y338357D01*

+X522142Y338284D01*

+X522184Y338218D01*

+X522236Y338159D01*

+X522297Y338109D01*

+X522364Y338068D01*

+X522438Y338039D01*

+X522514Y338022D01*

+X522593Y338017D01*

+X522671Y338024D01*

+X522748Y338044D01*

+X522820Y338075D01*

+X522886Y338117D01*

+X522945Y338169D01*

+X522994Y338231D01*

+X523115Y338415D01*

+Y293592D01*

+X522999Y293773D01*

+X522949Y293834D01*

+X522889Y293887D01*

+X522822Y293929D01*

+X522749Y293961D01*

+X522672Y293981D01*

+X522593Y293988D01*

+X522514Y293983D01*

+X522436Y293966D01*

+X522362Y293936D01*

+X522294Y293896D01*

+X522233Y293845D01*

+X522180Y293785D01*

+X522138Y293718D01*

+X522106Y293645D01*

+X522086Y293568D01*

+X522079Y293489D01*

+X522084Y293410D01*

+X522101Y293332D01*

+X522131Y293258D01*

+X522172Y293191D01*

+X522428Y292801D01*

+X522644Y292389D01*

+X522822Y291959D01*

+X522963Y291515D01*

+X523064Y291061D01*

+X523115Y290674D01*

+Y289593D01*

+X523064Y289207D01*

+X522963Y288753D01*

+X522822Y288309D01*

+X522644Y287879D01*

+X522428Y287466D01*

+X522177Y287074D01*

+X522135Y287007D01*

+X522106Y286934D01*

+X522089Y286857D01*

+X522084Y286779D01*

+X522091Y286701D01*

+X522111Y286624D01*

+X522142Y286552D01*

+X522184Y286486D01*

+X522236Y286426D01*

+X522297Y286376D01*

+X522364Y286336D01*

+X522438Y286307D01*

+X522514Y286290D01*

+X522593Y286285D01*

+X522671Y286292D01*

+X522748Y286312D01*

+X522820Y286343D01*

+X522886Y286385D01*

+X522945Y286437D01*

+X522994Y286499D01*

+X523115Y286683D01*

+Y269000D01*

+G37*

+G36*

+X517833D02*X512546D01*

+Y286676D01*

+X512662Y286495D01*

+X512712Y286433D01*

+X512772Y286381D01*

+X512839Y286338D01*

+X512912Y286307D01*

+X512989Y286287D01*

+X513068Y286280D01*

+X513148Y286285D01*

+X513225Y286302D01*

+X513299Y286332D01*

+X513368Y286372D01*

+X513429Y286423D01*

+X513481Y286482D01*

+X513524Y286550D01*

+X513555Y286623D01*

+X513575Y286700D01*

+X513583Y286779D01*

+X513577Y286858D01*

+X513560Y286936D01*

+X513531Y287010D01*

+X513489Y287077D01*

+X513234Y287466D01*

+X513018Y287879D01*

+X512839Y288309D01*

+X512698Y288753D01*

+X512597Y289207D01*

+X512546Y289593D01*

+Y290674D01*

+X512597Y291061D01*

+X512698Y291515D01*

+X512839Y291959D01*

+X513018Y292389D01*

+X513234Y292801D01*

+X513485Y293194D01*

+X513526Y293260D01*

+X513555Y293334D01*

+X513572Y293410D01*

+X513577Y293489D01*

+X513570Y293567D01*

+X513551Y293643D01*

+X513519Y293716D01*

+X513477Y293782D01*

+X513425Y293841D01*

+X513365Y293891D01*

+X513297Y293932D01*

+X513224Y293961D01*

+X513147Y293978D01*

+X513068Y293983D01*

+X512990Y293976D01*

+X512914Y293956D01*

+X512842Y293925D01*

+X512775Y293883D01*

+X512716Y293831D01*

+X512667Y293769D01*

+X512546Y293585D01*

+Y328115D01*

+X512872Y328037D01*

+X513500Y327988D01*

+X514128Y328037D01*

+X514740Y328184D01*

+X515322Y328425D01*

+X515858Y328754D01*

+X516337Y329163D01*

+X516746Y329642D01*

+X517075Y330178D01*

+X517316Y330760D01*

+X517463Y331372D01*

+X517500Y332000D01*

+X517463Y332628D01*

+X517316Y333240D01*

+X517075Y333822D01*

+X516746Y334358D01*

+X516337Y334837D01*

+X515858Y335246D01*

+X515322Y335575D01*

+X514740Y335816D01*

+X514128Y335963D01*

+X513500Y336012D01*

+X512872Y335963D01*

+X512546Y335885D01*

+Y338408D01*

+X512662Y338227D01*

+X512712Y338166D01*

+X512772Y338113D01*

+X512839Y338071D01*

+X512912Y338039D01*

+X512989Y338019D01*

+X513068Y338012D01*

+X513148Y338017D01*

+X513225Y338034D01*

+X513299Y338064D01*

+X513368Y338104D01*

+X513429Y338155D01*

+X513481Y338215D01*

+X513524Y338282D01*

+X513555Y338355D01*

+X513575Y338432D01*

+X513583Y338511D01*

+X513577Y338590D01*

+X513560Y338668D01*

+X513531Y338742D01*

+X513489Y338809D01*

+X513234Y339199D01*

+X513018Y339611D01*

+X512839Y340041D01*

+X512698Y340485D01*

+X512597Y340939D01*

+X512546Y341326D01*

+Y342407D01*

+X512597Y342793D01*

+X512698Y343247D01*

+X512839Y343691D01*

+X513018Y344121D01*

+X513234Y344534D01*

+X513485Y344926D01*

+X513526Y344993D01*

+X513555Y345066D01*

+X513572Y345143D01*

+X513577Y345221D01*

+X513570Y345299D01*

+X513551Y345376D01*

+X513519Y345448D01*

+X513477Y345514D01*

+X513425Y345574D01*

+X513365Y345624D01*

+X513297Y345664D01*

+X513224Y345693D01*

+X513147Y345710D01*

+X513068Y345715D01*

+X512990Y345708D01*

+X512914Y345688D01*

+X512842Y345657D01*

+X512775Y345615D01*

+X512716Y345563D01*

+X512667Y345501D01*

+X512546Y345317D01*

+Y390000D01*

+X517833D01*

+Y369712D01*

+X517755Y369706D01*

+X517028Y369531D01*

+X516337Y369245D01*

+X515699Y368855D01*

+X515131Y368369D01*

+X514645Y367801D01*

+X514255Y367163D01*

+X513969Y366472D01*

+X513794Y365745D01*

+X513735Y365000D01*

+X513794Y364255D01*

+X513969Y363528D01*

+X514255Y362837D01*

+X514645Y362199D01*

+X515131Y361631D01*

+X515699Y361145D01*

+X516337Y360755D01*

+X517028Y360469D01*

+X517755Y360294D01*

+X517833Y360288D01*

+Y348187D01*

+X517831Y348187D01*

+X517277Y348163D01*

+X516729Y348090D01*

+X516188Y347970D01*

+X515660Y347803D01*

+X515149Y347590D01*

+X514658Y347333D01*

+X514192Y347035D01*

+X514130Y346984D01*

+X514078Y346925D01*

+X514035Y346858D01*

+X514004Y346785D01*

+X513984Y346708D01*

+X513977Y346628D01*

+X513982Y346549D01*

+X513999Y346472D01*

+X514028Y346398D01*

+X514069Y346329D01*

+X514120Y346268D01*

+X514179Y346216D01*

+X514246Y346173D01*

+X514319Y346141D01*

+X514396Y346122D01*

+X514476Y346114D01*

+X514555Y346119D01*

+X514633Y346137D01*

+X514706Y346166D01*

+X514774Y346208D01*

+X515163Y346463D01*

+X515576Y346679D01*

+X516006Y346858D01*

+X516449Y346998D01*

+X516904Y347100D01*

+X517366Y347161D01*

+X517831Y347181D01*

+X517833Y347181D01*

+Y336551D01*

+X517831Y336551D01*

+X517366Y336572D01*

+X516904Y336633D01*

+X516449Y336734D01*

+X516006Y336874D01*

+X515576Y337053D01*

+X515163Y337269D01*

+X514771Y337520D01*

+X514704Y337562D01*

+X514631Y337591D01*

+X514554Y337608D01*

+X514476Y337613D01*

+X514397Y337606D01*

+X514321Y337586D01*

+X514249Y337555D01*

+X514182Y337513D01*

+X514123Y337461D01*

+X514073Y337400D01*

+X514033Y337332D01*

+X514004Y337259D01*

+X513987Y337182D01*

+X513982Y337104D01*

+X513989Y337026D01*

+X514009Y336949D01*

+X514040Y336877D01*

+X514082Y336811D01*

+X514134Y336751D01*

+X514195Y336703D01*

+X514658Y336399D01*

+X515149Y336142D01*

+X515660Y335929D01*

+X516188Y335762D01*

+X516729Y335642D01*

+X517277Y335569D01*

+X517831Y335545D01*

+X517833Y335545D01*

+Y296455D01*

+X517831Y296455D01*

+X517277Y296431D01*

+X516729Y296358D01*

+X516188Y296238D01*

+X515660Y296071D01*

+X515149Y295858D01*

+X514658Y295601D01*

+X514192Y295302D01*

+X514130Y295252D01*

+X514078Y295193D01*

+X514035Y295125D01*

+X514004Y295052D01*

+X513984Y294975D01*

+X513977Y294896D01*

+X513982Y294817D01*

+X513999Y294739D01*

+X514028Y294665D01*

+X514069Y294597D01*

+X514120Y294536D01*

+X514179Y294483D01*

+X514246Y294441D01*

+X514319Y294409D01*

+X514396Y294389D01*

+X514476Y294382D01*

+X514555Y294387D01*

+X514633Y294404D01*

+X514706Y294434D01*

+X514774Y294476D01*

+X515163Y294731D01*

+X515576Y294947D01*

+X516006Y295126D01*

+X516449Y295266D01*

+X516904Y295367D01*

+X517366Y295428D01*

+X517831Y295449D01*

+X517833Y295449D01*

+Y284819D01*

+X517831Y284819D01*

+X517366Y284839D01*

+X516904Y284900D01*

+X516449Y285002D01*

+X516006Y285142D01*

+X515576Y285321D01*

+X515163Y285537D01*

+X514771Y285788D01*

+X514704Y285829D01*

+X514631Y285858D01*

+X514554Y285876D01*

+X514476Y285881D01*

+X514397Y285873D01*

+X514321Y285854D01*

+X514249Y285823D01*

+X514182Y285780D01*

+X514123Y285728D01*

+X514073Y285668D01*

+X514033Y285600D01*

+X514004Y285527D01*

+X513987Y285450D01*

+X513982Y285372D01*

+X513989Y285293D01*

+X514009Y285217D01*

+X514040Y285145D01*

+X514082Y285078D01*

+X514134Y285019D01*

+X514195Y284970D01*

+X514658Y284667D01*

+X515149Y284410D01*

+X515660Y284197D01*

+X516188Y284030D01*

+X516729Y283910D01*

+X517277Y283837D01*

+X517831Y283813D01*

+X517833Y283813D01*

+Y269000D01*

+G37*

+G36*

+X512546Y341326D02*X512536Y341401D01*

+X512516Y341866D01*

+X512536Y342331D01*

+X512546Y342407D01*

+Y341326D01*

+G37*

+G36*

+Y289593D02*X512536Y289669D01*

+X512516Y290134D01*

+X512536Y290599D01*

+X512546Y290674D01*

+Y289593D01*

+G37*

+G36*

+X246000Y303369D02*X246057Y303249D01*

+X246143Y303000D01*

+X246206Y302744D01*

+X246243Y302484D01*

+X246256Y302220D01*

+X246243Y301957D01*

+X246206Y301696D01*

+X246143Y301440D01*

+X246057Y301192D01*

+X246000Y301068D01*

+Y303369D01*

+G37*

+G36*

+X512546Y269000D02*X502000D01*

+Y360257D01*

+X505485Y360264D01*

+X505715Y360319D01*

+X505933Y360409D01*

+X506134Y360533D01*

+X506314Y360686D01*

+X506467Y360866D01*

+X506591Y361067D01*

+X506681Y361285D01*

+X506736Y361515D01*

+X506750Y361750D01*

+X506736Y368485D01*

+X506681Y368715D01*

+X506591Y368933D01*

+X506467Y369134D01*

+X506314Y369314D01*

+X506134Y369467D01*

+X505933Y369591D01*

+X505715Y369681D01*

+X505485Y369736D01*

+X505250Y369750D01*

+X502000Y369743D01*

+Y390000D01*

+X512546D01*

+Y345317D01*

+X512363Y345039D01*

+X512107Y344548D01*

+X511894Y344037D01*

+X511727Y343509D01*

+X511607Y342968D01*

+X511534Y342419D01*

+X511510Y341866D01*

+X511534Y341313D01*

+X511607Y340764D01*

+X511727Y340223D01*

+X511894Y339696D01*

+X512107Y339184D01*

+X512363Y338694D01*

+X512546Y338408D01*

+Y335885D01*

+X512260Y335816D01*

+X511678Y335575D01*

+X511142Y335246D01*

+X510663Y334837D01*

+X510254Y334358D01*

+X509925Y333822D01*

+X509684Y333240D01*

+X509537Y332628D01*

+X509488Y332000D01*

+X509537Y331372D01*

+X509684Y330760D01*

+X509925Y330178D01*

+X510254Y329642D01*

+X510663Y329163D01*

+X511142Y328754D01*

+X511678Y328425D01*

+X512260Y328184D01*

+X512546Y328115D01*

+Y293585D01*

+X512363Y293306D01*

+X512107Y292816D01*

+X511894Y292304D01*

+X511727Y291777D01*

+X511607Y291236D01*

+X511534Y290687D01*

+X511510Y290134D01*

+X511534Y289581D01*

+X511607Y289032D01*

+X511727Y288491D01*

+X511894Y287963D01*

+X512107Y287452D01*

+X512363Y286961D01*

+X512546Y286676D01*

+Y269000D01*

+G37*

+G36*

+X502000D02*X495995D01*

+Y284489D01*

+X496273Y284727D01*

+X496529Y285026D01*

+X496734Y285362D01*

+X496885Y285725D01*

+X496977Y286108D01*

+X497000Y286500D01*

+X496977Y286892D01*

+X496885Y287275D01*

+X496734Y287638D01*

+X496529Y287974D01*

+X496273Y288273D01*

+X495995Y288511D01*

+Y328740D01*

+X496000Y328740D01*

+X496510Y328780D01*

+X497007Y328900D01*

+X497480Y329095D01*

+X497916Y329363D01*

+X498305Y329695D01*

+X498637Y330084D01*

+X498905Y330520D01*

+X499100Y330993D01*

+X499220Y331490D01*

+X499250Y332000D01*

+X499220Y332510D01*

+X499100Y333007D01*

+X498905Y333480D01*

+X498637Y333916D01*

+X498305Y334305D01*

+X497916Y334637D01*

+X497480Y334905D01*

+X497007Y335100D01*

+X496510Y335220D01*

+X496000Y335260D01*

+X495995Y335260D01*

+Y362428D01*

+X496245Y362837D01*

+X496531Y363528D01*

+X496706Y364255D01*

+X496750Y365000D01*

+X496706Y365745D01*

+X496531Y366472D01*

+X496245Y367163D01*

+X495995Y367572D01*

+Y390000D01*

+X502000D01*

+Y369743D01*

+X498515Y369736D01*

+X498285Y369681D01*

+X498067Y369591D01*

+X497866Y369467D01*

+X497686Y369314D01*

+X497533Y369134D01*

+X497409Y368933D01*

+X497319Y368715D01*

+X497264Y368485D01*

+X497250Y368250D01*

+X497264Y361515D01*

+X497319Y361285D01*

+X497409Y361067D01*

+X497533Y360866D01*

+X497686Y360686D01*

+X497866Y360533D01*

+X498067Y360409D01*

+X498285Y360319D01*

+X498515Y360264D01*

+X498750Y360250D01*

+X502000Y360257D01*

+Y269000D01*

+G37*

+G36*

+X495995Y367572D02*X495855Y367801D01*

+X495369Y368369D01*

+X494801Y368855D01*

+X494163Y369245D01*

+X493472Y369531D01*

+X492745Y369706D01*

+X492000Y369765D01*

+X491993Y369764D01*

+Y390000D01*

+X495995D01*

+Y367572D01*

+G37*

+G36*

+Y288511D02*X495974Y288529D01*

+X495638Y288734D01*

+X495275Y288885D01*

+X494892Y288977D01*

+X494500Y289008D01*

+X494108Y288977D01*

+X493725Y288885D01*

+X493362Y288734D01*

+X493026Y288529D01*

+X492727Y288273D01*

+X492471Y287974D01*

+X492266Y287638D01*

+X492115Y287275D01*

+X492023Y286892D01*

+X491993Y286505D01*

+Y290780D01*

+X492500Y290740D01*

+X493010Y290780D01*

+X493507Y290900D01*

+X493980Y291095D01*

+X494416Y291363D01*

+X494805Y291695D01*

+X495137Y292084D01*

+X495405Y292520D01*

+X495600Y292993D01*

+X495720Y293490D01*

+X495750Y294000D01*

+X495720Y294510D01*

+X495600Y295007D01*

+X495405Y295480D01*

+X495137Y295916D01*

+X494805Y296305D01*

+X494416Y296637D01*

+X493980Y296905D01*

+X493507Y297100D01*

+X493010Y297220D01*

+X492500Y297260D01*

+X491993Y297220D01*

+Y360236D01*

+X492000Y360235D01*

+X492745Y360294D01*

+X493472Y360469D01*

+X494163Y360755D01*

+X494801Y361145D01*

+X495369Y361631D01*

+X495855Y362199D01*

+X495995Y362428D01*

+Y335260D01*

+X495490Y335220D01*

+X494993Y335100D01*

+X494520Y334905D01*

+X494084Y334637D01*

+X493695Y334305D01*

+X493363Y333916D01*

+X493095Y333480D01*

+X492900Y333007D01*

+X492780Y332510D01*

+X492740Y332000D01*

+X492780Y331490D01*

+X492900Y330993D01*

+X493095Y330520D01*

+X493363Y330084D01*

+X493695Y329695D01*

+X494084Y329363D01*

+X494520Y329095D01*

+X494993Y328900D01*

+X495490Y328780D01*

+X495995Y328740D01*

+Y288511D01*

+G37*

+G36*

+Y269000D02*X493000D01*

+Y207500D01*

+X491993D01*

+Y273876D01*

+X492000Y274000D01*

+X491993Y274124D01*

+Y286495D01*

+X492023Y286108D01*

+X492115Y285725D01*

+X492266Y285362D01*

+X492471Y285026D01*

+X492727Y284727D01*

+X493026Y284471D01*

+X493362Y284266D01*

+X493725Y284115D01*

+X494108Y284023D01*

+X494500Y283992D01*

+X494892Y284023D01*

+X495275Y284115D01*

+X495638Y284266D01*

+X495974Y284471D01*

+X495995Y284489D01*

+Y269000D01*

+G37*

+G36*

+X491993Y207500D02*X482995D01*

+Y319740D01*

+X483000Y319740D01*

+X483510Y319780D01*

+X484007Y319900D01*

+X484480Y320095D01*

+X484916Y320363D01*

+X485305Y320695D01*

+X485637Y321084D01*

+X485905Y321520D01*

+X486100Y321993D01*

+X486220Y322490D01*

+X486250Y323000D01*

+X486220Y323510D01*

+X486100Y324007D01*

+X485905Y324480D01*

+X485637Y324916D01*

+X485305Y325305D01*

+X484916Y325637D01*

+X484480Y325905D01*

+X484007Y326100D01*

+X483510Y326220D01*

+X483000Y326260D01*

+X482995Y326260D01*

+Y390000D01*

+X491993D01*

+Y369764D01*

+X491255Y369706D01*

+X490528Y369531D01*

+X489837Y369245D01*

+X489199Y368855D01*

+X488631Y368369D01*

+X488145Y367801D01*

+X487755Y367163D01*

+X487469Y366472D01*

+X487294Y365745D01*

+X487235Y365000D01*

+X487294Y364255D01*

+X487469Y363528D01*

+X487755Y362837D01*

+X488145Y362199D01*

+X488631Y361631D01*

+X489199Y361145D01*

+X489837Y360755D01*

+X490528Y360469D01*

+X491255Y360294D01*

+X491993Y360236D01*

+Y297220D01*

+X491990Y297220D01*

+X491493Y297100D01*

+X491020Y296905D01*

+X490584Y296637D01*

+X490195Y296305D01*

+X489863Y295916D01*

+X489595Y295480D01*

+X489400Y295007D01*

+X489280Y294510D01*

+X489240Y294000D01*

+X489280Y293490D01*

+X489400Y292993D01*

+X489595Y292520D01*

+X489863Y292084D01*

+X490195Y291695D01*

+X490584Y291363D01*

+X491020Y291095D01*

+X491493Y290900D01*

+X491990Y290780D01*

+X491993Y290780D01*

+Y286505D01*

+X491992Y286500D01*

+X491993Y286495D01*

+Y274124D01*

+X491977Y274392D01*

+X491885Y274775D01*

+X491734Y275138D01*

+X491529Y275474D01*

+X491273Y275773D01*

+X490974Y276029D01*

+X490638Y276234D01*

+X490275Y276385D01*

+X489892Y276477D01*

+X489500Y276508D01*

+X489108Y276477D01*

+X488725Y276385D01*

+X488362Y276234D01*

+X488026Y276029D01*

+X487727Y275773D01*

+X487471Y275474D01*

+X487266Y275138D01*

+X487115Y274775D01*

+X487023Y274392D01*

+X486992Y274000D01*

+X487023Y273608D01*

+X487115Y273225D01*

+X487266Y272862D01*

+X487471Y272526D01*

+X487727Y272227D01*

+X488026Y271971D01*

+X488362Y271766D01*

+X488725Y271615D01*

+X489108Y271523D01*

+X489500Y271492D01*

+X489892Y271523D01*

+X490275Y271615D01*

+X490638Y271766D01*

+X490974Y271971D01*

+X491273Y272227D01*

+X491529Y272526D01*

+X491734Y272862D01*

+X491885Y273225D01*

+X491977Y273608D01*

+X491993Y273876D01*

+Y207500D01*

+G37*

+G36*

+X482995D02*X475993D01*

+Y212987D01*

+X476000Y212986D01*

+X476706Y213042D01*

+X477395Y213207D01*

+X478049Y213478D01*

+X478653Y213848D01*

+X479192Y214308D01*

+X479652Y214847D01*

+X480022Y215451D01*

+X480293Y216105D01*

+X480458Y216794D01*

+X480500Y217500D01*

+X480458Y218206D01*

+X480293Y218895D01*

+X480022Y219549D01*

+X479652Y220153D01*

+X479192Y220692D01*

+X478653Y221152D01*

+X478049Y221522D01*

+X477395Y221793D01*

+X476706Y221958D01*

+X476000Y222014D01*

+X475993Y222013D01*

+Y272987D01*

+X476000Y272986D01*

+X476706Y273042D01*

+X477395Y273207D01*

+X478049Y273478D01*

+X478653Y273848D01*

+X479192Y274308D01*

+X479652Y274847D01*

+X480022Y275451D01*

+X480293Y276105D01*

+X480458Y276794D01*

+X480500Y277500D01*

+X480458Y278206D01*

+X480293Y278895D01*

+X480022Y279549D01*

+X479652Y280153D01*

+X479192Y280692D01*

+X478653Y281152D01*

+X478049Y281522D01*

+X477395Y281793D01*

+X476706Y281958D01*

+X476000Y282014D01*

+X475993Y282013D01*

+Y290780D01*

+X476500Y290740D01*

+X477010Y290780D01*

+X477507Y290900D01*

+X477980Y291095D01*

+X478416Y291363D01*

+X478805Y291695D01*

+X479137Y292084D01*

+X479405Y292520D01*

+X479600Y292993D01*

+X479720Y293490D01*

+X479750Y294000D01*

+X479720Y294510D01*

+X479600Y295007D01*

+X479405Y295480D01*

+X479137Y295916D01*

+X478805Y296305D01*

+X478416Y296637D01*

+X477980Y296905D01*

+X477507Y297100D01*

+X477010Y297220D01*

+X476500Y297260D01*

+X475993Y297220D01*

+Y360256D01*

+X479985Y360264D01*

+X480215Y360319D01*

+X480433Y360409D01*

+X480634Y360533D01*

+X480814Y360686D01*

+X480967Y360866D01*

+X481091Y361067D01*

+X481181Y361285D01*

+X481236Y361515D01*

+X481250Y361750D01*

+X481236Y368485D01*

+X481181Y368715D01*

+X481091Y368933D01*

+X480967Y369134D01*

+X480814Y369314D01*

+X480634Y369467D01*

+X480433Y369591D01*

+X480215Y369681D01*

+X479985Y369736D01*

+X479750Y369750D01*

+X475993Y369742D01*

+Y390000D01*

+X482995D01*

+Y326260D01*

+X482490Y326220D01*

+X481993Y326100D01*

+X481520Y325905D01*

+X481084Y325637D01*

+X480695Y325305D01*

+X480363Y324916D01*

+X480095Y324480D01*

+X479900Y324007D01*

+X479780Y323510D01*

+X479740Y323000D01*

+X479780Y322490D01*

+X479900Y321993D01*

+X480095Y321520D01*

+X480363Y321084D01*

+X480695Y320695D01*

+X481084Y320363D01*

+X481520Y320095D01*

+X481993Y319900D01*

+X482490Y319780D01*

+X482995Y319740D01*

+Y207500D01*

+G37*

+G36*

+X475993D02*X465993D01*

+Y212987D01*

+X466000Y212986D01*

+X466706Y213042D01*

+X467395Y213207D01*

+X468049Y213478D01*

+X468653Y213848D01*

+X469192Y214308D01*

+X469652Y214847D01*

+X470022Y215451D01*

+X470293Y216105D01*

+X470458Y216794D01*

+X470500Y217500D01*

+X470458Y218206D01*

+X470293Y218895D01*

+X470022Y219549D01*

+X469652Y220153D01*

+X469192Y220692D01*

+X468653Y221152D01*

+X468049Y221522D01*

+X467395Y221793D01*

+X466706Y221958D01*

+X466000Y222014D01*

+X465993Y222013D01*

+Y243383D01*

+X466000Y243500D01*

+X465993Y243617D01*

+Y261988D01*

+X466273Y262227D01*

+X466529Y262526D01*

+X466734Y262862D01*

+X466885Y263225D01*

+X466977Y263608D01*

+X467000Y264000D01*

+X466977Y264392D01*

+X466885Y264775D01*

+X466734Y265138D01*

+X466529Y265474D01*

+X466273Y265773D01*

+X465993Y266012D01*

+Y267547D01*

+X466275Y267615D01*

+X466638Y267766D01*

+X466974Y267971D01*

+X467273Y268227D01*

+X467529Y268526D01*

+X467734Y268862D01*

+X467885Y269225D01*

+X467977Y269608D01*

+X468000Y270000D01*

+X467977Y270392D01*

+X467885Y270775D01*

+X467734Y271138D01*

+X467529Y271474D01*

+X467273Y271773D01*

+X466974Y272029D01*

+X466638Y272234D01*

+X466275Y272385D01*

+X465993Y272453D01*

+Y272987D01*

+X466000Y272986D01*

+X466706Y273042D01*

+X467395Y273207D01*

+X468049Y273478D01*

+X468653Y273848D01*

+X469192Y274308D01*

+X469652Y274847D01*

+X470022Y275451D01*

+X470293Y276105D01*

+X470458Y276794D01*

+X470500Y277500D01*

+X470458Y278206D01*

+X470293Y278895D01*

+X470022Y279549D01*

+X469652Y280153D01*

+X469192Y280692D01*

+X468653Y281152D01*

+X468049Y281522D01*

+X467395Y281793D01*

+X466706Y281958D01*

+X466000Y282014D01*

+X465993Y282013D01*

+Y309545D01*

+X466075Y309678D01*

+X466316Y310260D01*

+X466463Y310872D01*

+X466500Y311500D01*

+X466463Y312128D01*

+X466316Y312740D01*

+X466075Y313322D01*

+X465993Y313455D01*

+Y360275D01*

+X466500Y360235D01*

+X467245Y360294D01*

+X467972Y360469D01*

+X468663Y360755D01*

+X469301Y361145D01*

+X469869Y361631D01*

+X470355Y362199D01*

+X470745Y362837D01*

+X471031Y363528D01*

+X471206Y364255D01*

+X471250Y365000D01*

+X471206Y365745D01*

+X471031Y366472D01*

+X470745Y367163D01*

+X470355Y367801D01*

+X469869Y368369D01*

+X469301Y368855D01*

+X468663Y369245D01*

+X467972Y369531D01*

+X467245Y369706D01*

+X466500Y369765D01*

+X465993Y369725D01*

+Y390000D01*

+X475993D01*

+Y369742D01*

+X473015Y369736D01*

+X472785Y369681D01*

+X472567Y369591D01*

+X472366Y369467D01*

+X472186Y369314D01*

+X472033Y369134D01*

+X471909Y368933D01*

+X471819Y368715D01*

+X471764Y368485D01*

+X471750Y368250D01*

+X471764Y361515D01*

+X471819Y361285D01*

+X471909Y361067D01*

+X472033Y360866D01*

+X472186Y360686D01*

+X472366Y360533D01*

+X472567Y360409D01*

+X472785Y360319D01*

+X473015Y360264D01*

+X473250Y360250D01*

+X475993Y360256D01*

+Y297220D01*

+X475990Y297220D01*

+X475493Y297100D01*

+X475020Y296905D01*

+X474584Y296637D01*

+X474195Y296305D01*

+X473863Y295916D01*

+X473750Y295732D01*

+X473637Y295916D01*

+X473305Y296305D01*

+X472916Y296637D01*

+X472480Y296905D01*

+X472007Y297100D01*

+X471510Y297220D01*

+X471000Y297260D01*

+X470490Y297220D01*

+X469993Y297100D01*

+X469520Y296905D01*

+X469084Y296637D01*

+X468695Y296305D01*

+X468363Y295916D01*

+X468095Y295480D01*

+X467900Y295007D01*

+X467780Y294510D01*

+X467740Y294000D01*

+X467780Y293490D01*

+X467900Y292993D01*

+X468095Y292520D01*

+X468363Y292084D01*

+X468695Y291695D01*

+X469084Y291363D01*

+X469520Y291095D01*

+X469993Y290900D01*

+X470490Y290780D01*

+X471000Y290740D01*

+X471510Y290780D01*

+X472007Y290900D01*

+X472480Y291095D01*

+X472916Y291363D01*

+X473305Y291695D01*

+X473637Y292084D01*

+X473750Y292268D01*

+X473863Y292084D01*

+X474195Y291695D01*

+X474584Y291363D01*

+X475020Y291095D01*

+X475493Y290900D01*

+X475990Y290780D01*

+X475993Y290780D01*

+Y282013D01*

+X475294Y281958D01*

+X474605Y281793D01*

+X473951Y281522D01*

+X473347Y281152D01*

+X472808Y280692D01*

+X472348Y280153D01*

+X471978Y279549D01*

+X471707Y278895D01*

+X471542Y278206D01*

+X471486Y277500D01*

+X471542Y276794D01*

+X471707Y276105D01*

+X471978Y275451D01*

+X472348Y274847D01*

+X472808Y274308D01*

+X473347Y273848D01*

+X473951Y273478D01*

+X474605Y273207D01*

+X475294Y273042D01*

+X475993Y272987D01*

+Y222013D01*

+X475294Y221958D01*

+X474605Y221793D01*

+X473951Y221522D01*

+X473347Y221152D01*

+X472808Y220692D01*

+X472348Y220153D01*

+X471978Y219549D01*

+X471707Y218895D01*

+X471542Y218206D01*

+X471486Y217500D01*

+X471542Y216794D01*

+X471707Y216105D01*

+X471978Y215451D01*

+X472348Y214847D01*

+X472808Y214308D01*

+X473347Y213848D01*

+X473951Y213478D01*

+X474605Y213207D01*

+X475294Y213042D01*

+X475993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X465993D02*X455993D01*

+Y212987D01*

+X456000Y212986D01*

+X456706Y213042D01*

+X457395Y213207D01*

+X458049Y213478D01*

+X458653Y213848D01*

+X459192Y214308D01*

+X459652Y214847D01*

+X460022Y215451D01*

+X460293Y216105D01*

+X460458Y216794D01*

+X460500Y217500D01*

+X460458Y218206D01*

+X460293Y218895D01*

+X460022Y219549D01*

+X459652Y220153D01*

+X459192Y220692D01*

+X458653Y221152D01*

+X458049Y221522D01*

+X457395Y221793D01*

+X456706Y221958D01*

+X456000Y222014D01*

+X455993Y222013D01*

+Y247705D01*

+X456138Y247766D01*

+X456474Y247971D01*

+X456773Y248227D01*

+X457029Y248526D01*

+X457234Y248862D01*

+X457385Y249225D01*

+X457477Y249608D01*

+X457500Y250000D01*

+X457477Y250392D01*

+X457385Y250775D01*

+X457234Y251138D01*

+X457029Y251474D01*

+X456773Y251773D01*

+X456474Y252029D01*

+X456138Y252234D01*

+X455993Y252295D01*

+Y272987D01*

+X456000Y272986D01*

+X456706Y273042D01*

+X457395Y273207D01*

+X458049Y273478D01*

+X458653Y273848D01*

+X459192Y274308D01*

+X459652Y274847D01*

+X460022Y275451D01*

+X460293Y276105D01*

+X460458Y276794D01*

+X460500Y277500D01*

+X460458Y278206D01*

+X460293Y278895D01*

+X460022Y279549D01*

+X459652Y280153D01*

+X459192Y280692D01*

+X458653Y281152D01*

+X458049Y281522D01*

+X457395Y281793D01*

+X456706Y281958D01*

+X456000Y282014D01*

+X455993Y282013D01*

+Y390000D01*

+X465993D01*

+Y369725D01*

+X465755Y369706D01*

+X465028Y369531D01*

+X464337Y369245D01*

+X463699Y368855D01*

+X463131Y368369D01*

+X462645Y367801D01*

+X462255Y367163D01*

+X461969Y366472D01*

+X461794Y365745D01*

+X461735Y365000D01*

+X461794Y364255D01*

+X461969Y363528D01*

+X462255Y362837D01*

+X462645Y362199D01*

+X463131Y361631D01*

+X463699Y361145D01*

+X464337Y360755D01*

+X465028Y360469D01*

+X465755Y360294D01*

+X465993Y360275D01*

+Y313455D01*

+X465746Y313858D01*

+X465337Y314337D01*

+X464858Y314746D01*

+X464322Y315075D01*

+X463740Y315316D01*

+X463128Y315463D01*

+X462500Y315512D01*

+X461872Y315463D01*

+X461260Y315316D01*

+X460678Y315075D01*

+X460142Y314746D01*

+X459663Y314337D01*

+X459254Y313858D01*

+X458925Y313322D01*

+X458684Y312740D01*

+X458537Y312128D01*

+X458488Y311500D01*

+X458537Y310872D01*

+X458684Y310260D01*

+X458925Y309678D01*

+X459254Y309142D01*

+X459663Y308663D01*

+X460142Y308254D01*

+X460678Y307925D01*

+X461260Y307684D01*

+X461872Y307537D01*

+X462500Y307488D01*

+X463128Y307537D01*

+X463740Y307684D01*

+X464322Y307925D01*

+X464858Y308254D01*

+X465337Y308663D01*

+X465746Y309142D01*

+X465993Y309545D01*

+Y282013D01*

+X465294Y281958D01*

+X464605Y281793D01*

+X463951Y281522D01*

+X463347Y281152D01*

+X462808Y280692D01*

+X462348Y280153D01*

+X461978Y279549D01*

+X461707Y278895D01*

+X461542Y278206D01*

+X461486Y277500D01*

+X461542Y276794D01*

+X461707Y276105D01*

+X461978Y275451D01*

+X462348Y274847D01*

+X462808Y274308D01*

+X463347Y273848D01*

+X463951Y273478D01*

+X464605Y273207D01*

+X465294Y273042D01*

+X465993Y272987D01*

+Y272453D01*

+X465892Y272477D01*

+X465500Y272508D01*

+X465108Y272477D01*

+X464725Y272385D01*

+X464362Y272234D01*

+X464026Y272029D01*

+X463727Y271773D01*

+X463471Y271474D01*

+X463266Y271138D01*

+X463115Y270775D01*

+X463023Y270392D01*

+X462992Y270000D01*

+X463023Y269608D01*

+X463115Y269225D01*

+X463266Y268862D01*

+X463471Y268526D01*

+X463727Y268227D01*

+X464026Y267971D01*

+X464362Y267766D01*

+X464725Y267615D01*

+X465108Y267523D01*

+X465500Y267492D01*

+X465892Y267523D01*

+X465993Y267547D01*

+Y266012D01*

+X465974Y266029D01*

+X465638Y266234D01*

+X465275Y266385D01*

+X464892Y266477D01*

+X464500Y266508D01*

+X464108Y266477D01*

+X463725Y266385D01*

+X463362Y266234D01*

+X463026Y266029D01*

+X462727Y265773D01*

+X462471Y265474D01*

+X462266Y265138D01*

+X462115Y264775D01*

+X462023Y264392D01*

+X461992Y264000D01*

+X462023Y263608D01*

+X462115Y263225D01*

+X462266Y262862D01*

+X462471Y262526D01*

+X462727Y262227D01*

+X463026Y261971D01*

+X463362Y261766D01*

+X463725Y261615D01*

+X464108Y261523D01*

+X464500Y261492D01*

+X464892Y261523D01*

+X465275Y261615D01*

+X465638Y261766D01*

+X465974Y261971D01*

+X465993Y261988D01*

+Y243617D01*

+X465977Y243892D01*

+X465885Y244275D01*

+X465734Y244638D01*

+X465529Y244974D01*

+X465273Y245273D01*

+X464974Y245529D01*

+X464638Y245734D01*

+X464275Y245885D01*

+X463892Y245977D01*

+X463500Y246008D01*

+X463108Y245977D01*

+X462725Y245885D01*

+X462362Y245734D01*

+X462026Y245529D01*

+X461727Y245273D01*

+X461471Y244974D01*

+X461266Y244638D01*

+X461115Y244275D01*

+X461023Y243892D01*

+X460992Y243500D01*

+X461023Y243108D01*

+X461115Y242725D01*

+X461266Y242362D01*

+X461471Y242026D01*

+X461727Y241727D01*

+X462026Y241471D01*

+X462362Y241266D01*

+X462725Y241115D01*

+X463108Y241023D01*

+X463500Y240992D01*

+X463892Y241023D01*

+X464275Y241115D01*

+X464638Y241266D01*

+X464974Y241471D01*

+X465273Y241727D01*

+X465529Y242026D01*

+X465734Y242362D01*

+X465885Y242725D01*

+X465977Y243108D01*

+X465993Y243383D01*

+Y222013D01*

+X465294Y221958D01*

+X464605Y221793D01*

+X463951Y221522D01*

+X463347Y221152D01*

+X462808Y220692D01*

+X462348Y220153D01*

+X461978Y219549D01*

+X461707Y218895D01*

+X461542Y218206D01*

+X461486Y217500D01*

+X461542Y216794D01*

+X461707Y216105D01*

+X461978Y215451D01*

+X462348Y214847D01*

+X462808Y214308D01*

+X463347Y213848D01*

+X463951Y213478D01*

+X464605Y213207D01*

+X465294Y213042D01*

+X465993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X455993D02*X451000D01*

+Y237993D01*

+X451273Y238227D01*

+X451529Y238526D01*

+X451734Y238862D01*

+X451885Y239225D01*

+X451977Y239608D01*

+X452000Y240000D01*

+X451977Y240392D01*

+X451885Y240775D01*

+X451734Y241138D01*

+X451529Y241474D01*

+X451273Y241773D01*

+X451000Y242007D01*

+Y311493D01*

+X451273Y311727D01*

+X451529Y312026D01*

+X451734Y312362D01*

+X451885Y312725D01*

+X451977Y313108D01*

+X452000Y313500D01*

+X451977Y313892D01*

+X451885Y314275D01*

+X451734Y314638D01*

+X451529Y314974D01*

+X451273Y315273D01*

+X451000Y315507D01*

+Y360257D01*

+X454485Y360264D01*

+X454715Y360319D01*

+X454933Y360409D01*

+X455134Y360533D01*

+X455314Y360686D01*

+X455467Y360866D01*

+X455591Y361067D01*

+X455681Y361285D01*

+X455736Y361515D01*

+X455750Y361750D01*

+X455736Y368485D01*

+X455681Y368715D01*

+X455591Y368933D01*

+X455467Y369134D01*

+X455314Y369314D01*

+X455134Y369467D01*

+X454933Y369591D01*

+X454715Y369681D01*

+X454485Y369736D01*

+X454250Y369750D01*

+X451000Y369743D01*

+Y390000D01*

+X455993D01*

+Y282013D01*

+X455294Y281958D01*

+X454605Y281793D01*

+X453951Y281522D01*

+X453347Y281152D01*

+X452808Y280692D01*

+X452348Y280153D01*

+X451978Y279549D01*

+X451707Y278895D01*

+X451542Y278206D01*

+X451486Y277500D01*

+X451542Y276794D01*

+X451707Y276105D01*

+X451978Y275451D01*

+X452348Y274847D01*

+X452808Y274308D01*

+X453347Y273848D01*

+X453951Y273478D01*

+X454605Y273207D01*

+X455294Y273042D01*

+X455993Y272987D01*

+Y252295D01*

+X455775Y252385D01*

+X455392Y252477D01*

+X455000Y252508D01*

+X454608Y252477D01*

+X454225Y252385D01*

+X453862Y252234D01*

+X453526Y252029D01*

+X453227Y251773D01*

+X452971Y251474D01*

+X452766Y251138D01*

+X452615Y250775D01*

+X452523Y250392D01*

+X452492Y250000D01*

+X452523Y249608D01*

+X452615Y249225D01*

+X452766Y248862D01*

+X452971Y248526D01*

+X453227Y248227D01*

+X453526Y247971D01*

+X453862Y247766D01*

+X454225Y247615D01*

+X454608Y247523D01*

+X455000Y247492D01*

+X455392Y247523D01*

+X455775Y247615D01*

+X455993Y247705D01*

+Y222013D01*

+X455294Y221958D01*

+X454605Y221793D01*

+X453951Y221522D01*

+X453347Y221152D01*

+X452808Y220692D01*

+X452348Y220153D01*

+X451978Y219549D01*

+X451707Y218895D01*

+X451542Y218206D01*

+X451486Y217500D01*

+X451542Y216794D01*

+X451707Y216105D01*

+X451978Y215451D01*

+X452348Y214847D01*

+X452808Y214308D01*

+X453347Y213848D01*

+X453951Y213478D01*

+X454605Y213207D01*

+X455294Y213042D01*

+X455993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X451000D02*X445993D01*

+Y212987D01*

+X446000Y212986D01*

+X446706Y213042D01*

+X447395Y213207D01*

+X448049Y213478D01*

+X448653Y213848D01*

+X449192Y214308D01*

+X449652Y214847D01*

+X450022Y215451D01*

+X450293Y216105D01*

+X450458Y216794D01*

+X450500Y217500D01*

+X450458Y218206D01*

+X450293Y218895D01*

+X450022Y219549D01*

+X449652Y220153D01*

+X449192Y220692D01*

+X448653Y221152D01*

+X448049Y221522D01*

+X447395Y221793D01*

+X446706Y221958D01*

+X446000Y222014D01*

+X445993Y222013D01*

+Y272987D01*

+X446000Y272986D01*

+X446706Y273042D01*

+X447395Y273207D01*

+X448049Y273478D01*

+X448653Y273848D01*

+X449192Y274308D01*

+X449652Y274847D01*

+X450022Y275451D01*

+X450293Y276105D01*

+X450458Y276794D01*

+X450500Y277500D01*

+X450458Y278206D01*

+X450293Y278895D01*

+X450022Y279549D01*

+X449652Y280153D01*

+X449192Y280692D01*

+X448653Y281152D01*

+X448049Y281522D01*

+X447395Y281793D01*

+X446706Y281958D01*

+X446000Y282014D01*

+X445993Y282013D01*

+Y390000D01*

+X451000D01*

+Y369743D01*

+X447515Y369736D01*

+X447285Y369681D01*

+X447067Y369591D01*

+X446866Y369467D01*

+X446686Y369314D01*

+X446533Y369134D01*

+X446409Y368933D01*

+X446319Y368715D01*

+X446264Y368485D01*

+X446250Y368250D01*

+X446264Y361515D01*

+X446319Y361285D01*

+X446409Y361067D01*

+X446533Y360866D01*

+X446686Y360686D01*

+X446866Y360533D01*

+X447067Y360409D01*

+X447285Y360319D01*

+X447515Y360264D01*

+X447750Y360250D01*

+X451000Y360257D01*

+Y315507D01*

+X450974Y315529D01*

+X450638Y315734D01*

+X450275Y315885D01*

+X449892Y315977D01*

+X449500Y316008D01*

+X449108Y315977D01*

+X448725Y315885D01*

+X448362Y315734D01*

+X448026Y315529D01*

+X447727Y315273D01*

+X447471Y314974D01*

+X447266Y314638D01*

+X447115Y314275D01*

+X447023Y313892D01*

+X446992Y313500D01*

+X447023Y313108D01*

+X447115Y312725D01*

+X447266Y312362D01*

+X447471Y312026D01*

+X447727Y311727D01*

+X448026Y311471D01*

+X448362Y311266D01*

+X448725Y311115D01*

+X449108Y311023D01*

+X449500Y310992D01*

+X449892Y311023D01*

+X450275Y311115D01*

+X450638Y311266D01*

+X450974Y311471D01*

+X451000Y311493D01*

+Y242007D01*

+X450974Y242029D01*

+X450638Y242234D01*

+X450275Y242385D01*

+X449892Y242477D01*

+X449500Y242508D01*

+X449108Y242477D01*

+X448725Y242385D01*

+X448362Y242234D01*

+X448026Y242029D01*

+X447727Y241773D01*

+X447471Y241474D01*

+X447266Y241138D01*

+X447115Y240775D01*

+X447023Y240392D01*

+X446992Y240000D01*

+X447023Y239608D01*

+X447115Y239225D01*

+X447266Y238862D01*

+X447471Y238526D01*

+X447727Y238227D01*

+X448026Y237971D01*

+X448362Y237766D01*

+X448725Y237615D01*

+X449108Y237523D01*

+X449500Y237492D01*

+X449892Y237523D01*

+X450275Y237615D01*

+X450638Y237766D01*

+X450974Y237971D01*

+X451000Y237993D01*

+Y207500D01*

+G37*

+G36*

+X445993D02*X440993D01*

+Y360236D01*

+X441000Y360235D01*

+X441745Y360294D01*

+X442472Y360469D01*

+X443163Y360755D01*

+X443801Y361145D01*

+X444369Y361631D01*

+X444855Y362199D01*

+X445245Y362837D01*

+X445531Y363528D01*

+X445706Y364255D01*

+X445750Y365000D01*

+X445706Y365745D01*

+X445531Y366472D01*

+X445245Y367163D01*

+X444855Y367801D01*

+X444369Y368369D01*

+X443801Y368855D01*

+X443163Y369245D01*

+X442472Y369531D01*

+X441745Y369706D01*

+X441000Y369765D01*

+X440993Y369764D01*

+Y390000D01*

+X445993D01*

+Y282013D01*

+X445294Y281958D01*

+X444605Y281793D01*

+X443951Y281522D01*

+X443347Y281152D01*

+X442808Y280692D01*

+X442348Y280153D01*

+X441978Y279549D01*

+X441707Y278895D01*

+X441542Y278206D01*

+X441486Y277500D01*

+X441542Y276794D01*

+X441707Y276105D01*

+X441978Y275451D01*

+X442348Y274847D01*

+X442808Y274308D01*

+X443347Y273848D01*

+X443951Y273478D01*

+X444605Y273207D01*

+X445294Y273042D01*

+X445993Y272987D01*

+Y222013D01*

+X445294Y221958D01*

+X444605Y221793D01*

+X443951Y221522D01*

+X443347Y221152D01*

+X442808Y220692D01*

+X442348Y220153D01*

+X441978Y219549D01*

+X441707Y218895D01*

+X441542Y218206D01*

+X441486Y217500D01*

+X441542Y216794D01*

+X441707Y216105D01*

+X441978Y215451D01*

+X442348Y214847D01*

+X442808Y214308D01*

+X443347Y213848D01*

+X443951Y213478D01*

+X444605Y213207D01*

+X445294Y213042D01*

+X445993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X440993D02*X435993D01*

+Y212987D01*

+X436000Y212986D01*

+X436706Y213042D01*

+X437395Y213207D01*

+X438049Y213478D01*

+X438653Y213848D01*

+X439192Y214308D01*

+X439652Y214847D01*

+X440022Y215451D01*

+X440293Y216105D01*

+X440458Y216794D01*

+X440500Y217500D01*

+X440458Y218206D01*

+X440293Y218895D01*

+X440022Y219549D01*

+X439652Y220153D01*

+X439192Y220692D01*

+X438653Y221152D01*

+X438049Y221522D01*

+X437395Y221793D01*

+X436706Y221958D01*

+X436000Y222014D01*

+X435993Y222013D01*

+Y272987D01*

+X436000Y272986D01*

+X436706Y273042D01*

+X437395Y273207D01*

+X438049Y273478D01*

+X438653Y273848D01*

+X439192Y274308D01*

+X439652Y274847D01*

+X440022Y275451D01*

+X440293Y276105D01*

+X440458Y276794D01*

+X440500Y277500D01*

+X440458Y278206D01*

+X440293Y278895D01*

+X440022Y279549D01*

+X439652Y280153D01*

+X439192Y280692D01*

+X438653Y281152D01*

+X438049Y281522D01*

+X437395Y281793D01*

+X436706Y281958D01*

+X436000Y282014D01*

+X435993Y282013D01*

+Y390000D01*

+X440993D01*

+Y369764D01*

+X440255Y369706D01*

+X439528Y369531D01*

+X438837Y369245D01*

+X438199Y368855D01*

+X437631Y368369D01*

+X437145Y367801D01*

+X436755Y367163D01*

+X436469Y366472D01*

+X436294Y365745D01*

+X436235Y365000D01*

+X436294Y364255D01*

+X436469Y363528D01*

+X436755Y362837D01*

+X437145Y362199D01*

+X437631Y361631D01*

+X438199Y361145D01*

+X438837Y360755D01*

+X439528Y360469D01*

+X440255Y360294D01*

+X440993Y360236D01*

+Y207500D01*

+G37*

+G36*

+X435993D02*X428996D01*

+Y214141D01*

+X429192Y214308D01*

+X429652Y214847D01*

+X430022Y215451D01*

+X430293Y216105D01*

+X430458Y216794D01*

+X430500Y217500D01*

+X430458Y218206D01*

+X430293Y218895D01*

+X430022Y219549D01*

+X429652Y220153D01*

+X429192Y220692D01*

+X428996Y220859D01*

+Y251993D01*

+X429000Y251992D01*

+X429392Y252023D01*

+X429775Y252115D01*

+X430138Y252266D01*

+X430474Y252471D01*

+X430773Y252727D01*

+X431029Y253026D01*

+X431234Y253362D01*

+X431385Y253725D01*

+X431477Y254108D01*

+X431500Y254500D01*

+X431477Y254892D01*

+X431385Y255275D01*

+X431234Y255638D01*

+X431029Y255974D01*

+X430773Y256273D01*

+X430474Y256529D01*

+X430138Y256734D01*

+X429775Y256885D01*

+X429392Y256977D01*

+X429000Y257008D01*

+X428996Y257007D01*

+Y274141D01*

+X429192Y274308D01*

+X429652Y274847D01*

+X430022Y275451D01*

+X430293Y276105D01*

+X430458Y276794D01*

+X430500Y277500D01*

+X430458Y278206D01*

+X430293Y278895D01*

+X430022Y279549D01*

+X429652Y280153D01*

+X429192Y280692D01*

+X428996Y280859D01*

+Y360913D01*

+X429091Y361067D01*

+X429181Y361285D01*

+X429236Y361515D01*

+X429250Y361750D01*

+X429236Y368485D01*

+X429181Y368715D01*

+X429091Y368933D01*

+X428996Y369087D01*

+Y390000D01*

+X435993D01*

+Y282013D01*

+X435294Y281958D01*

+X434605Y281793D01*

+X433951Y281522D01*

+X433347Y281152D01*

+X432808Y280692D01*

+X432348Y280153D01*

+X431978Y279549D01*

+X431707Y278895D01*

+X431542Y278206D01*

+X431486Y277500D01*

+X431542Y276794D01*

+X431707Y276105D01*

+X431978Y275451D01*

+X432348Y274847D01*

+X432808Y274308D01*

+X433347Y273848D01*

+X433951Y273478D01*

+X434605Y273207D01*

+X435294Y273042D01*

+X435993Y272987D01*

+Y222013D01*

+X435294Y221958D01*

+X434605Y221793D01*

+X433951Y221522D01*

+X433347Y221152D01*

+X432808Y220692D01*

+X432348Y220153D01*

+X431978Y219549D01*

+X431707Y218895D01*

+X431542Y218206D01*

+X431486Y217500D01*

+X431542Y216794D01*

+X431707Y216105D01*

+X431978Y215451D01*

+X432348Y214847D01*

+X432808Y214308D01*

+X433347Y213848D01*

+X433951Y213478D01*

+X434605Y213207D01*

+X435294Y213042D01*

+X435993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X428996Y369087D02*X428967Y369134D01*

+X428814Y369314D01*

+X428634Y369467D01*

+X428433Y369591D01*

+X428215Y369681D01*

+X427985Y369736D01*

+X427750Y369750D01*

+X425993Y369746D01*

+Y390000D01*

+X428996D01*

+Y369087D01*

+G37*

+G36*

+Y280859D02*X428653Y281152D01*

+X428049Y281522D01*

+X427395Y281793D01*

+X426706Y281958D01*

+X426000Y282014D01*

+X425993Y282013D01*

+Y360260D01*

+X427985Y360264D01*

+X428215Y360319D01*

+X428433Y360409D01*

+X428634Y360533D01*

+X428814Y360686D01*

+X428967Y360866D01*

+X428996Y360913D01*

+Y280859D01*

+G37*

+G36*

+Y220859D02*X428653Y221152D01*

+X428049Y221522D01*

+X427395Y221793D01*

+X426706Y221958D01*

+X426000Y222014D01*

+X425993Y222013D01*

+Y272987D01*

+X426000Y272986D01*

+X426706Y273042D01*

+X427395Y273207D01*

+X428049Y273478D01*

+X428653Y273848D01*

+X428996Y274141D01*

+Y257007D01*

+X428608Y256977D01*

+X428225Y256885D01*

+X427862Y256734D01*

+X427526Y256529D01*

+X427227Y256273D01*

+X426971Y255974D01*

+X426766Y255638D01*

+X426615Y255275D01*

+X426523Y254892D01*

+X426492Y254500D01*

+X426523Y254108D01*

+X426615Y253725D01*

+X426766Y253362D01*

+X426971Y253026D01*

+X427227Y252727D01*

+X427526Y252471D01*

+X427862Y252266D01*

+X428225Y252115D01*

+X428608Y252023D01*

+X428996Y251993D01*

+Y220859D01*

+G37*

+G36*

+Y207500D02*X425993D01*

+Y212987D01*

+X426000Y212986D01*

+X426706Y213042D01*

+X427395Y213207D01*

+X428049Y213478D01*

+X428653Y213848D01*

+X428996Y214141D01*

+Y207500D01*

+G37*

+G36*

+X422496Y274674D02*X422808Y274308D01*

+X423347Y273848D01*

+X423951Y273478D01*

+X424605Y273207D01*

+X425294Y273042D01*

+X425993Y272987D01*

+Y222013D01*

+X425294Y221958D01*

+X424605Y221793D01*

+X423951Y221522D01*

+X423347Y221152D01*

+X422808Y220692D01*

+X422496Y220326D01*

+Y274674D01*

+G37*

+G36*

+Y360253D02*X425993Y360260D01*

+Y282013D01*

+X425294Y281958D01*

+X424605Y281793D01*

+X423951Y281522D01*

+X423347Y281152D01*

+X422808Y280692D01*

+X422496Y280326D01*

+Y328993D01*

+X422500Y328992D01*

+X422892Y329023D01*

+X423275Y329115D01*

+X423638Y329266D01*

+X423974Y329471D01*

+X424273Y329727D01*

+X424529Y330026D01*

+X424734Y330362D01*

+X424885Y330725D01*

+X424977Y331108D01*

+X425000Y331500D01*

+X424977Y331892D01*

+X424885Y332275D01*

+X424734Y332638D01*

+X424529Y332974D01*

+X424273Y333273D01*

+X423974Y333529D01*

+X423638Y333734D01*

+X423275Y333885D01*

+X422892Y333977D01*

+X422500Y334008D01*

+X422496Y334007D01*

+Y360253D01*

+G37*

+G36*

+Y390000D02*X425993D01*

+Y369746D01*

+X422496Y369739D01*

+Y390000D01*

+G37*

+G36*

+X425993Y207500D02*X422496D01*

+Y214674D01*

+X422808Y214308D01*

+X423347Y213848D01*

+X423951Y213478D01*

+X424605Y213207D01*

+X425294Y213042D01*

+X425993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X422496D02*X415993D01*

+Y212987D01*

+X416000Y212986D01*

+X416706Y213042D01*

+X417395Y213207D01*

+X418049Y213478D01*

+X418653Y213848D01*

+X419192Y214308D01*

+X419652Y214847D01*

+X420022Y215451D01*

+X420293Y216105D01*

+X420458Y216794D01*

+X420500Y217500D01*

+X420458Y218206D01*

+X420293Y218895D01*

+X420022Y219549D01*

+X419652Y220153D01*

+X419192Y220692D01*

+X418653Y221152D01*

+X418049Y221522D01*

+X417395Y221793D01*

+X416706Y221958D01*

+X416000Y222014D01*

+X415993Y222013D01*

+Y272987D01*

+X416000Y272986D01*

+X416706Y273042D01*

+X417395Y273207D01*

+X418049Y273478D01*

+X418653Y273848D01*

+X419192Y274308D01*

+X419652Y274847D01*

+X420022Y275451D01*

+X420293Y276105D01*

+X420458Y276794D01*

+X420500Y277500D01*

+X420458Y278206D01*

+X420293Y278895D01*

+X420022Y279549D01*

+X419652Y280153D01*

+X419192Y280692D01*

+X418653Y281152D01*

+X418049Y281522D01*

+X417395Y281793D01*

+X416706Y281958D01*

+X416000Y282014D01*

+X415993Y282013D01*

+Y284047D01*

+X416275Y284115D01*

+X416638Y284266D01*

+X416974Y284471D01*

+X417273Y284727D01*

+X417529Y285026D01*

+X417734Y285362D01*

+X417885Y285725D01*

+X417977Y286108D01*

+X418000Y286500D01*

+X417977Y286892D01*

+X417885Y287275D01*

+X417734Y287638D01*

+X417529Y287974D01*

+X417273Y288273D01*

+X416974Y288529D01*

+X416638Y288734D01*

+X416275Y288885D01*

+X415993Y288953D01*

+Y360477D01*

+X416663Y360755D01*

+X417301Y361145D01*

+X417869Y361631D01*

+X418355Y362199D01*

+X418745Y362837D01*

+X419031Y363528D01*

+X419206Y364255D01*

+X419250Y365000D01*

+X419206Y365745D01*

+X419031Y366472D01*

+X418745Y367163D01*

+X418355Y367801D01*

+X417869Y368369D01*

+X417301Y368855D01*

+X416663Y369245D01*

+X415993Y369523D01*

+Y390000D01*

+X422496D01*

+Y369739D01*

+X421015Y369736D01*

+X420785Y369681D01*

+X420567Y369591D01*

+X420366Y369467D01*

+X420186Y369314D01*

+X420033Y369134D01*

+X419909Y368933D01*

+X419819Y368715D01*

+X419764Y368485D01*

+X419750Y368250D01*

+X419764Y361515D01*

+X419819Y361285D01*

+X419909Y361067D01*

+X420033Y360866D01*

+X420186Y360686D01*

+X420366Y360533D01*

+X420567Y360409D01*

+X420785Y360319D01*

+X421015Y360264D01*

+X421250Y360250D01*

+X422496Y360253D01*

+Y334007D01*

+X422108Y333977D01*

+X421725Y333885D01*

+X421362Y333734D01*

+X421026Y333529D01*

+X420727Y333273D01*

+X420471Y332974D01*

+X420266Y332638D01*

+X420115Y332275D01*

+X420023Y331892D01*

+X419992Y331500D01*

+X420023Y331108D01*

+X420115Y330725D01*

+X420266Y330362D01*

+X420471Y330026D01*

+X420727Y329727D01*

+X421026Y329471D01*

+X421362Y329266D01*

+X421725Y329115D01*

+X422108Y329023D01*

+X422496Y328993D01*

+Y280326D01*

+X422348Y280153D01*

+X421978Y279549D01*

+X421707Y278895D01*

+X421542Y278206D01*

+X421486Y277500D01*

+X421542Y276794D01*

+X421707Y276105D01*

+X421978Y275451D01*

+X422348Y274847D01*

+X422496Y274674D01*

+Y220326D01*

+X422348Y220153D01*

+X421978Y219549D01*

+X421707Y218895D01*

+X421542Y218206D01*

+X421486Y217500D01*

+X421542Y216794D01*

+X421707Y216105D01*

+X421978Y215451D01*

+X422348Y214847D01*

+X422496Y214674D01*

+Y207500D01*

+G37*

+G36*

+X409994Y390000D02*X415993D01*

+Y369523D01*

+X415972Y369531D01*

+X415245Y369706D01*

+X414500Y369765D01*

+X413755Y369706D01*

+X413028Y369531D01*

+X412337Y369245D01*

+X411699Y368855D01*

+X411131Y368369D01*

+X410645Y367801D01*

+X410255Y367163D01*

+X409994Y366534D01*

+Y390000D01*

+G37*

+G36*

+X413073Y274082D02*X413347Y273848D01*

+X413951Y273478D01*

+X414605Y273207D01*

+X415294Y273042D01*

+X415993Y272987D01*

+Y222013D01*

+X415294Y221958D01*

+X414605Y221793D01*

+X413951Y221522D01*

+X413347Y221152D01*

+X413073Y220918D01*

+Y274082D01*

+G37*

+G36*

+Y285900D02*X413115Y285725D01*

+X413266Y285362D01*

+X413471Y285026D01*

+X413727Y284727D01*

+X414026Y284471D01*

+X414362Y284266D01*

+X414725Y284115D01*

+X415108Y284023D01*

+X415500Y283992D01*

+X415892Y284023D01*

+X415993Y284047D01*

+Y282013D01*

+X415294Y281958D01*

+X414605Y281793D01*

+X413951Y281522D01*

+X413347Y281152D01*

+X413073Y280918D01*

+Y285900D01*

+G37*

+G36*

+Y309889D02*X413357Y310353D01*

+X413583Y310899D01*

+X413721Y311474D01*

+X413756Y312063D01*

+X413721Y312652D01*

+X413583Y313227D01*

+X413357Y313773D01*

+X413073Y314237D01*

+Y317763D01*

+X413357Y318227D01*

+X413583Y318773D01*

+X413721Y319348D01*

+X413756Y319937D01*

+X413721Y320526D01*

+X413583Y321101D01*

+X413357Y321647D01*

+X413073Y322111D01*

+Y327606D01*

+X413357Y328069D01*

+X413583Y328615D01*

+X413721Y329190D01*

+X413756Y329780D01*

+X413721Y330369D01*

+X413583Y330944D01*

+X413357Y331490D01*

+X413073Y331953D01*

+Y360458D01*

+X413755Y360294D01*

+X414500Y360235D01*

+X415245Y360294D01*

+X415972Y360469D01*

+X415993Y360477D01*

+Y288953D01*

+X415892Y288977D01*

+X415500Y289008D01*

+X415108Y288977D01*

+X414725Y288885D01*

+X414362Y288734D01*

+X414026Y288529D01*

+X413727Y288273D01*

+X413471Y287974D01*

+X413266Y287638D01*

+X413115Y287275D01*

+X413073Y287100D01*

+Y300256D01*

+X413115Y300274D01*

+X413183Y300314D01*

+X413243Y300365D01*

+X413294Y300424D01*

+X413334Y300492D01*

+X413488Y300817D01*

+X413606Y301156D01*

+X413692Y301506D01*

+X413743Y301861D01*

+X413760Y302220D01*

+X413743Y302580D01*

+X413692Y302935D01*

+X413606Y303285D01*

+X413488Y303624D01*

+X413338Y303951D01*

+X413297Y304018D01*

+X413245Y304078D01*

+X413184Y304129D01*

+X413117Y304170D01*

+X413073Y304188D01*

+Y309889D01*

+G37*

+G36*

+X415993Y207500D02*X413073D01*

+Y214082D01*

+X413347Y213848D01*

+X413951Y213478D01*

+X414605Y213207D01*

+X415294Y213042D01*

+X415993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X413073Y331953D02*X413048Y331994D01*

+X412664Y332444D01*

+X412214Y332827D01*

+X411710Y333136D01*

+X411164Y333363D01*

+X410589Y333501D01*

+X410000Y333547D01*

+X409994Y333547D01*

+Y363466D01*

+X410255Y362837D01*

+X410645Y362199D01*

+X411131Y361631D01*

+X411699Y361145D01*

+X412337Y360755D01*

+X413028Y360469D01*

+X413073Y360458D01*

+Y331953D01*

+G37*

+G36*

+Y322111D02*X413048Y322151D01*

+X412664Y322601D01*

+X412214Y322985D01*

+X411710Y323294D01*

+X411164Y323520D01*

+X410589Y323658D01*

+X410000Y323704D01*

+X409994Y323704D01*

+Y326012D01*

+X410000Y326012D01*

+X410589Y326058D01*

+X411164Y326196D01*

+X411710Y326423D01*

+X412214Y326732D01*

+X412664Y327116D01*

+X413048Y327565D01*

+X413073Y327606D01*

+Y322111D01*

+G37*

+G36*

+Y314237D02*X413048Y314277D01*

+X412664Y314727D01*

+X412214Y315111D01*

+X411710Y315420D01*

+X411164Y315646D01*

+X410589Y315784D01*

+X410000Y315830D01*

+X409994Y315830D01*

+Y316170D01*

+X410000Y316170D01*

+X410589Y316216D01*

+X411164Y316354D01*

+X411710Y316580D01*

+X412214Y316889D01*

+X412664Y317273D01*

+X413048Y317723D01*

+X413073Y317763D01*

+Y314237D01*

+G37*

+G36*

+Y207500D02*X409994D01*

+Y215406D01*

+X410022Y215451D01*

+X410293Y216105D01*

+X410458Y216794D01*

+X410500Y217500D01*

+X410458Y218206D01*

+X410293Y218895D01*

+X410022Y219549D01*

+X409994Y219594D01*

+Y275406D01*

+X410022Y275451D01*

+X410293Y276105D01*

+X410458Y276794D01*

+X410500Y277500D01*

+X410458Y278206D01*

+X410293Y278895D01*

+X410022Y279549D01*

+X409994Y279594D01*

+Y298461D01*

+X410000Y298460D01*

+X410359Y298477D01*

+X410715Y298529D01*

+X411064Y298614D01*

+X411404Y298732D01*

+X411731Y298882D01*

+X411798Y298924D01*

+X411858Y298976D01*

+X411909Y299036D01*

+X411950Y299104D01*

+X411980Y299177D01*

+X411998Y299254D01*

+X412003Y299333D01*

+X411996Y299412D01*

+X411977Y299489D01*

+X411947Y299562D01*

+X411905Y299629D01*

+X411853Y299689D01*

+X411792Y299740D01*

+X411724Y299781D01*

+X411651Y299811D01*

+X411574Y299829D01*

+X411495Y299835D01*

+X411416Y299828D01*

+X411339Y299809D01*

+X411267Y299777D01*

+X411029Y299664D01*

+X410780Y299577D01*

+X410524Y299515D01*

+X410263Y299477D01*

+X410000Y299465D01*

+X409994Y299465D01*

+Y304976D01*

+X410000Y304976D01*

+X410263Y304964D01*

+X410524Y304926D01*

+X410780Y304864D01*

+X411029Y304777D01*

+X411268Y304667D01*

+X411340Y304635D01*

+X411417Y304616D01*

+X411495Y304610D01*

+X411573Y304615D01*

+X411650Y304633D01*

+X411723Y304663D01*

+X411790Y304703D01*

+X411851Y304754D01*

+X411902Y304813D01*

+X411944Y304880D01*

+X411974Y304953D01*

+X411993Y305029D01*

+X412000Y305108D01*

+X411994Y305186D01*

+X411977Y305263D01*

+X411947Y305336D01*

+X411906Y305403D01*

+X411856Y305463D01*

+X411796Y305515D01*

+X411729Y305555D01*

+X411404Y305709D01*

+X411064Y305827D01*

+X410715Y305912D01*

+X410359Y305963D01*

+X410000Y305981D01*

+X409994Y305980D01*

+Y308296D01*

+X410000Y308296D01*

+X410589Y308342D01*

+X411164Y308480D01*

+X411710Y308706D01*

+X412214Y309015D01*

+X412664Y309399D01*

+X413048Y309849D01*

+X413073Y309889D01*

+Y304188D01*

+X413043Y304200D01*

+X412966Y304218D01*

+X412887Y304224D01*

+X412808Y304217D01*

+X412731Y304198D01*

+X412658Y304167D01*

+X412591Y304125D01*

+X412531Y304073D01*

+X412480Y304013D01*

+X412439Y303945D01*

+X412409Y303872D01*

+X412392Y303794D01*

+X412386Y303715D01*

+X412393Y303637D01*

+X412412Y303560D01*

+X412444Y303487D01*

+X412557Y303249D01*

+X412643Y303000D01*

+X412706Y302744D01*

+X412743Y302484D01*

+X412756Y302220D01*

+X412743Y301957D01*

+X412706Y301696D01*

+X412643Y301440D01*

+X412557Y301192D01*

+X412447Y300952D01*

+X412415Y300880D01*

+X412396Y300804D01*

+X412389Y300726D01*

+X412395Y300647D01*

+X412413Y300570D01*

+X412442Y300497D01*

+X412483Y300430D01*

+X412533Y300370D01*

+X412593Y300318D01*

+X412660Y300277D01*

+X412732Y300246D01*

+X412809Y300227D01*

+X412887Y300220D01*

+X412966Y300226D01*

+X413042Y300244D01*

+X413073Y300256D01*

+Y287100D01*

+X413023Y286892D01*

+X412992Y286500D01*

+X413023Y286108D01*

+X413073Y285900D01*

+Y280918D01*

+X412808Y280692D01*

+X412348Y280153D01*

+X411978Y279549D01*

+X411707Y278895D01*

+X411542Y278206D01*

+X411486Y277500D01*

+X411542Y276794D01*

+X411707Y276105D01*

+X411978Y275451D01*

+X412348Y274847D01*

+X412808Y274308D01*

+X413073Y274082D01*

+Y220918D01*

+X412808Y220692D01*

+X412348Y220153D01*

+X411978Y219549D01*

+X411707Y218895D01*

+X411542Y218206D01*

+X411486Y217500D01*

+X411542Y216794D01*

+X411707Y216105D01*

+X411978Y215451D01*

+X412348Y214847D01*

+X412808Y214308D01*

+X413073Y214082D01*

+Y207500D01*

+G37*

+G36*

+X406927Y317763D02*X406952Y317723D01*

+X407336Y317273D01*

+X407786Y316889D01*

+X408290Y316580D01*

+X408836Y316354D01*

+X409411Y316216D01*

+X409994Y316170D01*

+Y315830D01*

+X409411Y315784D01*

+X408836Y315646D01*

+X408290Y315420D01*

+X407786Y315111D01*

+X407336Y314727D01*

+X406952Y314277D01*

+X406927Y314237D01*

+Y317763D01*

+G37*

+G36*

+Y327606D02*X406952Y327565D01*

+X407336Y327116D01*

+X407786Y326732D01*

+X408290Y326423D01*

+X408836Y326196D01*

+X409411Y326058D01*

+X409994Y326012D01*

+Y323704D01*

+X409411Y323658D01*

+X408836Y323520D01*

+X408290Y323294D01*

+X407786Y322985D01*

+X407336Y322601D01*

+X406952Y322151D01*

+X406927Y322111D01*

+Y327606D01*

+G37*

+G36*

+Y360916D02*X407301Y361145D01*

+X407869Y361631D01*

+X408355Y362199D01*

+X408745Y362837D01*

+X409031Y363528D01*

+X409206Y364255D01*

+X409250Y365000D01*

+X409206Y365745D01*

+X409031Y366472D01*

+X408745Y367163D01*

+X408355Y367801D01*

+X407869Y368369D01*

+X407301Y368855D01*

+X406927Y369084D01*

+Y390000D01*

+X409994D01*

+Y366534D01*

+X409969Y366472D01*

+X409794Y365745D01*

+X409735Y365000D01*

+X409794Y364255D01*

+X409969Y363528D01*

+X409994Y363466D01*

+Y333547D01*

+X409411Y333501D01*

+X408836Y333363D01*

+X408290Y333136D01*

+X407786Y332827D01*

+X407336Y332444D01*

+X406952Y331994D01*

+X406927Y331953D01*

+Y360916D01*

+G37*

+G36*

+X409994Y279594D02*X409652Y280153D01*

+X409192Y280692D01*

+X408653Y281152D01*

+X408049Y281522D01*

+X407395Y281793D01*

+X406927Y281905D01*

+Y300253D01*

+X406957Y300241D01*

+X407034Y300223D01*

+X407113Y300217D01*

+X407192Y300224D01*

+X407269Y300243D01*

+X407342Y300274D01*

+X407409Y300316D01*

+X407469Y300368D01*

+X407520Y300428D01*

+X407561Y300496D01*

+X407591Y300569D01*

+X407608Y300647D01*

+X407614Y300726D01*

+X407607Y300804D01*

+X407588Y300881D01*

+X407556Y300954D01*

+X407443Y301192D01*

+X407357Y301440D01*

+X407294Y301696D01*

+X407257Y301957D01*

+X407244Y302220D01*

+X407257Y302484D01*

+X407294Y302744D01*

+X407357Y303000D01*

+X407443Y303249D01*

+X407553Y303489D01*

+X407585Y303561D01*

+X407604Y303637D01*

+X407611Y303715D01*

+X407605Y303794D01*

+X407587Y303871D01*

+X407558Y303944D01*

+X407517Y304011D01*

+X407467Y304071D01*

+X407407Y304123D01*

+X407340Y304164D01*

+X407268Y304195D01*

+X407191Y304214D01*

+X407113Y304220D01*

+X407034Y304215D01*

+X406958Y304197D01*

+X406927Y304185D01*

+Y309889D01*

+X406952Y309849D01*

+X407336Y309399D01*

+X407786Y309015D01*

+X408290Y308706D01*

+X408836Y308480D01*

+X409411Y308342D01*

+X409994Y308296D01*

+Y305980D01*

+X409641Y305963D01*

+X409285Y305912D01*

+X408936Y305827D01*

+X408596Y305709D01*

+X408269Y305559D01*

+X408202Y305517D01*

+X408142Y305465D01*

+X408091Y305405D01*

+X408050Y305337D01*

+X408020Y305264D01*

+X408002Y305186D01*

+X407997Y305108D01*

+X408004Y305029D01*

+X408023Y304952D01*

+X408053Y304879D01*

+X408095Y304812D01*

+X408147Y304752D01*

+X408208Y304701D01*

+X408276Y304660D01*

+X408349Y304630D01*

+X408426Y304612D01*

+X408505Y304606D01*

+X408584Y304613D01*

+X408661Y304632D01*

+X408733Y304664D01*

+X408971Y304777D01*

+X409220Y304864D01*

+X409476Y304926D01*

+X409737Y304964D01*

+X409994Y304976D01*

+Y299465D01*

+X409737Y299477D01*

+X409476Y299515D01*

+X409220Y299577D01*

+X408971Y299664D01*

+X408732Y299774D01*

+X408660Y299806D01*

+X408583Y299825D01*

+X408505Y299831D01*

+X408427Y299826D01*

+X408350Y299808D01*

+X408277Y299778D01*

+X408210Y299738D01*

+X408149Y299687D01*

+X408098Y299628D01*

+X408056Y299561D01*

+X408026Y299488D01*

+X408007Y299412D01*

+X408000Y299333D01*

+X408006Y299255D01*

+X408023Y299178D01*

+X408053Y299105D01*

+X408094Y299038D01*

+X408144Y298978D01*

+X408204Y298926D01*

+X408271Y298886D01*

+X408596Y298732D01*

+X408936Y298614D01*

+X409285Y298529D01*

+X409641Y298477D01*

+X409994Y298461D01*

+Y279594D01*

+G37*

+G36*

+X406927Y369084D02*X406663Y369245D01*

+X405993Y369523D01*

+Y390000D01*

+X406927D01*

+Y369084D01*

+G37*

+G36*

+Y281905D02*X406706Y281958D01*

+X406000Y282014D01*

+X405993Y282013D01*

+Y360477D01*

+X406663Y360755D01*

+X406927Y360916D01*

+Y331953D01*

+X406643Y331490D01*

+X406417Y330944D01*

+X406279Y330369D01*

+X406233Y329780D01*

+X406279Y329190D01*

+X406417Y328615D01*

+X406643Y328069D01*

+X406927Y327606D01*

+Y322111D01*

+X406643Y321647D01*

+X406417Y321101D01*

+X406279Y320526D01*

+X406233Y319937D01*

+X406279Y319348D01*

+X406417Y318773D01*

+X406643Y318227D01*

+X406927Y317763D01*

+Y314237D01*

+X406643Y313773D01*

+X406417Y313227D01*

+X406279Y312652D01*

+X406233Y312063D01*

+X406279Y311474D01*

+X406417Y310899D01*

+X406643Y310353D01*

+X406927Y309889D01*

+Y304185D01*

+X406885Y304167D01*

+X406817Y304127D01*

+X406757Y304076D01*

+X406706Y304017D01*

+X406666Y303949D01*

+X406512Y303624D01*

+X406394Y303285D01*

+X406308Y302935D01*

+X406257Y302580D01*

+X406240Y302220D01*

+X406257Y301861D01*

+X406308Y301506D01*

+X406394Y301156D01*

+X406512Y300817D01*

+X406662Y300490D01*

+X406703Y300422D01*

+X406755Y300363D01*

+X406816Y300312D01*

+X406883Y300271D01*

+X406927Y300253D01*

+Y281905D01*

+G37*

+G36*

+X409994Y219594D02*X409652Y220153D01*

+X409192Y220692D01*

+X408653Y221152D01*

+X408049Y221522D01*

+X407395Y221793D01*

+X406706Y221958D01*

+X406000Y222014D01*

+X405993Y222013D01*

+Y272987D01*

+X406000Y272986D01*

+X406706Y273042D01*

+X407395Y273207D01*

+X408049Y273478D01*

+X408653Y273848D01*

+X409192Y274308D01*

+X409652Y274847D01*

+X409994Y275406D01*

+Y219594D01*

+G37*

+G36*

+Y207500D02*X405993D01*

+Y212987D01*

+X406000Y212986D01*

+X406706Y213042D01*

+X407395Y213207D01*

+X408049Y213478D01*

+X408653Y213848D01*

+X409192Y214308D01*

+X409652Y214847D01*

+X409994Y215406D01*

+Y207500D01*

+G37*

+G36*

+X404615Y290674D02*X404625Y290599D01*

+X404646Y290134D01*

+X404625Y289669D01*

+X404615Y289593D01*

+Y290674D01*

+G37*

+G36*

+Y342407D02*X404625Y342331D01*

+X404646Y341866D01*

+X404625Y341401D01*

+X404615Y341326D01*

+Y342407D01*

+G37*

+G36*

+Y273205D02*X405294Y273042D01*

+X405993Y272987D01*

+Y222013D01*

+X405294Y221958D01*

+X404615Y221795D01*

+Y273205D01*

+G37*

+G36*

+Y360244D02*X405245Y360294D01*

+X405972Y360469D01*

+X405993Y360477D01*

+Y282013D01*

+X405294Y281958D01*

+X404615Y281795D01*

+Y286683D01*

+X404798Y286961D01*

+X405055Y287452D01*

+X405267Y287963D01*

+X405435Y288491D01*

+X405555Y289032D01*

+X405627Y289581D01*

+X405652Y290134D01*

+X405627Y290687D01*

+X405555Y291236D01*

+X405435Y291777D01*

+X405267Y292304D01*

+X405055Y292816D01*

+X404798Y293306D01*

+X404615Y293592D01*

+Y338415D01*

+X404798Y338694D01*

+X405055Y339184D01*

+X405267Y339696D01*

+X405435Y340223D01*

+X405555Y340764D01*

+X405627Y341313D01*

+X405652Y341866D01*

+X405627Y342419D01*

+X405555Y342968D01*

+X405435Y343509D01*

+X405267Y344037D01*

+X405055Y344548D01*

+X404798Y345039D01*

+X404615Y345324D01*

+Y360244D01*

+G37*

+G36*

+Y390000D02*X405993D01*

+Y369523D01*

+X405972Y369531D01*

+X405245Y369706D01*

+X404615Y369756D01*

+Y390000D01*

+G37*

+G36*

+X405993Y207500D02*X404615D01*

+Y213205D01*

+X405294Y213042D01*

+X405993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X404615D02*X395993D01*

+Y212987D01*

+X396000Y212986D01*

+X396706Y213042D01*

+X397395Y213207D01*

+X398049Y213478D01*

+X398653Y213848D01*

+X399192Y214308D01*

+X399652Y214847D01*

+X400022Y215451D01*

+X400293Y216105D01*

+X400458Y216794D01*

+X400500Y217500D01*

+X400458Y218206D01*

+X400293Y218895D01*

+X400022Y219549D01*

+X399652Y220153D01*

+X399192Y220692D01*

+X398653Y221152D01*

+X398049Y221522D01*

+X397395Y221793D01*

+X396706Y221958D01*

+X396000Y222014D01*

+X395993Y222013D01*

+Y272987D01*

+X396000Y272986D01*

+X396706Y273042D01*

+X397395Y273207D01*

+X398049Y273478D01*

+X398653Y273848D01*

+X399192Y274308D01*

+X399652Y274847D01*

+X400022Y275451D01*

+X400293Y276105D01*

+X400458Y276794D01*

+X400500Y277500D01*

+X400458Y278206D01*

+X400293Y278895D01*

+X400022Y279549D01*

+X399652Y280153D01*

+X399192Y280692D01*

+X398653Y281152D01*

+X398049Y281522D01*

+X397395Y281793D01*

+X396706Y281958D01*

+X396000Y282014D01*

+X395993Y282013D01*

+Y284775D01*

+X396158Y284667D01*

+X396649Y284410D01*

+X397160Y284197D01*

+X397688Y284030D01*

+X398229Y283910D01*

+X398777Y283837D01*

+X399331Y283813D01*

+X399884Y283837D01*

+X400433Y283910D01*

+X400973Y284030D01*

+X401501Y284197D01*

+X402013Y284410D01*

+X402503Y284667D01*

+X402970Y284965D01*

+X403031Y285016D01*

+X403084Y285075D01*

+X403126Y285142D01*

+X403158Y285215D01*

+X403177Y285292D01*

+X403185Y285372D01*

+X403180Y285451D01*

+X403162Y285528D01*

+X403133Y285602D01*

+X403093Y285671D01*

+X403042Y285732D01*

+X402982Y285785D01*

+X402915Y285827D01*

+X402842Y285859D01*

+X402765Y285878D01*

+X402686Y285886D01*

+X402606Y285881D01*

+X402529Y285863D01*

+X402455Y285834D01*

+X402387Y285792D01*

+X401998Y285537D01*

+X401586Y285321D01*

+X401156Y285142D01*

+X400712Y285002D01*

+X400257Y284900D01*

+X399796Y284839D01*

+X399331Y284819D01*

+X398866Y284839D01*

+X398404Y284900D01*

+X397949Y285002D01*

+X397506Y285142D01*

+X397076Y285321D01*

+X396663Y285537D01*

+X396271Y285788D01*

+X396204Y285829D01*

+X396131Y285858D01*

+X396054Y285876D01*

+X395993Y285879D01*

+Y294383D01*

+X396055Y294387D01*

+X396133Y294404D01*

+X396206Y294434D01*

+X396274Y294476D01*

+X396663Y294731D01*

+X397076Y294947D01*

+X397506Y295126D01*

+X397949Y295266D01*

+X398404Y295367D01*

+X398866Y295428D01*

+X399331Y295449D01*

+X399796Y295428D01*

+X400257Y295367D01*

+X400712Y295266D01*

+X401156Y295126D01*

+X401586Y294947D01*

+X401998Y294731D01*

+X402390Y294480D01*

+X402457Y294438D01*

+X402530Y294409D01*

+X402607Y294392D01*

+X402686Y294387D01*

+X402764Y294394D01*

+X402840Y294414D01*

+X402913Y294445D01*

+X402979Y294487D01*

+X403038Y294539D01*

+X403088Y294600D01*

+X403128Y294668D01*

+X403157Y294741D01*

+X403175Y294818D01*

+X403180Y294896D01*

+X403172Y294974D01*

+X403153Y295051D01*

+X403122Y295123D01*

+X403080Y295189D01*

+X403028Y295249D01*

+X402966Y295297D01*

+X402503Y295601D01*

+X402013Y295858D01*

+X401501Y296071D01*

+X400973Y296238D01*

+X400433Y296358D01*

+X399884Y296431D01*

+X399331Y296455D01*

+X398777Y296431D01*

+X398229Y296358D01*

+X397688Y296238D01*

+X397160Y296071D01*

+X396649Y295858D01*

+X396158Y295601D01*

+X395993Y295495D01*

+Y336507D01*

+X396158Y336399D01*

+X396649Y336142D01*

+X397160Y335929D01*

+X397688Y335762D01*

+X398229Y335642D01*

+X398777Y335569D01*

+X399331Y335545D01*

+X399884Y335569D01*

+X400433Y335642D01*

+X400973Y335762D01*

+X401501Y335929D01*

+X402013Y336142D01*

+X402503Y336399D01*

+X402970Y336698D01*

+X403031Y336748D01*

+X403084Y336807D01*

+X403126Y336875D01*

+X403158Y336948D01*

+X403177Y337025D01*

+X403185Y337104D01*

+X403180Y337183D01*

+X403162Y337261D01*

+X403133Y337335D01*

+X403093Y337403D01*

+X403042Y337464D01*

+X402982Y337517D01*

+X402915Y337559D01*

+X402842Y337591D01*

+X402765Y337611D01*

+X402686Y337618D01*

+X402606Y337613D01*

+X402529Y337596D01*

+X402455Y337566D01*

+X402387Y337524D01*

+X401998Y337269D01*

+X401586Y337053D01*

+X401156Y336874D01*

+X400712Y336734D01*

+X400257Y336633D01*

+X399796Y336572D01*

+X399331Y336551D01*

+X398866Y336572D01*

+X398404Y336633D01*

+X397949Y336734D01*

+X397506Y336874D01*

+X397076Y337053D01*

+X396663Y337269D01*

+X396271Y337520D01*

+X396204Y337562D01*

+X396131Y337591D01*

+X396054Y337608D01*

+X395993Y337612D01*

+Y346115D01*

+X396055Y346119D01*

+X396133Y346137D01*

+X396206Y346166D01*

+X396274Y346208D01*

+X396663Y346463D01*

+X397076Y346679D01*

+X397506Y346858D01*

+X397949Y346998D01*

+X398404Y347100D01*

+X398866Y347161D01*

+X399331Y347181D01*

+X399796Y347161D01*

+X400257Y347100D01*

+X400712Y346998D01*

+X401156Y346858D01*

+X401586Y346679D01*

+X401998Y346463D01*

+X402390Y346212D01*

+X402457Y346171D01*

+X402530Y346142D01*

+X402607Y346124D01*

+X402686Y346119D01*

+X402764Y346127D01*

+X402840Y346146D01*

+X402913Y346177D01*

+X402979Y346220D01*

+X403038Y346272D01*

+X403088Y346332D01*

+X403128Y346400D01*

+X403157Y346473D01*

+X403175Y346550D01*

+X403180Y346628D01*

+X403172Y346707D01*

+X403153Y346783D01*

+X403122Y346855D01*

+X403080Y346922D01*

+X403028Y346981D01*

+X402966Y347030D01*

+X402503Y347333D01*

+X402013Y347590D01*

+X401501Y347803D01*

+X400973Y347970D01*

+X400433Y348090D01*

+X399884Y348163D01*

+X399331Y348187D01*

+X398777Y348163D01*

+X398229Y348090D01*

+X397688Y347970D01*

+X397160Y347803D01*

+X396649Y347590D01*

+X396158Y347333D01*

+X395993Y347228D01*

+Y360477D01*

+X396663Y360755D01*

+X397301Y361145D01*

+X397869Y361631D01*

+X398355Y362199D01*

+X398745Y362837D01*

+X399031Y363528D01*

+X399206Y364255D01*

+X399250Y365000D01*

+X399206Y365745D01*

+X399031Y366472D01*

+X398745Y367163D01*

+X398355Y367801D01*

+X397869Y368369D01*

+X397301Y368855D01*

+X396663Y369245D01*

+X395993Y369523D01*

+Y390000D01*

+X404615D01*

+Y369756D01*

+X404500Y369765D01*

+X403755Y369706D01*

+X403028Y369531D01*

+X402337Y369245D01*

+X401699Y368855D01*

+X401131Y368369D01*

+X400645Y367801D01*

+X400255Y367163D01*

+X399969Y366472D01*

+X399794Y365745D01*

+X399735Y365000D01*

+X399794Y364255D01*

+X399969Y363528D01*

+X400255Y362837D01*

+X400645Y362199D01*

+X401131Y361631D01*

+X401699Y361145D01*

+X402337Y360755D01*

+X403028Y360469D01*

+X403755Y360294D01*

+X404500Y360235D01*

+X404615Y360244D01*

+Y345324D01*

+X404499Y345505D01*

+X404449Y345567D01*

+X404389Y345619D01*

+X404322Y345662D01*

+X404249Y345693D01*

+X404172Y345713D01*

+X404093Y345720D01*

+X404014Y345715D01*

+X403936Y345698D01*

+X403862Y345668D01*

+X403794Y345628D01*

+X403733Y345577D01*

+X403680Y345518D01*

+X403638Y345450D01*

+X403606Y345377D01*

+X403586Y345300D01*

+X403579Y345221D01*

+X403584Y345142D01*

+X403601Y345064D01*

+X403631Y344990D01*

+X403672Y344923D01*

+X403928Y344534D01*

+X404144Y344121D01*

+X404322Y343691D01*

+X404463Y343247D01*

+X404564Y342793D01*

+X404615Y342407D01*

+Y341326D01*

+X404564Y340939D01*

+X404463Y340485D01*

+X404322Y340041D01*

+X404144Y339611D01*

+X403928Y339199D01*

+X403677Y338806D01*

+X403635Y338740D01*

+X403606Y338666D01*

+X403589Y338590D01*

+X403584Y338511D01*

+X403591Y338433D01*

+X403611Y338357D01*

+X403642Y338284D01*

+X403684Y338218D01*

+X403736Y338159D01*

+X403797Y338109D01*

+X403864Y338068D01*

+X403938Y338039D01*

+X404014Y338022D01*

+X404093Y338017D01*

+X404171Y338024D01*

+X404248Y338044D01*

+X404320Y338075D01*

+X404386Y338117D01*

+X404445Y338169D01*

+X404494Y338231D01*

+X404615Y338415D01*

+Y293592D01*

+X404499Y293773D01*

+X404449Y293834D01*

+X404389Y293887D01*

+X404322Y293929D01*

+X404249Y293961D01*

+X404172Y293981D01*

+X404093Y293988D01*

+X404014Y293983D01*

+X403936Y293966D01*

+X403862Y293936D01*

+X403794Y293896D01*

+X403733Y293845D01*

+X403680Y293785D01*

+X403638Y293718D01*

+X403606Y293645D01*

+X403586Y293568D01*

+X403579Y293489D01*

+X403584Y293410D01*

+X403601Y293332D01*

+X403631Y293258D01*

+X403672Y293191D01*

+X403928Y292801D01*

+X404144Y292389D01*

+X404322Y291959D01*

+X404463Y291515D01*

+X404564Y291061D01*

+X404615Y290674D01*

+Y289593D01*

+X404564Y289207D01*

+X404463Y288753D01*

+X404322Y288309D01*

+X404144Y287879D01*

+X403928Y287466D01*

+X403677Y287074D01*

+X403635Y287007D01*

+X403606Y286934D01*

+X403589Y286857D01*

+X403584Y286779D01*

+X403591Y286701D01*

+X403611Y286624D01*

+X403642Y286552D01*

+X403684Y286486D01*

+X403736Y286426D01*

+X403797Y286376D01*

+X403864Y286336D01*

+X403938Y286307D01*

+X404014Y286290D01*

+X404093Y286285D01*

+X404171Y286292D01*

+X404248Y286312D01*

+X404320Y286343D01*

+X404386Y286385D01*

+X404445Y286437D01*

+X404494Y286499D01*

+X404615Y286683D01*

+Y281795D01*

+X404605Y281793D01*

+X403951Y281522D01*

+X403347Y281152D01*

+X402808Y280692D01*

+X402348Y280153D01*

+X401978Y279549D01*

+X401707Y278895D01*

+X401542Y278206D01*

+X401486Y277500D01*

+X401542Y276794D01*

+X401707Y276105D01*

+X401978Y275451D01*

+X402348Y274847D01*

+X402808Y274308D01*

+X403347Y273848D01*

+X403951Y273478D01*

+X404605Y273207D01*

+X404615Y273205D01*

+Y221795D01*

+X404605Y221793D01*

+X403951Y221522D01*

+X403347Y221152D01*

+X402808Y220692D01*

+X402348Y220153D01*

+X401978Y219549D01*

+X401707Y218895D01*

+X401542Y218206D01*

+X401486Y217500D01*

+X401542Y216794D01*

+X401707Y216105D01*

+X401978Y215451D01*

+X402348Y214847D01*

+X402808Y214308D01*

+X403347Y213848D01*

+X403951Y213478D01*

+X404605Y213207D01*

+X404615Y213205D01*

+Y207500D01*

+G37*

+G36*

+X394046Y273439D02*X394605Y273207D01*

+X395294Y273042D01*

+X395993Y272987D01*

+Y222013D01*

+X395294Y221958D01*

+X394605Y221793D01*

+X394046Y221561D01*

+Y273439D01*

+G37*

+G36*

+Y360271D02*X394500Y360235D01*

+X395245Y360294D01*

+X395972Y360469D01*

+X395993Y360477D01*

+Y347228D01*

+X395692Y347035D01*

+X395630Y346984D01*

+X395578Y346925D01*

+X395535Y346858D01*

+X395504Y346785D01*

+X395484Y346708D01*

+X395477Y346628D01*

+X395482Y346549D01*

+X395499Y346472D01*

+X395528Y346398D01*

+X395569Y346329D01*

+X395620Y346268D01*

+X395679Y346216D01*

+X395746Y346173D01*

+X395819Y346141D01*

+X395896Y346122D01*

+X395976Y346114D01*

+X395993Y346115D01*

+Y337612D01*

+X395976Y337613D01*

+X395897Y337606D01*

+X395821Y337586D01*

+X395749Y337555D01*

+X395682Y337513D01*

+X395623Y337461D01*

+X395573Y337400D01*

+X395533Y337332D01*

+X395504Y337259D01*

+X395487Y337182D01*

+X395482Y337104D01*

+X395489Y337026D01*

+X395509Y336949D01*

+X395540Y336877D01*

+X395582Y336811D01*

+X395634Y336751D01*

+X395695Y336703D01*

+X395993Y336507D01*

+Y295495D01*

+X395692Y295302D01*

+X395630Y295252D01*

+X395578Y295193D01*

+X395535Y295125D01*

+X395504Y295052D01*

+X395484Y294975D01*

+X395477Y294896D01*

+X395482Y294817D01*

+X395499Y294739D01*

+X395528Y294665D01*

+X395569Y294597D01*

+X395620Y294536D01*

+X395679Y294483D01*

+X395746Y294441D01*

+X395819Y294409D01*

+X395896Y294389D01*

+X395976Y294382D01*

+X395993Y294383D01*

+Y285879D01*

+X395976Y285881D01*

+X395897Y285873D01*

+X395821Y285854D01*

+X395749Y285823D01*

+X395682Y285780D01*

+X395623Y285728D01*

+X395573Y285668D01*

+X395533Y285600D01*

+X395504Y285527D01*

+X395487Y285450D01*

+X395482Y285372D01*

+X395489Y285293D01*

+X395509Y285217D01*

+X395540Y285145D01*

+X395582Y285078D01*

+X395634Y285019D01*

+X395695Y284970D01*

+X395993Y284775D01*

+Y282013D01*

+X395294Y281958D01*

+X394605Y281793D01*

+X394046Y281561D01*

+Y286676D01*

+X394162Y286495D01*

+X394212Y286433D01*

+X394272Y286381D01*

+X394339Y286338D01*

+X394412Y286307D01*

+X394489Y286287D01*

+X394568Y286280D01*

+X394648Y286285D01*

+X394725Y286302D01*

+X394799Y286332D01*

+X394868Y286372D01*

+X394929Y286423D01*

+X394981Y286482D01*

+X395024Y286550D01*

+X395055Y286623D01*

+X395075Y286700D01*

+X395083Y286779D01*

+X395077Y286858D01*

+X395060Y286936D01*

+X395031Y287010D01*

+X394989Y287077D01*

+X394734Y287466D01*

+X394518Y287879D01*

+X394339Y288309D01*

+X394198Y288753D01*

+X394097Y289207D01*

+X394046Y289593D01*

+Y290674D01*

+X394097Y291061D01*

+X394198Y291515D01*

+X394339Y291959D01*

+X394518Y292389D01*

+X394734Y292801D01*

+X394985Y293194D01*

+X395026Y293260D01*

+X395055Y293334D01*

+X395072Y293410D01*

+X395077Y293489D01*

+X395070Y293567D01*

+X395051Y293643D01*

+X395019Y293716D01*

+X394977Y293782D01*

+X394925Y293841D01*

+X394865Y293891D01*

+X394797Y293932D01*

+X394724Y293961D01*

+X394647Y293978D01*

+X394568Y293983D01*

+X394490Y293976D01*

+X394414Y293956D01*

+X394342Y293925D01*

+X394275Y293883D01*

+X394216Y293831D01*

+X394167Y293769D01*

+X394046Y293585D01*

+Y338408D01*

+X394162Y338227D01*

+X394212Y338166D01*

+X394272Y338113D01*

+X394339Y338071D01*

+X394412Y338039D01*

+X394489Y338019D01*

+X394568Y338012D01*

+X394648Y338017D01*

+X394725Y338034D01*

+X394799Y338064D01*

+X394868Y338104D01*

+X394929Y338155D01*

+X394981Y338215D01*

+X395024Y338282D01*

+X395055Y338355D01*

+X395075Y338432D01*

+X395083Y338511D01*

+X395077Y338590D01*

+X395060Y338668D01*

+X395031Y338742D01*

+X394989Y338809D01*

+X394734Y339199D01*

+X394518Y339611D01*

+X394339Y340041D01*

+X394198Y340485D01*

+X394097Y340939D01*

+X394046Y341326D01*

+Y342407D01*

+X394097Y342793D01*

+X394198Y343247D01*

+X394339Y343691D01*

+X394518Y344121D01*

+X394734Y344534D01*

+X394985Y344926D01*

+X395026Y344993D01*

+X395055Y345066D01*

+X395072Y345143D01*

+X395077Y345221D01*

+X395070Y345299D01*

+X395051Y345376D01*

+X395019Y345448D01*

+X394977Y345514D01*

+X394925Y345574D01*

+X394865Y345624D01*

+X394797Y345664D01*

+X394724Y345693D01*

+X394647Y345710D01*

+X394568Y345715D01*

+X394490Y345708D01*

+X394414Y345688D01*

+X394342Y345657D01*

+X394275Y345615D01*

+X394216Y345563D01*

+X394167Y345501D01*

+X394046Y345317D01*

+Y360271D01*

+G37*

+G36*

+Y390000D02*X395993D01*

+Y369523D01*

+X395972Y369531D01*

+X395245Y369706D01*

+X394500Y369765D01*

+X394046Y369729D01*

+Y390000D01*

+G37*

+G36*

+X395993Y207500D02*X394046D01*

+Y213439D01*

+X394605Y213207D01*

+X395294Y213042D01*

+X395993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X394046Y289593D02*X394036Y289669D01*

+X394016Y290134D01*

+X394036Y290599D01*

+X394046Y290674D01*

+Y289593D01*

+G37*

+G36*

+Y341326D02*X394036Y341401D01*

+X394016Y341866D01*

+X394036Y342331D01*

+X394046Y342407D01*

+Y341326D01*

+G37*

+G36*

+Y207500D02*X389613D01*

+Y214802D01*

+X389652Y214847D01*

+X390022Y215451D01*

+X390293Y216105D01*

+X390458Y216794D01*

+X390500Y217500D01*

+X390458Y218206D01*

+X390293Y218895D01*

+X390022Y219549D01*

+X389652Y220153D01*

+X389613Y220198D01*

+Y275353D01*

+X389656Y275360D01*

+X389768Y275397D01*

+X389873Y275452D01*

+X389968Y275522D01*

+X390051Y275606D01*

+X390119Y275702D01*

+X390170Y275808D01*

+X390318Y276216D01*

+X390422Y276637D01*

+X390484Y277067D01*

+X390505Y277500D01*

+X390484Y277933D01*

+X390422Y278363D01*

+X390318Y278784D01*

+X390175Y279194D01*

+X390122Y279300D01*

+X390053Y279396D01*

+X389970Y279481D01*

+X389875Y279551D01*

+X389769Y279606D01*

+X389657Y279643D01*

+X389613Y279651D01*

+Y390000D01*

+X394046D01*

+Y369729D01*

+X393755Y369706D01*

+X393028Y369531D01*

+X392337Y369245D01*

+X391699Y368855D01*

+X391131Y368369D01*

+X390645Y367801D01*

+X390255Y367163D01*

+X389969Y366472D01*

+X389794Y365745D01*

+X389735Y365000D01*

+X389794Y364255D01*

+X389969Y363528D01*

+X390255Y362837D01*

+X390645Y362199D01*

+X391131Y361631D01*

+X391699Y361145D01*

+X392337Y360755D01*

+X393028Y360469D01*

+X393755Y360294D01*

+X394046Y360271D01*

+Y345317D01*

+X393863Y345039D01*

+X393607Y344548D01*

+X393394Y344037D01*

+X393227Y343509D01*

+X393107Y342968D01*

+X393034Y342419D01*

+X393010Y341866D01*

+X393034Y341313D01*

+X393107Y340764D01*

+X393227Y340223D01*

+X393394Y339696D01*

+X393607Y339184D01*

+X393863Y338694D01*

+X394046Y338408D01*

+Y293585D01*

+X393863Y293306D01*

+X393607Y292816D01*

+X393394Y292304D01*

+X393227Y291777D01*

+X393107Y291236D01*

+X393034Y290687D01*

+X393010Y290134D01*

+X393034Y289581D01*

+X393107Y289032D01*

+X393227Y288491D01*

+X393394Y287963D01*

+X393607Y287452D01*

+X393863Y286961D01*

+X394046Y286676D01*

+Y281561D01*

+X393951Y281522D01*

+X393347Y281152D01*

+X392808Y280692D01*

+X392348Y280153D01*

+X391978Y279549D01*

+X391707Y278895D01*

+X391542Y278206D01*

+X391486Y277500D01*

+X391542Y276794D01*

+X391707Y276105D01*

+X391978Y275451D01*

+X392348Y274847D01*

+X392808Y274308D01*

+X393347Y273848D01*

+X393951Y273478D01*

+X394046Y273439D01*

+Y221561D01*

+X393951Y221522D01*

+X393347Y221152D01*

+X392808Y220692D01*

+X392348Y220153D01*

+X391978Y219549D01*

+X391707Y218895D01*

+X391542Y218206D01*

+X391486Y217500D01*

+X391542Y216794D01*

+X391707Y216105D01*

+X391978Y215451D01*

+X392348Y214847D01*

+X392808Y214308D01*

+X393347Y213848D01*

+X393951Y213478D01*

+X394046Y213439D01*

+Y207500D01*

+G37*

+G36*

+X389613Y220198D02*X389192Y220692D01*

+X388653Y221152D01*

+X388049Y221522D01*

+X387395Y221793D01*

+X386706Y221958D01*

+X386000Y222014D01*

+X385993Y222013D01*

+Y272995D01*

+X386000Y272995D01*

+X386433Y273016D01*

+X386863Y273078D01*

+X387284Y273182D01*

+X387694Y273325D01*

+X387800Y273378D01*

+X387896Y273447D01*

+X387981Y273530D01*

+X388051Y273625D01*

+X388106Y273731D01*

+X388143Y273843D01*

+X388163Y273960D01*

+X388164Y274079D01*

+X388146Y274196D01*

+X388110Y274309D01*

+X388057Y274415D01*

+X387988Y274512D01*

+X387905Y274596D01*

+X387809Y274667D01*

+X387704Y274721D01*

+X387592Y274759D01*

+X387475Y274778D01*

+X387356Y274779D01*

+X387239Y274761D01*

+X387126Y274723D01*

+X386855Y274624D01*

+X386575Y274556D01*

+X386289Y274514D01*

+X386000Y274500D01*

+X385993Y274500D01*

+Y280500D01*

+X386000Y280500D01*

+X386289Y280486D01*

+X386575Y280444D01*

+X386855Y280376D01*

+X387128Y280280D01*

+X387239Y280242D01*

+X387356Y280225D01*

+X387474Y280225D01*

+X387591Y280245D01*

+X387703Y280282D01*

+X387807Y280336D01*

+X387902Y280406D01*

+X387985Y280491D01*

+X388054Y280587D01*

+X388107Y280692D01*

+X388143Y280805D01*

+X388160Y280921D01*

+X388159Y281039D01*

+X388140Y281156D01*

+X388103Y281268D01*

+X388048Y281373D01*

+X387978Y281468D01*

+X387894Y281551D01*

+X387798Y281619D01*

+X387692Y281670D01*

+X387284Y281818D01*

+X386863Y281922D01*

+X386433Y281984D01*

+X386000Y282005D01*

+X385993Y282005D01*

+Y360477D01*

+X386663Y360755D01*

+X387301Y361145D01*

+X387869Y361631D01*

+X388355Y362199D01*

+X388745Y362837D01*

+X389031Y363528D01*

+X389206Y364255D01*

+X389250Y365000D01*

+X389206Y365745D01*

+X389031Y366472D01*

+X388745Y367163D01*

+X388355Y367801D01*

+X387869Y368369D01*

+X387301Y368855D01*

+X386663Y369245D01*

+X385993Y369523D01*

+Y390000D01*

+X389613D01*

+Y279651D01*

+X389540Y279663D01*

+X389421Y279664D01*

+X389304Y279646D01*

+X389191Y279610D01*

+X389085Y279557D01*

+X388988Y279488D01*

+X388904Y279405D01*

+X388833Y279309D01*

+X388779Y279204D01*

+X388741Y279092D01*

+X388722Y278975D01*

+X388721Y278856D01*

+X388739Y278739D01*

+X388777Y278626D01*

+X388876Y278355D01*

+X388944Y278075D01*

+X388986Y277789D01*

+X389000Y277500D01*

+X388986Y277211D01*

+X388944Y276925D01*

+X388876Y276645D01*

+X388780Y276372D01*

+X388742Y276261D01*

+X388725Y276144D01*

+X388725Y276026D01*

+X388745Y275909D01*

+X388782Y275797D01*

+X388836Y275693D01*

+X388906Y275598D01*

+X388991Y275515D01*

+X389087Y275446D01*

+X389192Y275393D01*

+X389305Y275357D01*

+X389421Y275340D01*

+X389539Y275341D01*

+X389613Y275353D01*

+Y220198D01*

+G37*

+G36*

+Y207500D02*X385993D01*

+Y212987D01*

+X386000Y212986D01*

+X386706Y213042D01*

+X387395Y213207D01*

+X388049Y213478D01*

+X388653Y213848D01*

+X389192Y214308D01*

+X389613Y214802D01*

+Y207500D01*

+G37*

+G36*

+X382387Y360734D02*X383028Y360469D01*

+X383755Y360294D01*

+X384500Y360235D01*

+X385245Y360294D01*

+X385972Y360469D01*

+X385993Y360477D01*

+Y282005D01*

+X385567Y281984D01*

+X385137Y281922D01*

+X384716Y281818D01*

+X384306Y281675D01*

+X384200Y281622D01*

+X384104Y281553D01*

+X384019Y281470D01*

+X383949Y281375D01*

+X383894Y281269D01*

+X383857Y281157D01*

+X383837Y281040D01*

+X383836Y280921D01*

+X383854Y280804D01*

+X383890Y280691D01*

+X383943Y280585D01*

+X384012Y280488D01*

+X384095Y280404D01*

+X384191Y280333D01*

+X384296Y280279D01*

+X384408Y280241D01*

+X384525Y280222D01*

+X384644Y280221D01*

+X384761Y280239D01*

+X384874Y280277D01*

+X385145Y280376D01*

+X385425Y280444D01*

+X385711Y280486D01*

+X385993Y280500D01*

+Y274500D01*

+X385711Y274514D01*

+X385425Y274556D01*

+X385145Y274624D01*

+X384872Y274720D01*

+X384761Y274758D01*

+X384644Y274775D01*

+X384526Y274775D01*

+X384409Y274755D01*

+X384297Y274718D01*

+X384193Y274664D01*

+X384098Y274594D01*

+X384015Y274509D01*

+X383946Y274413D01*

+X383893Y274308D01*

+X383857Y274195D01*

+X383840Y274079D01*

+X383841Y273961D01*

+X383860Y273844D01*

+X383897Y273732D01*

+X383952Y273627D01*

+X384022Y273532D01*

+X384106Y273449D01*

+X384202Y273381D01*

+X384308Y273330D01*

+X384716Y273182D01*

+X385137Y273078D01*

+X385567Y273016D01*

+X385993Y272995D01*

+Y222013D01*

+X385294Y221958D01*

+X384605Y221793D01*

+X383951Y221522D01*

+X383347Y221152D01*

+X382808Y220692D01*

+X382387Y220198D01*

+Y275349D01*

+X382460Y275337D01*

+X382579Y275336D01*

+X382696Y275354D01*

+X382809Y275390D01*

+X382915Y275443D01*

+X383012Y275512D01*

+X383096Y275595D01*

+X383167Y275691D01*

+X383221Y275796D01*

+X383259Y275908D01*

+X383278Y276025D01*

+X383279Y276144D01*

+X383261Y276261D01*

+X383223Y276374D01*

+X383124Y276645D01*

+X383056Y276925D01*

+X383014Y277211D01*

+X383000Y277500D01*

+X383014Y277789D01*

+X383056Y278075D01*

+X383124Y278355D01*

+X383220Y278628D01*

+X383258Y278739D01*

+X383275Y278856D01*

+X383275Y278974D01*

+X383255Y279091D01*

+X383218Y279203D01*

+X383164Y279307D01*

+X383094Y279402D01*

+X383009Y279485D01*

+X382913Y279554D01*

+X382808Y279607D01*

+X382695Y279643D01*

+X382579Y279660D01*

+X382461Y279659D01*

+X382387Y279647D01*

+Y360734D01*

+G37*

+G36*

+Y390000D02*X385993D01*

+Y369523D01*

+X385972Y369531D01*

+X385245Y369706D01*

+X384500Y369765D01*

+X383755Y369706D01*

+X383028Y369531D01*

+X382387Y369266D01*

+Y390000D01*

+G37*

+G36*

+X385993Y207500D02*X382387D01*

+Y214802D01*

+X382808Y214308D01*

+X383347Y213848D01*

+X383951Y213478D01*

+X384605Y213207D01*

+X385294Y213042D01*

+X385993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X382387D02*X375993D01*

+Y212987D01*

+X376000Y212986D01*

+X376706Y213042D01*

+X377395Y213207D01*

+X378049Y213478D01*

+X378653Y213848D01*

+X379192Y214308D01*

+X379652Y214847D01*

+X380022Y215451D01*

+X380293Y216105D01*

+X380458Y216794D01*

+X380500Y217500D01*

+X380458Y218206D01*

+X380293Y218895D01*

+X380022Y219549D01*

+X379652Y220153D01*

+X379192Y220692D01*

+X378653Y221152D01*

+X378049Y221522D01*

+X377395Y221793D01*

+X376706Y221958D01*

+X376000Y222014D01*

+X375993Y222013D01*

+Y272987D01*

+X376000Y272986D01*

+X376706Y273042D01*

+X377395Y273207D01*

+X378049Y273478D01*

+X378653Y273848D01*

+X379192Y274308D01*

+X379652Y274847D01*

+X380022Y275451D01*

+X380293Y276105D01*

+X380458Y276794D01*

+X380500Y277500D01*

+X380458Y278206D01*

+X380293Y278895D01*

+X380022Y279549D01*

+X379652Y280153D01*

+X379192Y280692D01*

+X378653Y281152D01*

+X378049Y281522D01*

+X377395Y281793D01*

+X376706Y281958D01*

+X376000Y282014D01*

+X375993Y282013D01*

+Y390000D01*

+X382387D01*

+Y369266D01*

+X382337Y369245D01*

+X381699Y368855D01*

+X381131Y368369D01*

+X380645Y367801D01*

+X380255Y367163D01*

+X379969Y366472D01*

+X379794Y365745D01*

+X379735Y365000D01*

+X379794Y364255D01*

+X379969Y363528D01*

+X380255Y362837D01*

+X380645Y362199D01*

+X381131Y361631D01*

+X381699Y361145D01*

+X382337Y360755D01*

+X382387Y360734D01*

+Y279647D01*

+X382344Y279640D01*

+X382232Y279603D01*

+X382127Y279548D01*

+X382032Y279478D01*

+X381949Y279394D01*

+X381881Y279298D01*

+X381830Y279192D01*

+X381682Y278784D01*

+X381578Y278363D01*

+X381516Y277933D01*

+X381495Y277500D01*

+X381516Y277067D01*

+X381578Y276637D01*

+X381682Y276216D01*

+X381825Y275806D01*

+X381878Y275700D01*

+X381947Y275604D01*

+X382030Y275519D01*

+X382125Y275449D01*

+X382231Y275394D01*

+X382343Y275357D01*

+X382387Y275349D01*

+Y220198D01*

+X382348Y220153D01*

+X381978Y219549D01*

+X381707Y218895D01*

+X381542Y218206D01*

+X381486Y217500D01*

+X381542Y216794D01*

+X381707Y216105D01*

+X381978Y215451D01*

+X382348Y214847D01*

+X382387Y214802D01*

+Y207500D01*

+G37*

+G36*

+X375993D02*X365993D01*

+Y212987D01*

+X366000Y212986D01*

+X366706Y213042D01*

+X367395Y213207D01*

+X368049Y213478D01*

+X368653Y213848D01*

+X369192Y214308D01*

+X369652Y214847D01*

+X370022Y215451D01*

+X370293Y216105D01*

+X370458Y216794D01*

+X370500Y217500D01*

+X370458Y218206D01*

+X370293Y218895D01*

+X370022Y219549D01*

+X369652Y220153D01*

+X369192Y220692D01*

+X368653Y221152D01*

+X368049Y221522D01*

+X367395Y221793D01*

+X366706Y221958D01*

+X366000Y222014D01*

+X365993Y222013D01*

+Y272987D01*

+X366000Y272986D01*

+X366706Y273042D01*

+X367395Y273207D01*

+X368049Y273478D01*

+X368653Y273848D01*

+X369192Y274308D01*

+X369652Y274847D01*

+X370022Y275451D01*

+X370293Y276105D01*

+X370458Y276794D01*

+X370500Y277500D01*

+X370458Y278206D01*

+X370293Y278895D01*

+X370022Y279549D01*

+X369652Y280153D01*

+X369192Y280692D01*

+X368653Y281152D01*

+X368049Y281522D01*

+X367395Y281793D01*

+X366706Y281958D01*

+X366000Y282014D01*

+X365993Y282013D01*

+Y360250D01*

+X372485Y360264D01*

+X372715Y360319D01*

+X372933Y360409D01*

+X373134Y360533D01*

+X373314Y360686D01*

+X373467Y360866D01*

+X373591Y361067D01*

+X373681Y361285D01*

+X373736Y361515D01*

+X373750Y361750D01*

+X373736Y368485D01*

+X373681Y368715D01*

+X373591Y368933D01*

+X373467Y369134D01*

+X373314Y369314D01*

+X373134Y369467D01*

+X372933Y369591D01*

+X372715Y369681D01*

+X372485Y369736D01*

+X372250Y369750D01*

+X365993Y369737D01*

+Y390000D01*

+X375993D01*

+Y282013D01*

+X375294Y281958D01*

+X374605Y281793D01*

+X373951Y281522D01*

+X373347Y281152D01*

+X372808Y280692D01*

+X372348Y280153D01*

+X371978Y279549D01*

+X371707Y278895D01*

+X371542Y278206D01*

+X371486Y277500D01*

+X371542Y276794D01*

+X371707Y276105D01*

+X371978Y275451D01*

+X372348Y274847D01*

+X372808Y274308D01*

+X373347Y273848D01*

+X373951Y273478D01*

+X374605Y273207D01*

+X375294Y273042D01*

+X375993Y272987D01*

+Y222013D01*

+X375294Y221958D01*

+X374605Y221793D01*

+X373951Y221522D01*

+X373347Y221152D01*

+X372808Y220692D01*

+X372348Y220153D01*

+X371978Y219549D01*

+X371707Y218895D01*

+X371542Y218206D01*

+X371486Y217500D01*

+X371542Y216794D01*

+X371707Y216105D01*

+X371978Y215451D01*

+X372348Y214847D01*

+X372808Y214308D01*

+X373347Y213848D01*

+X373951Y213478D01*

+X374605Y213207D01*

+X375294Y213042D01*

+X375993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X365993D02*X357573D01*

+Y213281D01*

+X358049Y213478D01*

+X358653Y213848D01*

+X359192Y214308D01*

+X359652Y214847D01*

+X360022Y215451D01*

+X360293Y216105D01*

+X360458Y216794D01*

+X360500Y217500D01*

+X360458Y218206D01*

+X360293Y218895D01*

+X360022Y219549D01*

+X359652Y220153D01*

+X359192Y220692D01*

+X358653Y221152D01*

+X358049Y221522D01*

+X357573Y221719D01*

+Y273281D01*

+X358049Y273478D01*

+X358653Y273848D01*

+X359192Y274308D01*

+X359652Y274847D01*

+X360022Y275451D01*

+X360293Y276105D01*

+X360458Y276794D01*

+X360500Y277500D01*

+X360458Y278206D01*

+X360293Y278895D01*

+X360022Y279549D01*

+X359652Y280153D01*

+X359192Y280692D01*

+X358653Y281152D01*

+X358049Y281522D01*

+X357573Y281719D01*

+Y300256D01*

+X357615Y300274D01*

+X357683Y300314D01*

+X357743Y300365D01*

+X357794Y300424D01*

+X357834Y300492D01*

+X357988Y300817D01*

+X358106Y301156D01*

+X358192Y301506D01*

+X358243Y301861D01*

+X358260Y302220D01*

+X358243Y302580D01*

+X358192Y302935D01*

+X358106Y303285D01*

+X357988Y303624D01*

+X357838Y303951D01*

+X357797Y304018D01*

+X357745Y304078D01*

+X357684Y304129D01*

+X357617Y304170D01*

+X357573Y304188D01*

+Y309889D01*

+X357857Y310353D01*

+X358083Y310899D01*

+X358221Y311474D01*

+X358256Y312063D01*

+X358221Y312652D01*

+X358083Y313227D01*

+X357857Y313773D01*

+X357573Y314237D01*

+Y317763D01*

+X357857Y318227D01*

+X358083Y318773D01*

+X358221Y319348D01*

+X358256Y319937D01*

+X358221Y320526D01*

+X358083Y321101D01*

+X357857Y321647D01*

+X357573Y322111D01*

+Y327606D01*

+X357857Y328069D01*

+X358083Y328615D01*

+X358221Y329190D01*

+X358256Y329780D01*

+X358221Y330369D01*

+X358083Y330944D01*

+X357857Y331490D01*

+X357573Y331953D01*

+Y360458D01*

+X358255Y360294D01*

+X359000Y360235D01*

+X359745Y360294D01*

+X360472Y360469D01*

+X361163Y360755D01*

+X361801Y361145D01*

+X362369Y361631D01*

+X362855Y362199D01*

+X363245Y362837D01*

+X363531Y363528D01*

+X363706Y364255D01*

+X363750Y365000D01*

+X363706Y365745D01*

+X363531Y366472D01*

+X363245Y367163D01*

+X362855Y367801D01*

+X362369Y368369D01*

+X361801Y368855D01*

+X361163Y369245D01*

+X360472Y369531D01*

+X359745Y369706D01*

+X359000Y369765D01*

+X358255Y369706D01*

+X357573Y369542D01*

+Y390000D01*

+X365993D01*

+Y369737D01*

+X365515Y369736D01*

+X365285Y369681D01*

+X365067Y369591D01*

+X364866Y369467D01*

+X364686Y369314D01*

+X364533Y369134D01*

+X364409Y368933D01*

+X364319Y368715D01*

+X364264Y368485D01*

+X364250Y368250D01*

+X364264Y361515D01*

+X364319Y361285D01*

+X364409Y361067D01*

+X364533Y360866D01*

+X364686Y360686D01*

+X364866Y360533D01*

+X365067Y360409D01*

+X365285Y360319D01*

+X365515Y360264D01*

+X365750Y360250D01*

+X365993Y360250D01*

+Y282013D01*

+X365294Y281958D01*

+X364605Y281793D01*

+X363951Y281522D01*

+X363347Y281152D01*

+X362808Y280692D01*

+X362348Y280153D01*

+X361978Y279549D01*

+X361707Y278895D01*

+X361542Y278206D01*

+X361486Y277500D01*

+X361542Y276794D01*

+X361707Y276105D01*

+X361978Y275451D01*

+X362348Y274847D01*

+X362808Y274308D01*

+X363347Y273848D01*

+X363951Y273478D01*

+X364605Y273207D01*

+X365294Y273042D01*

+X365993Y272987D01*

+Y222013D01*

+X365294Y221958D01*

+X364605Y221793D01*

+X363951Y221522D01*

+X363347Y221152D01*

+X362808Y220692D01*

+X362348Y220153D01*

+X361978Y219549D01*

+X361707Y218895D01*

+X361542Y218206D01*

+X361486Y217500D01*

+X361542Y216794D01*

+X361707Y216105D01*

+X361978Y215451D01*

+X362348Y214847D01*

+X362808Y214308D01*

+X363347Y213848D01*

+X363951Y213478D01*

+X364605Y213207D01*

+X365294Y213042D01*

+X365993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X357573Y369542D02*X357528Y369531D01*

+X356837Y369245D01*

+X356199Y368855D01*

+X355993Y368678D01*

+Y390000D01*

+X357573D01*

+Y369542D01*

+G37*

+G36*

+Y331953D02*X357548Y331994D01*

+X357164Y332444D01*

+X356714Y332827D01*

+X356210Y333136D01*

+X355993Y333226D01*

+Y361322D01*

+X356199Y361145D01*

+X356837Y360755D01*

+X357528Y360469D01*

+X357573Y360458D01*

+Y331953D01*

+G37*

+G36*

+Y322111D02*X357548Y322151D01*

+X357164Y322601D01*

+X356714Y322985D01*

+X356210Y323294D01*

+X355993Y323384D01*

+Y326333D01*

+X356210Y326423D01*

+X356714Y326732D01*

+X357164Y327116D01*

+X357548Y327565D01*

+X357573Y327606D01*

+Y322111D01*

+G37*

+G36*

+Y314237D02*X357548Y314277D01*

+X357164Y314727D01*

+X356714Y315111D01*

+X356210Y315420D01*

+X355993Y315510D01*

+Y316490D01*

+X356210Y316580D01*

+X356714Y316889D01*

+X357164Y317273D01*

+X357548Y317723D01*

+X357573Y317763D01*

+Y314237D01*

+G37*

+G36*

+Y281719D02*X357395Y281793D01*

+X356706Y281958D01*

+X356000Y282014D01*

+X355993Y282013D01*

+Y298773D01*

+X356231Y298882D01*

+X356298Y298924D01*

+X356358Y298976D01*

+X356409Y299036D01*

+X356450Y299104D01*

+X356480Y299177D01*

+X356498Y299254D01*

+X356503Y299333D01*

+X356496Y299412D01*

+X356477Y299489D01*

+X356447Y299562D01*

+X356405Y299629D01*

+X356353Y299689D01*

+X356292Y299740D01*

+X356224Y299781D01*

+X356151Y299811D01*

+X356074Y299829D01*

+X355995Y299835D01*

+X355993Y299834D01*

+Y304610D01*

+X355995Y304610D01*

+X356073Y304615D01*

+X356150Y304633D01*

+X356223Y304663D01*

+X356290Y304703D01*

+X356351Y304754D01*

+X356402Y304813D01*

+X356444Y304880D01*

+X356474Y304953D01*

+X356493Y305029D01*

+X356500Y305108D01*

+X356494Y305186D01*

+X356477Y305263D01*

+X356447Y305336D01*

+X356406Y305403D01*

+X356356Y305463D01*

+X356296Y305515D01*

+X356229Y305555D01*

+X355993Y305667D01*

+Y308616D01*

+X356210Y308706D01*

+X356714Y309015D01*

+X357164Y309399D01*

+X357548Y309849D01*

+X357573Y309889D01*

+Y304188D01*

+X357543Y304200D01*

+X357466Y304218D01*

+X357387Y304224D01*

+X357308Y304217D01*

+X357231Y304198D01*

+X357158Y304167D01*

+X357091Y304125D01*

+X357031Y304073D01*

+X356980Y304013D01*

+X356939Y303945D01*

+X356909Y303872D01*

+X356892Y303794D01*

+X356886Y303715D01*

+X356893Y303637D01*

+X356912Y303560D01*

+X356944Y303487D01*

+X357057Y303249D01*

+X357143Y303000D01*

+X357206Y302744D01*

+X357243Y302484D01*

+X357256Y302220D01*

+X357243Y301957D01*

+X357206Y301696D01*

+X357143Y301440D01*

+X357057Y301192D01*

+X356947Y300952D01*

+X356915Y300880D01*

+X356896Y300804D01*

+X356889Y300726D01*

+X356895Y300647D01*

+X356913Y300570D01*

+X356942Y300497D01*

+X356983Y300430D01*

+X357033Y300370D01*

+X357093Y300318D01*

+X357160Y300277D01*

+X357232Y300246D01*

+X357309Y300227D01*

+X357387Y300220D01*

+X357466Y300226D01*

+X357542Y300244D01*

+X357573Y300256D01*

+Y281719D01*

+G37*

+G36*

+Y221719D02*X357395Y221793D01*

+X356706Y221958D01*

+X356000Y222014D01*

+X355993Y222013D01*

+Y272987D01*

+X356000Y272986D01*

+X356706Y273042D01*

+X357395Y273207D01*

+X357573Y273281D01*

+Y221719D01*

+G37*

+G36*

+Y207500D02*X355993D01*

+Y212987D01*

+X356000Y212986D01*

+X356706Y213042D01*

+X357395Y213207D01*

+X357573Y213281D01*

+Y207500D01*

+G37*

+G36*

+X349115Y290674D02*X349125Y290599D01*

+X349146Y290134D01*

+X349125Y289669D01*

+X349115Y289593D01*

+Y290674D01*

+G37*

+G36*

+Y342407D02*X349125Y342331D01*

+X349146Y341866D01*

+X349125Y341401D01*

+X349115Y341326D01*

+Y342407D01*

+G37*

+G36*

+X351427Y317763D02*X351452Y317723D01*

+X351836Y317273D01*

+X352286Y316889D01*

+X352790Y316580D01*

+X353336Y316354D01*

+X353911Y316216D01*

+X354500Y316170D01*

+X355089Y316216D01*

+X355664Y316354D01*

+X355993Y316490D01*

+Y315510D01*

+X355664Y315646D01*

+X355089Y315784D01*

+X354500Y315830D01*

+X353911Y315784D01*

+X353336Y315646D01*

+X352790Y315420D01*

+X352286Y315111D01*

+X351836Y314727D01*

+X351452Y314277D01*

+X351427Y314237D01*

+Y317763D01*

+G37*

+G36*

+Y327606D02*X351452Y327565D01*

+X351836Y327116D01*

+X352286Y326732D01*

+X352790Y326423D01*

+X353336Y326196D01*

+X353911Y326058D01*

+X354500Y326012D01*

+X355089Y326058D01*

+X355664Y326196D01*

+X355993Y326333D01*

+Y323384D01*

+X355664Y323520D01*

+X355089Y323658D01*

+X354500Y323704D01*

+X353911Y323658D01*

+X353336Y323520D01*

+X352790Y323294D01*

+X352286Y322985D01*

+X351836Y322601D01*

+X351452Y322151D01*

+X351427Y322111D01*

+Y327606D01*

+G37*

+G36*

+Y360916D02*X351801Y361145D01*

+X352369Y361631D01*

+X352855Y362199D01*

+X353245Y362837D01*

+X353531Y363528D01*

+X353706Y364255D01*

+X353750Y365000D01*

+X353706Y365745D01*

+X353531Y366472D01*

+X353245Y367163D01*

+X352855Y367801D01*

+X352369Y368369D01*

+X351801Y368855D01*

+X351427Y369084D01*

+Y390000D01*

+X355993D01*

+Y368678D01*

+X355631Y368369D01*

+X355145Y367801D01*

+X354755Y367163D01*

+X354469Y366472D01*

+X354294Y365745D01*

+X354235Y365000D01*

+X354294Y364255D01*

+X354469Y363528D01*

+X354755Y362837D01*

+X355145Y362199D01*

+X355631Y361631D01*

+X355993Y361322D01*

+Y333226D01*

+X355664Y333363D01*

+X355089Y333501D01*

+X354500Y333547D01*

+X353911Y333501D01*

+X353336Y333363D01*

+X352790Y333136D01*

+X352286Y332827D01*

+X351836Y332444D01*

+X351452Y331994D01*

+X351427Y331953D01*

+Y360916D01*

+G37*

+G36*

+X355993Y207500D02*X351427D01*

+Y300253D01*

+X351457Y300241D01*

+X351534Y300223D01*

+X351613Y300217D01*

+X351692Y300224D01*

+X351769Y300243D01*

+X351842Y300274D01*

+X351909Y300316D01*

+X351969Y300368D01*

+X352020Y300428D01*

+X352061Y300496D01*

+X352091Y300569D01*

+X352108Y300647D01*

+X352114Y300726D01*

+X352107Y300804D01*

+X352088Y300881D01*

+X352056Y300954D01*

+X351943Y301192D01*

+X351857Y301440D01*

+X351794Y301696D01*

+X351757Y301957D01*

+X351744Y302220D01*

+X351757Y302484D01*

+X351794Y302744D01*

+X351857Y303000D01*

+X351943Y303249D01*

+X352053Y303489D01*

+X352085Y303561D01*

+X352104Y303637D01*

+X352111Y303715D01*

+X352105Y303794D01*

+X352087Y303871D01*

+X352058Y303944D01*

+X352017Y304011D01*

+X351967Y304071D01*

+X351907Y304123D01*

+X351840Y304164D01*

+X351768Y304195D01*

+X351691Y304214D01*

+X351613Y304220D01*

+X351534Y304215D01*

+X351458Y304197D01*

+X351427Y304185D01*

+Y309889D01*

+X351452Y309849D01*

+X351836Y309399D01*

+X352286Y309015D01*

+X352790Y308706D01*

+X353336Y308480D01*

+X353911Y308342D01*

+X354500Y308296D01*

+X355089Y308342D01*

+X355664Y308480D01*

+X355993Y308616D01*

+Y305667D01*

+X355904Y305709D01*

+X355564Y305827D01*

+X355215Y305912D01*

+X354859Y305963D01*

+X354500Y305981D01*

+X354141Y305963D01*

+X353785Y305912D01*

+X353436Y305827D01*

+X353096Y305709D01*

+X352769Y305559D01*

+X352702Y305517D01*

+X352642Y305465D01*

+X352591Y305405D01*

+X352550Y305337D01*

+X352520Y305264D01*

+X352502Y305186D01*

+X352497Y305108D01*

+X352504Y305029D01*

+X352523Y304952D01*

+X352553Y304879D01*

+X352595Y304812D01*

+X352647Y304752D01*

+X352708Y304701D01*

+X352776Y304660D01*

+X352849Y304630D01*

+X352926Y304612D01*

+X353005Y304606D01*

+X353084Y304613D01*

+X353161Y304632D01*

+X353233Y304664D01*

+X353471Y304777D01*

+X353720Y304864D01*

+X353976Y304926D01*

+X354237Y304964D01*

+X354500Y304976D01*

+X354763Y304964D01*

+X355024Y304926D01*

+X355280Y304864D01*

+X355529Y304777D01*

+X355768Y304667D01*

+X355840Y304635D01*

+X355917Y304616D01*

+X355993Y304610D01*

+Y299834D01*

+X355916Y299828D01*

+X355839Y299809D01*

+X355767Y299777D01*

+X355529Y299664D01*

+X355280Y299577D01*

+X355024Y299515D01*

+X354763Y299477D01*

+X354500Y299465D01*

+X354237Y299477D01*

+X353976Y299515D01*

+X353720Y299577D01*

+X353471Y299664D01*

+X353232Y299774D01*

+X353160Y299806D01*

+X353083Y299825D01*

+X353005Y299831D01*

+X352927Y299826D01*

+X352850Y299808D01*

+X352777Y299778D01*

+X352710Y299738D01*

+X352649Y299687D01*

+X352598Y299628D01*

+X352556Y299561D01*

+X352526Y299488D01*

+X352507Y299412D01*

+X352500Y299333D01*

+X352506Y299255D01*

+X352523Y299178D01*

+X352553Y299105D01*

+X352594Y299038D01*

+X352644Y298978D01*

+X352704Y298926D01*

+X352771Y298886D01*

+X353096Y298732D01*

+X353436Y298614D01*

+X353785Y298529D01*

+X354141Y298477D01*

+X354500Y298460D01*

+X354859Y298477D01*

+X355215Y298529D01*

+X355564Y298614D01*

+X355904Y298732D01*

+X355993Y298773D01*

+Y282013D01*

+X355294Y281958D01*

+X354605Y281793D01*

+X353951Y281522D01*

+X353347Y281152D01*

+X352808Y280692D01*

+X352348Y280153D01*

+X351978Y279549D01*

+X351707Y278895D01*

+X351542Y278206D01*

+X351486Y277500D01*

+X351542Y276794D01*

+X351707Y276105D01*

+X351978Y275451D01*

+X352348Y274847D01*

+X352808Y274308D01*

+X353347Y273848D01*

+X353951Y273478D01*

+X354605Y273207D01*

+X355294Y273042D01*

+X355993Y272987D01*

+Y222013D01*

+X355294Y221958D01*

+X354605Y221793D01*

+X353951Y221522D01*

+X353347Y221152D01*

+X352808Y220692D01*

+X352348Y220153D01*

+X351978Y219549D01*

+X351707Y218895D01*

+X351542Y218206D01*

+X351486Y217500D01*

+X351542Y216794D01*

+X351707Y216105D01*

+X351978Y215451D01*

+X352348Y214847D01*

+X352808Y214308D01*

+X353347Y213848D01*

+X353951Y213478D01*

+X354605Y213207D01*

+X355294Y213042D01*

+X355993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X351427Y369084D02*X351163Y369245D01*

+X350472Y369531D01*

+X349745Y369706D01*

+X349115Y369756D01*

+Y390000D01*

+X351427D01*

+Y369084D01*

+G37*

+G36*

+Y207500D02*X349115D01*

+Y214243D01*

+X349192Y214308D01*

+X349652Y214847D01*

+X350022Y215451D01*

+X350293Y216105D01*

+X350458Y216794D01*

+X350500Y217500D01*

+X350458Y218206D01*

+X350293Y218895D01*

+X350022Y219549D01*

+X349652Y220153D01*

+X349192Y220692D01*

+X349115Y220757D01*

+Y274243D01*

+X349192Y274308D01*

+X349652Y274847D01*

+X350022Y275451D01*

+X350293Y276105D01*

+X350458Y276794D01*

+X350500Y277500D01*

+X350458Y278206D01*

+X350293Y278895D01*

+X350022Y279549D01*

+X349652Y280153D01*

+X349192Y280692D01*

+X349115Y280757D01*

+Y286683D01*

+X349298Y286961D01*

+X349555Y287452D01*

+X349767Y287963D01*

+X349935Y288491D01*

+X350055Y289032D01*

+X350127Y289581D01*

+X350152Y290134D01*

+X350127Y290687D01*

+X350055Y291236D01*

+X349935Y291777D01*

+X349767Y292304D01*

+X349555Y292816D01*

+X349298Y293306D01*

+X349115Y293592D01*

+Y338415D01*

+X349298Y338694D01*

+X349555Y339184D01*

+X349767Y339696D01*

+X349935Y340223D01*

+X350055Y340764D01*

+X350127Y341313D01*

+X350152Y341866D01*

+X350127Y342419D01*

+X350055Y342968D01*

+X349935Y343509D01*

+X349767Y344037D01*

+X349555Y344548D01*

+X349298Y345039D01*

+X349115Y345324D01*

+Y360244D01*

+X349745Y360294D01*

+X350472Y360469D01*

+X351163Y360755D01*

+X351427Y360916D01*

+Y331953D01*

+X351143Y331490D01*

+X350917Y330944D01*

+X350779Y330369D01*

+X350733Y329780D01*

+X350779Y329190D01*

+X350917Y328615D01*

+X351143Y328069D01*

+X351427Y327606D01*

+Y322111D01*

+X351143Y321647D01*

+X350917Y321101D01*

+X350779Y320526D01*

+X350733Y319937D01*

+X350779Y319348D01*

+X350917Y318773D01*

+X351143Y318227D01*

+X351427Y317763D01*

+Y314237D01*

+X351143Y313773D01*

+X350917Y313227D01*

+X350779Y312652D01*

+X350733Y312063D01*

+X350779Y311474D01*

+X350917Y310899D01*

+X351143Y310353D01*

+X351427Y309889D01*

+Y304185D01*

+X351385Y304167D01*

+X351317Y304127D01*

+X351257Y304076D01*

+X351206Y304017D01*

+X351166Y303949D01*

+X351012Y303624D01*

+X350894Y303285D01*

+X350808Y302935D01*

+X350757Y302580D01*

+X350740Y302220D01*

+X350757Y301861D01*

+X350808Y301506D01*

+X350894Y301156D01*

+X351012Y300817D01*

+X351162Y300490D01*

+X351203Y300422D01*

+X351255Y300363D01*

+X351316Y300312D01*

+X351383Y300271D01*

+X351427Y300253D01*

+Y207500D01*

+G37*

+G36*

+X349115Y369756D02*X349000Y369765D01*

+X348255Y369706D01*

+X347528Y369531D01*

+X346837Y369245D01*

+X346199Y368855D01*

+X345993Y368678D01*

+Y390000D01*

+X349115D01*

+Y369756D01*

+G37*

+G36*

+Y280757D02*X348653Y281152D01*

+X348049Y281522D01*

+X347395Y281793D01*

+X346706Y281958D01*

+X346000Y282014D01*

+X345993Y282013D01*

+Y284195D01*

+X346001Y284197D01*

+X346513Y284410D01*

+X347003Y284667D01*

+X347470Y284965D01*

+X347531Y285016D01*

+X347584Y285075D01*

+X347626Y285142D01*

+X347658Y285215D01*

+X347677Y285292D01*

+X347685Y285372D01*

+X347680Y285451D01*

+X347662Y285528D01*

+X347633Y285602D01*

+X347593Y285671D01*

+X347542Y285732D01*

+X347482Y285785D01*

+X347415Y285827D01*

+X347342Y285859D01*

+X347265Y285878D01*

+X347186Y285886D01*

+X347106Y285881D01*

+X347029Y285863D01*

+X346955Y285834D01*

+X346887Y285792D01*

+X346498Y285537D01*

+X346086Y285321D01*

+X345993Y285282D01*

+Y294985D01*

+X346086Y294947D01*

+X346498Y294731D01*

+X346890Y294480D01*

+X346957Y294438D01*

+X347030Y294409D01*

+X347107Y294392D01*

+X347186Y294387D01*

+X347264Y294394D01*

+X347340Y294414D01*

+X347413Y294445D01*

+X347479Y294487D01*

+X347538Y294539D01*

+X347588Y294600D01*

+X347628Y294668D01*

+X347657Y294741D01*

+X347675Y294818D01*

+X347680Y294896D01*

+X347672Y294974D01*

+X347653Y295051D01*

+X347622Y295123D01*

+X347580Y295189D01*

+X347528Y295249D01*

+X347466Y295297D01*

+X347003Y295601D01*

+X346513Y295858D01*

+X346001Y296071D01*

+X345993Y296073D01*

+Y335927D01*

+X346001Y335929D01*

+X346513Y336142D01*

+X347003Y336399D01*

+X347470Y336698D01*

+X347531Y336748D01*

+X347584Y336807D01*

+X347626Y336875D01*

+X347658Y336948D01*

+X347677Y337025D01*

+X347685Y337104D01*

+X347680Y337183D01*

+X347662Y337261D01*

+X347633Y337335D01*

+X347593Y337403D01*

+X347542Y337464D01*

+X347482Y337517D01*

+X347415Y337559D01*

+X347342Y337591D01*

+X347265Y337611D01*

+X347186Y337618D01*

+X347106Y337613D01*

+X347029Y337596D01*

+X346955Y337566D01*

+X346887Y337524D01*

+X346498Y337269D01*

+X346086Y337053D01*

+X345993Y337015D01*

+Y346718D01*

+X346086Y346679D01*

+X346498Y346463D01*

+X346890Y346212D01*

+X346957Y346171D01*

+X347030Y346142D01*

+X347107Y346124D01*

+X347186Y346119D01*

+X347264Y346127D01*

+X347340Y346146D01*

+X347413Y346177D01*

+X347479Y346220D01*

+X347538Y346272D01*

+X347588Y346332D01*

+X347628Y346400D01*

+X347657Y346473D01*

+X347675Y346550D01*

+X347680Y346628D01*

+X347672Y346707D01*

+X347653Y346783D01*

+X347622Y346855D01*

+X347580Y346922D01*

+X347528Y346981D01*

+X347466Y347030D01*

+X347003Y347333D01*

+X346513Y347590D01*

+X346001Y347803D01*

+X345993Y347805D01*

+Y361322D01*

+X346199Y361145D01*

+X346837Y360755D01*

+X347528Y360469D01*

+X348255Y360294D01*

+X349000Y360235D01*

+X349115Y360244D01*

+Y345324D01*

+X348999Y345505D01*

+X348949Y345567D01*

+X348889Y345619D01*

+X348822Y345662D01*

+X348749Y345693D01*

+X348672Y345713D01*

+X348593Y345720D01*

+X348514Y345715D01*

+X348436Y345698D01*

+X348362Y345668D01*

+X348294Y345628D01*

+X348233Y345577D01*

+X348180Y345518D01*

+X348138Y345450D01*

+X348106Y345377D01*

+X348086Y345300D01*

+X348079Y345221D01*

+X348084Y345142D01*

+X348101Y345064D01*

+X348131Y344990D01*

+X348172Y344923D01*

+X348428Y344534D01*

+X348644Y344121D01*

+X348822Y343691D01*

+X348963Y343247D01*

+X349064Y342793D01*

+X349115Y342407D01*

+Y341326D01*

+X349064Y340939D01*

+X348963Y340485D01*

+X348822Y340041D01*

+X348644Y339611D01*

+X348428Y339199D01*

+X348177Y338806D01*

+X348135Y338740D01*

+X348106Y338666D01*

+X348089Y338590D01*

+X348084Y338511D01*

+X348091Y338433D01*

+X348111Y338357D01*

+X348142Y338284D01*

+X348184Y338218D01*

+X348236Y338159D01*

+X348297Y338109D01*

+X348364Y338068D01*

+X348438Y338039D01*

+X348514Y338022D01*

+X348593Y338017D01*

+X348671Y338024D01*

+X348748Y338044D01*

+X348820Y338075D01*

+X348886Y338117D01*

+X348945Y338169D01*

+X348994Y338231D01*

+X349115Y338415D01*

+Y293592D01*

+X348999Y293773D01*

+X348949Y293834D01*

+X348889Y293887D01*

+X348822Y293929D01*

+X348749Y293961D01*

+X348672Y293981D01*

+X348593Y293988D01*

+X348514Y293983D01*

+X348436Y293966D01*

+X348362Y293936D01*

+X348294Y293896D01*

+X348233Y293845D01*

+X348180Y293785D01*

+X348138Y293718D01*

+X348106Y293645D01*

+X348086Y293568D01*

+X348079Y293489D01*

+X348084Y293410D01*

+X348101Y293332D01*

+X348131Y293258D01*

+X348172Y293191D01*

+X348428Y292801D01*

+X348644Y292389D01*

+X348822Y291959D01*

+X348963Y291515D01*

+X349064Y291061D01*

+X349115Y290674D01*

+Y289593D01*

+X349064Y289207D01*

+X348963Y288753D01*

+X348822Y288309D01*

+X348644Y287879D01*

+X348428Y287466D01*

+X348177Y287074D01*

+X348135Y287007D01*

+X348106Y286934D01*

+X348089Y286857D01*

+X348084Y286779D01*

+X348091Y286701D01*

+X348111Y286624D01*

+X348142Y286552D01*

+X348184Y286486D01*

+X348236Y286426D01*

+X348297Y286376D01*

+X348364Y286336D01*

+X348438Y286307D01*

+X348514Y286290D01*

+X348593Y286285D01*

+X348671Y286292D01*

+X348748Y286312D01*

+X348820Y286343D01*

+X348886Y286385D01*

+X348945Y286437D01*

+X348994Y286499D01*

+X349115Y286683D01*

+Y280757D01*

+G37*

+G36*

+Y220757D02*X348653Y221152D01*

+X348049Y221522D01*

+X347395Y221793D01*

+X346706Y221958D01*

+X346000Y222014D01*

+X345993Y222013D01*

+Y244883D01*

+X346000Y245000D01*

+X345993Y245117D01*

+Y272987D01*

+X346000Y272986D01*

+X346706Y273042D01*

+X347395Y273207D01*

+X348049Y273478D01*

+X348653Y273848D01*

+X349115Y274243D01*

+Y220757D01*

+G37*

+G36*

+Y207500D02*X345993D01*

+Y212987D01*

+X346000Y212986D01*

+X346706Y213042D01*

+X347395Y213207D01*

+X348049Y213478D01*

+X348653Y213848D01*

+X349115Y214243D01*

+Y207500D01*

+G37*

+G36*

+X345993D02*X338546D01*

+Y213783D01*

+X338653Y213848D01*

+X339192Y214308D01*

+X339652Y214847D01*

+X340022Y215451D01*

+X340293Y216105D01*

+X340458Y216794D01*

+X340500Y217500D01*

+X340458Y218206D01*

+X340293Y218895D01*

+X340022Y219549D01*

+X339652Y220153D01*

+X339192Y220692D01*

+X338653Y221152D01*

+X338546Y221217D01*

+Y232038D01*

+X338608Y232023D01*

+X339000Y231992D01*

+X339392Y232023D01*

+X339775Y232115D01*

+X340138Y232266D01*

+X340474Y232471D01*

+X340773Y232727D01*

+X341029Y233026D01*

+X341234Y233362D01*

+X341385Y233725D01*

+X341477Y234108D01*

+X341500Y234500D01*

+X341477Y234892D01*

+X341385Y235275D01*

+X341234Y235638D01*

+X341029Y235974D01*

+X340773Y236273D01*

+X340474Y236529D01*

+X340138Y236734D01*

+X339775Y236885D01*

+X339392Y236977D01*

+X339000Y237008D01*

+X338608Y236977D01*

+X338546Y236962D01*

+Y240033D01*

+X338773Y240227D01*

+X339029Y240526D01*

+X339234Y240862D01*

+X339385Y241225D01*

+X339477Y241608D01*

+X339500Y242000D01*

+X339477Y242392D01*

+X339385Y242775D01*

+X339234Y243138D01*

+X339029Y243474D01*

+X338773Y243773D01*

+X338546Y243967D01*

+Y273783D01*

+X338653Y273848D01*

+X339192Y274308D01*

+X339652Y274847D01*

+X340022Y275451D01*

+X340293Y276105D01*

+X340458Y276794D01*

+X340500Y277500D01*

+X340458Y278206D01*

+X340293Y278895D01*

+X340022Y279549D01*

+X339652Y280153D01*

+X339192Y280692D01*

+X338653Y281152D01*

+X338546Y281217D01*

+Y286676D01*

+X338662Y286495D01*

+X338712Y286433D01*

+X338772Y286381D01*

+X338839Y286338D01*

+X338912Y286307D01*

+X338989Y286287D01*

+X339068Y286280D01*

+X339148Y286285D01*

+X339225Y286302D01*

+X339299Y286332D01*

+X339368Y286372D01*

+X339429Y286423D01*

+X339481Y286482D01*

+X339524Y286550D01*

+X339555Y286623D01*

+X339575Y286700D01*

+X339583Y286779D01*

+X339577Y286858D01*

+X339560Y286936D01*

+X339531Y287010D01*

+X339489Y287077D01*

+X339234Y287466D01*

+X339018Y287879D01*

+X338839Y288309D01*

+X338698Y288753D01*

+X338597Y289207D01*

+X338546Y289593D01*

+Y290674D01*

+X338597Y291061D01*

+X338698Y291515D01*

+X338839Y291959D01*

+X339018Y292389D01*

+X339234Y292801D01*

+X339485Y293194D01*

+X339526Y293260D01*

+X339555Y293334D01*

+X339572Y293410D01*

+X339577Y293489D01*

+X339570Y293567D01*

+X339551Y293643D01*

+X339519Y293716D01*

+X339477Y293782D01*

+X339425Y293841D01*

+X339365Y293891D01*

+X339297Y293932D01*

+X339224Y293961D01*

+X339147Y293978D01*

+X339068Y293983D01*

+X338990Y293976D01*

+X338914Y293956D01*

+X338842Y293925D01*

+X338775Y293883D01*

+X338716Y293831D01*

+X338667Y293769D01*

+X338546Y293585D01*

+Y338408D01*

+X338662Y338227D01*

+X338712Y338166D01*

+X338772Y338113D01*

+X338839Y338071D01*

+X338912Y338039D01*

+X338989Y338019D01*

+X339068Y338012D01*

+X339148Y338017D01*

+X339225Y338034D01*

+X339299Y338064D01*

+X339368Y338104D01*

+X339429Y338155D01*

+X339481Y338215D01*

+X339524Y338282D01*

+X339555Y338355D01*

+X339575Y338432D01*

+X339583Y338511D01*

+X339577Y338590D01*

+X339560Y338668D01*

+X339531Y338742D01*

+X339489Y338809D01*

+X339234Y339199D01*

+X339018Y339611D01*

+X338839Y340041D01*

+X338698Y340485D01*

+X338597Y340939D01*

+X338546Y341326D01*

+Y342407D01*

+X338597Y342793D01*

+X338698Y343247D01*

+X338839Y343691D01*

+X339018Y344121D01*

+X339234Y344534D01*

+X339485Y344926D01*

+X339526Y344993D01*

+X339555Y345066D01*

+X339572Y345143D01*

+X339577Y345221D01*

+X339570Y345299D01*

+X339551Y345376D01*

+X339519Y345448D01*

+X339477Y345514D01*

+X339425Y345574D01*

+X339365Y345624D01*

+X339297Y345664D01*

+X339224Y345693D01*

+X339147Y345710D01*

+X339068Y345715D01*

+X338990Y345708D01*

+X338914Y345688D01*

+X338842Y345657D01*

+X338775Y345615D01*

+X338716Y345563D01*

+X338667Y345501D01*

+X338546Y345317D01*

+Y360271D01*

+X339000Y360235D01*

+X339745Y360294D01*

+X340472Y360469D01*

+X341163Y360755D01*

+X341801Y361145D01*

+X342369Y361631D01*

+X342855Y362199D01*

+X343245Y362837D01*

+X343531Y363528D01*

+X343706Y364255D01*

+X343750Y365000D01*

+X343706Y365745D01*

+X343531Y366472D01*

+X343245Y367163D01*

+X342855Y367801D01*

+X342369Y368369D01*

+X341801Y368855D01*

+X341163Y369245D01*

+X340472Y369531D01*

+X339745Y369706D01*

+X339000Y369765D01*

+X338546Y369729D01*

+Y390000D01*

+X345993D01*

+Y368678D01*

+X345631Y368369D01*

+X345145Y367801D01*

+X344755Y367163D01*

+X344469Y366472D01*

+X344294Y365745D01*

+X344235Y365000D01*

+X344294Y364255D01*

+X344469Y363528D01*

+X344755Y362837D01*

+X345145Y362199D01*

+X345631Y361631D01*

+X345993Y361322D01*

+Y347805D01*

+X345473Y347970D01*

+X344933Y348090D01*

+X344384Y348163D01*

+X343831Y348187D01*

+X343277Y348163D01*

+X342729Y348090D01*

+X342188Y347970D01*

+X341660Y347803D01*

+X341149Y347590D01*

+X340658Y347333D01*

+X340192Y347035D01*

+X340130Y346984D01*

+X340078Y346925D01*

+X340035Y346858D01*

+X340004Y346785D01*

+X339984Y346708D01*

+X339977Y346628D01*

+X339982Y346549D01*

+X339999Y346472D01*

+X340028Y346398D01*

+X340069Y346329D01*

+X340120Y346268D01*

+X340179Y346216D01*

+X340246Y346173D01*

+X340319Y346141D01*

+X340396Y346122D01*

+X340476Y346114D01*

+X340555Y346119D01*

+X340633Y346137D01*

+X340706Y346166D01*

+X340774Y346208D01*

+X341163Y346463D01*

+X341576Y346679D01*

+X342006Y346858D01*

+X342449Y346998D01*

+X342904Y347100D01*

+X343366Y347161D01*

+X343831Y347181D01*

+X344296Y347161D01*

+X344757Y347100D01*

+X345212Y346998D01*

+X345656Y346858D01*

+X345993Y346718D01*

+Y337015D01*

+X345656Y336874D01*

+X345212Y336734D01*

+X344757Y336633D01*

+X344296Y336572D01*

+X343831Y336551D01*

+X343366Y336572D01*

+X342904Y336633D01*

+X342449Y336734D01*

+X342006Y336874D01*

+X341576Y337053D01*

+X341163Y337269D01*

+X340771Y337520D01*

+X340704Y337562D01*

+X340631Y337591D01*

+X340554Y337608D01*

+X340476Y337613D01*

+X340397Y337606D01*

+X340321Y337586D01*

+X340249Y337555D01*

+X340182Y337513D01*

+X340123Y337461D01*

+X340073Y337400D01*

+X340033Y337332D01*

+X340004Y337259D01*

+X339987Y337182D01*

+X339982Y337104D01*

+X339989Y337026D01*

+X340009Y336949D01*

+X340040Y336877D01*

+X340082Y336811D01*

+X340134Y336751D01*

+X340195Y336703D01*

+X340658Y336399D01*

+X341149Y336142D01*

+X341660Y335929D01*

+X342188Y335762D01*

+X342729Y335642D01*

+X343277Y335569D01*

+X343831Y335545D01*

+X344384Y335569D01*

+X344933Y335642D01*

+X345473Y335762D01*

+X345993Y335927D01*

+Y296073D01*

+X345473Y296238D01*

+X344933Y296358D01*

+X344384Y296431D01*

+X343831Y296455D01*

+X343277Y296431D01*

+X342729Y296358D01*

+X342188Y296238D01*

+X341660Y296071D01*

+X341149Y295858D01*

+X340658Y295601D01*

+X340192Y295302D01*

+X340130Y295252D01*

+X340078Y295193D01*

+X340035Y295125D01*

+X340004Y295052D01*

+X339984Y294975D01*

+X339977Y294896D01*

+X339982Y294817D01*

+X339999Y294739D01*

+X340028Y294665D01*

+X340069Y294597D01*

+X340120Y294536D01*

+X340179Y294483D01*

+X340246Y294441D01*

+X340319Y294409D01*

+X340396Y294389D01*

+X340476Y294382D01*

+X340555Y294387D01*

+X340633Y294404D01*

+X340706Y294434D01*

+X340774Y294476D01*

+X341163Y294731D01*

+X341576Y294947D01*

+X342006Y295126D01*

+X342449Y295266D01*

+X342904Y295367D01*

+X343366Y295428D01*

+X343831Y295449D01*

+X344296Y295428D01*

+X344757Y295367D01*

+X345212Y295266D01*

+X345656Y295126D01*

+X345993Y294985D01*

+Y285282D01*

+X345656Y285142D01*

+X345212Y285002D01*

+X344757Y284900D01*

+X344296Y284839D01*

+X343831Y284819D01*

+X343366Y284839D01*

+X342904Y284900D01*

+X342449Y285002D01*

+X342006Y285142D01*

+X341576Y285321D01*

+X341163Y285537D01*

+X340771Y285788D01*

+X340704Y285829D01*

+X340631Y285858D01*

+X340554Y285876D01*

+X340476Y285881D01*

+X340397Y285873D01*

+X340321Y285854D01*

+X340249Y285823D01*

+X340182Y285780D01*

+X340123Y285728D01*

+X340073Y285668D01*

+X340033Y285600D01*

+X340004Y285527D01*

+X339987Y285450D01*

+X339982Y285372D01*

+X339989Y285293D01*

+X340009Y285217D01*

+X340040Y285145D01*

+X340082Y285078D01*

+X340134Y285019D01*

+X340195Y284970D01*

+X340658Y284667D01*

+X341149Y284410D01*

+X341660Y284197D01*

+X342188Y284030D01*

+X342729Y283910D01*

+X343277Y283837D01*

+X343831Y283813D01*

+X344384Y283837D01*

+X344933Y283910D01*

+X345473Y284030D01*

+X345993Y284195D01*

+Y282013D01*

+X345294Y281958D01*

+X344605Y281793D01*

+X343951Y281522D01*

+X343347Y281152D01*

+X342808Y280692D01*

+X342348Y280153D01*

+X341978Y279549D01*

+X341707Y278895D01*

+X341542Y278206D01*

+X341486Y277500D01*

+X341542Y276794D01*

+X341707Y276105D01*

+X341978Y275451D01*

+X342348Y274847D01*

+X342808Y274308D01*

+X343347Y273848D01*

+X343951Y273478D01*

+X344605Y273207D01*

+X345294Y273042D01*

+X345993Y272987D01*

+Y245117D01*

+X345977Y245392D01*

+X345885Y245775D01*

+X345734Y246138D01*

+X345529Y246474D01*

+X345273Y246773D01*

+X344974Y247029D01*

+X344638Y247234D01*

+X344275Y247385D01*

+X343892Y247477D01*

+X343500Y247508D01*

+X343108Y247477D01*

+X342725Y247385D01*

+X342362Y247234D01*

+X342026Y247029D01*

+X341727Y246773D01*

+X341471Y246474D01*

+X341266Y246138D01*

+X341115Y245775D01*

+X341023Y245392D01*

+X340992Y245000D01*

+X341023Y244608D01*

+X341115Y244225D01*

+X341266Y243862D01*

+X341471Y243526D01*

+X341727Y243227D01*

+X342026Y242971D01*

+X342362Y242766D01*

+X342725Y242615D01*

+X343108Y242523D01*

+X343500Y242492D01*

+X343892Y242523D01*

+X344275Y242615D01*

+X344638Y242766D01*

+X344974Y242971D01*

+X345273Y243227D01*

+X345529Y243526D01*

+X345734Y243862D01*

+X345885Y244225D01*

+X345977Y244608D01*

+X345993Y244883D01*

+Y222013D01*

+X345294Y221958D01*

+X344605Y221793D01*

+X343951Y221522D01*

+X343347Y221152D01*

+X342808Y220692D01*

+X342348Y220153D01*

+X341978Y219549D01*

+X341707Y218895D01*

+X341542Y218206D01*

+X341486Y217500D01*

+X341542Y216794D01*

+X341707Y216105D01*

+X341978Y215451D01*

+X342348Y214847D01*

+X342808Y214308D01*

+X343347Y213848D01*

+X343951Y213478D01*

+X344605Y213207D01*

+X345294Y213042D01*

+X345993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X338546Y289593D02*X338536Y289669D01*

+X338516Y290134D01*

+X338536Y290599D01*

+X338546Y290674D01*

+Y289593D01*

+G37*

+G36*

+Y341326D02*X338536Y341401D01*

+X338516Y341866D01*

+X338536Y342331D01*

+X338546Y342407D01*

+Y341326D01*

+G37*

+G36*

+Y369729D02*X338255Y369706D01*

+X337528Y369531D01*

+X336837Y369245D01*

+X336199Y368855D01*

+X335993Y368678D01*

+Y390000D01*

+X338546D01*

+Y369729D01*

+G37*

+G36*

+Y281217D02*X338049Y281522D01*

+X337395Y281793D01*

+X336706Y281958D01*

+X336000Y282014D01*

+X335993Y282013D01*

+Y361322D01*

+X336199Y361145D01*

+X336837Y360755D01*

+X337528Y360469D01*

+X338255Y360294D01*

+X338546Y360271D01*

+Y345317D01*

+X338363Y345039D01*

+X338107Y344548D01*

+X337894Y344037D01*

+X337727Y343509D01*

+X337607Y342968D01*

+X337534Y342419D01*

+X337510Y341866D01*

+X337534Y341313D01*

+X337607Y340764D01*

+X337727Y340223D01*

+X337894Y339696D01*

+X338107Y339184D01*

+X338363Y338694D01*

+X338546Y338408D01*

+Y293585D01*

+X338363Y293306D01*

+X338107Y292816D01*

+X337894Y292304D01*

+X337727Y291777D01*

+X337607Y291236D01*

+X337534Y290687D01*

+X337510Y290134D01*

+X337534Y289581D01*

+X337607Y289032D01*

+X337727Y288491D01*

+X337894Y287963D01*

+X338107Y287452D01*

+X338363Y286961D01*

+X338546Y286676D01*

+Y281217D01*

+G37*

+G36*

+Y243967D02*X338474Y244029D01*

+X338138Y244234D01*

+X337775Y244385D01*

+X337392Y244477D01*

+X337000Y244508D01*

+X336608Y244477D01*

+X336225Y244385D01*

+X335993Y244289D01*

+Y272987D01*

+X336000Y272986D01*

+X336706Y273042D01*

+X337395Y273207D01*

+X338049Y273478D01*

+X338546Y273783D01*

+Y243967D01*

+G37*

+G36*

+Y221217D02*X338049Y221522D01*

+X337395Y221793D01*

+X336706Y221958D01*

+X336000Y222014D01*

+X335993Y222013D01*

+Y239711D01*

+X336225Y239615D01*

+X336608Y239523D01*

+X337000Y239492D01*

+X337392Y239523D01*

+X337775Y239615D01*

+X338138Y239766D01*

+X338474Y239971D01*

+X338546Y240033D01*

+Y236962D01*

+X338225Y236885D01*

+X337862Y236734D01*

+X337526Y236529D01*

+X337227Y236273D01*

+X336971Y235974D01*

+X336766Y235638D01*

+X336615Y235275D01*

+X336523Y234892D01*

+X336492Y234500D01*

+X336523Y234108D01*

+X336615Y233725D01*

+X336766Y233362D01*

+X336971Y233026D01*

+X337227Y232727D01*

+X337526Y232471D01*

+X337862Y232266D01*

+X338225Y232115D01*

+X338546Y232038D01*

+Y221217D01*

+G37*

+G36*

+Y207500D02*X335993D01*

+Y212987D01*

+X336000Y212986D01*

+X336706Y213042D01*

+X337395Y213207D01*

+X338049Y213478D01*

+X338546Y213783D01*

+Y207500D01*

+G37*

+G36*

+X335993D02*X329496D01*

+Y214665D01*

+X329652Y214847D01*

+X330022Y215451D01*

+X330293Y216105D01*

+X330458Y216794D01*

+X330500Y217500D01*

+X330458Y218206D01*

+X330293Y218895D01*

+X330022Y219549D01*

+X329652Y220153D01*

+X329496Y220335D01*

+Y237993D01*

+X329500Y237992D01*

+X329892Y238023D01*

+X330275Y238115D01*

+X330638Y238266D01*

+X330974Y238471D01*

+X331273Y238727D01*

+X331529Y239026D01*

+X331734Y239362D01*

+X331885Y239725D01*

+X331977Y240108D01*

+X332000Y240500D01*

+X331977Y240892D01*

+X331885Y241275D01*

+X331734Y241638D01*

+X331529Y241974D01*

+X331273Y242273D01*

+X330974Y242529D01*

+X330638Y242734D01*

+X330275Y242885D01*

+X329892Y242977D01*

+X329500Y243008D01*

+X329496Y243007D01*

+Y274665D01*

+X329652Y274847D01*

+X330022Y275451D01*

+X330293Y276105D01*

+X330458Y276794D01*

+X330500Y277500D01*

+X330458Y278206D01*

+X330293Y278895D01*

+X330022Y279549D01*

+X329652Y280153D01*

+X329496Y280335D01*

+Y360274D01*

+X329745Y360294D01*

+X330472Y360469D01*

+X331163Y360755D01*

+X331801Y361145D01*

+X332369Y361631D01*

+X332855Y362199D01*

+X333245Y362837D01*

+X333531Y363528D01*

+X333706Y364255D01*

+X333750Y365000D01*

+X333706Y365745D01*

+X333531Y366472D01*

+X333245Y367163D01*

+X332855Y367801D01*

+X332369Y368369D01*

+X331801Y368855D01*

+X331163Y369245D01*

+X330472Y369531D01*

+X329745Y369706D01*

+X329496Y369726D01*

+Y390000D01*

+X335993D01*

+Y368678D01*

+X335631Y368369D01*

+X335145Y367801D01*

+X334755Y367163D01*

+X334469Y366472D01*

+X334294Y365745D01*

+X334235Y365000D01*

+X334294Y364255D01*

+X334469Y363528D01*

+X334755Y362837D01*

+X335145Y362199D01*

+X335631Y361631D01*

+X335993Y361322D01*

+Y282013D01*

+X335294Y281958D01*

+X334605Y281793D01*

+X333951Y281522D01*

+X333347Y281152D01*

+X332808Y280692D01*

+X332348Y280153D01*

+X331978Y279549D01*

+X331707Y278895D01*

+X331542Y278206D01*

+X331486Y277500D01*

+X331542Y276794D01*

+X331707Y276105D01*

+X331978Y275451D01*

+X332348Y274847D01*

+X332808Y274308D01*

+X333347Y273848D01*

+X333951Y273478D01*

+X334605Y273207D01*

+X335294Y273042D01*

+X335993Y272987D01*

+Y244289D01*

+X335862Y244234D01*

+X335526Y244029D01*

+X335227Y243773D01*

+X334971Y243474D01*

+X334766Y243138D01*

+X334615Y242775D01*

+X334523Y242392D01*

+X334492Y242000D01*

+X334523Y241608D01*

+X334615Y241225D01*

+X334766Y240862D01*

+X334971Y240526D01*

+X335227Y240227D01*

+X335526Y239971D01*

+X335862Y239766D01*

+X335993Y239711D01*

+Y222013D01*

+X335294Y221958D01*

+X334605Y221793D01*

+X333951Y221522D01*

+X333347Y221152D01*

+X332808Y220692D01*

+X332348Y220153D01*

+X331978Y219549D01*

+X331707Y218895D01*

+X331542Y218206D01*

+X331486Y217500D01*

+X331542Y216794D01*

+X331707Y216105D01*

+X331978Y215451D01*

+X332348Y214847D01*

+X332808Y214308D01*

+X333347Y213848D01*

+X333951Y213478D01*

+X334605Y213207D01*

+X335294Y213042D01*

+X335993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X329496Y369726D02*X329000Y369765D01*

+X328255Y369706D01*

+X327528Y369531D01*

+X326837Y369245D01*

+X326199Y368855D01*

+X325993Y368678D01*

+Y390000D01*

+X329496D01*

+Y369726D01*

+G37*

+G36*

+Y280335D02*X329192Y280692D01*

+X328653Y281152D01*

+X328049Y281522D01*

+X327395Y281793D01*

+X326706Y281958D01*

+X326000Y282014D01*

+X325993Y282013D01*

+Y361322D01*

+X326199Y361145D01*

+X326837Y360755D01*

+X327528Y360469D01*

+X328255Y360294D01*

+X329000Y360235D01*

+X329496Y360274D01*

+Y280335D01*

+G37*

+G36*

+Y220335D02*X329192Y220692D01*

+X328653Y221152D01*

+X328049Y221522D01*

+X327395Y221793D01*

+X326706Y221958D01*

+X326000Y222014D01*

+X325993Y222013D01*

+Y272987D01*

+X326000Y272986D01*

+X326706Y273042D01*

+X327395Y273207D01*

+X328049Y273478D01*

+X328653Y273848D01*

+X329192Y274308D01*

+X329496Y274665D01*

+Y243007D01*

+X329108Y242977D01*

+X328725Y242885D01*

+X328362Y242734D01*

+X328026Y242529D01*

+X327727Y242273D01*

+X327471Y241974D01*

+X327266Y241638D01*

+X327115Y241275D01*

+X327023Y240892D01*

+X326992Y240500D01*

+X327023Y240108D01*

+X327115Y239725D01*

+X327266Y239362D01*

+X327471Y239026D01*

+X327727Y238727D01*

+X328026Y238471D01*

+X328362Y238266D01*

+X328725Y238115D01*

+X329108Y238023D01*

+X329496Y237993D01*

+Y220335D01*

+G37*

+G36*

+Y207500D02*X325993D01*

+Y212987D01*

+X326000Y212986D01*

+X326706Y213042D01*

+X327395Y213207D01*

+X328049Y213478D01*

+X328653Y213848D01*

+X329192Y214308D01*

+X329496Y214665D01*

+Y207500D01*

+G37*

+G36*

+X325993D02*X315993D01*

+Y212987D01*

+X316000Y212986D01*

+X316706Y213042D01*

+X317395Y213207D01*

+X318049Y213478D01*

+X318653Y213848D01*

+X319192Y214308D01*

+X319652Y214847D01*

+X320022Y215451D01*

+X320293Y216105D01*

+X320458Y216794D01*

+X320500Y217500D01*

+X320458Y218206D01*

+X320293Y218895D01*

+X320022Y219549D01*

+X319652Y220153D01*

+X319192Y220692D01*

+X318653Y221152D01*

+X318049Y221522D01*

+X317395Y221793D01*

+X316706Y221958D01*

+X316000Y222014D01*

+X315993Y222013D01*

+Y272987D01*

+X316000Y272986D01*

+X316706Y273042D01*

+X317395Y273207D01*

+X318049Y273478D01*

+X318653Y273848D01*

+X319192Y274308D01*

+X319652Y274847D01*

+X320022Y275451D01*

+X320293Y276105D01*

+X320458Y276794D01*

+X320500Y277500D01*

+X320458Y278206D01*

+X320293Y278895D01*

+X320022Y279549D01*

+X319652Y280153D01*

+X319192Y280692D01*

+X318653Y281152D01*

+X318049Y281522D01*

+X317395Y281793D01*

+X316706Y281958D01*

+X316000Y282014D01*

+X315993Y282013D01*

+Y360262D01*

+X316985Y360264D01*

+X317215Y360319D01*

+X317433Y360409D01*

+X317634Y360533D01*

+X317814Y360686D01*

+X317967Y360866D01*

+X318091Y361067D01*

+X318181Y361285D01*

+X318236Y361515D01*

+X318250Y361750D01*

+X318236Y368485D01*

+X318181Y368715D01*

+X318091Y368933D01*

+X317967Y369134D01*

+X317814Y369314D01*

+X317634Y369467D01*

+X317433Y369591D01*

+X317215Y369681D01*

+X316985Y369736D01*

+X316750Y369750D01*

+X315993Y369748D01*

+Y390000D01*

+X325993D01*

+Y368678D01*

+X325631Y368369D01*

+X325145Y367801D01*

+X324755Y367163D01*

+X324469Y366472D01*

+X324294Y365745D01*

+X324235Y365000D01*

+X324294Y364255D01*

+X324469Y363528D01*

+X324755Y362837D01*

+X325145Y362199D01*

+X325631Y361631D01*

+X325993Y361322D01*

+Y282013D01*

+X325294Y281958D01*

+X324605Y281793D01*

+X323951Y281522D01*

+X323347Y281152D01*

+X322808Y280692D01*

+X322348Y280153D01*

+X321978Y279549D01*

+X321707Y278895D01*

+X321542Y278206D01*

+X321486Y277500D01*

+X321542Y276794D01*

+X321707Y276105D01*

+X321978Y275451D01*

+X322348Y274847D01*

+X322808Y274308D01*

+X323347Y273848D01*

+X323951Y273478D01*

+X324605Y273207D01*

+X325294Y273042D01*

+X325993Y272987D01*

+Y222013D01*

+X325294Y221958D01*

+X324605Y221793D01*

+X323951Y221522D01*

+X323347Y221152D01*

+X322808Y220692D01*

+X322348Y220153D01*

+X321978Y219549D01*

+X321707Y218895D01*

+X321542Y218206D01*

+X321486Y217500D01*

+X321542Y216794D01*

+X321707Y216105D01*

+X321978Y215451D01*

+X322348Y214847D01*

+X322808Y214308D01*

+X323347Y213848D01*

+X323951Y213478D01*

+X324605Y213207D01*

+X325294Y213042D01*

+X325993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X315993D02*X305993D01*

+Y212987D01*

+X306000Y212986D01*

+X306706Y213042D01*

+X307395Y213207D01*

+X308049Y213478D01*

+X308653Y213848D01*

+X309192Y214308D01*

+X309652Y214847D01*

+X310022Y215451D01*

+X310293Y216105D01*

+X310458Y216794D01*

+X310500Y217500D01*

+X310458Y218206D01*

+X310293Y218895D01*

+X310022Y219549D01*

+X309652Y220153D01*

+X309192Y220692D01*

+X308653Y221152D01*

+X308049Y221522D01*

+X307395Y221793D01*

+X306706Y221958D01*

+X306000Y222014D01*

+X305993Y222013D01*

+Y272987D01*

+X306000Y272986D01*

+X306706Y273042D01*

+X307395Y273207D01*

+X308049Y273478D01*

+X308653Y273848D01*

+X309192Y274308D01*

+X309652Y274847D01*

+X310022Y275451D01*

+X310293Y276105D01*

+X310458Y276794D01*

+X310500Y277500D01*

+X310458Y278206D01*

+X310293Y278895D01*

+X310022Y279549D01*

+X309652Y280153D01*

+X309192Y280692D01*

+X308653Y281152D01*

+X308049Y281522D01*

+X307395Y281793D01*

+X306706Y281958D01*

+X306000Y282014D01*

+X305993Y282013D01*

+Y360957D01*

+X306301Y361145D01*

+X306869Y361631D01*

+X307355Y362199D01*

+X307745Y362837D01*

+X308031Y363528D01*

+X308206Y364255D01*

+X308250Y365000D01*

+X308206Y365745D01*

+X308031Y366472D01*

+X307745Y367163D01*

+X307355Y367801D01*

+X306869Y368369D01*

+X306301Y368855D01*

+X305993Y369043D01*

+Y390000D01*

+X315993D01*

+Y369748D01*

+X310015Y369736D01*

+X309785Y369681D01*

+X309567Y369591D01*

+X309366Y369467D01*

+X309186Y369314D01*

+X309033Y369134D01*

+X308909Y368933D01*

+X308819Y368715D01*

+X308764Y368485D01*

+X308750Y368250D01*

+X308764Y361515D01*

+X308819Y361285D01*

+X308909Y361067D01*

+X309033Y360866D01*

+X309186Y360686D01*

+X309366Y360533D01*

+X309567Y360409D01*

+X309785Y360319D01*

+X310015Y360264D01*

+X310250Y360250D01*

+X315993Y360262D01*

+Y282013D01*

+X315294Y281958D01*

+X314605Y281793D01*

+X313951Y281522D01*

+X313347Y281152D01*

+X312808Y280692D01*

+X312348Y280153D01*

+X311978Y279549D01*

+X311707Y278895D01*

+X311542Y278206D01*

+X311486Y277500D01*

+X311542Y276794D01*

+X311707Y276105D01*

+X311978Y275451D01*

+X312348Y274847D01*

+X312808Y274308D01*

+X313347Y273848D01*

+X313951Y273478D01*

+X314605Y273207D01*

+X315294Y273042D01*

+X315993Y272987D01*

+Y222013D01*

+X315294Y221958D01*

+X314605Y221793D01*

+X313951Y221522D01*

+X313347Y221152D01*

+X312808Y220692D01*

+X312348Y220153D01*

+X311978Y219549D01*

+X311707Y218895D01*

+X311542Y218206D01*

+X311486Y217500D01*

+X311542Y216794D01*

+X311707Y216105D01*

+X311978Y215451D01*

+X312348Y214847D01*

+X312808Y214308D01*

+X313347Y213848D01*

+X313951Y213478D01*

+X314605Y213207D01*

+X315294Y213042D01*

+X315993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X300996Y390000D02*X305993D01*

+Y369043D01*

+X305663Y369245D01*

+X304972Y369531D01*

+X304245Y369706D01*

+X303500Y369765D01*

+X302755Y369706D01*

+X302028Y369531D01*

+X301337Y369245D01*

+X300996Y369037D01*

+Y390000D01*

+G37*

+G36*

+X302073Y309889D02*X302357Y310353D01*

+X302583Y310899D01*

+X302721Y311474D01*

+X302756Y312063D01*

+X302721Y312652D01*

+X302583Y313227D01*

+X302357Y313773D01*

+X302073Y314237D01*

+Y317763D01*

+X302357Y318227D01*

+X302583Y318773D01*

+X302721Y319348D01*

+X302756Y319937D01*

+X302721Y320526D01*

+X302583Y321101D01*

+X302357Y321647D01*

+X302073Y322111D01*

+Y327606D01*

+X302357Y328069D01*

+X302583Y328615D01*

+X302721Y329190D01*

+X302756Y329780D01*

+X302721Y330369D01*

+X302583Y330944D01*

+X302357Y331490D01*

+X302073Y331953D01*

+Y360458D01*

+X302755Y360294D01*

+X303500Y360235D01*

+X304245Y360294D01*

+X304972Y360469D01*

+X305663Y360755D01*

+X305993Y360957D01*

+Y282013D01*

+X305294Y281958D01*

+X304605Y281793D01*

+X303951Y281522D01*

+X303347Y281152D01*

+X302808Y280692D01*

+X302348Y280153D01*

+X302073Y279704D01*

+Y300256D01*

+X302115Y300274D01*

+X302183Y300314D01*

+X302243Y300365D01*

+X302294Y300424D01*

+X302334Y300492D01*

+X302488Y300817D01*

+X302606Y301156D01*

+X302692Y301506D01*

+X302743Y301861D01*

+X302760Y302220D01*

+X302743Y302580D01*

+X302692Y302935D01*

+X302606Y303285D01*

+X302488Y303624D01*

+X302338Y303951D01*

+X302297Y304018D01*

+X302245Y304078D01*

+X302184Y304129D01*

+X302117Y304170D01*

+X302073Y304188D01*

+Y309889D01*

+G37*

+G36*

+Y265739D02*X302138Y265766D01*

+X302474Y265971D01*

+X302773Y266227D01*

+X303029Y266526D01*

+X303234Y266862D01*

+X303385Y267225D01*

+X303477Y267608D01*

+X303500Y268000D01*

+X303477Y268392D01*

+X303385Y268775D01*

+X303234Y269138D01*

+X303029Y269474D01*

+X302773Y269773D01*

+X302474Y270029D01*

+X302138Y270234D01*

+X302073Y270261D01*

+Y275296D01*

+X302348Y274847D01*

+X302808Y274308D01*

+X303347Y273848D01*

+X303951Y273478D01*

+X304605Y273207D01*

+X305294Y273042D01*

+X305993Y272987D01*

+Y222013D01*

+X305294Y221958D01*

+X304605Y221793D01*

+X303951Y221522D01*

+X303347Y221152D01*

+X302808Y220692D01*

+X302348Y220153D01*

+X302073Y219704D01*

+Y265739D01*

+G37*

+G36*

+X305993Y207500D02*X302073D01*

+Y215296D01*

+X302348Y214847D01*

+X302808Y214308D01*

+X303347Y213848D01*

+X303951Y213478D01*

+X304605Y213207D01*

+X305294Y213042D01*

+X305993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X302073Y331953D02*X302048Y331994D01*

+X301664Y332444D01*

+X301214Y332827D01*

+X300996Y332961D01*

+Y360963D01*

+X301337Y360755D01*

+X302028Y360469D01*

+X302073Y360458D01*

+Y331953D01*

+G37*

+G36*

+Y322111D02*X302048Y322151D01*

+X301664Y322601D01*

+X301214Y322985D01*

+X300996Y323119D01*

+Y326598D01*

+X301214Y326732D01*

+X301664Y327116D01*

+X302048Y327565D01*

+X302073Y327606D01*

+Y322111D01*

+G37*

+G36*

+Y314237D02*X302048Y314277D01*

+X301664Y314727D01*

+X301214Y315111D01*

+X300996Y315245D01*

+Y316755D01*

+X301214Y316889D01*

+X301664Y317273D01*

+X302048Y317723D01*

+X302073Y317763D01*

+Y314237D01*

+G37*

+G36*

+Y270261D02*X301775Y270385D01*

+X301392Y270477D01*

+X301000Y270508D01*

+X300996Y270507D01*

+Y299249D01*

+X300998Y299254D01*

+X301003Y299333D01*

+X300996Y299412D01*

+X300996Y299413D01*

+Y305062D01*

+X301000Y305108D01*

+X300996Y305162D01*

+Y308881D01*

+X301214Y309015D01*

+X301664Y309399D01*

+X302048Y309849D01*

+X302073Y309889D01*

+Y304188D01*

+X302043Y304200D01*

+X301966Y304218D01*

+X301887Y304224D01*

+X301808Y304217D01*

+X301731Y304198D01*

+X301658Y304167D01*

+X301591Y304125D01*

+X301531Y304073D01*

+X301480Y304013D01*

+X301439Y303945D01*

+X301409Y303872D01*

+X301392Y303794D01*

+X301386Y303715D01*

+X301393Y303637D01*

+X301412Y303560D01*

+X301444Y303487D01*

+X301557Y303249D01*

+X301643Y303000D01*

+X301706Y302744D01*

+X301743Y302484D01*

+X301756Y302220D01*

+X301743Y301957D01*

+X301706Y301696D01*

+X301643Y301440D01*

+X301557Y301192D01*

+X301447Y300952D01*

+X301415Y300880D01*

+X301396Y300804D01*

+X301389Y300726D01*

+X301395Y300647D01*

+X301413Y300570D01*

+X301442Y300497D01*

+X301483Y300430D01*

+X301533Y300370D01*

+X301593Y300318D01*

+X301660Y300277D01*

+X301732Y300246D01*

+X301809Y300227D01*

+X301887Y300220D01*

+X301966Y300226D01*

+X302042Y300244D01*

+X302073Y300256D01*

+Y279704D01*

+X301978Y279549D01*

+X301707Y278895D01*

+X301542Y278206D01*

+X301486Y277500D01*

+X301542Y276794D01*

+X301707Y276105D01*

+X301978Y275451D01*

+X302073Y275296D01*

+Y270261D01*

+G37*

+G36*

+Y207500D02*X300996D01*

+Y265493D01*

+X301000Y265492D01*

+X301392Y265523D01*

+X301775Y265615D01*

+X302073Y265739D01*

+Y219704D01*

+X301978Y219549D01*

+X301707Y218895D01*

+X301542Y218206D01*

+X301486Y217500D01*

+X301542Y216794D01*

+X301707Y216105D01*

+X301978Y215451D01*

+X302073Y215296D01*

+Y207500D01*

+G37*

+G36*

+X300996Y332961D02*X300710Y333136D01*

+X300164Y333363D01*

+X299589Y333501D01*

+X299000Y333547D01*

+X298411Y333501D01*

+X297836Y333363D01*

+X297290Y333136D01*

+X296786Y332827D01*

+X296336Y332444D01*

+X295993Y332042D01*

+Y360957D01*

+X296301Y361145D01*

+X296869Y361631D01*

+X297355Y362199D01*

+X297745Y362837D01*

+X298031Y363528D01*

+X298206Y364255D01*

+X298250Y365000D01*

+X298206Y365745D01*

+X298031Y366472D01*

+X297745Y367163D01*

+X297355Y367801D01*

+X296869Y368369D01*

+X296301Y368855D01*

+X295993Y369043D01*

+Y390000D01*

+X300996D01*

+Y369037D01*

+X300699Y368855D01*

+X300131Y368369D01*

+X299645Y367801D01*

+X299255Y367163D01*

+X298969Y366472D01*

+X298794Y365745D01*

+X298735Y365000D01*

+X298794Y364255D01*

+X298969Y363528D01*

+X299255Y362837D01*

+X299645Y362199D01*

+X300131Y361631D01*

+X300699Y361145D01*

+X300996Y360963D01*

+Y332961D01*

+G37*

+G36*

+Y323119D02*X300710Y323294D01*

+X300164Y323520D01*

+X299589Y323658D01*

+X299000Y323704D01*

+X298411Y323658D01*

+X297836Y323520D01*

+X297290Y323294D01*

+X296786Y322985D01*

+X296336Y322601D01*

+X295993Y322200D01*

+Y327517D01*

+X296336Y327116D01*

+X296786Y326732D01*

+X297290Y326423D01*

+X297836Y326196D01*

+X298411Y326058D01*

+X299000Y326012D01*

+X299589Y326058D01*

+X300164Y326196D01*

+X300710Y326423D01*

+X300996Y326598D01*

+Y323119D01*

+G37*

+G36*

+Y315245D02*X300710Y315420D01*

+X300164Y315646D01*

+X299589Y315784D01*

+X299000Y315830D01*

+X298411Y315784D01*

+X297836Y315646D01*

+X297290Y315420D01*

+X296786Y315111D01*

+X296336Y314727D01*

+X295993Y314326D01*

+Y317674D01*

+X296336Y317273D01*

+X296786Y316889D01*

+X297290Y316580D01*

+X297836Y316354D01*

+X298411Y316216D01*

+X299000Y316170D01*

+X299589Y316216D01*

+X300164Y316354D01*

+X300710Y316580D01*

+X300996Y316755D01*

+Y315245D01*

+G37*

+G36*

+Y207500D02*X295993D01*

+Y212987D01*

+X296000Y212986D01*

+X296706Y213042D01*

+X297395Y213207D01*

+X298049Y213478D01*

+X298653Y213848D01*

+X299192Y214308D01*

+X299652Y214847D01*

+X300022Y215451D01*

+X300293Y216105D01*

+X300458Y216794D01*

+X300500Y217500D01*

+X300458Y218206D01*

+X300293Y218895D01*

+X300022Y219549D01*

+X299652Y220153D01*

+X299192Y220692D01*

+X298653Y221152D01*

+X298049Y221522D01*

+X297395Y221793D01*

+X296706Y221958D01*

+X296000Y222014D01*

+X295993Y222013D01*

+Y272987D01*

+X296000Y272986D01*

+X296706Y273042D01*

+X297395Y273207D01*

+X298049Y273478D01*

+X298653Y273848D01*

+X299192Y274308D01*

+X299652Y274847D01*

+X300022Y275451D01*

+X300293Y276105D01*

+X300458Y276794D01*

+X300500Y277500D01*

+X300458Y278206D01*

+X300293Y278895D01*

+X300022Y279549D01*

+X299652Y280153D01*

+X299192Y280692D01*

+X298653Y281152D01*

+X298049Y281522D01*

+X297395Y281793D01*

+X296706Y281958D01*

+X296000Y282014D01*

+X295993Y282013D01*

+Y300232D01*

+X296034Y300223D01*

+X296113Y300217D01*

+X296192Y300224D01*

+X296269Y300243D01*

+X296342Y300274D01*

+X296409Y300316D01*

+X296469Y300368D01*

+X296520Y300428D01*

+X296561Y300496D01*

+X296591Y300569D01*

+X296608Y300647D01*

+X296614Y300726D01*

+X296607Y300804D01*

+X296588Y300881D01*

+X296556Y300954D01*

+X296443Y301192D01*

+X296357Y301440D01*

+X296294Y301696D01*

+X296257Y301957D01*

+X296244Y302220D01*

+X296257Y302484D01*

+X296294Y302744D01*

+X296357Y303000D01*

+X296443Y303249D01*

+X296553Y303489D01*

+X296585Y303561D01*

+X296604Y303637D01*

+X296611Y303715D01*

+X296605Y303794D01*

+X296587Y303871D01*

+X296558Y303944D01*

+X296517Y304011D01*

+X296467Y304071D01*

+X296407Y304123D01*

+X296340Y304164D01*

+X296268Y304195D01*

+X296191Y304214D01*

+X296113Y304220D01*

+X296034Y304215D01*

+X295993Y304205D01*

+Y309800D01*

+X296336Y309399D01*

+X296786Y309015D01*

+X297290Y308706D01*

+X297836Y308480D01*

+X298411Y308342D01*

+X299000Y308296D01*

+X299589Y308342D01*

+X300164Y308480D01*

+X300710Y308706D01*

+X300996Y308881D01*

+Y305162D01*

+X300994Y305186D01*

+X300977Y305263D01*

+X300947Y305336D01*

+X300906Y305403D01*

+X300856Y305463D01*

+X300796Y305515D01*

+X300729Y305555D01*

+X300404Y305709D01*

+X300064Y305827D01*

+X299715Y305912D01*

+X299359Y305963D01*

+X299000Y305981D01*

+X298641Y305963D01*

+X298285Y305912D01*

+X297936Y305827D01*

+X297596Y305709D01*

+X297269Y305559D01*

+X297202Y305517D01*

+X297142Y305465D01*

+X297091Y305405D01*

+X297050Y305337D01*

+X297020Y305264D01*

+X297002Y305186D01*

+X296997Y305108D01*

+X297004Y305029D01*

+X297023Y304952D01*

+X297053Y304879D01*

+X297095Y304812D01*

+X297147Y304752D01*

+X297208Y304701D01*

+X297276Y304660D01*

+X297349Y304630D01*

+X297426Y304612D01*

+X297505Y304606D01*

+X297584Y304613D01*

+X297661Y304632D01*

+X297733Y304664D01*

+X297971Y304777D01*

+X298220Y304864D01*

+X298476Y304926D01*

+X298737Y304964D01*

+X299000Y304976D01*

+X299263Y304964D01*

+X299524Y304926D01*

+X299780Y304864D01*

+X300029Y304777D01*

+X300268Y304667D01*

+X300340Y304635D01*

+X300417Y304616D01*

+X300495Y304610D01*

+X300573Y304615D01*

+X300650Y304633D01*

+X300723Y304663D01*

+X300790Y304703D01*

+X300851Y304754D01*

+X300902Y304813D01*

+X300944Y304880D01*

+X300974Y304953D01*

+X300993Y305029D01*

+X300996Y305062D01*

+Y299413D01*

+X300977Y299489D01*

+X300947Y299562D01*

+X300905Y299629D01*

+X300853Y299689D01*

+X300792Y299740D01*

+X300724Y299781D01*

+X300651Y299811D01*

+X300574Y299829D01*

+X300495Y299835D01*

+X300416Y299828D01*

+X300339Y299809D01*

+X300267Y299777D01*

+X300029Y299664D01*

+X299780Y299577D01*

+X299524Y299515D01*

+X299263Y299477D01*

+X299000Y299465D01*

+X298737Y299477D01*

+X298476Y299515D01*

+X298220Y299577D01*

+X297971Y299664D01*

+X297732Y299774D01*

+X297660Y299806D01*

+X297583Y299825D01*

+X297505Y299831D01*

+X297427Y299826D01*

+X297350Y299808D01*

+X297277Y299778D01*

+X297210Y299738D01*

+X297149Y299687D01*

+X297098Y299628D01*

+X297056Y299561D01*

+X297026Y299488D01*

+X297007Y299412D01*

+X297000Y299333D01*

+X297006Y299255D01*

+X297023Y299178D01*

+X297053Y299105D01*

+X297094Y299038D01*

+X297144Y298978D01*

+X297204Y298926D01*

+X297271Y298886D01*

+X297596Y298732D01*

+X297936Y298614D01*

+X298285Y298529D01*

+X298641Y298477D01*

+X299000Y298460D01*

+X299359Y298477D01*

+X299715Y298529D01*

+X300064Y298614D01*

+X300404Y298732D01*

+X300731Y298882D01*

+X300798Y298924D01*

+X300858Y298976D01*

+X300909Y299036D01*

+X300950Y299104D01*

+X300980Y299177D01*

+X300996Y299249D01*

+Y270507D01*

+X300608Y270477D01*

+X300225Y270385D01*

+X299862Y270234D01*

+X299526Y270029D01*

+X299227Y269773D01*

+X298971Y269474D01*

+X298766Y269138D01*

+X298615Y268775D01*

+X298523Y268392D01*

+X298492Y268000D01*

+X298523Y267608D01*

+X298615Y267225D01*

+X298766Y266862D01*

+X298971Y266526D01*

+X299227Y266227D01*

+X299526Y265971D01*

+X299862Y265766D01*

+X300225Y265615D01*

+X300608Y265523D01*

+X300996Y265493D01*

+Y207500D01*

+G37*

+G36*

+X290996Y390000D02*X295993D01*

+Y369043D01*

+X295663Y369245D01*

+X294972Y369531D01*

+X294245Y369706D01*

+X293500Y369765D01*

+X292755Y369706D01*

+X292028Y369531D01*

+X291337Y369245D01*

+X290996Y369037D01*

+Y390000D01*

+G37*

+G36*

+X293615Y342407D02*X293625Y342331D01*

+X293646Y341866D01*

+X293625Y341401D01*

+X293615Y341326D01*

+Y342407D01*

+G37*

+G36*

+Y290674D02*X293625Y290599D01*

+X293646Y290134D01*

+X293625Y289669D01*

+X293615Y289593D01*

+Y290674D01*

+G37*

+G36*

+Y273684D02*X293951Y273478D01*

+X294605Y273207D01*

+X295294Y273042D01*

+X295993Y272987D01*

+Y222013D01*

+X295294Y221958D01*

+X294605Y221793D01*

+X293951Y221522D01*

+X293615Y221316D01*

+Y273684D01*

+G37*

+G36*

+Y360244D02*X294245Y360294D01*

+X294972Y360469D01*

+X295663Y360755D01*

+X295993Y360957D01*

+Y332042D01*

+X295952Y331994D01*

+X295643Y331490D01*

+X295417Y330944D01*

+X295279Y330369D01*

+X295233Y329780D01*

+X295279Y329190D01*

+X295417Y328615D01*

+X295643Y328069D01*

+X295952Y327565D01*

+X295993Y327517D01*

+Y322200D01*

+X295952Y322151D01*

+X295643Y321647D01*

+X295417Y321101D01*

+X295279Y320526D01*

+X295233Y319937D01*

+X295279Y319348D01*

+X295417Y318773D01*

+X295643Y318227D01*

+X295952Y317723D01*

+X295993Y317674D01*

+Y314326D01*

+X295952Y314277D01*

+X295643Y313773D01*

+X295417Y313227D01*

+X295279Y312652D01*

+X295233Y312063D01*

+X295279Y311474D01*

+X295417Y310899D01*

+X295643Y310353D01*

+X295952Y309849D01*

+X295993Y309800D01*

+Y304205D01*

+X295958Y304197D01*

+X295885Y304167D01*

+X295817Y304127D01*

+X295757Y304076D01*

+X295706Y304017D01*

+X295666Y303949D01*

+X295512Y303624D01*

+X295394Y303285D01*

+X295308Y302935D01*

+X295257Y302580D01*

+X295240Y302220D01*

+X295257Y301861D01*

+X295308Y301506D01*

+X295394Y301156D01*

+X295512Y300817D01*

+X295662Y300490D01*

+X295703Y300422D01*

+X295755Y300363D01*

+X295816Y300312D01*

+X295883Y300271D01*

+X295957Y300241D01*

+X295993Y300232D01*

+Y282013D01*

+X295294Y281958D01*

+X294605Y281793D01*

+X293951Y281522D01*

+X293615Y281316D01*

+Y286683D01*

+X293798Y286961D01*

+X294055Y287452D01*

+X294267Y287963D01*

+X294435Y288491D01*

+X294555Y289032D01*

+X294627Y289581D01*

+X294652Y290134D01*

+X294627Y290687D01*

+X294555Y291236D01*

+X294435Y291777D01*

+X294267Y292304D01*

+X294055Y292816D01*

+X293798Y293306D01*

+X293615Y293592D01*

+Y338415D01*

+X293798Y338694D01*

+X294055Y339184D01*

+X294267Y339696D01*

+X294435Y340223D01*

+X294555Y340764D01*

+X294627Y341313D01*

+X294652Y341866D01*

+X294627Y342419D01*

+X294555Y342968D01*

+X294435Y343509D01*

+X294267Y344037D01*

+X294055Y344548D01*

+X293798Y345039D01*

+X293615Y345324D01*

+Y360244D01*

+G37*

+G36*

+X295993Y207500D02*X293615D01*

+Y213684D01*

+X293951Y213478D01*

+X294605Y213207D01*

+X295294Y213042D01*

+X295993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X293615D02*X290996D01*

+Y265493D01*

+X291000Y265492D01*

+X291392Y265523D01*

+X291775Y265615D01*

+X292138Y265766D01*

+X292474Y265971D01*

+X292773Y266227D01*

+X293029Y266526D01*

+X293234Y266862D01*

+X293385Y267225D01*

+X293477Y267608D01*

+X293500Y268000D01*

+X293477Y268392D01*

+X293385Y268775D01*

+X293234Y269138D01*

+X293029Y269474D01*

+X292773Y269773D01*

+X292474Y270029D01*

+X292138Y270234D01*

+X291775Y270385D01*

+X291392Y270477D01*

+X291000Y270508D01*

+X290996Y270507D01*

+Y284403D01*

+X291013Y284410D01*

+X291503Y284667D01*

+X291970Y284965D01*

+X292031Y285016D01*

+X292084Y285075D01*

+X292126Y285142D01*

+X292158Y285215D01*

+X292177Y285292D01*

+X292185Y285372D01*

+X292180Y285451D01*

+X292162Y285528D01*

+X292133Y285602D01*

+X292093Y285671D01*

+X292042Y285732D01*

+X291982Y285785D01*

+X291915Y285827D01*

+X291842Y285859D01*

+X291765Y285878D01*

+X291686Y285886D01*

+X291606Y285881D01*

+X291529Y285863D01*

+X291455Y285834D01*

+X291387Y285792D01*

+X290998Y285537D01*

+X290996Y285536D01*

+Y294732D01*

+X290998Y294731D01*

+X291390Y294480D01*

+X291457Y294438D01*

+X291530Y294409D01*

+X291607Y294392D01*

+X291686Y294387D01*

+X291764Y294394D01*

+X291840Y294414D01*

+X291913Y294445D01*

+X291979Y294487D01*

+X292038Y294539D01*

+X292088Y294600D01*

+X292128Y294668D01*

+X292157Y294741D01*

+X292175Y294818D01*

+X292180Y294896D01*

+X292172Y294974D01*

+X292153Y295051D01*

+X292122Y295123D01*

+X292080Y295189D01*

+X292028Y295249D01*

+X291966Y295297D01*

+X291503Y295601D01*

+X291013Y295858D01*

+X290996Y295865D01*

+Y336135D01*

+X291013Y336142D01*

+X291503Y336399D01*

+X291970Y336698D01*

+X292031Y336748D01*

+X292084Y336807D01*

+X292126Y336875D01*

+X292158Y336948D01*

+X292177Y337025D01*

+X292185Y337104D01*

+X292180Y337183D01*

+X292162Y337261D01*

+X292133Y337335D01*

+X292093Y337403D01*

+X292042Y337464D01*

+X291982Y337517D01*

+X291915Y337559D01*

+X291842Y337591D01*

+X291765Y337611D01*

+X291686Y337618D01*

+X291606Y337613D01*

+X291529Y337596D01*

+X291455Y337566D01*

+X291387Y337524D01*

+X290998Y337269D01*

+X290996Y337268D01*

+Y346464D01*

+X290998Y346463D01*

+X291390Y346212D01*

+X291457Y346171D01*

+X291530Y346142D01*

+X291607Y346124D01*

+X291686Y346119D01*

+X291764Y346127D01*

+X291840Y346146D01*

+X291913Y346177D01*

+X291979Y346220D01*

+X292038Y346272D01*

+X292088Y346332D01*

+X292128Y346400D01*

+X292157Y346473D01*

+X292175Y346550D01*

+X292180Y346628D01*

+X292172Y346707D01*

+X292153Y346783D01*

+X292122Y346855D01*

+X292080Y346922D01*

+X292028Y346981D01*

+X291966Y347030D01*

+X291503Y347333D01*

+X291013Y347590D01*

+X290996Y347597D01*

+Y360963D01*

+X291337Y360755D01*

+X292028Y360469D01*

+X292755Y360294D01*

+X293500Y360235D01*

+X293615Y360244D01*

+Y345324D01*

+X293499Y345505D01*

+X293449Y345567D01*

+X293389Y345619D01*

+X293322Y345662D01*

+X293249Y345693D01*

+X293172Y345713D01*

+X293093Y345720D01*

+X293014Y345715D01*

+X292936Y345698D01*

+X292862Y345668D01*

+X292794Y345628D01*

+X292733Y345577D01*

+X292680Y345518D01*

+X292638Y345450D01*

+X292606Y345377D01*

+X292586Y345300D01*

+X292579Y345221D01*

+X292584Y345142D01*

+X292601Y345064D01*

+X292631Y344990D01*

+X292672Y344923D01*

+X292928Y344534D01*

+X293144Y344121D01*

+X293322Y343691D01*

+X293463Y343247D01*

+X293564Y342793D01*

+X293615Y342407D01*

+Y341326D01*

+X293564Y340939D01*

+X293463Y340485D01*

+X293322Y340041D01*

+X293144Y339611D01*

+X292928Y339199D01*

+X292677Y338806D01*

+X292635Y338740D01*

+X292606Y338666D01*

+X292589Y338590D01*

+X292584Y338511D01*

+X292591Y338433D01*

+X292611Y338357D01*

+X292642Y338284D01*

+X292684Y338218D01*

+X292736Y338159D01*

+X292797Y338109D01*

+X292864Y338068D01*

+X292938Y338039D01*

+X293014Y338022D01*

+X293093Y338017D01*

+X293171Y338024D01*

+X293248Y338044D01*

+X293320Y338075D01*

+X293386Y338117D01*

+X293445Y338169D01*

+X293494Y338231D01*

+X293615Y338415D01*

+Y293592D01*

+X293499Y293773D01*

+X293449Y293834D01*

+X293389Y293887D01*

+X293322Y293929D01*

+X293249Y293961D01*

+X293172Y293981D01*

+X293093Y293988D01*

+X293014Y293983D01*

+X292936Y293966D01*

+X292862Y293936D01*

+X292794Y293896D01*

+X292733Y293845D01*

+X292680Y293785D01*

+X292638Y293718D01*

+X292606Y293645D01*

+X292586Y293568D01*

+X292579Y293489D01*

+X292584Y293410D01*

+X292601Y293332D01*

+X292631Y293258D01*

+X292672Y293191D01*

+X292928Y292801D01*

+X293144Y292389D01*

+X293322Y291959D01*

+X293463Y291515D01*

+X293564Y291061D01*

+X293615Y290674D01*

+Y289593D01*

+X293564Y289207D01*

+X293463Y288753D01*

+X293322Y288309D01*

+X293144Y287879D01*

+X292928Y287466D01*

+X292677Y287074D01*

+X292635Y287007D01*

+X292606Y286934D01*

+X292589Y286857D01*

+X292584Y286779D01*

+X292591Y286701D01*

+X292611Y286624D01*

+X292642Y286552D01*

+X292684Y286486D01*

+X292736Y286426D01*

+X292797Y286376D01*

+X292864Y286336D01*

+X292938Y286307D01*

+X293014Y286290D01*

+X293093Y286285D01*

+X293171Y286292D01*

+X293248Y286312D01*

+X293320Y286343D01*

+X293386Y286385D01*

+X293445Y286437D01*

+X293494Y286499D01*

+X293615Y286683D01*

+Y281316D01*

+X293347Y281152D01*

+X292808Y280692D01*

+X292348Y280153D01*

+X291978Y279549D01*

+X291707Y278895D01*

+X291542Y278206D01*

+X291486Y277500D01*

+X291542Y276794D01*

+X291707Y276105D01*

+X291978Y275451D01*

+X292348Y274847D01*

+X292808Y274308D01*

+X293347Y273848D01*

+X293615Y273684D01*

+Y221316D01*

+X293347Y221152D01*

+X292808Y220692D01*

+X292348Y220153D01*

+X291978Y219549D01*

+X291707Y218895D01*

+X291542Y218206D01*

+X291486Y217500D01*

+X291542Y216794D01*

+X291707Y216105D01*

+X291978Y215451D01*

+X292348Y214847D01*

+X292808Y214308D01*

+X293347Y213848D01*

+X293615Y213684D01*

+Y207500D01*

+G37*

+G36*

+X290996Y347597D02*X290501Y347803D01*

+X289973Y347970D01*

+X289433Y348090D01*

+X288884Y348163D01*

+X288331Y348187D01*

+X287777Y348163D01*

+X287229Y348090D01*

+X286688Y347970D01*

+X286160Y347803D01*

+X285993Y347733D01*

+Y360957D01*

+X286301Y361145D01*

+X286869Y361631D01*

+X287355Y362199D01*

+X287745Y362837D01*

+X288031Y363528D01*

+X288206Y364255D01*

+X288250Y365000D01*

+X288206Y365745D01*

+X288031Y366472D01*

+X287745Y367163D01*

+X287355Y367801D01*

+X286869Y368369D01*

+X286301Y368855D01*

+X285993Y369043D01*

+Y390000D01*

+X290996D01*

+Y369037D01*

+X290699Y368855D01*

+X290131Y368369D01*

+X289645Y367801D01*

+X289255Y367163D01*

+X288969Y366472D01*

+X288794Y365745D01*

+X288735Y365000D01*

+X288794Y364255D01*

+X288969Y363528D01*

+X289255Y362837D01*

+X289645Y362199D01*

+X290131Y361631D01*

+X290699Y361145D01*

+X290996Y360963D01*

+Y347597D01*

+G37*

+G36*

+Y337268D02*X290586Y337053D01*

+X290156Y336874D01*

+X289712Y336734D01*

+X289257Y336633D01*

+X288796Y336572D01*

+X288331Y336551D01*

+X287866Y336572D01*

+X287404Y336633D01*

+X286949Y336734D01*

+X286506Y336874D01*

+X286076Y337053D01*

+X285993Y337096D01*

+Y346636D01*

+X286076Y346679D01*

+X286506Y346858D01*

+X286949Y346998D01*

+X287404Y347100D01*

+X287866Y347161D01*

+X288331Y347181D01*

+X288796Y347161D01*

+X289257Y347100D01*

+X289712Y346998D01*

+X290156Y346858D01*

+X290586Y346679D01*

+X290996Y346464D01*

+Y337268D01*

+G37*

+G36*

+Y295865D02*X290501Y296071D01*

+X289973Y296238D01*

+X289433Y296358D01*

+X288884Y296431D01*

+X288331Y296455D01*

+X287777Y296431D01*

+X287229Y296358D01*

+X286688Y296238D01*

+X286160Y296071D01*

+X285993Y296001D01*

+Y335999D01*

+X286160Y335929D01*

+X286688Y335762D01*

+X287229Y335642D01*

+X287777Y335569D01*

+X288331Y335545D01*

+X288884Y335569D01*

+X289433Y335642D01*

+X289973Y335762D01*

+X290501Y335929D01*

+X290996Y336135D01*

+Y295865D01*

+G37*

+G36*

+Y285536D02*X290586Y285321D01*

+X290156Y285142D01*

+X289712Y285002D01*

+X289257Y284900D01*

+X288796Y284839D01*

+X288331Y284819D01*

+X287866Y284839D01*

+X287404Y284900D01*

+X286949Y285002D01*

+X286506Y285142D01*

+X286076Y285321D01*

+X285993Y285364D01*

+Y294904D01*

+X286076Y294947D01*

+X286506Y295126D01*

+X286949Y295266D01*

+X287404Y295367D01*

+X287866Y295428D01*

+X288331Y295449D01*

+X288796Y295428D01*

+X289257Y295367D01*

+X289712Y295266D01*

+X290156Y295126D01*

+X290586Y294947D01*

+X290996Y294732D01*

+Y285536D01*

+G37*

+G36*

+Y207500D02*X285993D01*

+Y212987D01*

+X286000Y212986D01*

+X286706Y213042D01*

+X287395Y213207D01*

+X288049Y213478D01*

+X288653Y213848D01*

+X289192Y214308D01*

+X289652Y214847D01*

+X290022Y215451D01*

+X290293Y216105D01*

+X290458Y216794D01*

+X290500Y217500D01*

+X290458Y218206D01*

+X290293Y218895D01*

+X290022Y219549D01*

+X289652Y220153D01*

+X289192Y220692D01*

+X288653Y221152D01*

+X288049Y221522D01*

+X287395Y221793D01*

+X286706Y221958D01*

+X286000Y222014D01*

+X285993Y222013D01*

+Y272987D01*

+X286000Y272986D01*

+X286706Y273042D01*

+X287395Y273207D01*

+X288049Y273478D01*

+X288653Y273848D01*

+X289192Y274308D01*

+X289652Y274847D01*

+X290022Y275451D01*

+X290293Y276105D01*

+X290458Y276794D01*

+X290500Y277500D01*

+X290458Y278206D01*

+X290293Y278895D01*

+X290022Y279549D01*

+X289652Y280153D01*

+X289192Y280692D01*

+X288653Y281152D01*

+X288049Y281522D01*

+X287395Y281793D01*

+X286706Y281958D01*

+X286000Y282014D01*

+X285993Y282013D01*

+Y284267D01*

+X286160Y284197D01*

+X286688Y284030D01*

+X287229Y283910D01*

+X287777Y283837D01*

+X288331Y283813D01*

+X288884Y283837D01*

+X289433Y283910D01*

+X289973Y284030D01*

+X290501Y284197D01*

+X290996Y284403D01*

+Y270507D01*

+X290608Y270477D01*

+X290225Y270385D01*

+X289862Y270234D01*

+X289526Y270029D01*

+X289227Y269773D01*

+X288971Y269474D01*

+X288766Y269138D01*

+X288615Y268775D01*

+X288523Y268392D01*

+X288492Y268000D01*

+X288523Y267608D01*

+X288615Y267225D01*

+X288766Y266862D01*

+X288971Y266526D01*

+X289227Y266227D01*

+X289526Y265971D01*

+X289862Y265766D01*

+X290225Y265615D01*

+X290608Y265523D01*

+X290996Y265493D01*

+Y207500D01*

+G37*

+G36*

+X280996Y379935D02*X281000Y380000D01*

+X280996Y380065D01*

+Y390000D01*

+X285993D01*

+Y369043D01*

+X285663Y369245D01*

+X284972Y369531D01*

+X284245Y369706D01*

+X283500Y369765D01*

+X282755Y369706D01*

+X282028Y369531D01*

+X281337Y369245D01*

+X280996Y369037D01*

+Y379935D01*

+G37*

+G36*

+X283046Y360271D02*X283500Y360235D01*

+X284245Y360294D01*

+X284972Y360469D01*

+X285663Y360755D01*

+X285993Y360957D01*

+Y347733D01*

+X285649Y347590D01*

+X285158Y347333D01*

+X284692Y347035D01*

+X284630Y346984D01*

+X284578Y346925D01*

+X284535Y346858D01*

+X284504Y346785D01*

+X284484Y346708D01*

+X284477Y346628D01*

+X284482Y346549D01*

+X284499Y346472D01*

+X284528Y346398D01*

+X284569Y346329D01*

+X284620Y346268D01*

+X284679Y346216D01*

+X284746Y346173D01*

+X284819Y346141D01*

+X284896Y346122D01*

+X284976Y346114D01*

+X285055Y346119D01*

+X285133Y346137D01*

+X285206Y346166D01*

+X285274Y346208D01*

+X285663Y346463D01*

+X285993Y346636D01*

+Y337096D01*

+X285663Y337269D01*

+X285271Y337520D01*

+X285204Y337562D01*

+X285131Y337591D01*

+X285054Y337608D01*

+X284976Y337613D01*

+X284897Y337606D01*

+X284821Y337586D01*

+X284749Y337555D01*

+X284682Y337513D01*

+X284623Y337461D01*

+X284573Y337400D01*

+X284533Y337332D01*

+X284504Y337259D01*

+X284487Y337182D01*

+X284482Y337104D01*

+X284489Y337026D01*

+X284509Y336949D01*

+X284540Y336877D01*

+X284582Y336811D01*

+X284634Y336751D01*

+X284695Y336703D01*

+X285158Y336399D01*

+X285649Y336142D01*

+X285993Y335999D01*

+Y296001D01*

+X285649Y295858D01*

+X285158Y295601D01*

+X284692Y295302D01*

+X284630Y295252D01*

+X284578Y295193D01*

+X284535Y295125D01*

+X284504Y295052D01*

+X284484Y294975D01*

+X284477Y294896D01*

+X284482Y294817D01*

+X284499Y294739D01*

+X284528Y294665D01*

+X284569Y294597D01*

+X284620Y294536D01*

+X284679Y294483D01*

+X284746Y294441D01*

+X284819Y294409D01*

+X284896Y294389D01*

+X284976Y294382D01*

+X285055Y294387D01*

+X285133Y294404D01*

+X285206Y294434D01*

+X285274Y294476D01*

+X285663Y294731D01*

+X285993Y294904D01*

+Y285364D01*

+X285663Y285537D01*

+X285271Y285788D01*

+X285204Y285829D01*

+X285131Y285858D01*

+X285054Y285876D01*

+X284976Y285881D01*

+X284897Y285873D01*

+X284821Y285854D01*

+X284749Y285823D01*

+X284682Y285780D01*

+X284623Y285728D01*

+X284573Y285668D01*

+X284533Y285600D01*

+X284504Y285527D01*

+X284487Y285450D01*

+X284482Y285372D01*

+X284489Y285293D01*

+X284509Y285217D01*

+X284540Y285145D01*

+X284582Y285078D01*

+X284634Y285019D01*

+X284695Y284970D01*

+X285158Y284667D01*

+X285649Y284410D01*

+X285993Y284267D01*

+Y282013D01*

+X285294Y281958D01*

+X284605Y281793D01*

+X283951Y281522D01*

+X283347Y281152D01*

+X283046Y280895D01*

+Y286676D01*

+X283162Y286495D01*

+X283212Y286433D01*

+X283272Y286381D01*

+X283339Y286338D01*

+X283412Y286307D01*

+X283489Y286287D01*

+X283568Y286280D01*

+X283648Y286285D01*

+X283725Y286302D01*

+X283799Y286332D01*

+X283868Y286372D01*

+X283929Y286423D01*

+X283981Y286482D01*

+X284024Y286550D01*

+X284055Y286623D01*

+X284075Y286700D01*

+X284083Y286779D01*

+X284077Y286858D01*

+X284060Y286936D01*

+X284031Y287010D01*

+X283989Y287077D01*

+X283734Y287466D01*

+X283518Y287879D01*

+X283339Y288309D01*

+X283198Y288753D01*

+X283097Y289207D01*

+X283046Y289593D01*

+Y290674D01*

+X283097Y291061D01*

+X283198Y291515D01*

+X283339Y291959D01*

+X283518Y292389D01*

+X283734Y292801D01*

+X283985Y293194D01*

+X284026Y293260D01*

+X284055Y293334D01*

+X284072Y293410D01*

+X284077Y293489D01*

+X284070Y293567D01*

+X284051Y293643D01*

+X284019Y293716D01*

+X283977Y293782D01*

+X283925Y293841D01*

+X283865Y293891D01*

+X283797Y293932D01*

+X283724Y293961D01*

+X283647Y293978D01*

+X283568Y293983D01*

+X283490Y293976D01*

+X283414Y293956D01*

+X283342Y293925D01*

+X283275Y293883D01*

+X283216Y293831D01*

+X283167Y293769D01*

+X283046Y293585D01*

+Y338408D01*

+X283162Y338227D01*

+X283212Y338166D01*

+X283272Y338113D01*

+X283339Y338071D01*

+X283412Y338039D01*

+X283489Y338019D01*

+X283568Y338012D01*

+X283648Y338017D01*

+X283725Y338034D01*

+X283799Y338064D01*

+X283868Y338104D01*

+X283929Y338155D01*

+X283981Y338215D01*

+X284024Y338282D01*

+X284055Y338355D01*

+X284075Y338432D01*

+X284083Y338511D01*

+X284077Y338590D01*

+X284060Y338668D01*

+X284031Y338742D01*

+X283989Y338809D01*

+X283734Y339199D01*

+X283518Y339611D01*

+X283339Y340041D01*

+X283198Y340485D01*

+X283097Y340939D01*

+X283046Y341326D01*

+Y342407D01*

+X283097Y342793D01*

+X283198Y343247D01*

+X283339Y343691D01*

+X283518Y344121D01*

+X283734Y344534D01*

+X283985Y344926D01*

+X284026Y344993D01*

+X284055Y345066D01*

+X284072Y345143D01*

+X284077Y345221D01*

+X284070Y345299D01*

+X284051Y345376D01*

+X284019Y345448D01*

+X283977Y345514D01*

+X283925Y345574D01*

+X283865Y345624D01*

+X283797Y345664D01*

+X283724Y345693D01*

+X283647Y345710D01*

+X283568Y345715D01*

+X283490Y345708D01*

+X283414Y345688D01*

+X283342Y345657D01*

+X283275Y345615D01*

+X283216Y345563D01*

+X283167Y345501D01*

+X283046Y345317D01*

+Y360271D01*

+G37*

+G36*

+Y266554D02*X283234Y266862D01*

+X283385Y267225D01*

+X283477Y267608D01*

+X283500Y268000D01*

+X283477Y268392D01*

+X283385Y268775D01*

+X283234Y269138D01*

+X283046Y269446D01*

+Y274105D01*

+X283347Y273848D01*

+X283951Y273478D01*

+X284605Y273207D01*

+X285294Y273042D01*

+X285993Y272987D01*

+Y222013D01*

+X285294Y221958D01*

+X284605Y221793D01*

+X283951Y221522D01*

+X283347Y221152D01*

+X283046Y220895D01*

+Y266554D01*

+G37*

+G36*

+X285993Y207500D02*X283046D01*

+Y214105D01*

+X283347Y213848D01*

+X283951Y213478D01*

+X284605Y213207D01*

+X285294Y213042D01*

+X285993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X283046Y341326D02*X283036Y341401D01*

+X283016Y341866D01*

+X283036Y342331D01*

+X283046Y342407D01*

+Y341326D01*

+G37*

+G36*

+Y289593D02*X283036Y289669D01*

+X283016Y290134D01*

+X283036Y290599D01*

+X283046Y290674D01*

+Y289593D01*

+G37*

+G36*

+Y269446D02*X283029Y269474D01*

+X282773Y269773D01*

+X282474Y270029D01*

+X282138Y270234D01*

+X281775Y270385D01*

+X281392Y270477D01*

+X281000Y270508D01*

+X280996Y270507D01*

+Y360963D01*

+X281337Y360755D01*

+X282028Y360469D01*

+X282755Y360294D01*

+X283046Y360271D01*

+Y345317D01*

+X282863Y345039D01*

+X282607Y344548D01*

+X282394Y344037D01*

+X282227Y343509D01*

+X282107Y342968D01*

+X282034Y342419D01*

+X282010Y341866D01*

+X282034Y341313D01*

+X282107Y340764D01*

+X282227Y340223D01*

+X282394Y339696D01*

+X282607Y339184D01*

+X282863Y338694D01*

+X283046Y338408D01*

+Y293585D01*

+X282863Y293306D01*

+X282607Y292816D01*

+X282394Y292304D01*

+X282227Y291777D01*

+X282107Y291236D01*

+X282034Y290687D01*

+X282010Y290134D01*

+X282034Y289581D01*

+X282107Y289032D01*

+X282227Y288491D01*

+X282394Y287963D01*

+X282607Y287452D01*

+X282863Y286961D01*

+X283046Y286676D01*

+Y280895D01*

+X282808Y280692D01*

+X282348Y280153D01*

+X281978Y279549D01*

+X281707Y278895D01*

+X281542Y278206D01*

+X281486Y277500D01*

+X281542Y276794D01*

+X281707Y276105D01*

+X281978Y275451D01*

+X282348Y274847D01*

+X282808Y274308D01*

+X283046Y274105D01*

+Y269446D01*

+G37*

+G36*

+Y207500D02*X280996D01*

+Y265493D01*

+X281000Y265492D01*

+X281392Y265523D01*

+X281775Y265615D01*

+X282138Y265766D01*

+X282474Y265971D01*

+X282773Y266227D01*

+X283029Y266526D01*

+X283046Y266554D01*

+Y220895D01*

+X282808Y220692D01*

+X282348Y220153D01*

+X281978Y219549D01*

+X281707Y218895D01*

+X281542Y218206D01*

+X281486Y217500D01*

+X281542Y216794D01*

+X281707Y216105D01*

+X281978Y215451D01*

+X282348Y214847D01*

+X282808Y214308D01*

+X283046Y214105D01*

+Y207500D01*

+G37*

+G36*

+X280996Y380065D02*X280977Y380392D01*

+X280885Y380775D01*

+X280734Y381138D01*

+X280529Y381474D01*

+X280273Y381773D01*

+X279974Y382029D01*

+X279638Y382234D01*

+X279275Y382385D01*

+X278892Y382477D01*

+X278500Y382508D01*

+X278108Y382477D01*

+X277725Y382385D01*

+X277362Y382234D01*

+X277026Y382029D01*

+X276727Y381773D01*

+X276471Y381474D01*

+X276266Y381138D01*

+X276115Y380775D01*

+X276023Y380392D01*

+X275993Y380010D01*

+Y390000D01*

+X280996D01*

+Y380065D01*

+G37*

+G36*

+Y207500D02*X275993D01*

+Y212987D01*

+X276000Y212986D01*

+X276706Y213042D01*

+X277395Y213207D01*

+X278049Y213478D01*

+X278653Y213848D01*

+X279192Y214308D01*

+X279652Y214847D01*

+X280022Y215451D01*

+X280293Y216105D01*

+X280458Y216794D01*

+X280500Y217500D01*

+X280458Y218206D01*

+X280293Y218895D01*

+X280022Y219549D01*

+X279652Y220153D01*

+X279192Y220692D01*

+X278653Y221152D01*

+X278049Y221522D01*

+X277395Y221793D01*

+X276706Y221958D01*

+X276000Y222014D01*

+X275993Y222013D01*

+Y272987D01*

+X276000Y272986D01*

+X276706Y273042D01*

+X277395Y273207D01*

+X278049Y273478D01*

+X278653Y273848D01*

+X279192Y274308D01*

+X279652Y274847D01*

+X280022Y275451D01*

+X280293Y276105D01*

+X280458Y276794D01*

+X280500Y277500D01*

+X280458Y278206D01*

+X280293Y278895D01*

+X280022Y279549D01*

+X279652Y280153D01*

+X279192Y280692D01*

+X278653Y281152D01*

+X278049Y281522D01*

+X277395Y281793D01*

+X276706Y281958D01*

+X276000Y282014D01*

+X275993Y282013D01*

+Y335928D01*

+X276305Y336195D01*

+X276637Y336584D01*

+X276905Y337020D01*

+X277100Y337493D01*

+X277220Y337990D01*

+X277250Y338500D01*

+X277220Y339010D01*

+X277100Y339507D01*

+X276905Y339980D01*

+X276637Y340416D01*

+X276305Y340805D01*

+X275993Y341072D01*

+Y360957D01*

+X276301Y361145D01*

+X276869Y361631D01*

+X277355Y362199D01*

+X277745Y362837D01*

+X278031Y363528D01*

+X278206Y364255D01*

+X278250Y365000D01*

+X278206Y365745D01*

+X278031Y366472D01*

+X277745Y367163D01*

+X277355Y367801D01*

+X276869Y368369D01*

+X276301Y368855D01*

+X275993Y369043D01*

+Y379990D01*

+X276023Y379608D01*

+X276115Y379225D01*

+X276266Y378862D01*

+X276471Y378526D01*

+X276727Y378227D01*

+X277026Y377971D01*

+X277362Y377766D01*

+X277725Y377615D01*

+X278108Y377523D01*

+X278500Y377492D01*

+X278892Y377523D01*

+X279275Y377615D01*

+X279638Y377766D01*

+X279974Y377971D01*

+X280273Y378227D01*

+X280529Y378526D01*

+X280734Y378862D01*

+X280885Y379225D01*

+X280977Y379608D01*

+X280996Y379935D01*

+Y369037D01*

+X280699Y368855D01*

+X280131Y368369D01*

+X279645Y367801D01*

+X279255Y367163D01*

+X278969Y366472D01*

+X278794Y365745D01*

+X278735Y365000D01*

+X278794Y364255D01*

+X278969Y363528D01*

+X279255Y362837D01*

+X279645Y362199D01*

+X280131Y361631D01*

+X280699Y361145D01*

+X280996Y360963D01*

+Y270507D01*

+X280608Y270477D01*

+X280225Y270385D01*

+X279862Y270234D01*

+X279526Y270029D01*

+X279227Y269773D01*

+X278971Y269474D01*

+X278766Y269138D01*

+X278615Y268775D01*

+X278523Y268392D01*

+X278492Y268000D01*

+X278523Y267608D01*

+X278615Y267225D01*

+X278766Y266862D01*

+X278971Y266526D01*

+X279227Y266227D01*

+X279526Y265971D01*

+X279862Y265766D01*

+X280225Y265615D01*

+X280608Y265523D01*

+X280996Y265493D01*

+Y207500D01*

+G37*

+G36*

+X270996Y360963D02*X271337Y360755D01*

+X272028Y360469D01*

+X272755Y360294D01*

+X273500Y360235D01*

+X274245Y360294D01*

+X274972Y360469D01*

+X275663Y360755D01*

+X275993Y360957D01*

+Y341072D01*

+X275916Y341137D01*

+X275480Y341405D01*

+X275007Y341600D01*

+X274510Y341720D01*

+X274000Y341760D01*

+X273490Y341720D01*

+X272993Y341600D01*

+X272520Y341405D01*

+X272084Y341137D01*

+X271695Y340805D01*

+X271363Y340416D01*

+X271095Y339980D01*

+X270996Y339741D01*

+Y360963D01*

+G37*

+G36*

+Y390000D02*X275993D01*

+Y380010D01*

+X275992Y380000D01*

+X275993Y379990D01*

+Y369043D01*

+X275663Y369245D01*

+X274972Y369531D01*

+X274245Y369706D01*

+X273500Y369765D01*

+X272755Y369706D01*

+X272028Y369531D01*

+X271337Y369245D01*

+X270996Y369037D01*

+Y390000D01*

+G37*

+G36*

+X275993Y207500D02*X270996D01*

+Y265493D01*

+X271000Y265492D01*

+X271392Y265523D01*

+X271775Y265615D01*

+X272138Y265766D01*

+X272474Y265971D01*

+X272773Y266227D01*

+X273029Y266526D01*

+X273234Y266862D01*

+X273385Y267225D01*

+X273477Y267608D01*

+X273500Y268000D01*

+X273477Y268392D01*

+X273385Y268775D01*

+X273234Y269138D01*

+X273029Y269474D01*

+X272773Y269773D01*

+X272474Y270029D01*

+X272138Y270234D01*

+X271775Y270385D01*

+X271392Y270477D01*

+X271000Y270508D01*

+X270996Y270507D01*

+Y337259D01*

+X271095Y337020D01*

+X271363Y336584D01*

+X271695Y336195D01*

+X272084Y335863D01*

+X272520Y335595D01*

+X272993Y335400D01*

+X273490Y335280D01*

+X274000Y335240D01*

+X274510Y335280D01*

+X275007Y335400D01*

+X275480Y335595D01*

+X275916Y335863D01*

+X275993Y335928D01*

+Y282013D01*

+X275294Y281958D01*

+X274605Y281793D01*

+X273951Y281522D01*

+X273347Y281152D01*

+X272808Y280692D01*

+X272348Y280153D01*

+X271978Y279549D01*

+X271707Y278895D01*

+X271542Y278206D01*

+X271486Y277500D01*

+X271542Y276794D01*

+X271707Y276105D01*

+X271978Y275451D01*

+X272348Y274847D01*

+X272808Y274308D01*

+X273347Y273848D01*

+X273951Y273478D01*

+X274605Y273207D01*

+X275294Y273042D01*

+X275993Y272987D01*

+Y222013D01*

+X275294Y221958D01*

+X274605Y221793D01*

+X273951Y221522D01*

+X273347Y221152D01*

+X272808Y220692D01*

+X272348Y220153D01*

+X271978Y219549D01*

+X271707Y218895D01*

+X271542Y218206D01*

+X271486Y217500D01*

+X271542Y216794D01*

+X271707Y216105D01*

+X271978Y215451D01*

+X272348Y214847D01*

+X272808Y214308D01*

+X273347Y213848D01*

+X273951Y213478D01*

+X274605Y213207D01*

+X275294Y213042D01*

+X275993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X270996D02*X265993D01*

+Y212987D01*

+X266000Y212986D01*

+X266706Y213042D01*

+X267395Y213207D01*

+X268049Y213478D01*

+X268653Y213848D01*

+X269192Y214308D01*

+X269652Y214847D01*

+X270022Y215451D01*

+X270293Y216105D01*

+X270458Y216794D01*

+X270500Y217500D01*

+X270458Y218206D01*

+X270293Y218895D01*

+X270022Y219549D01*

+X269652Y220153D01*

+X269192Y220692D01*

+X268653Y221152D01*

+X268049Y221522D01*

+X267395Y221793D01*

+X266706Y221958D01*

+X266000Y222014D01*

+X265993Y222013D01*

+Y272987D01*

+X266000Y272986D01*

+X266706Y273042D01*

+X267395Y273207D01*

+X268049Y273478D01*

+X268653Y273848D01*

+X269192Y274308D01*

+X269652Y274847D01*

+X270022Y275451D01*

+X270293Y276105D01*

+X270458Y276794D01*

+X270500Y277500D01*

+X270458Y278206D01*

+X270293Y278895D01*

+X270022Y279549D01*

+X269652Y280153D01*

+X269192Y280692D01*

+X268653Y281152D01*

+X268049Y281522D01*

+X267395Y281793D01*

+X266706Y281958D01*

+X266000Y282014D01*

+X265993Y282013D01*

+Y337233D01*

+X266100Y337493D01*

+X266220Y337990D01*

+X266250Y338500D01*

+X266220Y339010D01*

+X266100Y339507D01*

+X265993Y339767D01*

+Y390000D01*

+X270996D01*

+Y369037D01*

+X270699Y368855D01*

+X270131Y368369D01*

+X269645Y367801D01*

+X269255Y367163D01*

+X268969Y366472D01*

+X268794Y365745D01*

+X268735Y365000D01*

+X268794Y364255D01*

+X268969Y363528D01*

+X269255Y362837D01*

+X269645Y362199D01*

+X270131Y361631D01*

+X270699Y361145D01*

+X270996Y360963D01*

+Y339741D01*

+X270900Y339507D01*

+X270780Y339010D01*

+X270740Y338500D01*

+X270780Y337990D01*

+X270900Y337493D01*

+X270996Y337259D01*

+Y270507D01*

+X270608Y270477D01*

+X270225Y270385D01*

+X269862Y270234D01*

+X269526Y270029D01*

+X269227Y269773D01*

+X268971Y269474D01*

+X268766Y269138D01*

+X268615Y268775D01*

+X268523Y268392D01*

+X268492Y268000D01*

+X268523Y267608D01*

+X268615Y267225D01*

+X268766Y266862D01*

+X268971Y266526D01*

+X269227Y266227D01*

+X269526Y265971D01*

+X269862Y265766D01*

+X270225Y265615D01*

+X270608Y265523D01*

+X270996Y265493D01*

+Y207500D01*

+G37*

+G36*

+X265993D02*X255993D01*

+Y212987D01*

+X256000Y212986D01*

+X256706Y213042D01*

+X257395Y213207D01*

+X258049Y213478D01*

+X258653Y213848D01*

+X259192Y214308D01*

+X259652Y214847D01*

+X260022Y215451D01*

+X260293Y216105D01*

+X260458Y216794D01*

+X260500Y217500D01*

+X260458Y218206D01*

+X260293Y218895D01*

+X260022Y219549D01*

+X259652Y220153D01*

+X259192Y220692D01*

+X258653Y221152D01*

+X258049Y221522D01*

+X257395Y221793D01*

+X256706Y221958D01*

+X256000Y222014D01*

+X255993Y222013D01*

+Y272987D01*

+X256000Y272986D01*

+X256706Y273042D01*

+X257395Y273207D01*

+X258049Y273478D01*

+X258653Y273848D01*

+X259192Y274308D01*

+X259652Y274847D01*

+X260022Y275451D01*

+X260293Y276105D01*

+X260458Y276794D01*

+X260500Y277500D01*

+X260458Y278206D01*

+X260293Y278895D01*

+X260022Y279549D01*

+X259652Y280153D01*

+X259192Y280692D01*

+X258653Y281152D01*

+X258049Y281522D01*

+X257395Y281793D01*

+X256706Y281958D01*

+X256000Y282014D01*

+X255993Y282013D01*

+Y360253D01*

+X261485Y360264D01*

+X261715Y360319D01*

+X261933Y360409D01*

+X262134Y360533D01*

+X262314Y360686D01*

+X262467Y360866D01*

+X262591Y361067D01*

+X262681Y361285D01*

+X262736Y361515D01*

+X262750Y361750D01*

+X262736Y368485D01*

+X262681Y368715D01*

+X262591Y368933D01*

+X262467Y369134D01*

+X262314Y369314D01*

+X262134Y369467D01*

+X261933Y369591D01*

+X261715Y369681D01*

+X261485Y369736D01*

+X261250Y369750D01*

+X255993Y369739D01*

+Y390000D01*

+X265993D01*

+Y339767D01*

+X265905Y339980D01*

+X265637Y340416D01*

+X265305Y340805D01*

+X264916Y341137D01*

+X264480Y341405D01*

+X264007Y341600D01*

+X263510Y341720D01*

+X263000Y341760D01*

+X262490Y341720D01*

+X261993Y341600D01*

+X261520Y341405D01*

+X261084Y341137D01*

+X260695Y340805D01*

+X260363Y340416D01*

+X260095Y339980D01*

+X259900Y339507D01*

+X259780Y339010D01*

+X259740Y338500D01*

+X259780Y337990D01*

+X259900Y337493D01*

+X260095Y337020D01*

+X260363Y336584D01*

+X260695Y336195D01*

+X261084Y335863D01*

+X261520Y335595D01*

+X261993Y335400D01*

+X262490Y335280D01*

+X263000Y335240D01*

+X263510Y335280D01*

+X264007Y335400D01*

+X264480Y335595D01*

+X264916Y335863D01*

+X265305Y336195D01*

+X265637Y336584D01*

+X265905Y337020D01*

+X265993Y337233D01*

+Y282013D01*

+X265294Y281958D01*

+X264605Y281793D01*

+X263951Y281522D01*

+X263347Y281152D01*

+X262808Y280692D01*

+X262348Y280153D01*

+X261978Y279549D01*

+X261707Y278895D01*

+X261542Y278206D01*

+X261486Y277500D01*

+X261542Y276794D01*

+X261707Y276105D01*

+X261978Y275451D01*

+X262348Y274847D01*

+X262808Y274308D01*

+X263347Y273848D01*

+X263951Y273478D01*

+X264605Y273207D01*

+X265294Y273042D01*

+X265993Y272987D01*

+Y222013D01*

+X265294Y221958D01*

+X264605Y221793D01*

+X263951Y221522D01*

+X263347Y221152D01*

+X262808Y220692D01*

+X262348Y220153D01*

+X261978Y219549D01*

+X261707Y218895D01*

+X261542Y218206D01*

+X261486Y217500D01*

+X261542Y216794D01*

+X261707Y216105D01*

+X261978Y215451D01*

+X262348Y214847D01*

+X262808Y214308D01*

+X263347Y213848D01*

+X263951Y213478D01*

+X264605Y213207D01*

+X265294Y213042D01*

+X265993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X255993D02*X249750D01*

+Y215248D01*

+X249868Y215257D01*

+X249982Y215285D01*

+X250092Y215330D01*

+X250192Y215391D01*

+X250282Y215468D01*

+X250359Y215558D01*

+X250420Y215658D01*

+X250465Y215768D01*

+X250493Y215882D01*

+X250500Y216000D01*

+Y219000D01*

+X250493Y219118D01*

+X250465Y219232D01*

+X250420Y219342D01*

+X250359Y219442D01*

+X250282Y219532D01*

+X250192Y219609D01*

+X250092Y219670D01*

+X249982Y219715D01*

+X249868Y219743D01*

+X249750Y219752D01*

+Y275007D01*

+X250022Y275451D01*

+X250293Y276105D01*

+X250458Y276794D01*

+X250500Y277500D01*

+X250458Y278206D01*

+X250293Y278895D01*

+X250022Y279549D01*

+X249750Y279993D01*

+Y360584D01*

+X250163Y360755D01*

+X250801Y361145D01*

+X251369Y361631D01*

+X251855Y362199D01*

+X252245Y362837D01*

+X252531Y363528D01*

+X252706Y364255D01*

+X252750Y365000D01*

+X252706Y365745D01*

+X252531Y366472D01*

+X252245Y367163D01*

+X251855Y367801D01*

+X251369Y368369D01*

+X250801Y368855D01*

+X250163Y369245D01*

+X249750Y369416D01*

+Y390000D01*

+X255993D01*

+Y369739D01*

+X254515Y369736D01*

+X254285Y369681D01*

+X254067Y369591D01*

+X253866Y369467D01*

+X253686Y369314D01*

+X253533Y369134D01*

+X253409Y368933D01*

+X253319Y368715D01*

+X253264Y368485D01*

+X253250Y368250D01*

+X253264Y361515D01*

+X253319Y361285D01*

+X253409Y361067D01*

+X253533Y360866D01*

+X253686Y360686D01*

+X253866Y360533D01*

+X254067Y360409D01*

+X254285Y360319D01*

+X254515Y360264D01*

+X254750Y360250D01*

+X255993Y360253D01*

+Y282013D01*

+X255294Y281958D01*

+X254605Y281793D01*

+X253951Y281522D01*

+X253347Y281152D01*

+X252808Y280692D01*

+X252348Y280153D01*

+X251978Y279549D01*

+X251707Y278895D01*

+X251542Y278206D01*

+X251486Y277500D01*

+X251542Y276794D01*

+X251707Y276105D01*

+X251978Y275451D01*

+X252348Y274847D01*

+X252808Y274308D01*

+X253347Y273848D01*

+X253951Y273478D01*

+X254605Y273207D01*

+X255294Y273042D01*

+X255993Y272987D01*

+Y222013D01*

+X255294Y221958D01*

+X254605Y221793D01*

+X253951Y221522D01*

+X253347Y221152D01*

+X252808Y220692D01*

+X252348Y220153D01*

+X251978Y219549D01*

+X251707Y218895D01*

+X251542Y218206D01*

+X251486Y217500D01*

+X251542Y216794D01*

+X251707Y216105D01*

+X251978Y215451D01*

+X252348Y214847D01*

+X252808Y214308D01*

+X253347Y213848D01*

+X253951Y213478D01*

+X254605Y213207D01*

+X255294Y213042D01*

+X255993Y212987D01*

+Y207500D01*

+G37*

+G36*

+X249750Y369416D02*X249472Y369531D01*

+X248745Y369706D01*

+X248000Y369765D01*

+X247255Y369706D01*

+X246528Y369531D01*

+X246000Y369313D01*

+Y390000D01*

+X249750D01*

+Y369416D01*

+G37*

+G36*

+Y279993D02*X249652Y280153D01*

+X249192Y280692D01*

+X248653Y281152D01*

+X248049Y281522D01*

+X247395Y281793D01*

+X246706Y281958D01*

+X246000Y282014D01*

+Y300410D01*

+X246033Y300370D01*

+X246093Y300318D01*

+X246160Y300277D01*

+X246232Y300246D01*

+X246309Y300227D01*

+X246387Y300220D01*

+X246466Y300226D01*

+X246542Y300244D01*

+X246615Y300274D01*

+X246683Y300314D01*

+X246743Y300365D01*

+X246794Y300424D01*

+X246834Y300492D01*

+X246988Y300817D01*

+X247106Y301156D01*

+X247192Y301506D01*

+X247243Y301861D01*

+X247260Y302220D01*

+X247243Y302580D01*

+X247192Y302935D01*

+X247106Y303285D01*

+X246988Y303624D01*

+X246838Y303951D01*

+X246797Y304018D01*

+X246745Y304078D01*

+X246684Y304129D01*

+X246617Y304170D01*

+X246543Y304200D01*

+X246466Y304218D01*

+X246387Y304224D01*

+X246308Y304217D01*

+X246231Y304198D01*

+X246158Y304167D01*

+X246091Y304125D01*

+X246031Y304073D01*

+X246000Y304036D01*

+Y309259D01*

+X246164Y309399D01*

+X246548Y309849D01*

+X246857Y310353D01*

+X247083Y310899D01*

+X247221Y311474D01*

+X247256Y312063D01*

+X247221Y312652D01*

+X247083Y313227D01*

+X246857Y313773D01*

+X246548Y314277D01*

+X246164Y314727D01*

+X246000Y314867D01*

+Y317133D01*

+X246164Y317273D01*

+X246548Y317723D01*

+X246857Y318227D01*

+X247083Y318773D01*

+X247221Y319348D01*

+X247256Y319937D01*

+X247221Y320526D01*

+X247083Y321101D01*

+X246857Y321647D01*

+X246548Y322151D01*

+X246164Y322601D01*

+X246000Y322741D01*

+Y326975D01*

+X246164Y327116D01*

+X246548Y327565D01*

+X246857Y328069D01*

+X247083Y328615D01*

+X247221Y329190D01*

+X247256Y329780D01*

+X247221Y330369D01*

+X247083Y330944D01*

+X246857Y331490D01*

+X246548Y331994D01*

+X246164Y332444D01*

+X246000Y332584D01*

+Y335240D01*

+X246510Y335280D01*

+X247007Y335400D01*

+X247480Y335595D01*

+X247916Y335863D01*

+X248305Y336195D01*

+X248637Y336584D01*

+X248905Y337020D01*

+X249100Y337493D01*

+X249220Y337990D01*

+X249250Y338500D01*

+X249220Y339010D01*

+X249100Y339507D01*

+X248905Y339980D01*

+X248637Y340416D01*

+X248305Y340805D01*

+X247916Y341137D01*

+X247480Y341405D01*

+X247007Y341600D01*

+X246510Y341720D01*

+X246000Y341760D01*

+Y360687D01*

+X246528Y360469D01*

+X247255Y360294D01*

+X248000Y360235D01*

+X248745Y360294D01*

+X249472Y360469D01*

+X249750Y360584D01*

+Y279993D01*

+G37*

+G36*

+Y207500D02*X246000D01*

+Y213000D01*

+X247500D01*

+X247618Y213007D01*

+X247732Y213035D01*

+X247842Y213080D01*

+X247942Y213141D01*

+X248032Y213218D01*

+X248109Y213308D01*

+X248170Y213408D01*

+X248215Y213518D01*

+X248243Y213632D01*

+X248252Y213750D01*

+X248243Y213868D01*

+X248215Y213982D01*

+X248170Y214092D01*

+X248109Y214192D01*

+X248032Y214282D01*

+X247942Y214359D01*

+X247842Y214420D01*

+X247732Y214465D01*

+X247618Y214493D01*

+X247500Y214500D01*

+X246000D01*

+Y220500D01*

+X247500D01*

+X247618Y220507D01*

+X247732Y220535D01*

+X247842Y220580D01*

+X247942Y220641D01*

+X248032Y220718D01*

+X248109Y220808D01*

+X248170Y220908D01*

+X248215Y221018D01*

+X248243Y221132D01*

+X248252Y221250D01*

+X248243Y221368D01*

+X248215Y221482D01*

+X248170Y221592D01*

+X248109Y221692D01*

+X248032Y221782D01*

+X247942Y221859D01*

+X247842Y221920D01*

+X247732Y221965D01*

+X247618Y221993D01*

+X247500Y222000D01*

+X246000D01*

+Y272986D01*

+X246706Y273042D01*

+X247395Y273207D01*

+X248049Y273478D01*

+X248653Y273848D01*

+X249192Y274308D01*

+X249652Y274847D01*

+X249750Y275007D01*

+Y219752D01*

+X249632Y219743D01*

+X249518Y219715D01*

+X249408Y219670D01*

+X249308Y219609D01*

+X249218Y219532D01*

+X249141Y219442D01*

+X249080Y219342D01*

+X249035Y219232D01*

+X249007Y219118D01*

+X249000Y219000D01*

+Y216000D01*

+X249007Y215882D01*

+X249035Y215768D01*

+X249080Y215658D01*

+X249141Y215558D01*

+X249218Y215468D01*

+X249308Y215391D01*

+X249408Y215330D01*

+X249518Y215285D01*

+X249632Y215257D01*

+X249750Y215248D01*

+Y207500D01*

+G37*

+G36*

+X242250Y308515D02*X242336Y308480D01*

+X242911Y308342D01*

+X243500Y308296D01*

+X244089Y308342D01*

+X244664Y308480D01*

+X245210Y308706D01*

+X245714Y309015D01*

+X246000Y309259D01*

+Y304036D01*

+X245980Y304013D01*

+X245939Y303945D01*

+X245909Y303872D01*

+X245892Y303794D01*

+X245886Y303715D01*

+X245893Y303637D01*

+X245912Y303560D01*

+X245944Y303487D01*

+X246000Y303369D01*

+Y301068D01*

+X245947Y300952D01*

+X245915Y300880D01*

+X245896Y300804D01*

+X245889Y300726D01*

+X245895Y300647D01*

+X245913Y300570D01*

+X245942Y300497D01*

+X245983Y300430D01*

+X246000Y300410D01*

+Y282014D01*

+X246000D01*

+X245294Y281958D01*

+X244605Y281793D01*

+X243951Y281522D01*

+X243347Y281152D01*

+X242808Y280692D01*

+X242348Y280153D01*

+X242250Y279993D01*

+Y298679D01*

+X242436Y298614D01*

+X242785Y298529D01*

+X243141Y298477D01*

+X243500Y298460D01*

+X243859Y298477D01*

+X244215Y298529D01*

+X244564Y298614D01*

+X244904Y298732D01*

+X245231Y298882D01*

+X245298Y298924D01*

+X245358Y298976D01*

+X245409Y299036D01*

+X245450Y299104D01*

+X245480Y299177D01*

+X245498Y299254D01*

+X245503Y299333D01*

+X245496Y299412D01*

+X245477Y299489D01*

+X245447Y299562D01*

+X245405Y299629D01*

+X245353Y299689D01*

+X245292Y299740D01*

+X245224Y299781D01*

+X245151Y299811D01*

+X245074Y299829D01*

+X244995Y299835D01*

+X244916Y299828D01*

+X244839Y299809D01*

+X244767Y299777D01*

+X244529Y299664D01*

+X244280Y299577D01*

+X244024Y299515D01*

+X243763Y299477D01*

+X243500Y299465D01*

+X243237Y299477D01*

+X242976Y299515D01*

+X242720Y299577D01*

+X242471Y299664D01*

+X242250Y299765D01*

+Y304672D01*

+X242471Y304777D01*

+X242720Y304864D01*

+X242976Y304926D01*

+X243237Y304964D01*

+X243500Y304976D01*

+X243763Y304964D01*

+X244024Y304926D01*

+X244280Y304864D01*

+X244529Y304777D01*

+X244768Y304667D01*

+X244840Y304635D01*

+X244917Y304616D01*

+X244995Y304610D01*

+X245073Y304615D01*

+X245150Y304633D01*

+X245223Y304663D01*

+X245290Y304703D01*

+X245351Y304754D01*

+X245402Y304813D01*

+X245444Y304880D01*

+X245474Y304953D01*

+X245493Y305029D01*

+X245500Y305108D01*

+X245494Y305186D01*

+X245477Y305263D01*

+X245447Y305336D01*

+X245406Y305403D01*

+X245356Y305463D01*

+X245296Y305515D01*

+X245229Y305555D01*

+X244904Y305709D01*

+X244564Y305827D01*

+X244215Y305912D01*

+X243859Y305963D01*

+X243500Y305981D01*

+X243141Y305963D01*

+X242785Y305912D01*

+X242436Y305827D01*

+X242250Y305762D01*

+Y308515D01*

+G37*

+G36*

+Y316389D02*X242336Y316354D01*

+X242911Y316216D01*

+X243500Y316170D01*

+X244089Y316216D01*

+X244664Y316354D01*

+X245210Y316580D01*

+X245714Y316889D01*

+X246000Y317133D01*

+Y314867D01*

+X245714Y315111D01*

+X245210Y315420D01*

+X244664Y315646D01*

+X244089Y315784D01*

+X243500Y315830D01*

+X242911Y315784D01*

+X242336Y315646D01*

+X242250Y315611D01*

+Y316389D01*

+G37*

+G36*

+Y326232D02*X242336Y326196D01*

+X242911Y326058D01*

+X243500Y326012D01*

+X244089Y326058D01*

+X244664Y326196D01*

+X245210Y326423D01*

+X245714Y326732D01*

+X246000Y326975D01*

+Y322741D01*

+X245714Y322985D01*

+X245210Y323294D01*

+X244664Y323520D01*

+X244089Y323658D01*

+X243500Y323704D01*

+X242911Y323658D01*

+X242336Y323520D01*

+X242250Y323485D01*

+Y326232D01*

+G37*

+G36*

+Y390000D02*X246000D01*

+Y369313D01*

+X245837Y369245D01*

+X245199Y368855D01*

+X244631Y368369D01*

+X244145Y367801D01*

+X243755Y367163D01*

+X243469Y366472D01*

+X243294Y365745D01*

+X243235Y365000D01*

+X243294Y364255D01*

+X243469Y363528D01*

+X243755Y362837D01*

+X244145Y362199D01*

+X244631Y361631D01*

+X245199Y361145D01*

+X245837Y360755D01*

+X246000Y360687D01*

+Y341760D01*

+X246000D01*

+X245490Y341720D01*

+X244993Y341600D01*

+X244520Y341405D01*

+X244084Y341137D01*

+X243695Y340805D01*

+X243363Y340416D01*

+X243095Y339980D01*

+X242900Y339507D01*

+X242780Y339010D01*

+X242740Y338500D01*

+X242780Y337990D01*

+X242900Y337493D01*

+X243095Y337020D01*

+X243363Y336584D01*

+X243695Y336195D01*

+X244084Y335863D01*

+X244520Y335595D01*

+X244993Y335400D01*

+X245490Y335280D01*

+X246000Y335240D01*

+X246000D01*

+Y332584D01*

+X245714Y332827D01*

+X245210Y333136D01*

+X244664Y333363D01*

+X244089Y333501D01*

+X243500Y333547D01*

+X242911Y333501D01*

+X242336Y333363D01*

+X242250Y333327D01*

+Y362848D01*

+X242531Y363528D01*

+X242706Y364255D01*

+X242750Y365000D01*

+X242706Y365745D01*

+X242531Y366472D01*

+X242250Y367152D01*

+Y390000D01*

+G37*

+G36*

+X246000Y207500D02*X242250D01*

+Y215248D01*

+X242368Y215257D01*

+X242482Y215285D01*

+X242592Y215330D01*

+X242692Y215391D01*

+X242782Y215468D01*

+X242859Y215558D01*

+X242920Y215658D01*

+X242965Y215768D01*

+X242993Y215882D01*

+X243000Y216000D01*

+Y219000D01*

+X242993Y219118D01*

+X242965Y219232D01*

+X242920Y219342D01*

+X242859Y219442D01*

+X242782Y219532D01*

+X242692Y219609D01*

+X242592Y219670D01*

+X242482Y219715D01*

+X242368Y219743D01*

+X242250Y219752D01*

+Y275007D01*

+X242348Y274847D01*

+X242808Y274308D01*

+X243347Y273848D01*

+X243951Y273478D01*

+X244605Y273207D01*

+X245294Y273042D01*

+X246000Y272986D01*

+X246000D01*

+Y222000D01*

+X244500D01*

+X244382Y221993D01*

+X244268Y221965D01*

+X244158Y221920D01*

+X244058Y221859D01*

+X243968Y221782D01*

+X243891Y221692D01*

+X243830Y221592D01*

+X243785Y221482D01*

+X243757Y221368D01*

+X243748Y221250D01*

+X243757Y221132D01*

+X243785Y221018D01*

+X243830Y220908D01*

+X243891Y220808D01*

+X243968Y220718D01*

+X244058Y220641D01*

+X244158Y220580D01*

+X244268Y220535D01*

+X244382Y220507D01*

+X244500Y220500D01*

+X246000D01*

+Y214500D01*

+X244500D01*

+X244382Y214493D01*

+X244268Y214465D01*

+X244158Y214420D01*

+X244058Y214359D01*

+X243968Y214282D01*

+X243891Y214192D01*

+X243830Y214092D01*

+X243785Y213982D01*

+X243757Y213868D01*

+X243748Y213750D01*

+X243757Y213632D01*

+X243785Y213518D01*

+X243830Y213408D01*

+X243891Y213308D01*

+X243968Y213218D01*

+X244058Y213141D01*

+X244158Y213080D01*

+X244268Y213035D01*

+X244382Y213007D01*

+X244500Y213000D01*

+X246000D01*

+Y207500D01*

+G37*

+G36*

+X240427Y317763D02*X240452Y317723D01*

+X240836Y317273D01*

+X241286Y316889D01*

+X241790Y316580D01*

+X242250Y316389D01*

+Y315611D01*

+X241790Y315420D01*

+X241286Y315111D01*

+X240836Y314727D01*

+X240452Y314277D01*

+X240427Y314237D01*

+Y317763D01*

+G37*

+G36*

+Y327606D02*X240452Y327565D01*

+X240836Y327116D01*

+X241286Y326732D01*

+X241790Y326423D01*

+X242250Y326232D01*

+Y323485D01*

+X241790Y323294D01*

+X241286Y322985D01*

+X240836Y322601D01*

+X240452Y322151D01*

+X240427Y322111D01*

+Y327606D01*

+G37*

+G36*

+Y360916D02*X240801Y361145D01*

+X241369Y361631D01*

+X241855Y362199D01*

+X242245Y362837D01*

+X242250Y362848D01*

+Y333327D01*

+X241790Y333136D01*

+X241286Y332827D01*

+X240836Y332444D01*

+X240452Y331994D01*

+X240427Y331953D01*

+Y360916D01*

+G37*

+G36*

+Y390000D02*X242250D01*

+Y367152D01*

+X242245Y367163D01*

+X241855Y367801D01*

+X241369Y368369D01*

+X240801Y368855D01*

+X240427Y369084D01*

+Y390000D01*

+G37*

+G36*

+X242250Y207500D02*X240427D01*

+Y300253D01*

+X240457Y300241D01*

+X240534Y300223D01*

+X240613Y300217D01*

+X240692Y300224D01*

+X240769Y300243D01*

+X240842Y300274D01*

+X240909Y300316D01*

+X240969Y300368D01*

+X241020Y300428D01*

+X241061Y300496D01*

+X241091Y300569D01*

+X241108Y300647D01*

+X241114Y300726D01*

+X241107Y300804D01*

+X241088Y300881D01*

+X241056Y300954D01*

+X240943Y301192D01*

+X240857Y301440D01*

+X240794Y301696D01*

+X240757Y301957D01*

+X240744Y302220D01*

+X240757Y302484D01*

+X240794Y302744D01*

+X240857Y303000D01*

+X240943Y303249D01*

+X241053Y303489D01*

+X241085Y303561D01*

+X241104Y303637D01*

+X241111Y303715D01*

+X241105Y303794D01*

+X241087Y303871D01*

+X241058Y303944D01*

+X241017Y304011D01*

+X240967Y304071D01*

+X240907Y304123D01*

+X240840Y304164D01*

+X240768Y304195D01*

+X240691Y304214D01*

+X240613Y304220D01*

+X240534Y304215D01*

+X240458Y304197D01*

+X240427Y304185D01*

+Y309889D01*

+X240452Y309849D01*

+X240836Y309399D01*

+X241286Y309015D01*

+X241790Y308706D01*

+X242250Y308515D01*

+Y305762D01*

+X242096Y305709D01*

+X241769Y305559D01*

+X241702Y305517D01*

+X241642Y305465D01*

+X241591Y305405D01*

+X241550Y305337D01*

+X241520Y305264D01*

+X241502Y305186D01*

+X241497Y305108D01*

+X241504Y305029D01*

+X241523Y304952D01*

+X241553Y304879D01*

+X241595Y304812D01*

+X241647Y304752D01*

+X241708Y304701D01*

+X241776Y304660D01*

+X241849Y304630D01*

+X241926Y304612D01*

+X242005Y304606D01*

+X242084Y304613D01*

+X242161Y304632D01*

+X242233Y304664D01*

+X242250Y304672D01*

+Y299765D01*

+X242232Y299774D01*

+X242160Y299806D01*

+X242083Y299825D01*

+X242005Y299831D01*

+X241927Y299826D01*

+X241850Y299808D01*

+X241777Y299778D01*

+X241710Y299738D01*

+X241649Y299687D01*

+X241598Y299628D01*

+X241556Y299561D01*

+X241526Y299488D01*

+X241507Y299412D01*

+X241500Y299333D01*

+X241506Y299255D01*

+X241523Y299178D01*

+X241553Y299105D01*

+X241594Y299038D01*

+X241644Y298978D01*

+X241704Y298926D01*

+X241771Y298886D01*

+X242096Y298732D01*

+X242250Y298679D01*

+Y279993D01*

+X241978Y279549D01*

+X241707Y278895D01*

+X241542Y278206D01*

+X241486Y277500D01*

+X241542Y276794D01*

+X241707Y276105D01*

+X241978Y275451D01*

+X242250Y275007D01*

+Y219752D01*

+X242132Y219743D01*

+X242018Y219715D01*

+X241908Y219670D01*

+X241808Y219609D01*

+X241718Y219532D01*

+X241641Y219442D01*

+X241580Y219342D01*

+X241535Y219232D01*

+X241507Y219118D01*

+X241500Y219000D01*

+Y216000D01*

+X241507Y215882D01*

+X241535Y215768D01*

+X241580Y215658D01*

+X241641Y215558D01*

+X241718Y215468D01*

+X241808Y215391D01*

+X241908Y215330D01*

+X242018Y215285D01*

+X242132Y215257D01*

+X242250Y215248D01*

+Y207500D01*

+G37*

+G36*

+X238115Y290674D02*X238125Y290599D01*

+X238146Y290134D01*

+X238125Y289669D01*

+X238115Y289593D01*

+Y290674D01*

+G37*

+G36*

+Y342407D02*X238125Y342331D01*

+X238146Y341866D01*

+X238125Y341401D01*

+X238115Y341326D01*

+Y342407D01*

+G37*

+G36*

+Y390000D02*X240427D01*

+Y369084D01*

+X240163Y369245D01*

+X239472Y369531D01*

+X238745Y369706D01*

+X238115Y369756D01*

+Y390000D01*

+G37*

+G36*

+X240427Y207500D02*X238115D01*

+Y286683D01*

+X238298Y286961D01*

+X238555Y287452D01*

+X238767Y287963D01*

+X238935Y288491D01*

+X239055Y289032D01*

+X239127Y289581D01*

+X239152Y290134D01*

+X239127Y290687D01*

+X239055Y291236D01*

+X238935Y291777D01*

+X238767Y292304D01*

+X238555Y292816D01*

+X238298Y293306D01*

+X238115Y293592D01*

+Y338415D01*

+X238298Y338694D01*

+X238555Y339184D01*

+X238767Y339696D01*

+X238935Y340223D01*

+X239055Y340764D01*

+X239127Y341313D01*

+X239152Y341866D01*

+X239127Y342419D01*

+X239055Y342968D01*

+X238935Y343509D01*

+X238767Y344037D01*

+X238555Y344548D01*

+X238298Y345039D01*

+X238115Y345324D01*

+Y360244D01*

+X238745Y360294D01*

+X239472Y360469D01*

+X240163Y360755D01*

+X240427Y360916D01*

+Y331953D01*

+X240143Y331490D01*

+X239917Y330944D01*

+X239779Y330369D01*

+X239733Y329780D01*

+X239779Y329190D01*

+X239917Y328615D01*

+X240143Y328069D01*

+X240427Y327606D01*

+Y322111D01*

+X240143Y321647D01*

+X239917Y321101D01*

+X239779Y320526D01*

+X239733Y319937D01*

+X239779Y319348D01*

+X239917Y318773D01*

+X240143Y318227D01*

+X240427Y317763D01*

+Y314237D01*

+X240143Y313773D01*

+X239917Y313227D01*

+X239779Y312652D01*

+X239733Y312063D01*

+X239779Y311474D01*

+X239917Y310899D01*

+X240143Y310353D01*

+X240427Y309889D01*

+Y304185D01*

+X240385Y304167D01*

+X240317Y304127D01*

+X240257Y304076D01*

+X240206Y304017D01*

+X240166Y303949D01*

+X240012Y303624D01*

+X239894Y303285D01*

+X239808Y302935D01*

+X239757Y302580D01*

+X239740Y302220D01*

+X239757Y301861D01*

+X239808Y301506D01*

+X239894Y301156D01*

+X240012Y300817D01*

+X240162Y300490D01*

+X240203Y300422D01*

+X240255Y300363D01*

+X240316Y300312D01*

+X240383Y300271D01*

+X240427Y300253D01*

+Y207500D01*

+G37*

+G36*

+X238115D02*X232833D01*

+Y283813D01*

+X233384Y283837D01*

+X233933Y283910D01*

+X234473Y284030D01*

+X235001Y284197D01*

+X235513Y284410D01*

+X236003Y284667D01*

+X236470Y284965D01*

+X236531Y285016D01*

+X236584Y285075D01*

+X236626Y285142D01*

+X236658Y285215D01*

+X236677Y285292D01*

+X236685Y285372D01*

+X236680Y285451D01*

+X236662Y285528D01*

+X236633Y285602D01*

+X236593Y285671D01*

+X236542Y285732D01*

+X236482Y285785D01*

+X236415Y285827D01*

+X236342Y285859D01*

+X236265Y285878D01*

+X236186Y285886D01*

+X236106Y285881D01*

+X236029Y285863D01*

+X235955Y285834D01*

+X235887Y285792D01*

+X235498Y285537D01*

+X235086Y285321D01*

+X234656Y285142D01*

+X234212Y285002D01*

+X233757Y284900D01*

+X233296Y284839D01*

+X232833Y284819D01*

+Y295449D01*

+X233296Y295428D01*

+X233757Y295367D01*

+X234212Y295266D01*

+X234656Y295126D01*

+X235086Y294947D01*

+X235498Y294731D01*

+X235890Y294480D01*

+X235957Y294438D01*

+X236030Y294409D01*

+X236107Y294392D01*

+X236186Y294387D01*

+X236264Y294394D01*

+X236340Y294414D01*

+X236413Y294445D01*

+X236479Y294487D01*

+X236538Y294539D01*

+X236588Y294600D01*

+X236628Y294668D01*

+X236657Y294741D01*

+X236675Y294818D01*

+X236680Y294896D01*

+X236672Y294974D01*

+X236653Y295051D01*

+X236622Y295123D01*

+X236580Y295189D01*

+X236528Y295249D01*

+X236466Y295297D01*

+X236003Y295601D01*

+X235513Y295858D01*

+X235001Y296071D01*

+X234473Y296238D01*

+X233933Y296358D01*

+X233384Y296431D01*

+X232833Y296455D01*

+Y335545D01*

+X233384Y335569D01*

+X233933Y335642D01*

+X234473Y335762D01*

+X235001Y335929D01*

+X235513Y336142D01*

+X236003Y336399D01*

+X236470Y336698D01*

+X236531Y336748D01*

+X236584Y336807D01*

+X236626Y336875D01*

+X236658Y336948D01*

+X236677Y337025D01*

+X236685Y337104D01*

+X236680Y337183D01*

+X236662Y337261D01*

+X236633Y337335D01*

+X236593Y337403D01*

+X236542Y337464D01*

+X236482Y337517D01*

+X236415Y337559D01*

+X236342Y337591D01*

+X236265Y337611D01*

+X236186Y337618D01*

+X236106Y337613D01*

+X236029Y337596D01*

+X235955Y337566D01*

+X235887Y337524D01*

+X235498Y337269D01*

+X235086Y337053D01*

+X234656Y336874D01*

+X234212Y336734D01*

+X233757Y336633D01*

+X233296Y336572D01*

+X232833Y336551D01*

+Y347181D01*

+X233296Y347161D01*

+X233757Y347100D01*

+X234212Y346998D01*

+X234656Y346858D01*

+X235086Y346679D01*

+X235498Y346463D01*

+X235890Y346212D01*

+X235957Y346171D01*

+X236030Y346142D01*

+X236107Y346124D01*

+X236186Y346119D01*

+X236264Y346127D01*

+X236340Y346146D01*

+X236413Y346177D01*

+X236479Y346220D01*

+X236538Y346272D01*

+X236588Y346332D01*

+X236628Y346400D01*

+X236657Y346473D01*

+X236675Y346550D01*

+X236680Y346628D01*

+X236672Y346707D01*

+X236653Y346783D01*

+X236622Y346855D01*

+X236580Y346922D01*

+X236528Y346981D01*

+X236466Y347030D01*

+X236003Y347333D01*

+X235513Y347590D01*

+X235001Y347803D01*

+X234473Y347970D01*

+X233933Y348090D01*

+X233384Y348163D01*

+X232833Y348187D01*

+Y390000D01*

+X238115D01*

+Y369756D01*

+X238000Y369765D01*

+X237255Y369706D01*

+X236528Y369531D01*

+X235837Y369245D01*

+X235199Y368855D01*

+X234631Y368369D01*

+X234145Y367801D01*

+X233755Y367163D01*

+X233469Y366472D01*

+X233294Y365745D01*

+X233235Y365000D01*

+X233294Y364255D01*

+X233469Y363528D01*

+X233755Y362837D01*

+X234145Y362199D01*

+X234631Y361631D01*

+X235199Y361145D01*

+X235837Y360755D01*

+X236528Y360469D01*

+X237255Y360294D01*

+X238000Y360235D01*

+X238115Y360244D01*

+Y345324D01*

+X237999Y345505D01*

+X237949Y345567D01*

+X237889Y345619D01*

+X237822Y345662D01*

+X237749Y345693D01*

+X237672Y345713D01*

+X237593Y345720D01*

+X237514Y345715D01*

+X237436Y345698D01*

+X237362Y345668D01*

+X237294Y345628D01*

+X237233Y345577D01*

+X237180Y345518D01*

+X237138Y345450D01*

+X237106Y345377D01*

+X237086Y345300D01*

+X237079Y345221D01*

+X237084Y345142D01*

+X237101Y345064D01*

+X237131Y344990D01*

+X237172Y344923D01*

+X237428Y344534D01*

+X237644Y344121D01*

+X237822Y343691D01*

+X237963Y343247D01*

+X238064Y342793D01*

+X238115Y342407D01*

+Y341326D01*

+X238064Y340939D01*

+X237963Y340485D01*

+X237822Y340041D01*

+X237644Y339611D01*

+X237428Y339199D01*

+X237177Y338806D01*

+X237135Y338740D01*

+X237106Y338666D01*

+X237089Y338590D01*

+X237084Y338511D01*

+X237091Y338433D01*

+X237111Y338357D01*

+X237142Y338284D01*

+X237184Y338218D01*

+X237236Y338159D01*

+X237297Y338109D01*

+X237364Y338068D01*

+X237438Y338039D01*

+X237514Y338022D01*

+X237593Y338017D01*

+X237671Y338024D01*

+X237748Y338044D01*

+X237820Y338075D01*

+X237886Y338117D01*

+X237945Y338169D01*

+X237994Y338231D01*

+X238115Y338415D01*

+Y293592D01*

+X237999Y293773D01*

+X237949Y293834D01*

+X237889Y293887D01*

+X237822Y293929D01*

+X237749Y293961D01*

+X237672Y293981D01*

+X237593Y293988D01*

+X237514Y293983D01*

+X237436Y293966D01*

+X237362Y293936D01*

+X237294Y293896D01*

+X237233Y293845D01*

+X237180Y293785D01*

+X237138Y293718D01*

+X237106Y293645D01*

+X237086Y293568D01*

+X237079Y293489D01*

+X237084Y293410D01*

+X237101Y293332D01*

+X237131Y293258D01*

+X237172Y293191D01*

+X237428Y292801D01*

+X237644Y292389D01*

+X237822Y291959D01*

+X237963Y291515D01*

+X238064Y291061D01*

+X238115Y290674D01*

+Y289593D01*

+X238064Y289207D01*

+X237963Y288753D01*

+X237822Y288309D01*

+X237644Y287879D01*

+X237428Y287466D01*

+X237177Y287074D01*

+X237135Y287007D01*

+X237106Y286934D01*

+X237089Y286857D01*

+X237084Y286779D01*

+X237091Y286701D01*

+X237111Y286624D01*

+X237142Y286552D01*

+X237184Y286486D01*

+X237236Y286426D01*

+X237297Y286376D01*

+X237364Y286336D01*

+X237438Y286307D01*

+X237514Y286290D01*

+X237593Y286285D01*

+X237671Y286292D01*

+X237748Y286312D01*

+X237820Y286343D01*

+X237886Y286385D01*

+X237945Y286437D01*

+X237994Y286499D01*

+X238115Y286683D01*

+Y207500D01*

+G37*

+G36*

+X232833D02*X227993D01*

+Y286287D01*

+X228068Y286280D01*

+X228148Y286285D01*

+X228225Y286302D01*

+X228299Y286332D01*

+X228368Y286372D01*

+X228429Y286423D01*

+X228481Y286482D01*

+X228524Y286550D01*

+X228555Y286623D01*

+X228575Y286700D01*

+X228583Y286779D01*

+X228577Y286858D01*

+X228560Y286936D01*

+X228531Y287010D01*

+X228489Y287077D01*

+X228234Y287466D01*

+X228018Y287879D01*

+X227993Y287939D01*

+Y292328D01*

+X228018Y292389D01*

+X228234Y292801D01*

+X228485Y293194D01*

+X228526Y293260D01*

+X228555Y293334D01*

+X228572Y293410D01*

+X228577Y293489D01*

+X228570Y293567D01*

+X228551Y293643D01*

+X228519Y293716D01*

+X228477Y293782D01*

+X228425Y293841D01*

+X228365Y293891D01*

+X228297Y293932D01*

+X228224Y293961D01*

+X228147Y293978D01*

+X228068Y293983D01*

+X227993Y293976D01*

+Y338019D01*

+X228068Y338012D01*

+X228148Y338017D01*

+X228225Y338034D01*

+X228299Y338064D01*

+X228368Y338104D01*

+X228429Y338155D01*

+X228481Y338215D01*

+X228524Y338282D01*

+X228555Y338355D01*

+X228575Y338432D01*

+X228583Y338511D01*

+X228577Y338590D01*

+X228560Y338668D01*

+X228531Y338742D01*

+X228489Y338809D01*

+X228234Y339199D01*

+X228018Y339611D01*

+X227993Y339672D01*

+Y344061D01*

+X228018Y344121D01*

+X228234Y344534D01*

+X228485Y344926D01*

+X228526Y344993D01*

+X228555Y345066D01*

+X228572Y345143D01*

+X228577Y345221D01*

+X228570Y345299D01*

+X228551Y345376D01*

+X228519Y345448D01*

+X228477Y345514D01*

+X228425Y345574D01*

+X228365Y345624D01*

+X228297Y345664D01*

+X228224Y345693D01*

+X228147Y345710D01*

+X228068Y345715D01*

+X227993Y345708D01*

+Y360236D01*

+X228000Y360235D01*

+X228745Y360294D01*

+X229472Y360469D01*

+X230163Y360755D01*

+X230801Y361145D01*

+X231369Y361631D01*

+X231855Y362199D01*

+X232245Y362837D01*

+X232531Y363528D01*

+X232706Y364255D01*

+X232750Y365000D01*

+X232706Y365745D01*

+X232531Y366472D01*

+X232245Y367163D01*

+X231855Y367801D01*

+X231369Y368369D01*

+X230801Y368855D01*

+X230163Y369245D01*

+X229472Y369531D01*

+X228745Y369706D01*

+X228000Y369765D01*

+X227993Y369764D01*

+Y390000D01*

+X232833D01*

+Y348187D01*

+X232831Y348187D01*

+X232277Y348163D01*

+X231729Y348090D01*

+X231188Y347970D01*

+X230660Y347803D01*

+X230149Y347590D01*

+X229658Y347333D01*

+X229192Y347035D01*

+X229130Y346984D01*

+X229078Y346925D01*

+X229035Y346858D01*

+X229004Y346785D01*

+X228984Y346708D01*

+X228977Y346628D01*

+X228982Y346549D01*

+X228999Y346472D01*

+X229028Y346398D01*

+X229069Y346329D01*

+X229120Y346268D01*

+X229179Y346216D01*

+X229246Y346173D01*

+X229319Y346141D01*

+X229396Y346122D01*

+X229476Y346114D01*

+X229555Y346119D01*

+X229633Y346137D01*

+X229706Y346166D01*

+X229774Y346208D01*

+X230163Y346463D01*

+X230576Y346679D01*

+X231006Y346858D01*

+X231449Y346998D01*

+X231904Y347100D01*

+X232366Y347161D01*

+X232831Y347181D01*

+X232833Y347181D01*

+Y336551D01*

+X232831Y336551D01*

+X232366Y336572D01*

+X231904Y336633D01*

+X231449Y336734D01*

+X231006Y336874D01*

+X230576Y337053D01*

+X230163Y337269D01*

+X229771Y337520D01*

+X229704Y337562D01*

+X229631Y337591D01*

+X229554Y337608D01*

+X229476Y337613D01*

+X229397Y337606D01*

+X229321Y337586D01*

+X229249Y337555D01*

+X229182Y337513D01*

+X229123Y337461D01*

+X229073Y337400D01*

+X229033Y337332D01*

+X229004Y337259D01*

+X228987Y337182D01*

+X228982Y337104D01*

+X228989Y337026D01*

+X229009Y336949D01*

+X229040Y336877D01*

+X229082Y336811D01*

+X229134Y336751D01*

+X229195Y336703D01*

+X229658Y336399D01*

+X230149Y336142D01*

+X230660Y335929D01*

+X231188Y335762D01*

+X231729Y335642D01*

+X232277Y335569D01*

+X232831Y335545D01*

+X232833Y335545D01*

+Y296455D01*

+X232831Y296455D01*

+X232277Y296431D01*

+X231729Y296358D01*

+X231188Y296238D01*

+X230660Y296071D01*

+X230149Y295858D01*

+X229658Y295601D01*

+X229192Y295302D01*

+X229130Y295252D01*

+X229078Y295193D01*

+X229035Y295125D01*

+X229004Y295052D01*

+X228984Y294975D01*

+X228977Y294896D01*

+X228982Y294817D01*

+X228999Y294739D01*

+X229028Y294665D01*

+X229069Y294597D01*

+X229120Y294536D01*

+X229179Y294483D01*

+X229246Y294441D01*

+X229319Y294409D01*

+X229396Y294389D01*

+X229476Y294382D01*

+X229555Y294387D01*

+X229633Y294404D01*

+X229706Y294434D01*

+X229774Y294476D01*

+X230163Y294731D01*

+X230576Y294947D01*

+X231006Y295126D01*

+X231449Y295266D01*

+X231904Y295367D01*

+X232366Y295428D01*

+X232831Y295449D01*

+X232833Y295449D01*

+Y284819D01*

+X232831Y284819D01*

+X232366Y284839D01*

+X231904Y284900D01*

+X231449Y285002D01*

+X231006Y285142D01*

+X230576Y285321D01*

+X230163Y285537D01*

+X229771Y285788D01*

+X229704Y285829D01*

+X229631Y285858D01*

+X229554Y285876D01*

+X229476Y285881D01*

+X229397Y285873D01*

+X229321Y285854D01*

+X229249Y285823D01*

+X229182Y285780D01*

+X229123Y285728D01*

+X229073Y285668D01*

+X229033Y285600D01*

+X229004Y285527D01*

+X228987Y285450D01*

+X228982Y285372D01*

+X228989Y285293D01*

+X229009Y285217D01*

+X229040Y285145D01*

+X229082Y285078D01*

+X229134Y285019D01*

+X229195Y284970D01*

+X229658Y284667D01*

+X230149Y284410D01*

+X230660Y284197D01*

+X231188Y284030D01*

+X231729Y283910D01*

+X232277Y283837D01*

+X232831Y283813D01*

+X232833Y283813D01*

+Y207500D01*

+G37*

+G36*

+X227993Y287939D02*X227839Y288309D01*

+X227698Y288753D01*

+X227597Y289207D01*

+X227536Y289669D01*

+X227516Y290134D01*

+X227536Y290599D01*

+X227597Y291061D01*

+X227698Y291515D01*

+X227839Y291959D01*

+X227993Y292328D01*

+Y287939D01*

+G37*

+G36*

+Y339672D02*X227839Y340041D01*

+X227698Y340485D01*

+X227597Y340939D01*

+X227536Y341401D01*

+X227516Y341866D01*

+X227536Y342331D01*

+X227597Y342793D01*

+X227698Y343247D01*

+X227839Y343691D01*

+X227993Y344061D01*

+Y339672D01*

+G37*

+G36*

+X224996Y390000D02*X227993D01*

+Y369764D01*

+X227255Y369706D01*

+X226528Y369531D01*

+X225837Y369245D01*

+X225199Y368855D01*

+X224996Y368681D01*

+Y390000D01*

+G37*

+G36*

+X227993Y207500D02*X224996D01*

+Y240993D01*

+X225000Y240992D01*

+X225392Y241023D01*

+X225775Y241115D01*

+X226138Y241266D01*

+X226474Y241471D01*

+X226773Y241727D01*

+X227029Y242026D01*

+X227234Y242362D01*

+X227385Y242725D01*

+X227477Y243108D01*

+X227500Y243500D01*

+X227477Y243892D01*

+X227385Y244275D01*

+X227234Y244638D01*

+X227029Y244974D01*

+X226773Y245273D01*

+X226474Y245529D01*

+X226138Y245734D01*

+X225775Y245885D01*

+X225392Y245977D01*

+X225000Y246008D01*

+X224996Y246007D01*

+Y361319D01*

+X225199Y361145D01*

+X225837Y360755D01*

+X226528Y360469D01*

+X227255Y360294D01*

+X227993Y360236D01*

+Y345708D01*

+X227990Y345708D01*

+X227914Y345688D01*

+X227842Y345657D01*

+X227775Y345615D01*

+X227716Y345563D01*

+X227667Y345501D01*

+X227363Y345039D01*

+X227107Y344548D01*

+X226894Y344037D01*

+X226727Y343509D01*

+X226607Y342968D01*

+X226534Y342419D01*

+X226510Y341866D01*

+X226534Y341313D01*

+X226607Y340764D01*

+X226727Y340223D01*

+X226894Y339696D01*

+X227107Y339184D01*

+X227363Y338694D01*

+X227662Y338227D01*

+X227712Y338166D01*

+X227772Y338113D01*

+X227839Y338071D01*

+X227912Y338039D01*

+X227989Y338019D01*

+X227993Y338019D01*

+Y293976D01*

+X227990Y293976D01*

+X227914Y293956D01*

+X227842Y293925D01*

+X227775Y293883D01*

+X227716Y293831D01*

+X227667Y293769D01*

+X227363Y293306D01*

+X227107Y292816D01*

+X226894Y292304D01*

+X226727Y291777D01*

+X226607Y291236D01*

+X226534Y290687D01*

+X226510Y290134D01*

+X226534Y289581D01*

+X226607Y289032D01*

+X226727Y288491D01*

+X226894Y287963D01*

+X227107Y287452D01*

+X227363Y286961D01*

+X227662Y286495D01*

+X227712Y286433D01*

+X227772Y286381D01*

+X227839Y286338D01*

+X227912Y286307D01*

+X227989Y286287D01*

+X227993Y286287D01*

+Y207500D01*

+G37*

+G36*

+X224996D02*X217993D01*

+Y229501D01*

+X218227Y229227D01*

+X218526Y228971D01*

+X218862Y228766D01*

+X219225Y228615D01*

+X219608Y228523D01*

+X220000Y228492D01*

+X220392Y228523D01*

+X220775Y228615D01*

+X221138Y228766D01*

+X221474Y228971D01*

+X221773Y229227D01*

+X222029Y229526D01*

+X222234Y229862D01*

+X222385Y230225D01*

+X222477Y230608D01*

+X222500Y231000D01*

+X222477Y231392D01*

+X222385Y231775D01*

+X222234Y232138D01*

+X222029Y232474D01*

+X221773Y232773D01*

+X221474Y233029D01*

+X221138Y233234D01*

+X220775Y233385D01*

+X220392Y233477D01*

+X220000Y233508D01*

+X219608Y233477D01*

+X219225Y233385D01*

+X218862Y233234D01*

+X218526Y233029D01*

+X218227Y232773D01*

+X217993Y232499D01*

+Y312768D01*

+X218095Y312520D01*

+X218363Y312084D01*

+X218695Y311695D01*

+X219084Y311363D01*

+X219520Y311095D01*

+X219993Y310900D01*

+X220490Y310780D01*

+X221000Y310740D01*

+X221510Y310780D01*

+X222007Y310900D01*

+X222480Y311095D01*

+X222916Y311363D01*

+X223305Y311695D01*

+X223637Y312084D01*

+X223905Y312520D01*

+X224100Y312993D01*

+X224220Y313490D01*

+X224250Y314000D01*

+X224220Y314510D01*

+X224100Y315007D01*

+X223905Y315480D01*

+X223637Y315916D01*

+X223305Y316305D01*

+X222916Y316637D01*

+X222480Y316905D01*

+X222007Y317100D01*

+X221510Y317220D01*

+X221000Y317260D01*

+X220490Y317220D01*

+X219993Y317100D01*

+X219520Y316905D01*

+X219084Y316637D01*

+X218695Y316305D01*

+X218363Y315916D01*

+X218095Y315480D01*

+X217993Y315232D01*

+Y360236D01*

+X218000Y360235D01*

+X218745Y360294D01*

+X219472Y360469D01*

+X220163Y360755D01*

+X220801Y361145D01*

+X221369Y361631D01*

+X221855Y362199D01*

+X222245Y362837D01*

+X222531Y363528D01*

+X222706Y364255D01*

+X222750Y365000D01*

+X222706Y365745D01*

+X222531Y366472D01*

+X222245Y367163D01*

+X221855Y367801D01*

+X221369Y368369D01*

+X220801Y368855D01*

+X220163Y369245D01*

+X219472Y369531D01*

+X218745Y369706D01*

+X218000Y369765D01*

+X217993Y369764D01*

+Y390000D01*

+X224996D01*

+Y368681D01*

+X224631Y368369D01*

+X224145Y367801D01*

+X223755Y367163D01*

+X223469Y366472D01*

+X223294Y365745D01*

+X223235Y365000D01*

+X223294Y364255D01*

+X223469Y363528D01*

+X223755Y362837D01*

+X224145Y362199D01*

+X224631Y361631D01*

+X224996Y361319D01*

+Y246007D01*

+X224608Y245977D01*

+X224225Y245885D01*

+X223862Y245734D01*

+X223526Y245529D01*

+X223227Y245273D01*

+X222971Y244974D01*

+X222766Y244638D01*

+X222615Y244275D01*

+X222523Y243892D01*

+X222492Y243500D01*

+X222523Y243108D01*

+X222615Y242725D01*

+X222766Y242362D01*

+X222971Y242026D01*

+X223227Y241727D01*

+X223526Y241471D01*

+X223862Y241266D01*

+X224225Y241115D01*

+X224608Y241023D01*

+X224996Y240993D01*

+Y207500D01*

+G37*

+G36*

+X213495Y390000D02*X217993D01*

+Y369764D01*

+X217255Y369706D01*

+X216528Y369531D01*

+X215837Y369245D01*

+X215199Y368855D01*

+X214631Y368369D01*

+X214145Y367801D01*

+X213755Y367163D01*

+X213495Y366536D01*

+Y390000D01*

+G37*

+G36*

+X217993Y207500D02*X213495D01*

+Y241498D01*

+X213526Y241471D01*

+X213862Y241266D01*

+X214225Y241115D01*

+X214608Y241023D01*

+X215000Y240992D01*

+X215392Y241023D01*

+X215775Y241115D01*

+X216138Y241266D01*

+X216474Y241471D01*

+X216773Y241727D01*

+X217029Y242026D01*

+X217234Y242362D01*

+X217385Y242725D01*

+X217477Y243108D01*

+X217500Y243500D01*

+X217477Y243892D01*

+X217385Y244275D01*

+X217234Y244638D01*

+X217029Y244974D01*

+X216773Y245273D01*

+X216474Y245529D01*

+X216138Y245734D01*

+X215775Y245885D01*

+X215392Y245977D01*

+X215000Y246008D01*

+X214608Y245977D01*

+X214225Y245885D01*

+X213862Y245734D01*

+X213526Y245529D01*

+X213495Y245502D01*

+Y310740D01*

+X213500Y310740D01*

+X214010Y310780D01*

+X214507Y310900D01*

+X214980Y311095D01*

+X215416Y311363D01*

+X215805Y311695D01*

+X216137Y312084D01*

+X216405Y312520D01*

+X216600Y312993D01*

+X216720Y313490D01*

+X216750Y314000D01*

+X216720Y314510D01*

+X216600Y315007D01*

+X216405Y315480D01*

+X216137Y315916D01*

+X215805Y316305D01*

+X215416Y316637D01*

+X214980Y316905D01*

+X214507Y317100D01*

+X214010Y317220D01*

+X213500Y317260D01*

+X213495Y317260D01*

+Y363464D01*

+X213755Y362837D01*

+X214145Y362199D01*

+X214631Y361631D01*

+X215199Y361145D01*

+X215837Y360755D01*

+X216528Y360469D01*

+X217255Y360294D01*

+X217993Y360236D01*

+Y315232D01*

+X217900Y315007D01*

+X217780Y314510D01*

+X217740Y314000D01*

+X217780Y313490D01*

+X217900Y312993D01*

+X217993Y312768D01*

+Y232499D01*

+X217971Y232474D01*

+X217766Y232138D01*

+X217615Y231775D01*

+X217523Y231392D01*

+X217492Y231000D01*

+X217523Y230608D01*

+X217615Y230225D01*

+X217766Y229862D01*

+X217971Y229526D01*

+X217993Y229501D01*

+Y207500D01*

+G37*

+G36*

+X213495D02*X209996D01*

+Y228493D01*

+X210000Y228492D01*

+X210392Y228523D01*

+X210775Y228615D01*

+X211138Y228766D01*

+X211474Y228971D01*

+X211773Y229227D01*

+X212029Y229526D01*

+X212234Y229862D01*

+X212385Y230225D01*

+X212477Y230608D01*

+X212500Y231000D01*

+X212477Y231392D01*

+X212385Y231775D01*

+X212234Y232138D01*

+X212029Y232474D01*

+X211773Y232773D01*

+X211474Y233029D01*

+X211138Y233234D01*

+X210775Y233385D01*

+X210392Y233477D01*

+X210000Y233508D01*

+X209996Y233507D01*

+Y390000D01*

+X213495D01*

+Y366536D01*

+X213469Y366472D01*

+X213294Y365745D01*

+X213235Y365000D01*

+X213294Y364255D01*

+X213469Y363528D01*

+X213495Y363464D01*

+Y317260D01*

+X212990Y317220D01*

+X212493Y317100D01*

+X212020Y316905D01*

+X211584Y316637D01*

+X211195Y316305D01*

+X210863Y315916D01*

+X210595Y315480D01*

+X210400Y315007D01*

+X210280Y314510D01*

+X210240Y314000D01*

+X210280Y313490D01*

+X210400Y312993D01*

+X210595Y312520D01*

+X210863Y312084D01*

+X211195Y311695D01*

+X211584Y311363D01*

+X212020Y311095D01*

+X212493Y310900D01*

+X212990Y310780D01*

+X213495Y310740D01*

+Y245502D01*

+X213227Y245273D01*

+X212971Y244974D01*

+X212766Y244638D01*

+X212615Y244275D01*

+X212523Y243892D01*

+X212492Y243500D01*

+X212523Y243108D01*

+X212615Y242725D01*

+X212766Y242362D01*

+X212971Y242026D01*

+X213227Y241727D01*

+X213495Y241498D01*

+Y207500D01*

+G37*

+G36*

+X209996D02*X202500D01*

+Y243402D01*

+X202523Y243108D01*

+X202615Y242725D01*

+X202766Y242362D01*

+X202971Y242026D01*

+X203227Y241727D01*

+X203526Y241471D01*

+X203862Y241266D01*

+X204225Y241115D01*

+X204608Y241023D01*

+X205000Y240992D01*

+X205392Y241023D01*

+X205775Y241115D01*

+X206138Y241266D01*

+X206474Y241471D01*

+X206773Y241727D01*

+X207029Y242026D01*

+X207234Y242362D01*

+X207385Y242725D01*

+X207477Y243108D01*

+X207500Y243500D01*

+X207477Y243892D01*

+X207385Y244275D01*

+X207234Y244638D01*

+X207029Y244974D01*

+X206773Y245273D01*

+X206474Y245529D01*

+X206138Y245734D01*

+X205775Y245885D01*

+X205392Y245977D01*

+X205000Y246008D01*

+X204608Y245977D01*

+X204225Y245885D01*

+X203862Y245734D01*

+X203526Y245529D01*

+X203227Y245273D01*

+X202971Y244974D01*

+X202766Y244638D01*

+X202615Y244275D01*

+X202523Y243892D01*

+X202500Y243598D01*

+Y311923D01*

+X202695Y311695D01*

+X203084Y311363D01*

+X203520Y311095D01*

+X203993Y310900D01*

+X204490Y310780D01*

+X205000Y310740D01*

+X205510Y310780D01*

+X206007Y310900D01*

+X206480Y311095D01*

+X206916Y311363D01*

+X207305Y311695D01*

+X207637Y312084D01*

+X207905Y312520D01*

+X208100Y312993D01*

+X208220Y313490D01*

+X208250Y314000D01*

+X208220Y314510D01*

+X208100Y315007D01*

+X207905Y315480D01*

+X207637Y315916D01*

+X207305Y316305D01*

+X206916Y316637D01*

+X206480Y316905D01*

+X206007Y317100D01*

+X205510Y317220D01*

+X205000Y317260D01*

+X204490Y317220D01*

+X203993Y317100D01*

+X203520Y316905D01*

+X203084Y316637D01*

+X202695Y316305D01*

+X202500Y316077D01*

+Y360257D01*

+X205985Y360264D01*

+X206215Y360319D01*

+X206433Y360409D01*

+X206634Y360533D01*

+X206814Y360686D01*

+X206967Y360866D01*

+X207091Y361067D01*

+X207181Y361285D01*

+X207236Y361515D01*

+X207250Y361750D01*

+X207236Y368485D01*

+X207181Y368715D01*

+X207091Y368933D01*

+X206967Y369134D01*

+X206814Y369314D01*

+X206634Y369467D01*

+X206433Y369591D01*

+X206215Y369681D01*

+X205985Y369736D01*

+X205750Y369750D01*

+X202500Y369743D01*

+Y390000D01*

+X209996D01*

+Y233507D01*

+X209608Y233477D01*

+X209225Y233385D01*

+X208862Y233234D01*

+X208526Y233029D01*

+X208227Y232773D01*

+X207971Y232474D01*

+X207766Y232138D01*

+X207615Y231775D01*

+X207523Y231392D01*

+X207492Y231000D01*

+X207523Y230608D01*

+X207615Y230225D01*

+X207766Y229862D01*

+X207971Y229526D01*

+X208227Y229227D01*

+X208526Y228971D01*

+X208862Y228766D01*

+X209225Y228615D01*

+X209608Y228523D01*

+X209996Y228493D01*

+Y207500D01*

+G37*

+G36*

+X202500D02*X192493D01*

+Y360236D01*

+X192500Y360235D01*

+X193245Y360294D01*

+X193972Y360469D01*

+X194663Y360755D01*

+X195301Y361145D01*

+X195869Y361631D01*

+X196355Y362199D01*

+X196745Y362837D01*

+X197031Y363528D01*

+X197206Y364255D01*

+X197250Y365000D01*

+X197206Y365745D01*

+X197031Y366472D01*

+X196745Y367163D01*

+X196355Y367801D01*

+X195869Y368369D01*

+X195301Y368855D01*

+X194663Y369245D01*

+X193972Y369531D01*

+X193245Y369706D01*

+X192500Y369765D01*

+X192493Y369764D01*

+Y390000D01*

+X202500D01*

+Y369743D01*

+X199015Y369736D01*

+X198785Y369681D01*

+X198567Y369591D01*

+X198366Y369467D01*

+X198186Y369314D01*

+X198033Y369134D01*

+X197909Y368933D01*

+X197819Y368715D01*

+X197764Y368485D01*

+X197750Y368250D01*

+X197764Y361515D01*

+X197819Y361285D01*

+X197909Y361067D01*

+X198033Y360866D01*

+X198186Y360686D01*

+X198366Y360533D01*

+X198567Y360409D01*

+X198785Y360319D01*

+X199015Y360264D01*

+X199250Y360250D01*

+X202500Y360257D01*

+Y316077D01*

+X202363Y315916D01*

+X202095Y315480D01*

+X201900Y315007D01*

+X201780Y314510D01*

+X201740Y314000D01*

+X201780Y313490D01*

+X201900Y312993D01*

+X202095Y312520D01*

+X202363Y312084D01*

+X202500Y311923D01*

+Y243598D01*

+X202492Y243500D01*

+X202500Y243402D01*

+Y231000D01*

+X202477Y231392D01*

+X202385Y231775D01*

+X202234Y232138D01*

+X202029Y232474D01*

+X201773Y232773D01*

+X201474Y233029D01*

+X201138Y233234D01*

+X200775Y233385D01*

+X200392Y233477D01*

+X200000Y233508D01*

+X199608Y233477D01*

+X199225Y233385D01*

+X198862Y233234D01*

+X198526Y233029D01*

+X198227Y232773D01*

+X197971Y232474D01*

+X197766Y232138D01*

+X197615Y231775D01*

+X197523Y231392D01*

+X197492Y231000D01*

+X197523Y230608D01*

+X197615Y230225D01*

+X197766Y229862D01*

+X197971Y229526D01*

+X198227Y229227D01*

+X198526Y228971D01*

+X198862Y228766D01*

+X199225Y228615D01*

+X199608Y228523D01*

+X200000Y228492D01*

+X200392Y228523D01*

+X200775Y228615D01*

+X201138Y228766D01*

+X201474Y228971D01*

+X201773Y229227D01*

+X202029Y229526D01*

+X202234Y229862D01*

+X202385Y230225D01*

+X202477Y230608D01*

+X202500Y231000D01*

+Y207500D01*

+G37*

+G36*

+X182493Y291382D02*X182564Y291061D01*

+X182625Y290599D01*

+X182646Y290134D01*

+X182625Y289669D01*

+X182564Y289207D01*

+X182493Y288886D01*

+Y291382D01*

+G37*

+G36*

+Y343114D02*X182564Y342793D01*

+X182625Y342331D01*

+X182646Y341866D01*

+X182625Y341401D01*

+X182564Y340939D01*

+X182493Y340618D01*

+Y343114D01*

+G37*

+G36*

+X188002Y390000D02*X192493D01*

+Y369764D01*

+X191755Y369706D01*

+X191028Y369531D01*

+X190337Y369245D01*

+X189699Y368855D01*

+X189131Y368369D01*

+X188645Y367801D01*

+X188255Y367163D01*

+X188002Y366552D01*

+Y390000D01*

+G37*

+G36*

+X192493Y207500D02*X191073D01*

+Y300256D01*

+X191115Y300274D01*

+X191183Y300314D01*

+X191243Y300365D01*

+X191294Y300424D01*

+X191334Y300492D01*

+X191488Y300817D01*

+X191606Y301156D01*

+X191692Y301506D01*

+X191743Y301861D01*

+X191760Y302220D01*

+X191743Y302580D01*

+X191692Y302935D01*

+X191606Y303285D01*

+X191488Y303624D01*

+X191338Y303951D01*

+X191297Y304018D01*

+X191245Y304078D01*

+X191184Y304129D01*

+X191117Y304170D01*

+X191073Y304188D01*

+Y309889D01*

+X191357Y310353D01*

+X191583Y310899D01*

+X191721Y311474D01*

+X191756Y312063D01*

+X191721Y312652D01*

+X191583Y313227D01*

+X191357Y313773D01*

+X191073Y314237D01*

+Y317763D01*

+X191357Y318227D01*

+X191583Y318773D01*

+X191721Y319348D01*

+X191756Y319937D01*

+X191721Y320526D01*

+X191583Y321101D01*

+X191357Y321647D01*

+X191073Y322111D01*

+Y327606D01*

+X191357Y328069D01*

+X191583Y328615D01*

+X191721Y329190D01*

+X191756Y329780D01*

+X191721Y330369D01*

+X191583Y330944D01*

+X191357Y331490D01*

+X191073Y331953D01*

+Y360458D01*

+X191755Y360294D01*

+X192493Y360236D01*

+Y207500D01*

+G37*

+G36*

+X191073Y331953D02*X191048Y331994D01*

+X190664Y332444D01*

+X190214Y332827D01*

+X189710Y333136D01*

+X189164Y333363D01*

+X188589Y333501D01*

+X188002Y333547D01*

+Y363448D01*

+X188255Y362837D01*

+X188645Y362199D01*

+X189131Y361631D01*

+X189699Y361145D01*

+X190337Y360755D01*

+X191028Y360469D01*

+X191073Y360458D01*

+Y331953D01*

+G37*

+G36*

+Y322111D02*X191048Y322151D01*

+X190664Y322601D01*

+X190214Y322985D01*

+X189710Y323294D01*

+X189164Y323520D01*

+X188589Y323658D01*

+X188002Y323704D01*

+Y326012D01*

+X188589Y326058D01*

+X189164Y326196D01*

+X189710Y326423D01*

+X190214Y326732D01*

+X190664Y327116D01*

+X191048Y327565D01*

+X191073Y327606D01*

+Y322111D01*

+G37*

+G36*

+Y314237D02*X191048Y314277D01*

+X190664Y314727D01*

+X190214Y315111D01*

+X189710Y315420D01*

+X189164Y315646D01*

+X188589Y315784D01*

+X188002Y315830D01*

+Y316170D01*

+X188589Y316216D01*

+X189164Y316354D01*

+X189710Y316580D01*

+X190214Y316889D01*

+X190664Y317273D01*

+X191048Y317723D01*

+X191073Y317763D01*

+Y314237D01*

+G37*

+G36*

+Y207500D02*X188002D01*

+Y298460D01*

+X188359Y298477D01*

+X188715Y298529D01*

+X189064Y298614D01*

+X189404Y298732D01*

+X189731Y298882D01*

+X189798Y298924D01*

+X189858Y298976D01*

+X189909Y299036D01*

+X189950Y299104D01*

+X189980Y299177D01*

+X189998Y299254D01*

+X190003Y299333D01*

+X189996Y299412D01*

+X189977Y299489D01*

+X189947Y299562D01*

+X189905Y299629D01*

+X189853Y299689D01*

+X189792Y299740D01*

+X189724Y299781D01*

+X189651Y299811D01*

+X189574Y299829D01*

+X189495Y299835D01*

+X189416Y299828D01*

+X189339Y299809D01*

+X189267Y299777D01*

+X189029Y299664D01*

+X188780Y299577D01*

+X188524Y299515D01*

+X188263Y299477D01*

+X188002Y299465D01*

+Y304976D01*

+X188263Y304964D01*

+X188524Y304926D01*

+X188780Y304864D01*

+X189029Y304777D01*

+X189268Y304667D01*

+X189340Y304635D01*

+X189417Y304616D01*

+X189495Y304610D01*

+X189573Y304615D01*

+X189650Y304633D01*

+X189723Y304663D01*

+X189790Y304703D01*

+X189851Y304754D01*

+X189902Y304813D01*

+X189944Y304880D01*

+X189974Y304953D01*

+X189993Y305029D01*

+X190000Y305108D01*

+X189994Y305186D01*

+X189977Y305263D01*

+X189947Y305336D01*

+X189906Y305403D01*

+X189856Y305463D01*

+X189796Y305515D01*

+X189729Y305555D01*

+X189404Y305709D01*

+X189064Y305827D01*

+X188715Y305912D01*

+X188359Y305963D01*

+X188002Y305981D01*

+Y308296D01*

+X188589Y308342D01*

+X189164Y308480D01*

+X189710Y308706D01*

+X190214Y309015D01*

+X190664Y309399D01*

+X191048Y309849D01*

+X191073Y309889D01*

+Y304188D01*

+X191043Y304200D01*

+X190966Y304218D01*

+X190887Y304224D01*

+X190808Y304217D01*

+X190731Y304198D01*

+X190658Y304167D01*

+X190591Y304125D01*

+X190531Y304073D01*

+X190480Y304013D01*

+X190439Y303945D01*

+X190409Y303872D01*

+X190392Y303794D01*

+X190386Y303715D01*

+X190393Y303637D01*

+X190412Y303560D01*

+X190444Y303487D01*

+X190557Y303249D01*

+X190643Y303000D01*

+X190706Y302744D01*

+X190743Y302484D01*

+X190756Y302220D01*

+X190743Y301957D01*

+X190706Y301696D01*

+X190643Y301440D01*

+X190557Y301192D01*

+X190447Y300952D01*

+X190415Y300880D01*

+X190396Y300804D01*

+X190389Y300726D01*

+X190395Y300647D01*

+X190413Y300570D01*

+X190442Y300497D01*

+X190483Y300430D01*

+X190533Y300370D01*

+X190593Y300318D01*

+X190660Y300277D01*

+X190732Y300246D01*

+X190809Y300227D01*

+X190887Y300220D01*

+X190966Y300226D01*

+X191042Y300244D01*

+X191073Y300256D01*

+Y207500D01*

+G37*

+G36*

+X184927Y317763D02*X184952Y317723D01*

+X185336Y317273D01*

+X185786Y316889D01*

+X186290Y316580D01*

+X186836Y316354D01*

+X187411Y316216D01*

+X188000Y316170D01*

+X188002Y316170D01*

+Y315830D01*

+X188000Y315830D01*

+X187411Y315784D01*

+X186836Y315646D01*

+X186290Y315420D01*

+X185786Y315111D01*

+X185336Y314727D01*

+X184952Y314277D01*

+X184927Y314237D01*

+Y317763D01*

+G37*

+G36*

+Y327606D02*X184952Y327565D01*

+X185336Y327116D01*

+X185786Y326732D01*

+X186290Y326423D01*

+X186836Y326196D01*

+X187411Y326058D01*

+X188000Y326012D01*

+X188002Y326012D01*

+Y323704D01*

+X188000Y323704D01*

+X187411Y323658D01*

+X186836Y323520D01*

+X186290Y323294D01*

+X185786Y322985D01*

+X185336Y322601D01*

+X184952Y322151D01*

+X184927Y322111D01*

+Y327606D01*

+G37*

+G36*

+Y360916D02*X185301Y361145D01*

+X185869Y361631D01*

+X186355Y362199D01*

+X186745Y362837D01*

+X187031Y363528D01*

+X187206Y364255D01*

+X187250Y365000D01*

+X187206Y365745D01*

+X187031Y366472D01*

+X186745Y367163D01*

+X186355Y367801D01*

+X185869Y368369D01*

+X185301Y368855D01*

+X184927Y369084D01*

+Y390000D01*

+X188002D01*

+Y366552D01*

+X187969Y366472D01*

+X187794Y365745D01*

+X187735Y365000D01*

+X187794Y364255D01*

+X187969Y363528D01*

+X188002Y363448D01*

+Y333547D01*

+X188000Y333547D01*

+X187411Y333501D01*

+X186836Y333363D01*

+X186290Y333136D01*

+X185786Y332827D01*

+X185336Y332444D01*

+X184952Y331994D01*

+X184927Y331953D01*

+Y360916D01*

+G37*

+G36*

+X188002Y207500D02*X184927D01*

+Y300253D01*

+X184957Y300241D01*

+X185034Y300223D01*

+X185113Y300217D01*

+X185192Y300224D01*

+X185269Y300243D01*

+X185342Y300274D01*

+X185409Y300316D01*

+X185469Y300368D01*

+X185520Y300428D01*

+X185561Y300496D01*

+X185591Y300569D01*

+X185608Y300647D01*

+X185614Y300726D01*

+X185607Y300804D01*

+X185588Y300881D01*

+X185556Y300954D01*

+X185443Y301192D01*

+X185357Y301440D01*

+X185294Y301696D01*

+X185257Y301957D01*

+X185244Y302220D01*

+X185257Y302484D01*

+X185294Y302744D01*

+X185357Y303000D01*

+X185443Y303249D01*

+X185553Y303489D01*

+X185585Y303561D01*

+X185604Y303637D01*

+X185611Y303715D01*

+X185605Y303794D01*

+X185587Y303871D01*

+X185558Y303944D01*

+X185517Y304011D01*

+X185467Y304071D01*

+X185407Y304123D01*

+X185340Y304164D01*

+X185268Y304195D01*

+X185191Y304214D01*

+X185113Y304220D01*

+X185034Y304215D01*

+X184958Y304197D01*

+X184927Y304185D01*

+Y309889D01*

+X184952Y309849D01*

+X185336Y309399D01*

+X185786Y309015D01*

+X186290Y308706D01*

+X186836Y308480D01*

+X187411Y308342D01*

+X188000Y308296D01*

+X188002Y308296D01*

+Y305981D01*

+X188000Y305981D01*

+X187641Y305963D01*

+X187285Y305912D01*

+X186936Y305827D01*

+X186596Y305709D01*

+X186269Y305559D01*

+X186202Y305517D01*

+X186142Y305465D01*

+X186091Y305405D01*

+X186050Y305337D01*

+X186020Y305264D01*

+X186002Y305186D01*

+X185997Y305108D01*

+X186004Y305029D01*

+X186023Y304952D01*

+X186053Y304879D01*

+X186095Y304812D01*

+X186147Y304752D01*

+X186208Y304701D01*

+X186276Y304660D01*

+X186349Y304630D01*

+X186426Y304612D01*

+X186505Y304606D01*

+X186584Y304613D01*

+X186661Y304632D01*

+X186733Y304664D01*

+X186971Y304777D01*

+X187220Y304864D01*

+X187476Y304926D01*

+X187737Y304964D01*

+X188000Y304976D01*

+X188002Y304976D01*

+Y299465D01*

+X188000Y299465D01*

+X187737Y299477D01*

+X187476Y299515D01*

+X187220Y299577D01*

+X186971Y299664D01*

+X186732Y299774D01*

+X186660Y299806D01*

+X186583Y299825D01*

+X186505Y299831D01*

+X186427Y299826D01*

+X186350Y299808D01*

+X186277Y299778D01*

+X186210Y299738D01*

+X186149Y299687D01*

+X186098Y299628D01*

+X186056Y299561D01*

+X186026Y299488D01*

+X186007Y299412D01*

+X186000Y299333D01*

+X186006Y299255D01*

+X186023Y299178D01*

+X186053Y299105D01*

+X186094Y299038D01*

+X186144Y298978D01*

+X186204Y298926D01*

+X186271Y298886D01*

+X186596Y298732D01*

+X186936Y298614D01*

+X187285Y298529D01*

+X187641Y298477D01*

+X188000Y298460D01*

+X188002Y298460D01*

+Y207500D01*

+G37*

+G36*

+X184927Y369084D02*X184663Y369245D01*

+X183972Y369531D01*

+X183245Y369706D01*

+X182500Y369765D01*

+X182493Y369764D01*

+Y390000D01*

+X184927D01*

+Y369084D01*

+G37*

+G36*

+Y207500D02*X182493D01*

+Y286496D01*

+X182494Y286499D01*

+X182798Y286961D01*

+X183055Y287452D01*

+X183267Y287963D01*

+X183435Y288491D01*

+X183555Y289032D01*

+X183627Y289581D01*

+X183652Y290134D01*

+X183627Y290687D01*

+X183555Y291236D01*

+X183435Y291777D01*

+X183267Y292304D01*

+X183055Y292816D01*

+X182798Y293306D01*

+X182499Y293773D01*

+X182493Y293781D01*

+Y338229D01*

+X182494Y338231D01*

+X182798Y338694D01*

+X183055Y339184D01*

+X183267Y339696D01*

+X183435Y340223D01*

+X183555Y340764D01*

+X183627Y341313D01*

+X183652Y341866D01*

+X183627Y342419D01*

+X183555Y342968D01*

+X183435Y343509D01*

+X183267Y344037D01*

+X183055Y344548D01*

+X182798Y345039D01*

+X182499Y345505D01*

+X182493Y345513D01*

+Y360236D01*

+X182500Y360235D01*

+X183245Y360294D01*

+X183972Y360469D01*

+X184663Y360755D01*

+X184927Y360916D01*

+Y331953D01*

+X184643Y331490D01*

+X184417Y330944D01*

+X184279Y330369D01*

+X184233Y329780D01*

+X184279Y329190D01*

+X184417Y328615D01*

+X184643Y328069D01*

+X184927Y327606D01*

+Y322111D01*

+X184643Y321647D01*

+X184417Y321101D01*

+X184279Y320526D01*

+X184233Y319937D01*

+X184279Y319348D01*

+X184417Y318773D01*

+X184643Y318227D01*

+X184927Y317763D01*

+Y314237D01*

+X184643Y313773D01*

+X184417Y313227D01*

+X184279Y312652D01*

+X184233Y312063D01*

+X184279Y311474D01*

+X184417Y310899D01*

+X184643Y310353D01*

+X184927Y309889D01*

+Y304185D01*

+X184885Y304167D01*

+X184817Y304127D01*

+X184757Y304076D01*

+X184706Y304017D01*

+X184666Y303949D01*

+X184512Y303624D01*

+X184394Y303285D01*

+X184308Y302935D01*

+X184257Y302580D01*

+X184240Y302220D01*

+X184257Y301861D01*

+X184308Y301506D01*

+X184394Y301156D01*

+X184512Y300817D01*

+X184662Y300490D01*

+X184703Y300422D01*

+X184755Y300363D01*

+X184816Y300312D01*

+X184883Y300271D01*

+X184927Y300253D01*

+Y207500D01*

+G37*

+G36*

+X182493D02*X177333D01*

+Y283813D01*

+X177884Y283837D01*

+X178433Y283910D01*

+X178973Y284030D01*

+X179501Y284197D01*

+X180013Y284410D01*

+X180503Y284667D01*

+X180970Y284965D01*

+X181031Y285016D01*

+X181084Y285075D01*

+X181126Y285142D01*

+X181158Y285215D01*

+X181177Y285292D01*

+X181185Y285372D01*

+X181180Y285451D01*

+X181162Y285528D01*

+X181133Y285602D01*

+X181093Y285671D01*

+X181042Y285732D01*

+X180982Y285785D01*

+X180915Y285827D01*

+X180842Y285859D01*

+X180765Y285878D01*

+X180686Y285886D01*

+X180606Y285881D01*

+X180529Y285863D01*

+X180455Y285834D01*

+X180387Y285792D01*

+X179998Y285537D01*

+X179586Y285321D01*

+X179156Y285142D01*

+X178712Y285002D01*

+X178257Y284900D01*

+X177796Y284839D01*

+X177333Y284819D01*

+Y295449D01*

+X177796Y295428D01*

+X178257Y295367D01*

+X178712Y295266D01*

+X179156Y295126D01*

+X179586Y294947D01*

+X179998Y294731D01*

+X180390Y294480D01*

+X180457Y294438D01*

+X180530Y294409D01*

+X180607Y294392D01*

+X180686Y294387D01*

+X180764Y294394D01*

+X180840Y294414D01*

+X180913Y294445D01*

+X180979Y294487D01*

+X181038Y294539D01*

+X181088Y294600D01*

+X181128Y294668D01*

+X181157Y294741D01*

+X181175Y294818D01*

+X181180Y294896D01*

+X181172Y294974D01*

+X181153Y295051D01*

+X181122Y295123D01*

+X181080Y295189D01*

+X181028Y295249D01*

+X180966Y295297D01*

+X180503Y295601D01*

+X180013Y295858D01*

+X179501Y296071D01*

+X178973Y296238D01*

+X178433Y296358D01*

+X177884Y296431D01*

+X177333Y296455D01*

+Y335545D01*

+X177884Y335569D01*

+X178433Y335642D01*

+X178973Y335762D01*

+X179501Y335929D01*

+X180013Y336142D01*

+X180503Y336399D01*

+X180970Y336698D01*

+X181031Y336748D01*

+X181084Y336807D01*

+X181126Y336875D01*

+X181158Y336948D01*

+X181177Y337025D01*

+X181185Y337104D01*

+X181180Y337183D01*

+X181162Y337261D01*

+X181133Y337335D01*

+X181093Y337403D01*

+X181042Y337464D01*

+X180982Y337517D01*

+X180915Y337559D01*

+X180842Y337591D01*

+X180765Y337611D01*

+X180686Y337618D01*

+X180606Y337613D01*

+X180529Y337596D01*

+X180455Y337566D01*

+X180387Y337524D01*

+X179998Y337269D01*

+X179586Y337053D01*

+X179156Y336874D01*

+X178712Y336734D01*

+X178257Y336633D01*

+X177796Y336572D01*

+X177333Y336551D01*

+Y347181D01*

+X177796Y347161D01*

+X178257Y347100D01*

+X178712Y346998D01*

+X179156Y346858D01*

+X179586Y346679D01*

+X179998Y346463D01*

+X180390Y346212D01*

+X180457Y346171D01*

+X180530Y346142D01*

+X180607Y346124D01*

+X180686Y346119D01*

+X180764Y346127D01*

+X180840Y346146D01*

+X180913Y346177D01*

+X180979Y346220D01*

+X181038Y346272D01*

+X181088Y346332D01*

+X181128Y346400D01*

+X181157Y346473D01*

+X181175Y346550D01*

+X181180Y346628D01*

+X181172Y346707D01*

+X181153Y346783D01*

+X181122Y346855D01*

+X181080Y346922D01*

+X181028Y346981D01*

+X180966Y347030D01*

+X180503Y347333D01*

+X180013Y347590D01*

+X179501Y347803D01*

+X178973Y347970D01*

+X178433Y348090D01*

+X177884Y348163D01*

+X177333Y348187D01*

+Y390000D01*

+X182493D01*

+Y369764D01*

+X181755Y369706D01*

+X181028Y369531D01*

+X180337Y369245D01*

+X179699Y368855D01*

+X179131Y368369D01*

+X178645Y367801D01*

+X178255Y367163D01*

+X177969Y366472D01*

+X177794Y365745D01*

+X177735Y365000D01*

+X177794Y364255D01*

+X177969Y363528D01*

+X178255Y362837D01*

+X178645Y362199D01*

+X179131Y361631D01*

+X179699Y361145D01*

+X180337Y360755D01*

+X181028Y360469D01*

+X181755Y360294D01*

+X182493Y360236D01*

+Y345513D01*

+X182449Y345567D01*

+X182389Y345619D01*

+X182322Y345662D01*

+X182249Y345693D01*

+X182172Y345713D01*

+X182093Y345720D01*

+X182014Y345715D01*

+X181936Y345698D01*

+X181862Y345668D01*

+X181794Y345628D01*

+X181733Y345577D01*

+X181680Y345518D01*

+X181638Y345450D01*

+X181606Y345377D01*

+X181586Y345300D01*

+X181579Y345221D01*

+X181584Y345142D01*

+X181601Y345064D01*

+X181631Y344990D01*

+X181672Y344923D01*

+X181928Y344534D01*

+X182144Y344121D01*

+X182322Y343691D01*

+X182463Y343247D01*

+X182493Y343114D01*

+Y340618D01*

+X182463Y340485D01*

+X182322Y340041D01*

+X182144Y339611D01*

+X181928Y339199D01*

+X181677Y338806D01*

+X181635Y338740D01*

+X181606Y338666D01*

+X181589Y338590D01*

+X181584Y338511D01*

+X181591Y338433D01*

+X181611Y338357D01*

+X181642Y338284D01*

+X181684Y338218D01*

+X181736Y338159D01*

+X181797Y338109D01*

+X181864Y338068D01*

+X181938Y338039D01*

+X182014Y338022D01*

+X182093Y338017D01*

+X182171Y338024D01*

+X182248Y338044D01*

+X182320Y338075D01*

+X182386Y338117D01*

+X182445Y338169D01*

+X182493Y338229D01*

+Y293781D01*

+X182449Y293834D01*

+X182389Y293887D01*

+X182322Y293929D01*

+X182249Y293961D01*

+X182172Y293981D01*

+X182093Y293988D01*

+X182014Y293983D01*

+X181936Y293966D01*

+X181862Y293936D01*

+X181794Y293896D01*

+X181733Y293845D01*

+X181680Y293785D01*

+X181638Y293718D01*

+X181606Y293645D01*

+X181586Y293568D01*

+X181579Y293489D01*

+X181584Y293410D01*

+X181601Y293332D01*

+X181631Y293258D01*

+X181672Y293191D01*

+X181928Y292801D01*

+X182144Y292389D01*

+X182322Y291959D01*

+X182463Y291515D01*

+X182493Y291382D01*

+Y288886D01*

+X182463Y288753D01*

+X182322Y288309D01*

+X182144Y287879D01*

+X181928Y287466D01*

+X181677Y287074D01*

+X181635Y287007D01*

+X181606Y286934D01*

+X181589Y286857D01*

+X181584Y286779D01*

+X181591Y286701D01*

+X181611Y286624D01*

+X181642Y286552D01*

+X181684Y286486D01*

+X181736Y286426D01*

+X181797Y286376D01*

+X181864Y286336D01*

+X181938Y286307D01*

+X182014Y286290D01*

+X182093Y286285D01*

+X182171Y286292D01*

+X182248Y286312D01*

+X182320Y286343D01*

+X182386Y286385D01*

+X182445Y286437D01*

+X182493Y286496D01*

+Y207500D01*

+G37*

+G36*

+X177333D02*X172493D01*

+Y286287D01*

+X172568Y286280D01*

+X172648Y286285D01*

+X172725Y286302D01*

+X172799Y286332D01*

+X172868Y286372D01*

+X172929Y286423D01*

+X172981Y286482D01*

+X173024Y286550D01*

+X173055Y286623D01*

+X173075Y286700D01*

+X173083Y286779D01*

+X173077Y286858D01*

+X173060Y286936D01*

+X173031Y287010D01*

+X172989Y287077D01*

+X172734Y287466D01*

+X172518Y287879D01*

+X172493Y287939D01*

+Y292328D01*

+X172518Y292389D01*

+X172734Y292801D01*

+X172985Y293194D01*

+X173026Y293260D01*

+X173055Y293334D01*

+X173072Y293410D01*

+X173077Y293489D01*

+X173070Y293567D01*

+X173051Y293643D01*

+X173019Y293716D01*

+X172977Y293782D01*

+X172925Y293841D01*

+X172865Y293891D01*

+X172797Y293932D01*

+X172724Y293961D01*

+X172647Y293978D01*

+X172568Y293983D01*

+X172493Y293976D01*

+Y338019D01*

+X172568Y338012D01*

+X172648Y338017D01*

+X172725Y338034D01*

+X172799Y338064D01*

+X172868Y338104D01*

+X172929Y338155D01*

+X172981Y338215D01*

+X173024Y338282D01*

+X173055Y338355D01*

+X173075Y338432D01*

+X173083Y338511D01*

+X173077Y338590D01*

+X173060Y338668D01*

+X173031Y338742D01*

+X172989Y338809D01*

+X172734Y339199D01*

+X172518Y339611D01*

+X172493Y339672D01*

+Y344061D01*

+X172518Y344121D01*

+X172734Y344534D01*

+X172985Y344926D01*

+X173026Y344993D01*

+X173055Y345066D01*

+X173072Y345143D01*

+X173077Y345221D01*

+X173070Y345299D01*

+X173051Y345376D01*

+X173019Y345448D01*

+X172977Y345514D01*

+X172925Y345574D01*

+X172865Y345624D01*

+X172797Y345664D01*

+X172724Y345693D01*

+X172647Y345710D01*

+X172568Y345715D01*

+X172493Y345708D01*

+Y360236D01*

+X172500Y360235D01*

+X173245Y360294D01*

+X173972Y360469D01*

+X174663Y360755D01*

+X175301Y361145D01*

+X175869Y361631D01*

+X176355Y362199D01*

+X176745Y362837D01*

+X177031Y363528D01*

+X177206Y364255D01*

+X177250Y365000D01*

+X177206Y365745D01*

+X177031Y366472D01*

+X176745Y367163D01*

+X176355Y367801D01*

+X175869Y368369D01*

+X175301Y368855D01*

+X174663Y369245D01*

+X173972Y369531D01*

+X173245Y369706D01*

+X172500Y369765D01*

+X172493Y369764D01*

+Y390000D01*

+X177333D01*

+Y348187D01*

+X177331Y348187D01*

+X176777Y348163D01*

+X176229Y348090D01*

+X175688Y347970D01*

+X175160Y347803D01*

+X174649Y347590D01*

+X174158Y347333D01*

+X173692Y347035D01*

+X173630Y346984D01*

+X173578Y346925D01*

+X173535Y346858D01*

+X173504Y346785D01*

+X173484Y346708D01*

+X173477Y346628D01*

+X173482Y346549D01*

+X173499Y346472D01*

+X173528Y346398D01*

+X173569Y346329D01*

+X173620Y346268D01*

+X173679Y346216D01*

+X173746Y346173D01*

+X173819Y346141D01*

+X173896Y346122D01*

+X173976Y346114D01*

+X174055Y346119D01*

+X174133Y346137D01*

+X174206Y346166D01*

+X174274Y346208D01*

+X174663Y346463D01*

+X175076Y346679D01*

+X175506Y346858D01*

+X175949Y346998D01*

+X176404Y347100D01*

+X176866Y347161D01*

+X177331Y347181D01*

+X177333Y347181D01*

+Y336551D01*

+X177331Y336551D01*

+X176866Y336572D01*

+X176404Y336633D01*

+X175949Y336734D01*

+X175506Y336874D01*

+X175076Y337053D01*

+X174663Y337269D01*

+X174271Y337520D01*

+X174204Y337562D01*

+X174131Y337591D01*

+X174054Y337608D01*

+X173976Y337613D01*

+X173897Y337606D01*

+X173821Y337586D01*

+X173749Y337555D01*

+X173682Y337513D01*

+X173623Y337461D01*

+X173573Y337400D01*

+X173533Y337332D01*

+X173504Y337259D01*

+X173487Y337182D01*

+X173482Y337104D01*

+X173489Y337026D01*

+X173509Y336949D01*

+X173540Y336877D01*

+X173582Y336811D01*

+X173634Y336751D01*

+X173695Y336703D01*

+X174158Y336399D01*

+X174649Y336142D01*

+X175160Y335929D01*

+X175688Y335762D01*

+X176229Y335642D01*

+X176777Y335569D01*

+X177331Y335545D01*

+X177333Y335545D01*

+Y296455D01*

+X177331Y296455D01*

+X176777Y296431D01*

+X176229Y296358D01*

+X175688Y296238D01*

+X175160Y296071D01*

+X174649Y295858D01*

+X174158Y295601D01*

+X173692Y295302D01*

+X173630Y295252D01*

+X173578Y295193D01*

+X173535Y295125D01*

+X173504Y295052D01*

+X173484Y294975D01*

+X173477Y294896D01*

+X173482Y294817D01*

+X173499Y294739D01*

+X173528Y294665D01*

+X173569Y294597D01*

+X173620Y294536D01*

+X173679Y294483D01*

+X173746Y294441D01*

+X173819Y294409D01*

+X173896Y294389D01*

+X173976Y294382D01*

+X174055Y294387D01*

+X174133Y294404D01*

+X174206Y294434D01*

+X174274Y294476D01*

+X174663Y294731D01*

+X175076Y294947D01*

+X175506Y295126D01*

+X175949Y295266D01*

+X176404Y295367D01*

+X176866Y295428D01*

+X177331Y295449D01*

+X177333Y295449D01*

+Y284819D01*

+X177331Y284819D01*

+X176866Y284839D01*

+X176404Y284900D01*

+X175949Y285002D01*

+X175506Y285142D01*

+X175076Y285321D01*

+X174663Y285537D01*

+X174271Y285788D01*

+X174204Y285829D01*

+X174131Y285858D01*

+X174054Y285876D01*

+X173976Y285881D01*

+X173897Y285873D01*

+X173821Y285854D01*

+X173749Y285823D01*

+X173682Y285780D01*

+X173623Y285728D01*

+X173573Y285668D01*

+X173533Y285600D01*

+X173504Y285527D01*

+X173487Y285450D01*

+X173482Y285372D01*

+X173489Y285293D01*

+X173509Y285217D01*

+X173540Y285145D01*

+X173582Y285078D01*

+X173634Y285019D01*

+X173695Y284970D01*

+X174158Y284667D01*

+X174649Y284410D01*

+X175160Y284197D01*

+X175688Y284030D01*

+X176229Y283910D01*

+X176777Y283837D01*

+X177331Y283813D01*

+X177333Y283813D01*

+Y207500D01*

+G37*

+G36*

+X172493Y287939D02*X172339Y288309D01*

+X172198Y288753D01*

+X172097Y289207D01*

+X172036Y289669D01*

+X172016Y290134D01*

+X172036Y290599D01*

+X172097Y291061D01*

+X172198Y291515D01*

+X172339Y291959D01*

+X172493Y292328D01*

+Y287939D01*

+G37*

+G36*

+Y339672D02*X172339Y340041D01*

+X172198Y340485D01*

+X172097Y340939D01*

+X172036Y341401D01*

+X172016Y341866D01*

+X172036Y342331D01*

+X172097Y342793D01*

+X172198Y343247D01*

+X172339Y343691D01*

+X172493Y344061D01*

+Y339672D01*

+G37*

+G36*

+Y207500D02*X162493D01*

+Y360236D01*

+X162500Y360235D01*

+X163245Y360294D01*

+X163972Y360469D01*

+X164663Y360755D01*

+X165301Y361145D01*

+X165869Y361631D01*

+X166355Y362199D01*

+X166745Y362837D01*

+X167031Y363528D01*

+X167206Y364255D01*

+X167250Y365000D01*

+X167206Y365745D01*

+X167031Y366472D01*

+X166745Y367163D01*

+X166355Y367801D01*

+X165869Y368369D01*

+X165301Y368855D01*

+X164663Y369245D01*

+X163972Y369531D01*

+X163245Y369706D01*

+X162500Y369765D01*

+X162493Y369764D01*

+Y390000D01*

+X172493D01*

+Y369764D01*

+X171755Y369706D01*

+X171028Y369531D01*

+X170337Y369245D01*

+X169699Y368855D01*

+X169131Y368369D01*

+X168645Y367801D01*

+X168255Y367163D01*

+X167969Y366472D01*

+X167794Y365745D01*

+X167735Y365000D01*

+X167794Y364255D01*

+X167969Y363528D01*

+X168255Y362837D01*

+X168645Y362199D01*

+X169131Y361631D01*

+X169699Y361145D01*

+X170337Y360755D01*

+X171028Y360469D01*

+X171755Y360294D01*

+X172493Y360236D01*

+Y345708D01*

+X172490Y345708D01*

+X172414Y345688D01*

+X172342Y345657D01*

+X172275Y345615D01*

+X172216Y345563D01*

+X172167Y345501D01*

+X171863Y345039D01*

+X171607Y344548D01*

+X171394Y344037D01*

+X171227Y343509D01*

+X171107Y342968D01*

+X171034Y342419D01*

+X171010Y341866D01*

+X171034Y341313D01*

+X171107Y340764D01*

+X171227Y340223D01*

+X171394Y339696D01*

+X171607Y339184D01*

+X171863Y338694D01*

+X172162Y338227D01*

+X172212Y338166D01*

+X172272Y338113D01*

+X172339Y338071D01*

+X172412Y338039D01*

+X172489Y338019D01*

+X172493Y338019D01*

+Y293976D01*

+X172490Y293976D01*

+X172414Y293956D01*

+X172342Y293925D01*

+X172275Y293883D01*

+X172216Y293831D01*

+X172167Y293769D01*

+X171863Y293306D01*

+X171607Y292816D01*

+X171394Y292304D01*

+X171227Y291777D01*

+X171107Y291236D01*

+X171034Y290687D01*

+X171010Y290134D01*

+X171034Y289581D01*

+X171107Y289032D01*

+X171227Y288491D01*

+X171394Y287963D01*

+X171607Y287452D01*

+X171863Y286961D01*

+X172162Y286495D01*

+X172212Y286433D01*

+X172272Y286381D01*

+X172339Y286338D01*

+X172412Y286307D01*

+X172489Y286287D01*

+X172493Y286287D01*

+Y207500D01*

+G37*

+G36*

+X162493D02*X149960D01*

+X150540Y208900D01*

+X150907Y210431D01*

+X151000Y212000D01*

+X150907Y213569D01*

+X150540Y215100D01*

+X149938Y216554D01*

+X149115Y217896D01*

+X148093Y219093D01*

+X146896Y220115D01*

+X145554Y220938D01*

+X144100Y221540D01*

+X142569Y221907D01*

+X141000Y222031D01*

+Y369969D01*

+X142569Y370093D01*

+X144100Y370460D01*

+X145554Y371062D01*

+X146896Y371885D01*

+X148093Y372907D01*

+X149115Y374104D01*

+X149938Y375446D01*

+X150540Y376900D01*

+X150907Y378431D01*

+X151000Y380000D01*

+X150907Y381569D01*

+X150540Y383100D01*

+X149938Y384554D01*

+X149115Y385896D01*

+X148093Y387093D01*

+X146896Y388115D01*

+X145554Y388938D01*

+X144100Y389540D01*

+X142569Y389907D01*

+X141392Y390000D01*

+X162493D01*

+Y369764D01*

+X161755Y369706D01*

+X161028Y369531D01*

+X160337Y369245D01*

+X159699Y368855D01*

+X159131Y368369D01*

+X158645Y367801D01*

+X158255Y367163D01*

+X157969Y366472D01*

+X157794Y365745D01*

+X157735Y365000D01*

+X157794Y364255D01*

+X157969Y363528D01*

+X158255Y362837D01*

+X158645Y362199D01*

+X159131Y361631D01*

+X159699Y361145D01*

+X160337Y360755D01*

+X161028Y360469D01*

+X161755Y360294D01*

+X162493Y360236D01*

+Y207500D01*

+G37*

+G36*

+X701500Y320500D02*Y222031D01*

+X699931Y221907D01*

+X698400Y221540D01*

+X696946Y220938D01*

+X695604Y220115D01*

+X694407Y219093D01*

+X693385Y217896D01*

+X692562Y216554D01*

+X691960Y215100D01*

+X691593Y213569D01*

+X691469Y212000D01*

+X667996D01*

+Y242993D01*

+X668000Y242992D01*

+X668392Y243023D01*

+X668775Y243115D01*

+X669138Y243266D01*

+X669474Y243471D01*

+X669773Y243727D01*

+X670029Y244026D01*

+X670234Y244362D01*

+X670385Y244725D01*

+X670477Y245108D01*

+X670500Y245500D01*

+X670477Y245892D01*

+X670385Y246275D01*

+X670234Y246638D01*

+X670029Y246974D01*

+X669773Y247273D01*

+X669474Y247529D01*

+X669138Y247734D01*

+X668775Y247885D01*

+X668392Y247977D01*

+X668000Y248008D01*

+X667996Y248007D01*

+Y320500D01*

+X701500D01*

+G37*

+G36*

+X667996Y212000D02*X648496D01*

+Y243493D01*

+X648500Y243492D01*

+X648892Y243523D01*

+X649275Y243615D01*

+X649638Y243766D01*

+X649974Y243971D01*

+X650273Y244227D01*

+X650529Y244526D01*

+X650734Y244862D01*

+X650885Y245225D01*

+X650977Y245608D01*

+X651000Y246000D01*

+X650977Y246392D01*

+X650885Y246775D01*

+X650734Y247138D01*

+X650529Y247474D01*

+X650273Y247773D01*

+X649974Y248029D01*

+X649638Y248234D01*

+X649275Y248385D01*

+X648892Y248477D01*

+X648500Y248508D01*

+X648496Y248507D01*

+Y275050D01*

+X648608Y275023D01*

+X649000Y274992D01*

+X649392Y275023D01*

+X649775Y275115D01*

+X650138Y275266D01*

+X650474Y275471D01*

+X650773Y275727D01*

+X651029Y276026D01*

+X651234Y276362D01*

+X651250Y276399D01*

+X651266Y276362D01*

+X651471Y276026D01*

+X651727Y275727D01*

+X652026Y275471D01*

+X652362Y275266D01*

+X652725Y275115D01*

+X653108Y275023D01*

+X653500Y274992D01*

+X653892Y275023D01*

+X654275Y275115D01*

+X654638Y275266D01*

+X654974Y275471D01*

+X655273Y275727D01*

+X655529Y276026D01*

+X655734Y276362D01*

+X655871Y276690D01*

+X655971Y276526D01*

+X656227Y276227D01*

+X656526Y275971D01*

+X656862Y275766D01*

+X657225Y275615D01*

+X657608Y275523D01*

+X658000Y275492D01*

+X658392Y275523D01*

+X658775Y275615D01*

+X659138Y275766D01*

+X659474Y275971D01*

+X659773Y276227D01*

+X660029Y276526D01*

+X660234Y276862D01*

+X660385Y277225D01*

+X660477Y277608D01*

+X660500Y278000D01*

+X660477Y278392D01*

+X660385Y278775D01*

+X660234Y279138D01*

+X660029Y279474D01*

+X659773Y279773D01*

+X659474Y280029D01*

+X659138Y280234D01*

+X658775Y280385D01*

+X658392Y280477D01*

+X658000Y280508D01*

+X657608Y280477D01*

+X657225Y280385D01*

+X656862Y280234D01*

+X656526Y280029D01*

+X656227Y279773D01*

+X655971Y279474D01*

+X655766Y279138D01*

+X655629Y278810D01*

+X655529Y278974D01*

+X655273Y279273D01*

+X654974Y279529D01*

+X654638Y279734D01*

+X654275Y279885D01*

+X653892Y279977D01*

+X653500Y280008D01*

+X653108Y279977D01*

+X652725Y279885D01*

+X652362Y279734D01*

+X652026Y279529D01*

+X651727Y279273D01*

+X651471Y278974D01*

+X651266Y278638D01*

+X651250Y278601D01*

+X651234Y278638D01*

+X651029Y278974D01*

+X650773Y279273D01*

+X650474Y279529D01*

+X650138Y279734D01*

+X649775Y279885D01*

+X649392Y279977D01*

+X649000Y280008D01*

+X648608Y279977D01*

+X648496Y279950D01*

+Y283207D01*

+X648638Y283266D01*

+X648974Y283471D01*

+X649273Y283727D01*

+X649529Y284026D01*

+X649734Y284362D01*

+X649885Y284725D01*

+X649977Y285108D01*

+X650000Y285500D01*

+X649977Y285892D01*

+X649885Y286275D01*

+X649734Y286638D01*

+X649529Y286974D01*

+X649273Y287273D01*

+X648974Y287529D01*

+X648638Y287734D01*

+X648496Y287793D01*

+Y339000D01*

+X661500D01*

+Y320500D01*

+X667996D01*

+Y248007D01*

+X667608Y247977D01*

+X667225Y247885D01*

+X666862Y247734D01*

+X666526Y247529D01*

+X666227Y247273D01*

+X665971Y246974D01*

+X665766Y246638D01*

+X665615Y246275D01*

+X665523Y245892D01*

+X665492Y245500D01*

+X665523Y245108D01*

+X665615Y244725D01*

+X665766Y244362D01*

+X665971Y244026D01*

+X666227Y243727D01*

+X666526Y243471D01*

+X666862Y243266D01*

+X667225Y243115D01*

+X667608Y243023D01*

+X667996Y242993D01*

+Y212000D01*

+G37*

+G36*

+X648496D02*X637496D01*

+Y300493D01*

+X637500Y300492D01*

+X637892Y300523D01*

+X638275Y300615D01*

+X638638Y300766D01*

+X638974Y300971D01*

+X639273Y301227D01*

+X639529Y301526D01*

+X639734Y301862D01*

+X639885Y302225D01*

+X639977Y302608D01*

+X640000Y303000D01*

+X639977Y303392D01*

+X639885Y303775D01*

+X639734Y304138D01*

+X639529Y304474D01*

+X639273Y304773D01*

+X638974Y305029D01*

+X638638Y305234D01*

+X638275Y305385D01*

+X637892Y305477D01*

+X637500Y305508D01*

+X637496Y305507D01*

+Y339000D01*

+X648496D01*

+Y287793D01*

+X648275Y287885D01*

+X647892Y287977D01*

+X647500Y288008D01*

+X647108Y287977D01*

+X646725Y287885D01*

+X646362Y287734D01*

+X646026Y287529D01*

+X645727Y287273D01*

+X645471Y286974D01*

+X645266Y286638D01*

+X645115Y286275D01*

+X645023Y285892D01*

+X644992Y285500D01*

+X645023Y285108D01*

+X645115Y284725D01*

+X645266Y284362D01*

+X645471Y284026D01*

+X645727Y283727D01*

+X646026Y283471D01*

+X646362Y283266D01*

+X646725Y283115D01*

+X647108Y283023D01*

+X647500Y282992D01*

+X647892Y283023D01*

+X648275Y283115D01*

+X648496Y283207D01*

+Y279950D01*

+X648225Y279885D01*

+X647862Y279734D01*

+X647526Y279529D01*

+X647227Y279273D01*

+X646971Y278974D01*

+X646766Y278638D01*

+X646615Y278275D01*

+X646523Y277892D01*

+X646492Y277500D01*

+X646523Y277108D01*

+X646615Y276725D01*

+X646766Y276362D01*

+X646971Y276026D01*

+X647227Y275727D01*

+X647526Y275471D01*

+X647862Y275266D01*

+X648225Y275115D01*

+X648496Y275050D01*

+Y248507D01*

+X648108Y248477D01*

+X647725Y248385D01*

+X647362Y248234D01*

+X647026Y248029D01*

+X646727Y247773D01*

+X646471Y247474D01*

+X646266Y247138D01*

+X646115Y246775D01*

+X646023Y246392D01*

+X645992Y246000D01*

+X646023Y245608D01*

+X646115Y245225D01*

+X646266Y244862D01*

+X646471Y244526D01*

+X646727Y244227D01*

+X647026Y243971D01*

+X647362Y243766D01*

+X647725Y243615D01*

+X648108Y243523D01*

+X648496Y243493D01*

+Y212000D01*

+G37*

+G36*

+X637496D02*X628496D01*

+Y243493D01*

+X628500Y243492D01*

+X628892Y243523D01*

+X629275Y243615D01*

+X629638Y243766D01*

+X629974Y243971D01*

+X630273Y244227D01*

+X630529Y244526D01*

+X630734Y244862D01*

+X630885Y245225D01*

+X630977Y245608D01*

+X631000Y246000D01*

+X630977Y246392D01*

+X630885Y246775D01*

+X630734Y247138D01*

+X630529Y247474D01*

+X630273Y247773D01*

+X629974Y248029D01*

+X629638Y248234D01*

+X629275Y248385D01*

+X628892Y248477D01*

+X628500Y248508D01*

+X628496Y248507D01*

+Y275990D01*

+X628773Y276227D01*

+X629029Y276526D01*

+X629234Y276862D01*

+X629385Y277225D01*

+X629477Y277608D01*

+X629500Y278000D01*

+X629477Y278392D01*

+X629385Y278775D01*

+X629234Y279138D01*

+X629029Y279474D01*

+X628773Y279773D01*

+X628496Y280010D01*

+Y323490D01*

+X628773Y323727D01*

+X629029Y324026D01*

+X629234Y324362D01*

+X629385Y324725D01*

+X629477Y325108D01*

+X629500Y325500D01*

+X629477Y325892D01*

+X629385Y326275D01*

+X629234Y326638D01*

+X629029Y326974D01*

+X628773Y327273D01*

+X628496Y327510D01*

+Y339000D01*

+X637496D01*

+Y305507D01*

+X637108Y305477D01*

+X636725Y305385D01*

+X636362Y305234D01*

+X636026Y305029D01*

+X635727Y304773D01*

+X635471Y304474D01*

+X635266Y304138D01*

+X635115Y303775D01*

+X635023Y303392D01*

+X634992Y303000D01*

+X635023Y302608D01*

+X635115Y302225D01*

+X635266Y301862D01*

+X635471Y301526D01*

+X635727Y301227D01*

+X636026Y300971D01*

+X636362Y300766D01*

+X636725Y300615D01*

+X637108Y300523D01*

+X637496Y300493D01*

+Y212000D01*

+G37*

+G36*

+X620996Y308997D02*X621026Y308971D01*

+X621362Y308766D01*

+X621399Y308750D01*

+X621362Y308734D01*

+X621026Y308529D01*

+X620996Y308503D01*

+Y308997D01*

+G37*

+G36*

+X628496Y212000D02*X620996D01*

+Y231493D01*

+X621000Y231492D01*

+X621392Y231523D01*

+X621775Y231615D01*

+X622138Y231766D01*

+X622474Y231971D01*

+X622773Y232227D01*

+X623029Y232526D01*

+X623234Y232862D01*

+X623385Y233225D01*

+X623477Y233608D01*

+X623500Y234000D01*

+X623477Y234392D01*

+X623385Y234775D01*

+X623234Y235138D01*

+X623029Y235474D01*

+X622773Y235773D01*

+X622474Y236029D01*

+X622138Y236234D01*

+X622101Y236250D01*

+X622138Y236266D01*

+X622474Y236471D01*

+X622773Y236727D01*

+X623029Y237026D01*

+X623234Y237362D01*

+X623385Y237725D01*

+X623477Y238108D01*

+X623500Y238500D01*

+X623477Y238892D01*

+X623385Y239275D01*

+X623234Y239638D01*

+X623029Y239974D01*

+X622773Y240273D01*

+X622474Y240529D01*

+X622138Y240734D01*

+X621775Y240885D01*

+X621392Y240977D01*

+X621000Y241008D01*

+X620996Y241007D01*

+Y304497D01*

+X621026Y304471D01*

+X621362Y304266D01*

+X621725Y304115D01*

+X622108Y304023D01*

+X622500Y303992D01*

+X622712Y304009D01*

+X622615Y303775D01*

+X622523Y303392D01*

+X622492Y303000D01*

+X622523Y302608D01*

+X622615Y302225D01*

+X622766Y301862D01*

+X622971Y301526D01*

+X623227Y301227D01*

+X623526Y300971D01*

+X623862Y300766D01*

+X624225Y300615D01*

+X624608Y300523D01*

+X625000Y300492D01*

+X625392Y300523D01*

+X625775Y300615D01*

+X626138Y300766D01*

+X626474Y300971D01*

+X626773Y301227D01*

+X627029Y301526D01*

+X627234Y301862D01*

+X627385Y302225D01*

+X627477Y302608D01*

+X627500Y303000D01*

+X627477Y303392D01*

+X627385Y303775D01*

+X627234Y304138D01*

+X627029Y304474D01*

+X626773Y304773D01*

+X626474Y305029D01*

+X626138Y305234D01*

+X625775Y305385D01*

+X625392Y305477D01*

+X625000Y305508D01*

+X624788Y305491D01*

+X624885Y305725D01*

+X624977Y306108D01*

+X625000Y306500D01*

+X624977Y306892D01*

+X624885Y307275D01*

+X624734Y307638D01*

+X624529Y307974D01*

+X624273Y308273D01*

+X623974Y308529D01*

+X623638Y308734D01*

+X623601Y308750D01*

+X623638Y308766D01*

+X623974Y308971D01*

+X624273Y309227D01*

+X624529Y309526D01*

+X624734Y309862D01*

+X624885Y310225D01*

+X624977Y310608D01*

+X625000Y311000D01*

+X624977Y311392D01*

+X624885Y311775D01*

+X624734Y312138D01*

+X624529Y312474D01*

+X624273Y312773D01*

+X623974Y313029D01*

+X623638Y313234D01*

+X623275Y313385D01*

+X622892Y313477D01*

+X622500Y313508D01*

+X622108Y313477D01*

+X621725Y313385D01*

+X621362Y313234D01*

+X621026Y313029D01*

+X620996Y313003D01*

+Y317997D01*

+X621026Y317971D01*

+X621362Y317766D01*

+X621725Y317615D01*

+X622108Y317523D01*

+X622500Y317492D01*

+X622892Y317523D01*

+X623275Y317615D01*

+X623638Y317766D01*

+X623974Y317971D01*

+X624273Y318227D01*

+X624529Y318526D01*

+X624734Y318862D01*

+X624885Y319225D01*

+X624977Y319608D01*

+X625000Y320000D01*

+X624977Y320392D01*

+X624885Y320775D01*

+X624734Y321138D01*

+X624529Y321474D01*

+X624273Y321773D01*

+X623974Y322029D01*

+X623638Y322234D01*

+X623275Y322385D01*

+X622892Y322477D01*

+X622500Y322508D01*

+X622108Y322477D01*

+X621725Y322385D01*

+X621362Y322234D01*

+X621026Y322029D01*

+X620996Y322003D01*

+Y339000D01*

+X628496D01*

+Y327510D01*

+X628474Y327529D01*

+X628138Y327734D01*

+X627775Y327885D01*

+X627392Y327977D01*

+X627000Y328008D01*

+X626608Y327977D01*

+X626225Y327885D01*

+X625862Y327734D01*

+X625526Y327529D01*

+X625227Y327273D01*

+X624971Y326974D01*

+X624766Y326638D01*

+X624615Y326275D01*

+X624523Y325892D01*

+X624492Y325500D01*

+X624523Y325108D01*

+X624615Y324725D01*

+X624766Y324362D01*

+X624971Y324026D01*

+X625227Y323727D01*

+X625526Y323471D01*

+X625862Y323266D01*

+X626225Y323115D01*

+X626608Y323023D01*

+X627000Y322992D01*

+X627392Y323023D01*

+X627775Y323115D01*

+X628138Y323266D01*

+X628474Y323471D01*

+X628496Y323490D01*

+Y280010D01*

+X628474Y280029D01*

+X628138Y280234D01*

+X627775Y280385D01*

+X627392Y280477D01*

+X627000Y280508D01*

+X626608Y280477D01*

+X626225Y280385D01*

+X625862Y280234D01*

+X625526Y280029D01*

+X625227Y279773D01*

+X624971Y279474D01*

+X624766Y279138D01*

+X624615Y278775D01*

+X624523Y278392D01*

+X624492Y278000D01*

+X624523Y277608D01*

+X624615Y277225D01*

+X624766Y276862D01*

+X624971Y276526D01*

+X625227Y276227D01*

+X625526Y275971D01*

+X625862Y275766D01*

+X626225Y275615D01*

+X626608Y275523D01*

+X627000Y275492D01*

+X627392Y275523D01*

+X627775Y275615D01*

+X628138Y275766D01*

+X628474Y275971D01*

+X628496Y275990D01*

+Y248507D01*

+X628108Y248477D01*

+X627725Y248385D01*

+X627362Y248234D01*

+X627026Y248029D01*

+X626727Y247773D01*

+X626471Y247474D01*

+X626266Y247138D01*

+X626115Y246775D01*

+X626023Y246392D01*

+X625992Y246000D01*

+X626023Y245608D01*

+X626115Y245225D01*

+X626266Y244862D01*

+X626471Y244526D01*

+X626727Y244227D01*

+X627026Y243971D01*

+X627362Y243766D01*

+X627725Y243615D01*

+X628108Y243523D01*

+X628496Y243493D01*

+Y212000D01*

+G37*

+G36*

+X620996D02*X616496D01*

+Y277993D01*

+X616500Y277992D01*

+X616892Y278023D01*

+X617275Y278115D01*

+X617638Y278266D01*

+X617974Y278471D01*

+X618273Y278727D01*

+X618529Y279026D01*

+X618734Y279362D01*

+X618885Y279725D01*

+X618977Y280108D01*

+X619000Y280500D01*

+X618977Y280892D01*

+X618885Y281275D01*

+X618734Y281638D01*

+X618529Y281974D01*

+X618273Y282273D01*

+X617974Y282529D01*

+X617638Y282734D01*

+X617275Y282885D01*

+X616892Y282977D01*

+X616500Y283008D01*

+X616496Y283007D01*

+Y287993D01*

+X616500Y287992D01*

+X616892Y288023D01*

+X617275Y288115D01*

+X617638Y288266D01*

+X617974Y288471D01*

+X618273Y288727D01*

+X618529Y289026D01*

+X618734Y289362D01*

+X618885Y289725D01*

+X618977Y290108D01*

+X619000Y290500D01*

+X618977Y290892D01*

+X618885Y291275D01*

+X618734Y291638D01*

+X618529Y291974D01*

+X618273Y292273D01*

+X617974Y292529D01*

+X617638Y292734D01*

+X617275Y292885D01*

+X616892Y292977D01*

+X616500Y293008D01*

+X616496Y293007D01*

+Y339000D01*

+X620996D01*

+Y322003D01*

+X620727Y321773D01*

+X620471Y321474D01*

+X620266Y321138D01*

+X620115Y320775D01*

+X620023Y320392D01*

+X619992Y320000D01*

+X620023Y319608D01*

+X620115Y319225D01*

+X620266Y318862D01*

+X620471Y318526D01*

+X620727Y318227D01*

+X620996Y317997D01*

+Y313003D01*

+X620727Y312773D01*

+X620471Y312474D01*

+X620266Y312138D01*

+X620115Y311775D01*

+X620023Y311392D01*

+X619992Y311000D01*

+X620023Y310608D01*

+X620115Y310225D01*

+X620266Y309862D01*

+X620471Y309526D01*

+X620727Y309227D01*

+X620996Y308997D01*

+Y308503D01*

+X620727Y308273D01*

+X620471Y307974D01*

+X620266Y307638D01*

+X620115Y307275D01*

+X620023Y306892D01*

+X619992Y306500D01*

+X620023Y306108D01*

+X620115Y305725D01*

+X620266Y305362D01*

+X620471Y305026D01*

+X620727Y304727D01*

+X620996Y304497D01*

+Y241007D01*

+X620608Y240977D01*

+X620225Y240885D01*

+X619862Y240734D01*

+X619526Y240529D01*

+X619227Y240273D01*

+X618971Y239974D01*

+X618766Y239638D01*

+X618615Y239275D01*

+X618523Y238892D01*

+X618492Y238500D01*

+X618523Y238108D01*

+X618615Y237725D01*

+X618766Y237362D01*

+X618971Y237026D01*

+X619227Y236727D01*

+X619526Y236471D01*

+X619862Y236266D01*

+X619899Y236250D01*

+X619862Y236234D01*

+X619526Y236029D01*

+X619227Y235773D01*

+X618971Y235474D01*

+X618766Y235138D01*

+X618615Y234775D01*

+X618523Y234392D01*

+X618492Y234000D01*

+X618523Y233608D01*

+X618615Y233225D01*

+X618766Y232862D01*

+X618971Y232526D01*

+X619227Y232227D01*

+X619526Y231971D01*

+X619862Y231766D01*

+X620225Y231615D01*

+X620608Y231523D01*

+X620996Y231493D01*

+Y212000D01*

+G37*

+G36*

+X616496D02*X597996D01*

+Y290993D01*

+X598000Y290992D01*

+X598392Y291023D01*

+X598775Y291115D01*

+X599138Y291266D01*

+X599474Y291471D01*

+X599773Y291727D01*

+X600029Y292026D01*

+X600234Y292362D01*

+X600385Y292725D01*

+X600477Y293108D01*

+X600500Y293500D01*

+X600477Y293892D01*

+X600385Y294275D01*

+X600234Y294638D01*

+X600029Y294974D01*

+X599773Y295273D01*

+X599474Y295529D01*

+X599138Y295734D01*

+X598775Y295885D01*

+X598392Y295977D01*

+X598000Y296008D01*

+X597996Y296007D01*

+Y301996D01*

+X600500Y304500D01*

+Y332500D01*

+X607000Y339000D01*

+X616496D01*

+Y293007D01*

+X616108Y292977D01*

+X615725Y292885D01*

+X615362Y292734D01*

+X615026Y292529D01*

+X614727Y292273D01*

+X614471Y291974D01*

+X614266Y291638D01*

+X614115Y291275D01*

+X614023Y290892D01*

+X613992Y290500D01*

+X614023Y290108D01*

+X614115Y289725D01*

+X614266Y289362D01*

+X614471Y289026D01*

+X614727Y288727D01*

+X615026Y288471D01*

+X615362Y288266D01*

+X615725Y288115D01*

+X616108Y288023D01*

+X616496Y287993D01*

+Y283007D01*

+X616108Y282977D01*

+X615725Y282885D01*

+X615362Y282734D01*

+X615026Y282529D01*

+X614727Y282273D01*

+X614471Y281974D01*

+X614266Y281638D01*

+X614115Y281275D01*

+X614023Y280892D01*

+X613992Y280500D01*

+X614023Y280108D01*

+X614115Y279725D01*

+X614266Y279362D01*

+X614471Y279026D01*

+X614727Y278727D01*

+X615026Y278471D01*

+X615362Y278266D01*

+X615725Y278115D01*

+X616108Y278023D01*

+X616496Y277993D01*

+Y212000D01*

+G37*

+G36*

+X597996D02*X593996D01*

+Y242993D01*

+X594000Y242992D01*

+X594392Y243023D01*

+X594775Y243115D01*

+X595138Y243266D01*

+X595474Y243471D01*

+X595773Y243727D01*

+X596029Y244026D01*

+X596234Y244362D01*

+X596385Y244725D01*

+X596477Y245108D01*

+X596500Y245500D01*

+X596477Y245892D01*

+X596385Y246275D01*

+X596234Y246638D01*

+X596029Y246974D01*

+X595773Y247273D01*

+X595474Y247529D01*

+X595138Y247734D01*

+X594775Y247885D01*

+X594392Y247977D01*

+X594000Y248008D01*

+X593996Y248007D01*

+Y275048D01*

+X594275Y275115D01*

+X594638Y275266D01*

+X594974Y275471D01*

+X595273Y275727D01*

+X595529Y276026D01*

+X595734Y276362D01*

+X595885Y276725D01*

+X595977Y277108D01*

+X596000Y277500D01*

+X595977Y277892D01*

+X595885Y278275D01*

+X595734Y278638D01*

+X595529Y278974D01*

+X595273Y279273D01*

+X594974Y279529D01*

+X594638Y279734D01*

+X594275Y279885D01*

+X593996Y279952D01*

+Y297996D01*

+X597996Y301996D01*

+Y296007D01*

+X597608Y295977D01*

+X597225Y295885D01*

+X596862Y295734D01*

+X596526Y295529D01*

+X596227Y295273D01*

+X595971Y294974D01*

+X595766Y294638D01*

+X595615Y294275D01*

+X595523Y293892D01*

+X595492Y293500D01*

+X595523Y293108D01*

+X595615Y292725D01*

+X595766Y292362D01*

+X595971Y292026D01*

+X596227Y291727D01*

+X596526Y291471D01*

+X596862Y291266D01*

+X597225Y291115D01*

+X597608Y291023D01*

+X597996Y290993D01*

+Y212000D01*

+G37*

+G36*

+X593996Y279952D02*X593892Y279977D01*

+X593500Y280008D01*

+X593108Y279977D01*

+X592725Y279885D01*

+X592362Y279734D01*

+X592026Y279529D01*

+X592000Y279507D01*

+Y296000D01*

+X593996Y297996D01*

+Y279952D01*

+G37*

+G36*

+Y212000D02*X584995D01*

+Y251938D01*

+X585084Y251863D01*

+X585520Y251595D01*

+X585993Y251400D01*

+X586490Y251280D01*

+X587000Y251240D01*

+X587510Y251280D01*

+X588007Y251400D01*

+X588480Y251595D01*

+X588916Y251863D01*

+X589305Y252195D01*

+X589637Y252584D01*

+X589905Y253020D01*

+X590100Y253493D01*

+X590220Y253990D01*

+X590250Y254500D01*

+X590220Y255010D01*

+X590100Y255507D01*

+X589905Y255980D01*

+X589637Y256416D01*

+X589305Y256805D01*

+X588916Y257137D01*

+X588480Y257405D01*

+X588007Y257600D01*

+X587510Y257720D01*

+X587000Y257760D01*

+X586490Y257720D01*

+X585993Y257600D01*

+X585520Y257405D01*

+X585445Y257359D01*

+X585637Y257584D01*

+X585905Y258020D01*

+X586100Y258493D01*

+X586220Y258990D01*

+X586250Y259500D01*

+X586220Y260010D01*

+X586100Y260507D01*

+X585905Y260980D01*

+X585637Y261416D01*

+X585445Y261641D01*

+X585520Y261595D01*

+X585993Y261400D01*

+X586490Y261280D01*

+X587000Y261240D01*

+X587510Y261280D01*

+X588007Y261400D01*

+X588480Y261595D01*

+X588916Y261863D01*

+X589305Y262195D01*

+X589637Y262584D01*

+X589905Y263020D01*

+X590100Y263493D01*

+X590220Y263990D01*

+X590250Y264500D01*

+X590220Y265010D01*

+X590100Y265507D01*

+X589905Y265980D01*

+X589637Y266416D01*

+X589305Y266805D01*

+X588916Y267137D01*

+X588480Y267405D01*

+X588007Y267600D01*

+X587510Y267720D01*

+X587000Y267760D01*

+X586490Y267720D01*

+X585993Y267600D01*

+X585520Y267405D01*

+X585084Y267137D01*

+X584995Y267062D01*

+Y268000D01*

+X592000D01*

+Y275493D01*

+X592026Y275471D01*

+X592362Y275266D01*

+X592725Y275115D01*

+X593108Y275023D01*

+X593500Y274992D01*

+X593892Y275023D01*

+X593996Y275048D01*

+Y248007D01*

+X593608Y247977D01*

+X593225Y247885D01*

+X592862Y247734D01*

+X592526Y247529D01*

+X592227Y247273D01*

+X591971Y246974D01*

+X591766Y246638D01*

+X591615Y246275D01*

+X591523Y245892D01*

+X591492Y245500D01*

+X591523Y245108D01*

+X591615Y244725D01*

+X591766Y244362D01*

+X591971Y244026D01*

+X592227Y243727D01*

+X592526Y243471D01*

+X592862Y243266D01*

+X593225Y243115D01*

+X593608Y243023D01*

+X593996Y242993D01*

+Y212000D01*

+G37*

+G36*

+X584995D02*X494000D01*

+Y256843D01*

+X494037Y256372D01*

+X494184Y255760D01*

+X494425Y255178D01*

+X494754Y254642D01*

+X495163Y254163D01*

+X495642Y253754D01*

+X496178Y253425D01*

+X496760Y253184D01*

+X497372Y253037D01*

+X498000Y252988D01*

+X498628Y253037D01*

+X499240Y253184D01*

+X499822Y253425D01*

+X500358Y253754D01*

+X500837Y254163D01*

+X501246Y254642D01*

+X501575Y255178D01*

+X501816Y255760D01*

+X501963Y256372D01*

+X502000Y257000D01*

+X501963Y257628D01*

+X501816Y258240D01*

+X501575Y258822D01*

+X501246Y259358D01*

+X500837Y259837D01*

+X500358Y260246D01*

+X499944Y260500D01*

+X500358Y260754D01*

+X500837Y261163D01*

+X501246Y261642D01*

+X501575Y262178D01*

+X501816Y262760D01*

+X501963Y263372D01*

+X502000Y264000D01*

+X501963Y264628D01*

+X501816Y265240D01*

+X501575Y265822D01*

+X501246Y266358D01*

+X500837Y266837D01*

+X500358Y267246D01*

+X499822Y267575D01*

+X499240Y267816D01*

+X498628Y267963D01*

+X498157Y268000D01*

+X584995D01*

+Y267062D01*

+X584695Y266805D01*

+X584363Y266416D01*

+X584095Y265980D01*

+X583900Y265507D01*

+X583780Y265010D01*

+X583740Y264500D01*

+X583780Y263990D01*

+X583900Y263493D01*

+X584095Y263020D01*

+X584363Y262584D01*

+X584555Y262359D01*

+X584480Y262405D01*

+X584007Y262600D01*

+X583510Y262720D01*

+X583000Y262760D01*

+X582490Y262720D01*

+X581993Y262600D01*

+X581520Y262405D01*

+X581084Y262137D01*

+X580695Y261805D01*

+X580363Y261416D01*

+X580095Y260980D01*

+X579900Y260507D01*

+X579780Y260010D01*

+X579740Y259500D01*

+X579780Y258990D01*

+X579900Y258493D01*

+X580095Y258020D01*

+X580363Y257584D01*

+X580695Y257195D01*

+X581084Y256863D01*

+X581520Y256595D01*

+X581993Y256400D01*

+X582490Y256280D01*

+X583000Y256240D01*

+X583510Y256280D01*

+X584007Y256400D01*

+X584480Y256595D01*

+X584555Y256641D01*

+X584363Y256416D01*

+X584095Y255980D01*

+X583900Y255507D01*

+X583780Y255010D01*

+X583740Y254500D01*

+X583780Y253990D01*

+X583900Y253493D01*

+X584095Y253020D01*

+X584363Y252584D01*

+X584695Y252195D01*

+X584995Y251938D01*

+Y212000D01*

+G37*

+G36*

+X646250Y368250D02*Y361750D01*

+X652750D01*

+Y368250D01*

+X646250D01*

+G37*

+G54D54*X639500Y365000D03*

+G54D55*X666110Y374000D03*

+X679890D03*

+X666110Y352346D03*

+X679890D03*

+G54D54*X629500Y365000D03*

+X619500D03*

+G54D56*X701500Y380000D03*

+G54D57*X631000Y290500D03*

+Y286760D03*

+Y294240D03*

+X636709Y290500D03*

+X625291D03*

+G54D56*X701500Y212000D03*

+G54D54*X609500Y365000D03*

+G54D53*G36*

+X525250Y368250D02*Y361750D01*

+X531750D01*

+Y368250D01*

+X525250D01*

+G37*

+G54D54*X518500Y365000D03*

+G54D53*G36*

+X550750Y368250D02*Y361750D01*

+X557250D01*

+Y368250D01*

+X550750D01*

+G37*

+G54D54*X544000Y365000D03*

+X599500D03*

+G54D55*X569110Y374000D03*

+X582890D03*

+Y352346D03*

+X569110D03*

+G54D58*X554500Y329780D03*

+Y312063D03*

+X528500D03*

+X554500Y302220D03*

+G54D59*X543831Y290134D03*

+G54D58*X528500Y302220D03*

+G54D59*X517831Y290134D03*

+G54D58*X554500Y319937D03*

+G54D59*X543831Y341866D03*

+G54D58*X528500Y329780D03*

+Y319937D03*

+G54D59*X517831Y341866D03*

+G54D53*G36*

+X243000Y220500D02*Y214500D01*

+X249000D01*

+Y220500D01*

+X243000D01*

+G37*

+G54D60*X256000Y217500D03*

+X266000D03*

+X276000D03*

+X286000D03*

+X296000D03*

+X306000D03*

+X316000D03*

+X326000D03*

+X336000D03*

+X346000D03*

+X356000D03*

+X366000D03*

+X376000D03*

+X386000D03*

+X396000D03*

+X406000D03*

+X416000D03*

+X406000Y277500D03*

+X396000D03*

+X386000D03*

+X376000D03*

+X366000D03*

+X356000D03*

+X346000D03*

+X336000D03*

+X326000D03*

+X316000D03*

+X306000D03*

+X296000D03*

+X286000D03*

+X276000D03*

+X266000D03*

+X256000D03*

+X246000D03*

+X426000Y217500D03*

+X436000D03*

+X446000D03*

+X456000D03*

+X466000D03*

+X476000D03*

+Y277500D03*

+X466000D03*

+X456000D03*

+X446000D03*

+X436000D03*

+X426000D03*

+X416000D03*

+G54D58*X410000Y329780D03*

+G54D59*X399331Y341866D03*

+G54D58*X410000Y319937D03*

+Y312063D03*

+Y302220D03*

+G54D59*X399331Y290134D03*

+G54D53*G36*

+X447750Y368250D02*Y361750D01*

+X454250D01*

+Y368250D01*

+X447750D01*

+G37*

+G54D54*X441000Y365000D03*

+G54D53*G36*

+X421250Y368250D02*Y361750D01*

+X427750D01*

+Y368250D01*

+X421250D01*

+G37*

+G54D54*X414500Y365000D03*

+G54D53*G36*

+X473250Y368250D02*Y361750D01*

+X479750D01*

+Y368250D01*

+X473250D01*

+G37*

+G54D54*X466500Y365000D03*

+G54D53*G36*

+X498750Y368250D02*Y361750D01*

+X505250D01*

+Y368250D01*

+X498750D01*

+G37*

+G54D54*X492000Y365000D03*

+X404500D03*

+X394500D03*

+X384500D03*

+G54D53*G36*

+X365750Y368250D02*Y361750D01*

+X372250D01*

+Y368250D01*

+X365750D01*

+G37*

+G54D54*X359000Y365000D03*

+X349000D03*

+X339000D03*

+X329000D03*

+G54D58*X354500Y329780D03*

+G54D59*X343831Y341866D03*

+G54D53*G36*

+X310250Y368250D02*Y361750D01*

+X316750D01*

+Y368250D01*

+X310250D01*

+G37*

+G54D54*X303500Y365000D03*

+X293500D03*

+X283500D03*

+X273500D03*

+G54D53*G36*

+X254750Y368250D02*Y361750D01*

+X261250D01*

+Y368250D01*

+X254750D01*

+G37*

+G54D54*X248000Y365000D03*

+X238000D03*

+X228000D03*

+X218000D03*

+G54D53*G36*

+X199250Y368250D02*Y361750D01*

+X205750D01*

+Y368250D01*

+X199250D01*

+G37*

+G54D54*X192500Y365000D03*

+X182500D03*

+X172500D03*

+X162500D03*

+G54D56*X141000Y380000D03*

+G54D58*X354500Y319937D03*

+X299000D03*

+Y312063D03*

+Y302220D03*

+G54D59*X288331Y290134D03*

+G54D58*X354500Y312063D03*

+Y302220D03*

+G54D59*X343831Y290134D03*

+G54D58*X299000Y329780D03*

+G54D59*X288331Y341866D03*

+G54D58*X243500Y329780D03*

+Y319937D03*

+Y312063D03*

+Y302220D03*

+X188000D03*

+G54D59*X232831Y341866D03*

+G54D58*X188000Y329780D03*

+Y319937D03*

+Y312063D03*

+G54D59*X177331Y341866D03*

+X232831Y290134D03*

+X177331D03*

+G54D56*X141000Y212000D03*

+G54D61*X628500Y246000D03*

+X653500Y277500D03*

+X648500Y246000D03*

+X658000Y278000D03*

+X649000Y277500D03*

+X668000Y245500D03*

+X680500Y244000D03*

+Y237500D03*

+X662500Y232000D03*

+X655000D03*

+X599500D03*

+X607500D03*

+X691500Y237500D03*

+Y244000D03*

+X686000Y231000D03*

+X598000Y293500D03*

+X569000Y297500D03*

+X575500Y285000D03*

+X621000Y234000D03*

+Y238500D03*

+X594000Y245500D03*

+G54D62*X587000Y264500D03*

+Y254500D03*

+X583000Y259500D03*

+G54D61*X562000Y316000D03*

+X532500Y288000D03*

+X593500Y277500D03*

+X627000Y278000D03*

+X616500Y280500D03*

+Y290500D03*

+X625000Y303000D03*

+X622500Y306500D03*

+X647500Y285500D03*

+X637500Y303000D03*

+X622500Y311000D03*

+Y320000D03*

+X627000Y325500D03*

+G54D62*X596000Y320000D03*

+G54D61*Y312500D03*

+X570500Y244000D03*

+X581500Y237500D03*

+Y244000D03*

+X576000Y231000D03*

+X570500Y237500D03*

+X539000Y244000D03*

+Y237500D03*

+X518500D03*

+Y244000D03*

+X513000Y231000D03*

+X507500Y237500D03*

+X550000D03*

+X544500Y231000D03*

+X550000Y244000D03*

+X507500D03*

+X449500Y313500D03*

+G54D60*X462500Y311500D03*

+X442000Y326000D03*

+G54D62*X496000Y332000D03*

+X246000Y338500D03*

+X274000D03*

+X263000D03*

+G54D61*X422500Y331500D03*

+X416000Y373500D03*

+X313500Y323500D03*

+G54D60*X513500Y332000D03*

+G54D61*X569000Y328500D03*

+G54D63*X576000Y322500D03*

+G54D62*X568500Y323500D03*

+G54D60*X563500Y334500D03*

+X554500Y339000D03*

+G54D61*X583000Y328500D03*

+G54D62*X583500Y323500D03*

+X596500Y333500D03*

+X589000D03*

+Y326000D03*

+X596500D03*

+G54D61*X573500Y348500D03*

+X564500D03*

+X578000Y349000D03*

+G54D63*X591500Y350000D03*

+G54D61*X646500Y351500D03*

+X595000Y352000D03*

+G54D63*X588000Y363000D03*

+Y359000D03*

+G54D60*X606000Y381500D03*

+X600500Y386500D03*

+X595000Y381500D03*

+X589500Y386500D03*

+G54D61*X360500Y373500D03*

+X305000D03*

+X249500D03*

+X194000D03*

+X278500Y380000D03*

+X271000Y268000D03*

+X281000D03*

+X291000D03*

+X301000D03*

+G54D62*X492500Y294000D03*

+X485000D03*

+X476500D03*

+X471000D03*

+G54D61*X494500Y286500D03*

+X415500D03*

+G54D62*X483000Y323000D03*

+G54D60*X502000Y315000D03*

+X498000Y257000D03*

+G54D61*X246000Y261500D03*

+X429000Y254500D03*

+G54D60*X498000Y264000D03*

+G54D61*X463500Y243500D03*

+X489500Y274000D03*

+X464500Y264000D03*

+X465500Y270000D03*

+X449500Y240000D03*

+X455000Y250000D03*

+G54D62*X191500Y258000D03*

+Y237000D03*

+X205000Y314000D03*

+X213500D03*

+X221000D03*

+G54D61*X386000Y233500D03*

+X376500Y306500D03*

+X225000Y243500D03*

+X215000D03*

+X205000D03*

+X220000Y231000D03*

+X210000D03*

+X200000D03*

+X329500Y240500D03*

+X339000Y234500D03*

+X337000Y242000D03*

+X343500Y245000D03*

+G54D64*G54D65*G54D64*G54D65*G54D64*G54D66*G54D65*G54D64*G54D66*G54D64*G54D67*G54D65*G54D66*G54D64*G54D65*G54D64*G54D67*G54D64*G54D67*G54D66*G54D64*G54D65*G54D64*G54D65*G54D66*G54D64*G54D66*G54D64*G54D65*G54D64*G54D68*G54D69*G54D68*G54D70*G54D71*G54D70*G54D68*G54D69*G54D72*G54D73*G54D72*G54D73*G54D72*G54D73*G54D72*G54D73*G54D74*G54D72*G54D73*G54D72*G54D73*G54D68*G54D72*G54D73*G54D68*G54D70*G54D72*G54D73*G54D72*G54D73*G54D72*G54D73*G54D72*G54D73*G54D72*G54D73*G54D70*M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.group2.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.group2.gbr
new file mode 100644
index 0000000..900cbdc
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.group2.gbr
@@ -0,0 +1,1790 @@
+G04 start of page 4 for group 2 idx 2 *

+G04 Title: uart, signal3 *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNGROUP2*%

+%ADD100C,0.0380*%

+%ADD99C,0.0906*%

+%ADD98C,0.0354*%

+%ADD97C,0.0118*%

+%ADD96C,0.1285*%

+%ADD95C,0.0433*%

+%ADD94C,0.0400*%

+%ADD93C,0.0118*%

+%ADD92C,0.0200*%

+%ADD91C,0.0240*%

+%ADD90C,0.0450*%

+%ADD89C,0.0360*%

+%ADD88C,0.0600*%

+%ADD87C,0.1063*%

+%ADD86C,0.0551*%

+%ADD85C,0.0256*%

+%ADD84C,0.1800*%

+%ADD83C,0.0630*%

+%ADD82C,0.0060*%

+%ADD81C,0.0350*%

+%ADD80C,0.0100*%

+%ADD79C,0.0150*%

+%ADD78C,0.0650*%

+%ADD77C,0.0250*%

+%ADD76C,0.1150*%

+%ADD75C,0.0001*%

+G54D75*G36*

+X691496Y379657D02*X691593Y378431D01*

+X691960Y376900D01*

+X692562Y375446D01*

+X693385Y374104D01*

+X694407Y372907D01*

+X695604Y371885D01*

+X696946Y371062D01*

+X698400Y370460D01*

+X699931Y370093D01*

+X701500Y369969D01*

+Y222031D01*

+X699931Y221907D01*

+X698400Y221540D01*

+X696946Y220938D01*

+X695604Y220115D01*

+X694407Y219093D01*

+X693385Y217896D01*

+X692562Y216554D01*

+X691960Y215100D01*

+X691593Y213569D01*

+X691496Y212343D01*

+Y234993D01*

+X691500Y234992D01*

+X691892Y235023D01*

+X692275Y235115D01*

+X692638Y235266D01*

+X692974Y235471D01*

+X693273Y235727D01*

+X693529Y236026D01*

+X693734Y236362D01*

+X693885Y236725D01*

+X693977Y237108D01*

+X694000Y237500D01*

+X693977Y237892D01*

+X693885Y238275D01*

+X693734Y238638D01*

+X693529Y238974D01*

+X693273Y239273D01*

+X692974Y239529D01*

+X692638Y239734D01*

+X692275Y239885D01*

+X691892Y239977D01*

+X691500Y240008D01*

+X691496Y240007D01*

+Y241493D01*

+X691500Y241492D01*

+X691892Y241523D01*

+X692275Y241615D01*

+X692638Y241766D01*

+X692974Y241971D01*

+X693273Y242227D01*

+X693529Y242526D01*

+X693734Y242862D01*

+X693885Y243225D01*

+X693977Y243608D01*

+X694000Y244000D01*

+X693977Y244392D01*

+X693885Y244775D01*

+X693734Y245138D01*

+X693529Y245474D01*

+X693273Y245773D01*

+X692974Y246029D01*

+X692638Y246234D01*

+X692275Y246385D01*

+X691892Y246477D01*

+X691500Y246508D01*

+X691496Y246507D01*

+Y379657D01*

+G37*

+G36*

+X685996Y380000D02*X691469D01*

+X691496Y379657D01*

+Y246507D01*

+X691108Y246477D01*

+X690725Y246385D01*

+X690362Y246234D01*

+X690026Y246029D01*

+X689727Y245773D01*

+X689471Y245474D01*

+X689266Y245138D01*

+X689115Y244775D01*

+X689023Y244392D01*

+X688992Y244000D01*

+X689023Y243608D01*

+X689115Y243225D01*

+X689266Y242862D01*

+X689471Y242526D01*

+X689727Y242227D01*

+X690026Y241971D01*

+X690362Y241766D01*

+X690725Y241615D01*

+X691108Y241523D01*

+X691496Y241493D01*

+Y240007D01*

+X691108Y239977D01*

+X690725Y239885D01*

+X690362Y239734D01*

+X690026Y239529D01*

+X689727Y239273D01*

+X689471Y238974D01*

+X689266Y238638D01*

+X689115Y238275D01*

+X689023Y237892D01*

+X688992Y237500D01*

+X689023Y237108D01*

+X689115Y236725D01*

+X689266Y236362D01*

+X689471Y236026D01*

+X689727Y235727D01*

+X690026Y235471D01*

+X690362Y235266D01*

+X690725Y235115D01*

+X691108Y235023D01*

+X691496Y234993D01*

+Y212343D01*

+X691469Y212000D01*

+X685996D01*

+Y228493D01*

+X686000Y228492D01*

+X686392Y228523D01*

+X686775Y228615D01*

+X687138Y228766D01*

+X687474Y228971D01*

+X687773Y229227D01*

+X688029Y229526D01*

+X688234Y229862D01*

+X688385Y230225D01*

+X688477Y230608D01*

+X688500Y231000D01*

+X688477Y231392D01*

+X688385Y231775D01*

+X688234Y232138D01*

+X688029Y232474D01*

+X687773Y232773D01*

+X687474Y233029D01*

+X687138Y233234D01*

+X686775Y233385D01*

+X686392Y233477D01*

+X686000Y233508D01*

+X685996Y233507D01*

+Y380000D01*

+G37*

+G36*

+X680496D02*X685996D01*

+Y233507D01*

+X685608Y233477D01*

+X685225Y233385D01*

+X684862Y233234D01*

+X684526Y233029D01*

+X684227Y232773D01*

+X683971Y232474D01*

+X683766Y232138D01*

+X683615Y231775D01*

+X683523Y231392D01*

+X683492Y231000D01*

+X683523Y230608D01*

+X683615Y230225D01*

+X683766Y229862D01*

+X683971Y229526D01*

+X684227Y229227D01*

+X684526Y228971D01*

+X684862Y228766D01*

+X685225Y228615D01*

+X685608Y228523D01*

+X685996Y228493D01*

+Y212000D01*

+X680496D01*

+Y234993D01*

+X680500Y234992D01*

+X680892Y235023D01*

+X681275Y235115D01*

+X681638Y235266D01*

+X681974Y235471D01*

+X682273Y235727D01*

+X682529Y236026D01*

+X682734Y236362D01*

+X682885Y236725D01*

+X682977Y237108D01*

+X683000Y237500D01*

+X682977Y237892D01*

+X682885Y238275D01*

+X682734Y238638D01*

+X682529Y238974D01*

+X682273Y239273D01*

+X681974Y239529D01*

+X681638Y239734D01*

+X681275Y239885D01*

+X680892Y239977D01*

+X680500Y240008D01*

+X680496Y240007D01*

+Y241493D01*

+X680500Y241492D01*

+X680892Y241523D01*

+X681275Y241615D01*

+X681638Y241766D01*

+X681974Y241971D01*

+X682273Y242227D01*

+X682529Y242526D01*

+X682734Y242862D01*

+X682885Y243225D01*

+X682977Y243608D01*

+X683000Y244000D01*

+X682977Y244392D01*

+X682885Y244775D01*

+X682734Y245138D01*

+X682529Y245474D01*

+X682273Y245773D01*

+X681974Y246029D01*

+X681638Y246234D01*

+X681275Y246385D01*

+X680892Y246477D01*

+X680500Y246508D01*

+X680496Y246507D01*

+Y348232D01*

+X680541Y348235D01*

+X681176Y348388D01*

+X681779Y348638D01*

+X682336Y348979D01*

+X682833Y349403D01*

+X683257Y349900D01*

+X683598Y350457D01*

+X683848Y351060D01*

+X684001Y351695D01*

+X684039Y352346D01*

+X684001Y352998D01*

+X683848Y353633D01*

+X683598Y354236D01*

+X683257Y354793D01*

+X682833Y355290D01*

+X682336Y355714D01*

+X681779Y356055D01*

+X681176Y356305D01*

+X680541Y356458D01*

+X680496Y356461D01*

+Y369885D01*

+X680541Y369889D01*

+X681176Y370041D01*

+X681779Y370291D01*

+X682336Y370633D01*

+X682833Y371057D01*

+X683257Y371553D01*

+X683598Y372110D01*

+X683848Y372714D01*

+X684001Y373349D01*

+X684039Y374000D01*

+X684001Y374651D01*

+X683848Y375286D01*

+X683598Y375890D01*

+X683257Y376447D01*

+X682833Y376943D01*

+X682336Y377367D01*

+X681779Y377709D01*

+X681176Y377959D01*

+X680541Y378111D01*

+X680496Y378115D01*

+Y380000D01*

+G37*

+G36*

+X667996D02*X680496D01*

+Y378115D01*

+X679890Y378162D01*

+X679239Y378111D01*

+X678604Y377959D01*

+X678000Y377709D01*

+X677443Y377367D01*

+X676946Y376943D01*

+X676522Y376447D01*

+X676181Y375890D01*

+X675931Y375286D01*

+X675779Y374651D01*

+X675727Y374000D01*

+X675779Y373349D01*

+X675931Y372714D01*

+X676181Y372110D01*

+X676522Y371553D01*

+X676946Y371057D01*

+X677443Y370633D01*

+X678000Y370291D01*

+X678604Y370041D01*

+X679239Y369889D01*

+X679890Y369838D01*

+X680496Y369885D01*

+Y356461D01*

+X679890Y356509D01*

+X679239Y356458D01*

+X678604Y356305D01*

+X678000Y356055D01*

+X677443Y355714D01*

+X676946Y355290D01*

+X676522Y354793D01*

+X676181Y354236D01*

+X675931Y353633D01*

+X675779Y352998D01*

+X675727Y352346D01*

+X675779Y351695D01*

+X675931Y351060D01*

+X676181Y350457D01*

+X676522Y349900D01*

+X676946Y349403D01*

+X677443Y348979D01*

+X678000Y348638D01*

+X678604Y348388D01*

+X679239Y348235D01*

+X679890Y348184D01*

+X680496Y348232D01*

+Y246507D01*

+X680108Y246477D01*

+X679725Y246385D01*

+X679362Y246234D01*

+X679026Y246029D01*

+X678727Y245773D01*

+X678471Y245474D01*

+X678266Y245138D01*

+X678115Y244775D01*

+X678023Y244392D01*

+X677992Y244000D01*

+X678023Y243608D01*

+X678115Y243225D01*

+X678266Y242862D01*

+X678471Y242526D01*

+X678727Y242227D01*

+X679026Y241971D01*

+X679362Y241766D01*

+X679725Y241615D01*

+X680108Y241523D01*

+X680496Y241493D01*

+Y240007D01*

+X680108Y239977D01*

+X679725Y239885D01*

+X679362Y239734D01*

+X679026Y239529D01*

+X678727Y239273D01*

+X678471Y238974D01*

+X678266Y238638D01*

+X678115Y238275D01*

+X678023Y237892D01*

+X677992Y237500D01*

+X678023Y237108D01*

+X678115Y236725D01*

+X678266Y236362D01*

+X678471Y236026D01*

+X678727Y235727D01*

+X679026Y235471D01*

+X679362Y235266D01*

+X679725Y235115D01*

+X680108Y235023D01*

+X680496Y234993D01*

+Y212000D01*

+X667996D01*

+Y242993D01*

+X668000Y242992D01*

+X668392Y243023D01*

+X668775Y243115D01*

+X669138Y243266D01*

+X669474Y243471D01*

+X669773Y243727D01*

+X670029Y244026D01*

+X670234Y244362D01*

+X670385Y244725D01*

+X670477Y245108D01*

+X670500Y245500D01*

+X670477Y245892D01*

+X670385Y246275D01*

+X670234Y246638D01*

+X670029Y246974D01*

+X669773Y247273D01*

+X669474Y247529D01*

+X669138Y247734D01*

+X668775Y247885D01*

+X668392Y247977D01*

+X668000Y248008D01*

+X667996Y248007D01*

+Y380000D01*

+G37*

+G36*

+X662496D02*X667996D01*

+Y248007D01*

+X667608Y247977D01*

+X667225Y247885D01*

+X666862Y247734D01*

+X666526Y247529D01*

+X666227Y247273D01*

+X665971Y246974D01*

+X665766Y246638D01*

+X665615Y246275D01*

+X665523Y245892D01*

+X665492Y245500D01*

+X665523Y245108D01*

+X665615Y244725D01*

+X665766Y244362D01*

+X665971Y244026D01*

+X666227Y243727D01*

+X666526Y243471D01*

+X666862Y243266D01*

+X667225Y243115D01*

+X667608Y243023D01*

+X667996Y242993D01*

+Y212000D01*

+X662496D01*

+Y229493D01*

+X662500Y229492D01*

+X662892Y229523D01*

+X663275Y229615D01*

+X663638Y229766D01*

+X663974Y229971D01*

+X664273Y230227D01*

+X664529Y230526D01*

+X664734Y230862D01*

+X664885Y231225D01*

+X664977Y231608D01*

+X665000Y232000D01*

+X664977Y232392D01*

+X664885Y232775D01*

+X664734Y233138D01*

+X664529Y233474D01*

+X664273Y233773D01*

+X663974Y234029D01*

+X663638Y234234D01*

+X663275Y234385D01*

+X662892Y234477D01*

+X662500Y234508D01*

+X662496Y234507D01*

+Y380000D01*

+G37*

+G36*

+X654996Y268000D02*X658000D01*

+Y271107D01*

+X658021Y271132D01*

+X659868Y272979D01*

+X659951Y273049D01*

+X660231Y273378D01*

+X660232Y273379D01*

+X660458Y273748D01*

+X660623Y274148D01*

+X660725Y274568D01*

+X660758Y275000D01*

+X660750Y275108D01*

+Y278000D01*

+X660725Y278432D01*

+X660623Y278852D01*

+X660458Y279252D01*

+X660232Y279621D01*

+X659951Y279951D01*

+X659621Y280232D01*

+X659252Y280458D01*

+X658852Y280623D01*

+X658432Y280725D01*

+X658000Y280758D01*

+Y380000D01*

+X662496D01*

+Y234507D01*

+X662108Y234477D01*

+X661725Y234385D01*

+X661362Y234234D01*

+X661026Y234029D01*

+X660727Y233773D01*

+X660471Y233474D01*

+X660266Y233138D01*

+X660115Y232775D01*

+X660023Y232392D01*

+X659992Y232000D01*

+X660023Y231608D01*

+X660115Y231225D01*

+X660266Y230862D01*

+X660471Y230526D01*

+X660727Y230227D01*

+X661026Y229971D01*

+X661362Y229766D01*

+X661725Y229615D01*

+X662108Y229523D01*

+X662496Y229493D01*

+Y212000D01*

+X654996D01*

+Y229493D01*

+X655000Y229492D01*

+X655392Y229523D01*

+X655775Y229615D01*

+X656138Y229766D01*

+X656474Y229971D01*

+X656773Y230227D01*

+X657029Y230526D01*

+X657234Y230862D01*

+X657385Y231225D01*

+X657477Y231608D01*

+X657500Y232000D01*

+X657477Y232392D01*

+X657385Y232775D01*

+X657234Y233138D01*

+X657029Y233474D01*

+X656773Y233773D01*

+X656474Y234029D01*

+X656138Y234234D01*

+X655775Y234385D01*

+X655392Y234477D01*

+X655000Y234508D01*

+X654996Y234507D01*

+Y268000D01*

+G37*

+G36*

+X648496D02*X654996D01*

+Y234507D01*

+X654608Y234477D01*

+X654225Y234385D01*

+X653862Y234234D01*

+X653526Y234029D01*

+X653227Y233773D01*

+X652971Y233474D01*

+X652766Y233138D01*

+X652615Y232775D01*

+X652523Y232392D01*

+X652492Y232000D01*

+X652523Y231608D01*

+X652615Y231225D01*

+X652766Y230862D01*

+X652971Y230526D01*

+X653227Y230227D01*

+X653526Y229971D01*

+X653862Y229766D01*

+X654225Y229615D01*

+X654608Y229523D01*

+X654996Y229493D01*

+Y212000D01*

+X648496D01*

+Y243493D01*

+X648500Y243492D01*

+X648892Y243523D01*

+X649275Y243615D01*

+X649638Y243766D01*

+X649974Y243971D01*

+X650273Y244227D01*

+X650529Y244526D01*

+X650734Y244862D01*

+X650885Y245225D01*

+X650977Y245608D01*

+X651000Y246000D01*

+X650977Y246392D01*

+X650885Y246775D01*

+X650734Y247138D01*

+X650529Y247474D01*

+X650273Y247773D01*

+X649974Y248029D01*

+X649638Y248234D01*

+X649275Y248385D01*

+X648892Y248477D01*

+X648500Y248508D01*

+X648496Y248507D01*

+Y268000D01*

+G37*

+G36*

+X628496D02*X648496D01*

+Y248507D01*

+X648108Y248477D01*

+X647725Y248385D01*

+X647362Y248234D01*

+X647026Y248029D01*

+X646727Y247773D01*

+X646471Y247474D01*

+X646266Y247138D01*

+X646115Y246775D01*

+X646023Y246392D01*

+X645992Y246000D01*

+X646023Y245608D01*

+X646115Y245225D01*

+X646266Y244862D01*

+X646471Y244526D01*

+X646727Y244227D01*

+X647026Y243971D01*

+X647362Y243766D01*

+X647725Y243615D01*

+X648108Y243523D01*

+X648496Y243493D01*

+Y212000D01*

+X628496D01*

+Y243493D01*

+X628500Y243492D01*

+X628892Y243523D01*

+X629275Y243615D01*

+X629638Y243766D01*

+X629974Y243971D01*

+X630273Y244227D01*

+X630529Y244526D01*

+X630734Y244862D01*

+X630885Y245225D01*

+X630977Y245608D01*

+X631000Y246000D01*

+X630977Y246392D01*

+X630885Y246775D01*

+X630734Y247138D01*

+X630529Y247474D01*

+X630273Y247773D01*

+X629974Y248029D01*

+X629638Y248234D01*

+X629275Y248385D01*

+X628892Y248477D01*

+X628500Y248508D01*

+X628496Y248507D01*

+Y268000D01*

+G37*

+G36*

+X620996D02*X628496D01*

+Y248507D01*

+X628108Y248477D01*

+X627725Y248385D01*

+X627362Y248234D01*

+X627026Y248029D01*

+X626727Y247773D01*

+X626471Y247474D01*

+X626266Y247138D01*

+X626115Y246775D01*

+X626023Y246392D01*

+X625992Y246000D01*

+X626023Y245608D01*

+X626115Y245225D01*

+X626266Y244862D01*

+X626471Y244526D01*

+X626727Y244227D01*

+X627026Y243971D01*

+X627362Y243766D01*

+X627725Y243615D01*

+X628108Y243523D01*

+X628496Y243493D01*

+Y212000D01*

+X620996D01*

+Y231493D01*

+X621000Y231492D01*

+X621392Y231523D01*

+X621775Y231615D01*

+X622138Y231766D01*

+X622474Y231971D01*

+X622773Y232227D01*

+X623029Y232526D01*

+X623234Y232862D01*

+X623385Y233225D01*

+X623477Y233608D01*

+X623500Y234000D01*

+X623477Y234392D01*

+X623385Y234775D01*

+X623234Y235138D01*

+X623029Y235474D01*

+X622773Y235773D01*

+X622474Y236029D01*

+X622138Y236234D01*

+X622101Y236250D01*

+X622138Y236266D01*

+X622474Y236471D01*

+X622773Y236727D01*

+X623029Y237026D01*

+X623234Y237362D01*

+X623385Y237725D01*

+X623477Y238108D01*

+X623500Y238500D01*

+X623477Y238892D01*

+X623385Y239275D01*

+X623234Y239638D01*

+X623029Y239974D01*

+X622773Y240273D01*

+X622474Y240529D01*

+X622138Y240734D01*

+X621775Y240885D01*

+X621392Y240977D01*

+X621000Y241008D01*

+X620996Y241007D01*

+Y268000D01*

+G37*

+G36*

+X607496D02*X620996D01*

+Y241007D01*

+X620608Y240977D01*

+X620225Y240885D01*

+X619862Y240734D01*

+X619526Y240529D01*

+X619227Y240273D01*

+X618971Y239974D01*

+X618766Y239638D01*

+X618615Y239275D01*

+X618523Y238892D01*

+X618492Y238500D01*

+X618523Y238108D01*

+X618615Y237725D01*

+X618766Y237362D01*

+X618971Y237026D01*

+X619227Y236727D01*

+X619526Y236471D01*

+X619862Y236266D01*

+X619899Y236250D01*

+X619862Y236234D01*

+X619526Y236029D01*

+X619227Y235773D01*

+X618971Y235474D01*

+X618766Y235138D01*

+X618615Y234775D01*

+X618523Y234392D01*

+X618492Y234000D01*

+X618523Y233608D01*

+X618615Y233225D01*

+X618766Y232862D01*

+X618971Y232526D01*

+X619227Y232227D01*

+X619526Y231971D01*

+X619862Y231766D01*

+X620225Y231615D01*

+X620608Y231523D01*

+X620996Y231493D01*

+Y212000D01*

+X607496D01*

+Y229493D01*

+X607500Y229492D01*

+X607892Y229523D01*

+X608275Y229615D01*

+X608638Y229766D01*

+X608974Y229971D01*

+X609273Y230227D01*

+X609529Y230526D01*

+X609734Y230862D01*

+X609885Y231225D01*

+X609977Y231608D01*

+X610000Y232000D01*

+X609977Y232392D01*

+X609885Y232775D01*

+X609734Y233138D01*

+X609529Y233474D01*

+X609273Y233773D01*

+X608974Y234029D01*

+X608638Y234234D01*

+X608275Y234385D01*

+X607892Y234477D01*

+X607500Y234508D01*

+X607496Y234507D01*

+Y268000D01*

+G37*

+G36*

+X599496D02*X607496D01*

+Y234507D01*

+X607108Y234477D01*

+X606725Y234385D01*

+X606362Y234234D01*

+X606026Y234029D01*

+X605727Y233773D01*

+X605471Y233474D01*

+X605266Y233138D01*

+X605115Y232775D01*

+X605023Y232392D01*

+X604992Y232000D01*

+X605023Y231608D01*

+X605115Y231225D01*

+X605266Y230862D01*

+X605471Y230526D01*

+X605727Y230227D01*

+X606026Y229971D01*

+X606362Y229766D01*

+X606725Y229615D01*

+X607108Y229523D01*

+X607496Y229493D01*

+Y212000D01*

+X599496D01*

+Y229493D01*

+X599500Y229492D01*

+X599892Y229523D01*

+X600275Y229615D01*

+X600638Y229766D01*

+X600974Y229971D01*

+X601273Y230227D01*

+X601529Y230526D01*

+X601734Y230862D01*

+X601885Y231225D01*

+X601977Y231608D01*

+X602000Y232000D01*

+X601977Y232392D01*

+X601885Y232775D01*

+X601734Y233138D01*

+X601529Y233474D01*

+X601273Y233773D01*

+X600974Y234029D01*

+X600638Y234234D01*

+X600275Y234385D01*

+X599892Y234477D01*

+X599500Y234508D01*

+X599496Y234507D01*

+Y268000D01*

+G37*

+G36*

+X581496D02*X595800D01*

+Y248997D01*

+X594705Y247902D01*

+X594392Y247977D01*

+X594000Y248008D01*

+X593608Y247977D01*

+X593225Y247885D01*

+X592862Y247734D01*

+X592526Y247529D01*

+X592227Y247273D01*

+X591971Y246974D01*

+X591766Y246638D01*

+X591615Y246275D01*

+X591523Y245892D01*

+X591492Y245500D01*

+X591523Y245108D01*

+X591615Y244725D01*

+X591766Y244362D01*

+X591971Y244026D01*

+X592227Y243727D01*

+X592526Y243471D01*

+X592862Y243266D01*

+X593225Y243115D01*

+X593608Y243023D01*

+X594000Y242992D01*

+X594392Y243023D01*

+X594775Y243115D01*

+X595138Y243266D01*

+X595474Y243471D01*

+X595773Y243727D01*

+X596029Y244026D01*

+X596234Y244362D01*

+X596385Y244725D01*

+X596477Y245108D01*

+X596500Y245500D01*

+X596477Y245892D01*

+X596402Y246205D01*

+X597815Y247618D01*

+X597851Y247649D01*

+X597974Y247792D01*

+X597974Y247792D01*

+X598073Y247954D01*

+X598145Y248128D01*

+X598189Y248312D01*

+X598204Y248500D01*

+X598200Y248547D01*

+Y268000D01*

+X599496D01*

+Y234507D01*

+X599108Y234477D01*

+X598725Y234385D01*

+X598362Y234234D01*

+X598026Y234029D01*

+X597727Y233773D01*

+X597471Y233474D01*

+X597266Y233138D01*

+X597115Y232775D01*

+X597023Y232392D01*

+X596992Y232000D01*

+X597023Y231608D01*

+X597115Y231225D01*

+X597266Y230862D01*

+X597471Y230526D01*

+X597727Y230227D01*

+X598026Y229971D01*

+X598362Y229766D01*

+X598725Y229615D01*

+X599108Y229523D01*

+X599496Y229493D01*

+Y212000D01*

+X581496D01*

+Y234993D01*

+X581500Y234992D01*

+X581892Y235023D01*

+X582275Y235115D01*

+X582638Y235266D01*

+X582974Y235471D01*

+X583273Y235727D01*

+X583529Y236026D01*

+X583734Y236362D01*

+X583885Y236725D01*

+X583977Y237108D01*

+X584000Y237500D01*

+X583977Y237892D01*

+X583885Y238275D01*

+X583734Y238638D01*

+X583529Y238974D01*

+X583273Y239273D01*

+X582974Y239529D01*

+X582638Y239734D01*

+X582275Y239885D01*

+X581892Y239977D01*

+X581500Y240008D01*

+X581496Y240007D01*

+Y241493D01*

+X581500Y241492D01*

+X581892Y241523D01*

+X582275Y241615D01*

+X582638Y241766D01*

+X582974Y241971D01*

+X583273Y242227D01*

+X583529Y242526D01*

+X583734Y242862D01*

+X583885Y243225D01*

+X583977Y243608D01*

+X584000Y244000D01*

+X583977Y244392D01*

+X583885Y244775D01*

+X583734Y245138D01*

+X583529Y245474D01*

+X583273Y245773D01*

+X582974Y246029D01*

+X582638Y246234D01*

+X582275Y246385D01*

+X581892Y246477D01*

+X581500Y246508D01*

+X581496Y246507D01*

+Y268000D01*

+G37*

+G36*

+X575996D02*X581496D01*

+Y246507D01*

+X581108Y246477D01*

+X580725Y246385D01*

+X580362Y246234D01*

+X580026Y246029D01*

+X579727Y245773D01*

+X579471Y245474D01*

+X579266Y245138D01*

+X579115Y244775D01*

+X579023Y244392D01*

+X578992Y244000D01*

+X579023Y243608D01*

+X579115Y243225D01*

+X579266Y242862D01*

+X579471Y242526D01*

+X579727Y242227D01*

+X580026Y241971D01*

+X580362Y241766D01*

+X580725Y241615D01*

+X581108Y241523D01*

+X581496Y241493D01*

+Y240007D01*

+X581108Y239977D01*

+X580725Y239885D01*

+X580362Y239734D01*

+X580026Y239529D01*

+X579727Y239273D01*

+X579471Y238974D01*

+X579266Y238638D01*

+X579115Y238275D01*

+X579023Y237892D01*

+X578992Y237500D01*

+X579023Y237108D01*

+X579115Y236725D01*

+X579266Y236362D01*

+X579471Y236026D01*

+X579727Y235727D01*

+X580026Y235471D01*

+X580362Y235266D01*

+X580725Y235115D01*

+X581108Y235023D01*

+X581496Y234993D01*

+Y212000D01*

+X575996D01*

+Y228493D01*

+X576000Y228492D01*

+X576392Y228523D01*

+X576775Y228615D01*

+X577138Y228766D01*

+X577474Y228971D01*

+X577773Y229227D01*

+X578029Y229526D01*

+X578234Y229862D01*

+X578385Y230225D01*

+X578477Y230608D01*

+X578500Y231000D01*

+X578477Y231392D01*

+X578385Y231775D01*

+X578234Y232138D01*

+X578029Y232474D01*

+X577773Y232773D01*

+X577474Y233029D01*

+X577138Y233234D01*

+X576775Y233385D01*

+X576392Y233477D01*

+X576000Y233508D01*

+X575996Y233507D01*

+Y268000D01*

+G37*

+G36*

+X570496D02*X575996D01*

+Y233507D01*

+X575608Y233477D01*

+X575225Y233385D01*

+X574862Y233234D01*

+X574526Y233029D01*

+X574227Y232773D01*

+X573971Y232474D01*

+X573766Y232138D01*

+X573615Y231775D01*

+X573523Y231392D01*

+X573492Y231000D01*

+X573523Y230608D01*

+X573615Y230225D01*

+X573766Y229862D01*

+X573971Y229526D01*

+X574227Y229227D01*

+X574526Y228971D01*

+X574862Y228766D01*

+X575225Y228615D01*

+X575608Y228523D01*

+X575996Y228493D01*

+Y212000D01*

+X570496D01*

+Y234993D01*

+X570500Y234992D01*

+X570892Y235023D01*

+X571275Y235115D01*

+X571638Y235266D01*

+X571974Y235471D01*

+X572273Y235727D01*

+X572529Y236026D01*

+X572734Y236362D01*

+X572885Y236725D01*

+X572977Y237108D01*

+X573000Y237500D01*

+X572977Y237892D01*

+X572885Y238275D01*

+X572734Y238638D01*

+X572529Y238974D01*

+X572273Y239273D01*

+X571974Y239529D01*

+X571638Y239734D01*

+X571275Y239885D01*

+X570892Y239977D01*

+X570500Y240008D01*

+X570496Y240007D01*

+Y241493D01*

+X570500Y241492D01*

+X570892Y241523D01*

+X571275Y241615D01*

+X571638Y241766D01*

+X571974Y241971D01*

+X572273Y242227D01*

+X572529Y242526D01*

+X572734Y242862D01*

+X572885Y243225D01*

+X572977Y243608D01*

+X573000Y244000D01*

+X572977Y244392D01*

+X572885Y244775D01*

+X572734Y245138D01*

+X572529Y245474D01*

+X572273Y245773D01*

+X571974Y246029D01*

+X571638Y246234D01*

+X571275Y246385D01*

+X570892Y246477D01*

+X570500Y246508D01*

+X570496Y246507D01*

+Y268000D01*

+G37*

+G36*

+X551000D02*X570496D01*

+Y246507D01*

+X570108Y246477D01*

+X569725Y246385D01*

+X569362Y246234D01*

+X569026Y246029D01*

+X568727Y245773D01*

+X568471Y245474D01*

+X568266Y245138D01*

+X568115Y244775D01*

+X568023Y244392D01*

+X567992Y244000D01*

+X568023Y243608D01*

+X568115Y243225D01*

+X568266Y242862D01*

+X568471Y242526D01*

+X568727Y242227D01*

+X569026Y241971D01*

+X569362Y241766D01*

+X569725Y241615D01*

+X570108Y241523D01*

+X570496Y241493D01*

+Y240007D01*

+X570108Y239977D01*

+X569725Y239885D01*

+X569362Y239734D01*

+X569026Y239529D01*

+X568727Y239273D01*

+X568471Y238974D01*

+X568266Y238638D01*

+X568115Y238275D01*

+X568023Y237892D01*

+X567992Y237500D01*

+X568023Y237108D01*

+X568115Y236725D01*

+X568266Y236362D01*

+X568471Y236026D01*

+X568727Y235727D01*

+X569026Y235471D01*

+X569362Y235266D01*

+X569725Y235115D01*

+X570108Y235023D01*

+X570496Y234993D01*

+Y212000D01*

+X551000D01*

+Y235208D01*

+X551138Y235266D01*

+X551474Y235471D01*

+X551773Y235727D01*

+X552029Y236026D01*

+X552234Y236362D01*

+X552385Y236725D01*

+X552477Y237108D01*

+X552500Y237500D01*

+X552477Y237892D01*

+X552385Y238275D01*

+X552234Y238638D01*

+X552029Y238974D01*

+X551773Y239273D01*

+X551474Y239529D01*

+X551138Y239734D01*

+X551000Y239792D01*

+Y241708D01*

+X551138Y241766D01*

+X551474Y241971D01*

+X551773Y242227D01*

+X552029Y242526D01*

+X552234Y242862D01*

+X552385Y243225D01*

+X552477Y243608D01*

+X552500Y244000D01*

+X552477Y244392D01*

+X552385Y244775D01*

+X552234Y245138D01*

+X552029Y245474D01*

+X551773Y245773D01*

+X551474Y246029D01*

+X551138Y246234D01*

+X551000Y246292D01*

+Y268000D01*

+G37*

+G36*

+X595995Y344000D02*X599500D01*

+Y316000D01*

+X595995D01*

+Y316740D01*

+X596000Y316740D01*

+X596510Y316780D01*

+X597007Y316900D01*

+X597480Y317095D01*

+X597916Y317363D01*

+X598305Y317695D01*

+X598637Y318084D01*

+X598905Y318520D01*

+X599100Y318993D01*

+X599220Y319490D01*

+X599250Y320000D01*

+X599220Y320510D01*

+X599100Y321007D01*

+X598905Y321480D01*

+X598637Y321916D01*

+X598305Y322305D01*

+X597916Y322637D01*

+X597480Y322905D01*

+X597007Y323100D01*

+X596510Y323220D01*

+X596000Y323260D01*

+X595995Y323260D01*

+Y344000D01*

+G37*

+G36*

+X582996D02*X595995D01*

+Y323260D01*

+X595490Y323220D01*

+X594993Y323100D01*

+X594520Y322905D01*

+X594084Y322637D01*

+X593695Y322305D01*

+X593363Y321916D01*

+X593095Y321480D01*

+X592900Y321007D01*

+X592780Y320510D01*

+X592740Y320000D01*

+X592780Y319490D01*

+X592900Y318993D01*

+X593095Y318520D01*

+X593363Y318084D01*

+X593695Y317695D01*

+X594084Y317363D01*

+X594520Y317095D01*

+X594993Y316900D01*

+X595490Y316780D01*

+X595995Y316740D01*

+Y316000D01*

+X582996D01*

+Y325993D01*

+X583000Y325992D01*

+X583392Y326023D01*

+X583775Y326115D01*

+X584138Y326266D01*

+X584474Y326471D01*

+X584773Y326727D01*

+X585029Y327026D01*

+X585234Y327362D01*

+X585385Y327725D01*

+X585477Y328108D01*

+X585500Y328500D01*

+X585477Y328892D01*

+X585385Y329275D01*

+X585234Y329638D01*

+X585029Y329974D01*

+X584773Y330273D01*

+X584474Y330529D01*

+X584138Y330734D01*

+X583775Y330885D01*

+X583392Y330977D01*

+X583000Y331008D01*

+X582996Y331007D01*

+Y344000D01*

+G37*

+G36*

+X567500Y316000D02*Y326493D01*

+X567526Y326471D01*

+X567862Y326266D01*

+X568225Y326115D01*

+X568608Y326023D01*

+X569000Y325992D01*

+X569392Y326023D01*

+X569775Y326115D01*

+X570138Y326266D01*

+X570474Y326471D01*

+X570773Y326727D01*

+X571029Y327026D01*

+X571234Y327362D01*

+X571385Y327725D01*

+X571477Y328108D01*

+X571500Y328500D01*

+X571477Y328892D01*

+X571385Y329275D01*

+X571234Y329638D01*

+X571029Y329974D01*

+X570773Y330273D01*

+X570474Y330529D01*

+X570138Y330734D01*

+X569775Y330885D01*

+X569392Y330977D01*

+X569000Y331008D01*

+X568608Y330977D01*

+X568225Y330885D01*

+X567862Y330734D01*

+X567526Y330529D01*

+X567500Y330507D01*

+Y333051D01*

+X567554Y333183D01*

+X567711Y333833D01*

+X567763Y334500D01*

+X567711Y335167D01*

+X567554Y335817D01*

+X567500Y335949D01*

+Y344000D01*

+X582996D01*

+Y331007D01*

+X582608Y330977D01*

+X582225Y330885D01*

+X581862Y330734D01*

+X581526Y330529D01*

+X581227Y330273D01*

+X580971Y329974D01*

+X580766Y329638D01*

+X580615Y329275D01*

+X580523Y328892D01*

+X580492Y328500D01*

+X580523Y328108D01*

+X580615Y327725D01*

+X580766Y327362D01*

+X580971Y327026D01*

+X581227Y326727D01*

+X581526Y326471D01*

+X581862Y326266D01*

+X582225Y326115D01*

+X582608Y326023D01*

+X582996Y325993D01*

+Y316000D01*

+X567500D01*

+G37*

+G54D76*X172500Y384000D02*X606000D01*

+G54D77*X394500Y365000D02*Y384000D01*

+X339000Y365000D02*Y384000D01*

+G54D78*X554500Y339000D02*X559000D01*

+G54D79*X544000Y365000D02*X538000Y359000D01*

+X387000Y352500D02*X383500Y349000D01*

+X380000Y352000D02*X278500D01*

+X383500Y349000D02*X284500D01*

+X278500Y352000D02*X269000Y342500D01*

+X284500Y349000D02*X274000Y338500D01*

+X269000Y342500D02*X267000D01*

+X263000Y338500D01*

+G54D78*X410000Y329780D02*X433720Y353500D01*

+G54D79*X432000Y359000D02*X425500Y352500D01*

+X434000Y364500D02*X427500Y358000D01*

+G54D78*X433720Y353500D02*X548500D01*

+G54D79*X375000Y355500D02*X277500D01*

+X268000Y346000D01*

+X253500D01*

+X246000Y338500D01*

+X538000Y359000D02*X432000D01*

+G54D78*X559000Y339000D02*X563500Y334500D01*

+G54D79*X518500Y365000D02*X510500Y373000D01*

+X440000D01*

+X434000Y367000D01*

+Y364500D01*

+X384500Y365000D02*X375000Y355500D01*

+X427500Y358000D02*X386000D01*

+X380000Y352000D01*

+X425500Y352500D02*X387000D01*

+G54D80*X434000Y320000D02*X422500Y331500D01*

+X487500Y272000D02*X489500Y274000D01*

+X466000Y277500D02*Y292000D01*

+X455000Y303000D01*

+Y315000D01*

+X450000Y320000D01*

+X434000D01*

+X449500Y313500D02*X433000Y297000D01*

+X281000Y298000D02*X303500D01*

+X308000D02*X347000D01*

+X303500D02*X306000Y300500D01*

+X349000D01*

+X404500Y301000D02*X362500Y300500D01*

+X349000D02*X352500Y297000D01*

+X347000Y298000D02*X350500Y294500D01*

+X352500Y297000D02*X359000D01*

+X362500Y300500D02*X359000Y297000D01*

+X350500Y294500D02*X386000D01*

+X389000Y297500D01*

+X433000Y297000D02*X408500D01*

+X404500Y301000D01*

+X389000Y297500D02*X403000D01*

+X414000Y286500D01*

+X415500D01*

+G54D79*X634000Y288500D02*Y299500D01*

+X637500Y303000D01*

+X625000D02*X637500D01*

+G54D80*X622500Y311000D02*X611000Y299500D01*

+X622500Y306500D02*X625500Y309500D01*

+Y317000D01*

+X622500Y320000D01*

+G54D79*X627000Y325500D02*X637500Y315000D01*

+Y303000D01*

+G54D81*X619000Y286000D02*X632000Y273000D01*

+X619000Y286000D02*X613000D01*

+X605500Y293500D01*

+G54D79*X631000Y286760D02*X632260D01*

+G54D77*X476500Y294000D02*X498000Y272500D01*

+Y257000D01*

+G54D81*X658000Y278000D02*Y275000D01*

+X656000Y273000D01*

+X632000D01*

+G54D79*X632260Y286760D02*X634000Y288500D01*

+G54D81*X598000Y293500D02*X605500D01*

+G54D80*X611000Y299500D02*X599500D01*

+X597000Y289000D02*X595000Y291000D01*

+Y295000D01*

+X599500Y299500D01*

+X594000Y245500D02*X597000Y248500D01*

+Y289000D01*

+X595000Y352000D02*X595500Y351500D01*

+X595000Y352000D02*Y349500D01*

+X591000Y345500D01*

+X567500D01*

+X595500Y351500D02*X646500D01*

+G54D81*X554000Y365000D02*Y384000D01*

+X528500Y365000D02*Y384000D01*

+G54D82*X588000Y363000D02*X591500Y359500D01*

+Y350000D01*

+X588000Y359000D02*Y345500D01*

+G54D80*X567500D02*X564500Y348500D01*

+G54D78*X548500Y353500D02*X554500Y347500D01*

+Y339000D01*

+X188000Y329780D02*X410000D01*

+G54D77*X283500Y365000D02*Y384000D01*

+X228000Y365000D02*Y384000D01*

+X172500Y365000D02*Y384000D01*

+G54D80*X311000Y280500D02*X308500Y283000D01*

+X301500D01*

+X296000Y277500D01*

+X287500D02*X308000Y298000D01*

+X286000Y277500D02*X287500D01*

+X276000D02*Y293000D01*

+X281000Y298000D01*

+X376000Y217500D02*Y233500D01*

+X366000Y217500D02*Y229500D01*

+X282000Y211500D02*X480500D01*

+X487500Y218500D01*

+X376000Y233500D02*X382500Y240000D01*

+X366000Y229500D02*X380000Y243500D01*

+X463500D01*

+X382500Y240000D02*X449500D01*

+X454500Y249500D02*X359000D01*

+X429000Y254500D02*X327500D01*

+X454500Y249500D02*X455000Y250000D01*

+X332500Y246500D02*X312500D01*

+X291000Y268000D01*

+X487500Y218500D02*Y272000D01*

+X465500Y270000D02*X365500D01*

+X464500Y264000D02*X365000D01*

+X327500Y254500D02*X311000Y271000D01*

+Y280500D01*

+X365500Y270000D02*X361000Y274500D01*

+X365000Y264000D02*X356000Y273000D01*

+Y277500D01*

+X361000Y274500D02*Y280500D01*

+X358000Y283500D01*

+X352000D01*

+X346000Y277500D01*

+X276000Y217500D02*X282000Y211500D01*

+X336000Y226500D02*X315000D01*

+X306000Y217500D01*

+X339000Y234500D02*X304500D01*

+X359000Y249500D02*X336000Y226500D01*

+X304500Y234500D02*X271000Y268000D01*

+X329500Y240500D02*X308500D01*

+X281000Y268000D01*

+X343500Y245000D02*X338000Y250500D01*

+X318500D01*

+X301000Y268000D01*

+X337000Y242000D02*X332500Y246500D01*

+G54D75*G36*

+X646250Y368250D02*Y361750D01*

+X652750D01*

+Y368250D01*

+X646250D01*

+G37*

+G54D78*X639500Y365000D03*

+G54D83*X666110Y374000D03*

+X679890D03*

+X666110Y352346D03*

+X679890D03*

+G54D78*X629500Y365000D03*

+X619500D03*

+G54D84*X701500Y380000D03*

+G54D85*X631000Y290500D03*

+Y286760D03*

+Y294240D03*

+X636709Y290500D03*

+X625291D03*

+G54D84*X701500Y212000D03*

+G54D78*X609500Y365000D03*

+G54D75*G36*

+X525250Y368250D02*Y361750D01*

+X531750D01*

+Y368250D01*

+X525250D01*

+G37*

+G54D78*X518500Y365000D03*

+G54D75*G36*

+X550750Y368250D02*Y361750D01*

+X557250D01*

+Y368250D01*

+X550750D01*

+G37*

+G54D78*X544000Y365000D03*

+X599500D03*

+G54D83*X569110Y374000D03*

+X582890D03*

+Y352346D03*

+X569110D03*

+G54D86*X554500Y329780D03*

+Y312063D03*

+X528500D03*

+X554500Y302220D03*

+G54D87*X543831Y290134D03*

+G54D86*X528500Y302220D03*

+G54D87*X517831Y290134D03*

+G54D86*X554500Y319937D03*

+G54D87*X543831Y341866D03*

+G54D86*X528500Y329780D03*

+Y319937D03*

+G54D87*X517831Y341866D03*

+G54D75*G36*

+X243000Y220500D02*Y214500D01*

+X249000D01*

+Y220500D01*

+X243000D01*

+G37*

+G54D88*X256000Y217500D03*

+X266000D03*

+X276000D03*

+X286000D03*

+X296000D03*

+X306000D03*

+X316000D03*

+X326000D03*

+X336000D03*

+X346000D03*

+X356000D03*

+X366000D03*

+X376000D03*

+X386000D03*

+X396000D03*

+X406000D03*

+X416000D03*

+X406000Y277500D03*

+X396000D03*

+X386000D03*

+X376000D03*

+X366000D03*

+X356000D03*

+X346000D03*

+X336000D03*

+X326000D03*

+X316000D03*

+X306000D03*

+X296000D03*

+X286000D03*

+X276000D03*

+X266000D03*

+X256000D03*

+X246000D03*

+X426000Y217500D03*

+X436000D03*

+X446000D03*

+X456000D03*

+X466000D03*

+X476000D03*

+Y277500D03*

+X466000D03*

+X456000D03*

+X446000D03*

+X436000D03*

+X426000D03*

+X416000D03*

+G54D86*X410000Y329780D03*

+G54D87*X399331Y341866D03*

+G54D86*X410000Y319937D03*

+Y312063D03*

+Y302220D03*

+G54D87*X399331Y290134D03*

+G54D75*G36*

+X447750Y368250D02*Y361750D01*

+X454250D01*

+Y368250D01*

+X447750D01*

+G37*

+G54D78*X441000Y365000D03*

+G54D75*G36*

+X421250Y368250D02*Y361750D01*

+X427750D01*

+Y368250D01*

+X421250D01*

+G37*

+G54D78*X414500Y365000D03*

+G54D75*G36*

+X473250Y368250D02*Y361750D01*

+X479750D01*

+Y368250D01*

+X473250D01*

+G37*

+G54D78*X466500Y365000D03*

+G54D75*G36*

+X498750Y368250D02*Y361750D01*

+X505250D01*

+Y368250D01*

+X498750D01*

+G37*

+G54D78*X492000Y365000D03*

+X404500D03*

+X394500D03*

+X384500D03*

+G54D75*G36*

+X365750Y368250D02*Y361750D01*

+X372250D01*

+Y368250D01*

+X365750D01*

+G37*

+G54D78*X359000Y365000D03*

+X349000D03*

+X339000D03*

+X329000D03*

+G54D86*X354500Y329780D03*

+G54D87*X343831Y341866D03*

+G54D75*G36*

+X310250Y368250D02*Y361750D01*

+X316750D01*

+Y368250D01*

+X310250D01*

+G37*

+G54D78*X303500Y365000D03*

+X293500D03*

+X283500D03*

+X273500D03*

+G54D75*G36*

+X254750Y368250D02*Y361750D01*

+X261250D01*

+Y368250D01*

+X254750D01*

+G37*

+G54D78*X248000Y365000D03*

+X238000D03*

+X228000D03*

+X218000D03*

+G54D75*G36*

+X199250Y368250D02*Y361750D01*

+X205750D01*

+Y368250D01*

+X199250D01*

+G37*

+G54D78*X192500Y365000D03*

+X182500D03*

+X172500D03*

+X162500D03*

+G54D84*X141000Y380000D03*

+G54D86*X354500Y319937D03*

+X299000D03*

+Y312063D03*

+Y302220D03*

+G54D87*X288331Y290134D03*

+G54D86*X354500Y312063D03*

+Y302220D03*

+G54D87*X343831Y290134D03*

+G54D86*X299000Y329780D03*

+G54D87*X288331Y341866D03*

+G54D86*X243500Y329780D03*

+Y319937D03*

+Y312063D03*

+Y302220D03*

+X188000D03*

+G54D87*X232831Y341866D03*

+G54D86*X188000Y329780D03*

+Y319937D03*

+Y312063D03*

+G54D87*X177331Y341866D03*

+X232831Y290134D03*

+X177331D03*

+G54D84*X141000Y212000D03*

+G54D89*X628500Y246000D03*

+X653500Y277500D03*

+X648500Y246000D03*

+X658000Y278000D03*

+X649000Y277500D03*

+X668000Y245500D03*

+X680500Y244000D03*

+Y237500D03*

+X662500Y232000D03*

+X655000D03*

+X599500D03*

+X607500D03*

+X691500Y237500D03*

+Y244000D03*

+X686000Y231000D03*

+X598000Y293500D03*

+X569000Y297500D03*

+X575500Y285000D03*

+X621000Y234000D03*

+Y238500D03*

+X594000Y245500D03*

+G54D90*X587000Y264500D03*

+Y254500D03*

+X583000Y259500D03*

+G54D89*X562000Y316000D03*

+X532500Y288000D03*

+X593500Y277500D03*

+X627000Y278000D03*

+X616500Y280500D03*

+Y290500D03*

+X625000Y303000D03*

+X622500Y306500D03*

+X647500Y285500D03*

+X637500Y303000D03*

+X622500Y311000D03*

+Y320000D03*

+X627000Y325500D03*

+G54D90*X596000Y320000D03*

+G54D89*Y312500D03*

+X570500Y244000D03*

+X581500Y237500D03*

+Y244000D03*

+X576000Y231000D03*

+X570500Y237500D03*

+X539000Y244000D03*

+Y237500D03*

+X518500D03*

+Y244000D03*

+X513000Y231000D03*

+X507500Y237500D03*

+X550000D03*

+X544500Y231000D03*

+X550000Y244000D03*

+X507500D03*

+X449500Y313500D03*

+G54D88*X462500Y311500D03*

+X442000Y326000D03*

+G54D90*X496000Y332000D03*

+X246000Y338500D03*

+X274000D03*

+X263000D03*

+G54D89*X422500Y331500D03*

+X416000Y373500D03*

+X313500Y323500D03*

+G54D88*X513500Y332000D03*

+G54D89*X569000Y328500D03*

+G54D91*X576000Y322500D03*

+G54D90*X568500Y323500D03*

+G54D88*X563500Y334500D03*

+X554500Y339000D03*

+G54D89*X583000Y328500D03*

+G54D90*X583500Y323500D03*

+X596500Y333500D03*

+X589000D03*

+Y326000D03*

+X596500D03*

+G54D89*X573500Y348500D03*

+X564500D03*

+X578000Y349000D03*

+G54D91*X591500Y350000D03*

+G54D89*X646500Y351500D03*

+X595000Y352000D03*

+G54D91*X588000Y363000D03*

+Y359000D03*

+G54D88*X606000Y381500D03*

+X600500Y386500D03*

+X595000Y381500D03*

+X589500Y386500D03*

+G54D89*X360500Y373500D03*

+X305000D03*

+X249500D03*

+X194000D03*

+X278500Y380000D03*

+X271000Y268000D03*

+X281000D03*

+X291000D03*

+X301000D03*

+G54D90*X492500Y294000D03*

+X485000D03*

+X476500D03*

+X471000D03*

+G54D89*X494500Y286500D03*

+X415500D03*

+G54D90*X483000Y323000D03*

+G54D88*X502000Y315000D03*

+X498000Y257000D03*

+G54D89*X246000Y261500D03*

+X429000Y254500D03*

+G54D88*X498000Y264000D03*

+G54D89*X463500Y243500D03*

+X489500Y274000D03*

+X464500Y264000D03*

+X465500Y270000D03*

+X449500Y240000D03*

+X455000Y250000D03*

+G54D90*X191500Y258000D03*

+Y237000D03*

+X205000Y314000D03*

+X213500D03*

+X221000D03*

+G54D89*X386000Y233500D03*

+X376500Y306500D03*

+X225000Y243500D03*

+X215000D03*

+X205000D03*

+X220000Y231000D03*

+X210000D03*

+X200000D03*

+X329500Y240500D03*

+X339000Y234500D03*

+X337000Y242000D03*

+X343500Y245000D03*

+G54D92*G54D77*G54D92*G54D77*G54D92*G54D81*G54D77*G54D92*G54D81*G54D92*G54D93*G54D77*G54D81*G54D92*G54D77*G54D92*G54D93*G54D92*G54D93*G54D81*G54D92*G54D77*G54D92*G54D77*G54D81*G54D92*G54D81*G54D92*G54D77*G54D92*G54D94*G54D95*G54D94*G54D96*G54D97*G54D96*G54D94*G54D95*G54D98*G54D99*G54D98*G54D99*G54D98*G54D99*G54D98*G54D99*G54D100*G54D98*G54D99*G54D98*G54D99*G54D94*G54D98*G54D99*G54D94*G54D96*G54D98*G54D99*G54D98*G54D99*G54D98*G54D99*G54D98*G54D99*G54D98*G54D99*G54D96*M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.outline.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.outline.gbr
new file mode 100644
index 0000000..886ca18
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.outline.gbr
@@ -0,0 +1,21 @@
+G04 start of page 6 for group 4 idx 4 *

+G04 Title: uart, outline *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNOUTLINE*%

+%ADD136C,0.0100*%

+G54D136*X714000Y390000D02*Y202000D01*

+X131000Y392500D02*X711500D01*

+X131000Y199500D02*X711500D01*

+X128500Y390000D02*Y202000D01*

+X711500Y392500D02*G75*G02X714000Y390000I0J-2500D01*G01*

+Y202000D02*G75*G02X711500Y199500I-2500J0D01*G01*

+X128500Y390000D02*G75*G02X131000Y392500I2500J0D01*G01*

+Y199500D02*G75*G02X128500Y202000I0J2500D01*G01*

+M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.plated-drill.cnc b/motors/uart_schematic/shipped_files/uart-20190115/uart.plated-drill.cnc
new file mode 100644
index 0000000..9ff6b31
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.plated-drill.cnc
@@ -0,0 +1,304 @@
+M48

+INCH

+T146C0.035

+T145C0.025

+T144C0.020

+T143C0.038

+T142C0.091

+T141C0.035

+T140C0.012

+T139C0.129

+T138C0.043

+T137C0.040

+%

+T140

+X057600Y032250

+X058800Y036300

+X058800Y035900

+X059150Y035000

+X062529Y029050

+X063100Y029424

+X063100Y029050

+X063100Y028676

+X063671Y029050

+T144

+X019400Y037350

+X020000Y023100

+X020500Y024350

+X021000Y023100

+X021500Y024350

+X022000Y023100

+X022500Y024350

+X024600Y026150

+X024950Y037350

+X027100Y026800

+X027850Y038000

+X028100Y026800

+X029100Y026800

+X030100Y026800

+X030500Y037350

+X031350Y032350

+X032950Y024050

+X033700Y024200

+X033900Y023450

+X034350Y024500

+X036050Y037350

+X037650Y030650

+X038600Y023350

+X041550Y028650

+X041600Y037350

+X042250Y033150

+X042900Y025450

+X044950Y031350

+X044950Y024000

+X045500Y025000

+X046350Y024350

+X046450Y026400

+X046550Y027000

+X048950Y027400

+X049450Y028650

+X050750Y024400

+X050750Y023750

+X051300Y023100

+X051850Y024400

+X051850Y023750

+X053250Y028800

+X053900Y024400

+X053900Y023750

+X054450Y023100

+X055000Y024400

+X055000Y023750

+X056200Y031600

+X056450Y034850

+X056900Y032850

+X056900Y029750

+X057050Y024400

+X057050Y023750

+X057350Y034850

+X057550Y028500

+X057600Y023100

+X057800Y034900

+X058150Y024400

+X058150Y023750

+X058300Y032850

+X059350Y027750

+X059400Y024550

+X059500Y035200

+X059600Y031250

+X059800Y029350

+X059950Y023200

+X060750Y023200

+X061650Y029050

+X061650Y028050

+X062100Y023850

+X062100Y023400

+X062250Y032000

+X062250Y031100

+X062250Y030650

+X062500Y030300

+X062700Y032550

+X062700Y027800

+X062850Y024600

+X063750Y030300

+X064650Y035150

+X064750Y028550

+X064850Y024600

+X064900Y027750

+X065350Y027750

+X065500Y023200

+X065800Y027800

+X066250Y023200

+X066800Y024550

+X068050Y024400

+X068050Y023750

+X068600Y023100

+X069150Y024400

+X069150Y023750

+T145

+X019150Y025800

+X019150Y023700

+X020500Y031400

+X021350Y031400

+X022100Y031400

+X024600Y033850

+X026300Y033850

+X027400Y033850

+X047100Y029400

+X047650Y029400

+X048300Y032300

+X048500Y029400

+X049250Y029400

+X049600Y033200

+X056850Y032350

+X058300Y025950

+X058350Y032350

+X058700Y026450

+X058700Y025450

+X058900Y033350

+X058900Y032600

+X059600Y032000

+X059650Y033350

+X059650Y032600

+T146

+X044200Y032600

+X046250Y031150

+X049800Y026400

+X049800Y025700

+X050200Y031500

+X051350Y033200

+X055450Y033900

+X056350Y033450

+X058950Y038650

+X059500Y038150

+X060050Y038650

+X060600Y038150

+T141

+X018800Y032978

+X018800Y031994

+X018800Y031206

+X018800Y030222

+X024350Y032978

+X024350Y031994

+X024350Y031206

+X024350Y030222

+X029900Y032978

+X029900Y031994

+X029900Y031206

+X029900Y030222

+X035450Y032978

+X035450Y031994

+X035450Y031206

+X035450Y030222

+X041000Y032978

+X041000Y031994

+X041000Y031206

+X041000Y030222

+X052850Y032978

+X052850Y031994

+X052850Y031206

+X052850Y030222

+X055450Y032978

+X055450Y031994

+X055450Y031206

+X055450Y030222

+T143

+X024600Y027750

+X024600Y021750

+X025600Y027750

+X025600Y021750

+X026600Y027750

+X026600Y021750

+X027600Y027750

+X027600Y021750

+X028600Y027750

+X028600Y021750

+X029600Y027750

+X029600Y021750

+X030600Y027750

+X030600Y021750

+X031600Y027750

+X031600Y021750

+X032600Y027750

+X032600Y021750

+X033600Y027750

+X033600Y021750

+X034600Y027750

+X034600Y021750

+X035600Y027750

+X035600Y021750

+X036600Y027750

+X036600Y021750

+X037600Y027750

+X037600Y021750

+X038600Y027750

+X038600Y021750

+X039600Y027750

+X039600Y021750

+X040600Y027750

+X040600Y021750

+X041600Y027750

+X041600Y021750

+X042600Y027750

+X042600Y021750

+X043600Y027750

+X043600Y021750

+X044600Y027750

+X044600Y021750

+X045600Y027750

+X045600Y021750

+X046600Y027750

+X046600Y021750

+X047600Y027750

+X047600Y021750

+T137

+X016250Y036500

+X017250Y036500

+X018250Y036500

+X019250Y036500

+X020250Y036500

+X021800Y036500

+X022800Y036500

+X023800Y036500

+X024800Y036500

+X025800Y036500

+X027350Y036500

+X028350Y036500

+X029350Y036500

+X030350Y036500

+X031350Y036500

+X032900Y036500

+X033900Y036500

+X034900Y036500

+X035900Y036500

+X036900Y036500

+X038450Y036500

+X039450Y036500

+X040450Y036500

+X041450Y036500

+X042450Y036500

+X044100Y036500

+X045100Y036500

+X046650Y036500

+X047650Y036500

+X049200Y036500

+X050200Y036500

+X051850Y036500

+X052850Y036500

+X054400Y036500

+X055400Y036500

+X059950Y036500

+X060950Y036500

+X061950Y036500

+X062950Y036500

+X063950Y036500

+X064950Y036500

+T138

+X056911Y037400

+X056911Y035235

+X058289Y037400

+X058289Y035235

+X066611Y037400

+X066611Y035235

+X067989Y037400

+X067989Y035235

+T142

+X017733Y034187

+X017733Y029013

+X023283Y034187

+X023283Y029013

+X028833Y034187

+X028833Y029013

+X034383Y034187

+X034383Y029013

+X039933Y034187

+X039933Y029013

+X051783Y034187

+X051783Y029013

+X054383Y034187

+X054383Y029013

+T139

+X014100Y038000

+X014100Y021200

+X070150Y038000

+X070150Y021200

+M30

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.top.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.top.gbr
new file mode 100644
index 0000000..682b7a5
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.top.gbr
@@ -0,0 +1,1733 @@
+G04 start of page 2 for group 0 idx 0 *

+G04 Title: uart, top *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNTOP*%

+%ADD52C,0.0380*%

+%ADD51C,0.0906*%

+%ADD50C,0.0354*%

+%ADD49C,0.0118*%

+%ADD48C,0.1285*%

+%ADD47C,0.0433*%

+%ADD46C,0.0400*%

+%ADD45C,0.0118*%

+%ADD44C,0.0200*%

+%ADD43C,0.0240*%

+%ADD42C,0.0450*%

+%ADD41C,0.0360*%

+%ADD40R,0.0098X0.0098*%

+%ADD39R,0.0197X0.0197*%

+%ADD38R,0.1890X0.1890*%

+%ADD37R,0.0551X0.0551*%

+%ADD36R,0.0221X0.0221*%

+%ADD35R,0.0362X0.0362*%

+%ADD34R,0.0528X0.0528*%

+%ADD33R,0.0472X0.0472*%

+%ADD32R,0.0280X0.0280*%

+%ADD31R,0.0295X0.0295*%

+%ADD30R,0.0512X0.0512*%

+%ADD29R,0.0630X0.0630*%

+%ADD28R,0.1594X0.1594*%

+%ADD27R,0.0294X0.0294*%

+%ADD26R,0.0200X0.0200*%

+%ADD25R,0.0358X0.0358*%

+%ADD24C,0.0600*%

+%ADD23C,0.1063*%

+%ADD22C,0.0551*%

+%ADD21C,0.0256*%

+%ADD20C,0.1800*%

+%ADD19C,0.0630*%

+%ADD18C,0.0650*%

+%ADD17C,0.0057*%

+%ADD16C,0.0150*%

+%ADD15C,0.0060*%

+%ADD14C,0.0250*%

+%ADD13C,0.0100*%

+%ADD12C,0.0350*%

+%ADD11C,0.0001*%

+G54D11*G36*

+X640500Y320500D02*X661500D01*

+Y293000D01*

+X670500Y284000D01*

+Y269000D01*

+X656500D01*

+Y275500D01*

+X659000D01*

+X661000Y277500D01*

+Y278500D01*

+X659000Y280500D01*

+X652500D01*

+X650500Y278500D01*

+Y257000D01*

+X631500D01*

+Y277500D01*

+X640500Y286500D01*

+Y320500D01*

+G37*

+G36*

+X620000D02*Y301500D01*

+X623000Y298500D01*

+Y278500D01*

+X626000Y275500D01*

+X630500D01*

+Y257000D01*

+X611500D01*

+Y269000D01*

+X596500D01*

+Y280000D01*

+X600500Y284000D01*

+Y320500D01*

+X620000D01*

+G37*

+G36*

+X679883Y390000D02*X701108D01*

+X699931Y389907D01*

+X698400Y389540D01*

+X696946Y388938D01*

+X695604Y388115D01*

+X694407Y387093D01*

+X693385Y385896D01*

+X692562Y384554D01*

+X691960Y383100D01*

+X691593Y381569D01*

+X691469Y380000D01*

+X691593Y378431D01*

+X691960Y376900D01*

+X692562Y375446D01*

+X693385Y374104D01*

+X694407Y372907D01*

+X695604Y371885D01*

+X696946Y371062D01*

+X698400Y370460D01*

+X699931Y370093D01*

+X701500Y369969D01*

+Y267000D01*

+X679883D01*

+Y348185D01*

+X679890Y348184D01*

+X680541Y348235D01*

+X681176Y348388D01*

+X681779Y348638D01*

+X682336Y348979D01*

+X682833Y349403D01*

+X683257Y349900D01*

+X683598Y350457D01*

+X683848Y351060D01*

+X684001Y351695D01*

+X684039Y352346D01*

+X684001Y352998D01*

+X683848Y353633D01*

+X683598Y354236D01*

+X683257Y354793D01*

+X682833Y355290D01*

+X682336Y355714D01*

+X681779Y356055D01*

+X681176Y356305D01*

+X680541Y356458D01*

+X679890Y356509D01*

+X679883Y356508D01*

+Y369838D01*

+X679890Y369838D01*

+X680541Y369889D01*

+X681176Y370041D01*

+X681779Y370291D01*

+X682336Y370633D01*

+X682833Y371057D01*

+X683257Y371553D01*

+X683598Y372110D01*

+X683848Y372714D01*

+X684001Y373349D01*

+X684039Y374000D01*

+X684001Y374651D01*

+X683848Y375286D01*

+X683598Y375890D01*

+X683257Y376447D01*

+X682833Y376943D01*

+X682336Y377367D01*

+X681779Y377709D01*

+X681176Y377959D01*

+X680541Y378111D01*

+X679890Y378162D01*

+X679883Y378162D01*

+Y390000D01*

+G37*

+G36*

+X671500Y267000D02*Y284500D01*

+X666104Y289896D01*

+Y348185D01*

+X666110Y348184D01*

+X666761Y348235D01*

+X667396Y348388D01*

+X668000Y348638D01*

+X668557Y348979D01*

+X669054Y349403D01*

+X669478Y349900D01*

+X669819Y350457D01*

+X670069Y351060D01*

+X670221Y351695D01*

+X670260Y352346D01*

+X670221Y352998D01*

+X670069Y353633D01*

+X669819Y354236D01*

+X669478Y354793D01*

+X669054Y355290D01*

+X668557Y355714D01*

+X668000Y356055D01*

+X667396Y356305D01*

+X666761Y356458D01*

+X666110Y356509D01*

+X666104Y356508D01*

+Y369838D01*

+X666110Y369838D01*

+X666761Y369889D01*

+X667396Y370041D01*

+X668000Y370291D01*

+X668557Y370633D01*

+X669054Y371057D01*

+X669478Y371553D01*

+X669819Y372110D01*

+X670069Y372714D01*

+X670221Y373349D01*

+X670260Y374000D01*

+X670221Y374651D01*

+X670069Y375286D01*

+X669819Y375890D01*

+X669478Y376447D01*

+X669054Y376943D01*

+X668557Y377367D01*

+X668000Y377709D01*

+X667396Y377959D01*

+X666761Y378111D01*

+X666110Y378162D01*

+X666104Y378162D01*

+Y390000D01*

+X679883D01*

+Y378162D01*

+X679239Y378111D01*

+X678604Y377959D01*

+X678000Y377709D01*

+X677443Y377367D01*

+X676946Y376943D01*

+X676522Y376447D01*

+X676181Y375890D01*

+X675931Y375286D01*

+X675779Y374651D01*

+X675727Y374000D01*

+X675779Y373349D01*

+X675931Y372714D01*

+X676181Y372110D01*

+X676522Y371553D01*

+X676946Y371057D01*

+X677443Y370633D01*

+X678000Y370291D01*

+X678604Y370041D01*

+X679239Y369889D01*

+X679883Y369838D01*

+Y356508D01*

+X679239Y356458D01*

+X678604Y356305D01*

+X678000Y356055D01*

+X677443Y355714D01*

+X676946Y355290D01*

+X676522Y354793D01*

+X676181Y354236D01*

+X675931Y353633D01*

+X675779Y352998D01*

+X675727Y352346D01*

+X675779Y351695D01*

+X675931Y351060D01*

+X676181Y350457D01*

+X676522Y349900D01*

+X676946Y349403D01*

+X677443Y348979D01*

+X678000Y348638D01*

+X678604Y348388D01*

+X679239Y348235D01*

+X679883Y348185D01*

+Y267000D01*

+X671500D01*

+G37*

+G36*

+X666104Y289896D02*X662500Y293500D01*

+Y344000D01*

+X646496D01*

+Y348993D01*

+X646500Y348992D01*

+X646892Y349023D01*

+X647275Y349115D01*

+X647638Y349266D01*

+X647974Y349471D01*

+X648273Y349727D01*

+X648529Y350026D01*

+X648734Y350362D01*

+X648885Y350725D01*

+X648977Y351108D01*

+X649000Y351500D01*

+X648977Y351892D01*

+X648885Y352275D01*

+X648734Y352638D01*

+X648529Y352974D01*

+X648273Y353273D01*

+X647974Y353529D01*

+X647638Y353734D01*

+X647275Y353885D01*

+X646892Y353977D01*

+X646500Y354008D01*

+X646496Y354007D01*

+Y360251D01*

+X652985Y360264D01*

+X653215Y360319D01*

+X653433Y360409D01*

+X653634Y360533D01*

+X653814Y360686D01*

+X653967Y360866D01*

+X654091Y361067D01*

+X654181Y361285D01*

+X654236Y361515D01*

+X654250Y361750D01*

+X654236Y368485D01*

+X654181Y368715D01*

+X654091Y368933D01*

+X653967Y369134D01*

+X653814Y369314D01*

+X653634Y369467D01*

+X653433Y369591D01*

+X653215Y369681D01*

+X652985Y369736D01*

+X652750Y369750D01*

+X646496Y369737D01*

+Y390000D01*

+X666104D01*

+Y378162D01*

+X665459Y378111D01*

+X664824Y377959D01*

+X664221Y377709D01*

+X663664Y377367D01*

+X663167Y376943D01*

+X662743Y376447D01*

+X662402Y375890D01*

+X662152Y375286D01*

+X661999Y374651D01*

+X661948Y374000D01*

+X661999Y373349D01*

+X662152Y372714D01*

+X662402Y372110D01*

+X662743Y371553D01*

+X663167Y371057D01*

+X663664Y370633D01*

+X664221Y370291D01*

+X664824Y370041D01*

+X665459Y369889D01*

+X666104Y369838D01*

+Y356508D01*

+X665459Y356458D01*

+X664824Y356305D01*

+X664221Y356055D01*

+X663664Y355714D01*

+X663167Y355290D01*

+X662743Y354793D01*

+X662402Y354236D01*

+X662152Y353633D01*

+X661999Y352998D01*

+X661948Y352346D01*

+X661999Y351695D01*

+X662152Y351060D01*

+X662402Y350457D01*

+X662743Y349900D01*

+X663167Y349403D01*

+X663664Y348979D01*

+X664221Y348638D01*

+X664824Y348388D01*

+X665459Y348235D01*

+X666104Y348185D01*

+Y289896D01*

+G37*

+G36*

+X646496Y344000D02*X639493D01*

+Y360236D01*

+X639500Y360235D01*

+X640245Y360294D01*

+X640972Y360469D01*

+X641663Y360755D01*

+X642301Y361145D01*

+X642869Y361631D01*

+X643355Y362199D01*

+X643745Y362837D01*

+X644031Y363528D01*

+X644206Y364255D01*

+X644250Y365000D01*

+X644206Y365745D01*

+X644031Y366472D01*

+X643745Y367163D01*

+X643355Y367801D01*

+X642869Y368369D01*

+X642301Y368855D01*

+X641663Y369245D01*

+X640972Y369531D01*

+X640245Y369706D01*

+X639500Y369765D01*

+X639493Y369764D01*

+Y390000D01*

+X646496D01*

+Y369737D01*

+X646015Y369736D01*

+X645785Y369681D01*

+X645567Y369591D01*

+X645366Y369467D01*

+X645186Y369314D01*

+X645033Y369134D01*

+X644909Y368933D01*

+X644819Y368715D01*

+X644764Y368485D01*

+X644750Y368250D01*

+X644764Y361515D01*

+X644819Y361285D01*

+X644909Y361067D01*

+X645033Y360866D01*

+X645186Y360686D01*

+X645366Y360533D01*

+X645567Y360409D01*

+X645785Y360319D01*

+X646015Y360264D01*

+X646250Y360250D01*

+X646496Y360251D01*

+Y354007D01*

+X646108Y353977D01*

+X645725Y353885D01*

+X645362Y353734D01*

+X645026Y353529D01*

+X644727Y353273D01*

+X644471Y352974D01*

+X644266Y352638D01*

+X644115Y352275D01*

+X644023Y351892D01*

+X643992Y351500D01*

+X644023Y351108D01*

+X644115Y350725D01*

+X644266Y350362D01*

+X644471Y350026D01*

+X644727Y349727D01*

+X645026Y349471D01*

+X645362Y349266D01*

+X645725Y349115D01*

+X646108Y349023D01*

+X646496Y348993D01*

+Y344000D01*

+G37*

+G36*

+X639493D02*X629493D01*

+Y360236D01*

+X629500Y360235D01*

+X630245Y360294D01*

+X630972Y360469D01*

+X631663Y360755D01*

+X632301Y361145D01*

+X632869Y361631D01*

+X633355Y362199D01*

+X633745Y362837D01*

+X634031Y363528D01*

+X634206Y364255D01*

+X634250Y365000D01*

+X634206Y365745D01*

+X634031Y366472D01*

+X633745Y367163D01*

+X633355Y367801D01*

+X632869Y368369D01*

+X632301Y368855D01*

+X631663Y369245D01*

+X630972Y369531D01*

+X630245Y369706D01*

+X629500Y369765D01*

+X629493Y369764D01*

+Y390000D01*

+X639493D01*

+Y369764D01*

+X638755Y369706D01*

+X638028Y369531D01*

+X637337Y369245D01*

+X636699Y368855D01*

+X636131Y368369D01*

+X635645Y367801D01*

+X635255Y367163D01*

+X634969Y366472D01*

+X634794Y365745D01*

+X634735Y365000D01*

+X634794Y364255D01*

+X634969Y363528D01*

+X635255Y362837D01*

+X635645Y362199D01*

+X636131Y361631D01*

+X636699Y361145D01*

+X637337Y360755D01*

+X638028Y360469D01*

+X638755Y360294D01*

+X639493Y360236D01*

+Y344000D01*

+G37*

+G36*

+X629493D02*X619493D01*

+Y360236D01*

+X619500Y360235D01*

+X620245Y360294D01*

+X620972Y360469D01*

+X621663Y360755D01*

+X622301Y361145D01*

+X622869Y361631D01*

+X623355Y362199D01*

+X623745Y362837D01*

+X624031Y363528D01*

+X624206Y364255D01*

+X624250Y365000D01*

+X624206Y365745D01*

+X624031Y366472D01*

+X623745Y367163D01*

+X623355Y367801D01*

+X622869Y368369D01*

+X622301Y368855D01*

+X621663Y369245D01*

+X620972Y369531D01*

+X620245Y369706D01*

+X619500Y369765D01*

+X619493Y369764D01*

+Y390000D01*

+X629493D01*

+Y369764D01*

+X628755Y369706D01*

+X628028Y369531D01*

+X627337Y369245D01*

+X626699Y368855D01*

+X626131Y368369D01*

+X625645Y367801D01*

+X625255Y367163D01*

+X624969Y366472D01*

+X624794Y365745D01*

+X624735Y365000D01*

+X624794Y364255D01*

+X624969Y363528D01*

+X625255Y362837D01*

+X625645Y362199D01*

+X626131Y361631D01*

+X626699Y361145D01*

+X627337Y360755D01*

+X628028Y360469D01*

+X628755Y360294D01*

+X629493Y360236D01*

+Y344000D01*

+G37*

+G36*

+X619493D02*X609493D01*

+Y360236D01*

+X609500Y360235D01*

+X610245Y360294D01*

+X610972Y360469D01*

+X611663Y360755D01*

+X612301Y361145D01*

+X612869Y361631D01*

+X613355Y362199D01*

+X613745Y362837D01*

+X614031Y363528D01*

+X614206Y364255D01*

+X614250Y365000D01*

+X614206Y365745D01*

+X614031Y366472D01*

+X613745Y367163D01*

+X613355Y367801D01*

+X612869Y368369D01*

+X612301Y368855D01*

+X611663Y369245D01*

+X610972Y369531D01*

+X610245Y369706D01*

+X609500Y369765D01*

+X609493Y369764D01*

+Y390000D01*

+X619493D01*

+Y369764D01*

+X618755Y369706D01*

+X618028Y369531D01*

+X617337Y369245D01*

+X616699Y368855D01*

+X616131Y368369D01*

+X615645Y367801D01*

+X615255Y367163D01*

+X614969Y366472D01*

+X614794Y365745D01*

+X614735Y365000D01*

+X614794Y364255D01*

+X614969Y363528D01*

+X615255Y362837D01*

+X615645Y362199D01*

+X616131Y361631D01*

+X616699Y361145D01*

+X617337Y360755D01*

+X618028Y360469D01*

+X618755Y360294D01*

+X619493Y360236D01*

+Y344000D01*

+G37*

+G36*

+X609493D02*X599500D01*

+Y323500D01*

+X599493D01*

+Y360236D01*

+X599500Y360235D01*

+X600245Y360294D01*

+X600972Y360469D01*

+X601663Y360755D01*

+X602301Y361145D01*

+X602869Y361631D01*

+X603355Y362199D01*

+X603745Y362837D01*

+X604031Y363528D01*

+X604206Y364255D01*

+X604250Y365000D01*

+X604206Y365745D01*

+X604031Y366472D01*

+X603745Y367163D01*

+X603355Y367801D01*

+X602869Y368369D01*

+X602301Y368855D01*

+X601663Y369245D01*

+X600972Y369531D01*

+X600245Y369706D01*

+X599500Y369765D01*

+X599493Y369764D01*

+Y390000D01*

+X609493D01*

+Y369764D01*

+X608755Y369706D01*

+X608028Y369531D01*

+X607337Y369245D01*

+X606699Y368855D01*

+X606131Y368369D01*

+X605645Y367801D01*

+X605255Y367163D01*

+X604969Y366472D01*

+X604794Y365745D01*

+X604735Y365000D01*

+X604794Y364255D01*

+X604969Y363528D01*

+X605255Y362837D01*

+X605645Y362199D01*

+X606131Y361631D01*

+X606699Y361145D01*

+X607337Y360755D01*

+X608028Y360469D01*

+X608755Y360294D01*

+X609493Y360236D01*

+Y344000D01*

+G37*

+G36*

+X599493Y323500D02*X587997D01*

+Y337315D01*

+X588029Y337347D01*

+X588096Y337404D01*

+X588326Y337673D01*

+X588326Y337673D01*

+X588511Y337975D01*

+X588646Y338303D01*

+X588729Y338647D01*

+X588757Y339000D01*

+X588750Y339088D01*

+Y347568D01*

+X589529Y348347D01*

+X589596Y348404D01*

+X589826Y348673D01*

+X589826Y348673D01*

+X590011Y348975D01*

+X590013Y348980D01*

+X590038Y348938D01*

+X590223Y348723D01*

+X590438Y348538D01*

+X590680Y348390D01*

+X590942Y348282D01*

+X591217Y348216D01*

+X591500Y348193D01*

+X591783Y348216D01*

+X592058Y348282D01*

+X592320Y348390D01*

+X592562Y348538D01*

+X592777Y348723D01*

+X592962Y348938D01*

+X593110Y349180D01*

+X593218Y349442D01*

+X593284Y349717D01*

+X593301Y350000D01*

+X593291Y350172D01*

+X593526Y349971D01*

+X593862Y349766D01*

+X594225Y349615D01*

+X594608Y349523D01*

+X595000Y349492D01*

+X595392Y349523D01*

+X595775Y349615D01*

+X596138Y349766D01*

+X596474Y349971D01*

+X596773Y350227D01*

+X597029Y350526D01*

+X597234Y350862D01*

+X597385Y351225D01*

+X597477Y351608D01*

+X597500Y352000D01*

+X597477Y352392D01*

+X597385Y352775D01*

+X597234Y353138D01*

+X597029Y353474D01*

+X596773Y353773D01*

+X596474Y354029D01*

+X596138Y354234D01*

+X595775Y354385D01*

+X595392Y354477D01*

+X595000Y354508D01*

+X594608Y354477D01*

+X594225Y354385D01*

+X593862Y354234D01*

+X593526Y354029D01*

+X593227Y353773D01*

+X592971Y353474D01*

+X592766Y353138D01*

+X592615Y352775D01*

+X592523Y352392D01*

+X592492Y352000D01*

+X592523Y351608D01*

+X592558Y351464D01*

+X592320Y351610D01*

+X592058Y351718D01*

+X591783Y351784D01*

+X591500Y351807D01*

+X591217Y351784D01*

+X590942Y351718D01*

+X590680Y351610D01*

+X590438Y351462D01*

+X590250Y351301D01*

+Y354412D01*

+X590257Y354500D01*

+X590229Y354853D01*

+X590146Y355197D01*

+X590107Y355293D01*

+X590011Y355525D01*

+X589896Y355712D01*

+X589826Y355827D01*

+X589826Y355827D01*

+X589596Y356096D01*

+X589529Y356153D01*

+X588431Y357251D01*

+X588558Y357282D01*

+X588820Y357390D01*

+X589062Y357538D01*

+X589277Y357723D01*

+X589462Y357938D01*

+X589610Y358180D01*

+X589718Y358442D01*

+X589784Y358717D01*

+X589801Y359000D01*

+X589784Y359283D01*

+X589718Y359558D01*

+X589610Y359820D01*

+X589462Y360062D01*

+X589277Y360277D01*

+X589062Y360462D01*

+X588820Y360610D01*

+X588558Y360718D01*

+X588283Y360784D01*

+X588000Y360807D01*

+X587997Y360806D01*

+Y361194D01*

+X588000Y361193D01*

+X588283Y361216D01*

+X588558Y361282D01*

+X588820Y361390D01*

+X589062Y361538D01*

+X589277Y361723D01*

+X589462Y361938D01*

+X589610Y362180D01*

+X589718Y362442D01*

+X589784Y362717D01*

+X589801Y363000D01*

+X589784Y363283D01*

+X589718Y363558D01*

+X589610Y363820D01*

+X589462Y364062D01*

+X589277Y364277D01*

+X589062Y364462D01*

+X588820Y364610D01*

+X588558Y364718D01*

+X588283Y364784D01*

+X588000Y364807D01*

+X587997Y364806D01*

+Y390000D01*

+X599493D01*

+Y369764D01*

+X598755Y369706D01*

+X598028Y369531D01*

+X597337Y369245D01*

+X596699Y368855D01*

+X596131Y368369D01*

+X595645Y367801D01*

+X595255Y367163D01*

+X594969Y366472D01*

+X594794Y365745D01*

+X594735Y365000D01*

+X594794Y364255D01*

+X594969Y363528D01*

+X595255Y362837D01*

+X595645Y362199D01*

+X596131Y361631D01*

+X596699Y361145D01*

+X597337Y360755D01*

+X598028Y360469D01*

+X598755Y360294D01*

+X599493Y360236D01*

+Y323500D01*

+G37*

+G36*

+X587997Y360806D02*X587717Y360784D01*

+X587442Y360718D01*

+X587180Y360610D01*

+X586938Y360462D01*

+X586723Y360277D01*

+X586538Y360062D01*

+X586390Y359820D01*

+X586282Y359558D01*

+X586239Y359380D01*

+X586025Y359511D01*

+X586000Y359521D01*

+Y371252D01*

+X586257Y371553D01*

+X586598Y372110D01*

+X586848Y372714D01*

+X587001Y373349D01*

+X587039Y374000D01*

+X587001Y374651D01*

+X586848Y375286D01*

+X586598Y375890D01*

+X586257Y376447D01*

+X586000Y376748D01*

+Y390000D01*

+X587997D01*

+Y364806D01*

+X587717Y364784D01*

+X587442Y364718D01*

+X587180Y364610D01*

+X586938Y364462D01*

+X586723Y364277D01*

+X586538Y364062D01*

+X586390Y363820D01*

+X586282Y363558D01*

+X586216Y363283D01*

+X586193Y363000D01*

+X586216Y362717D01*

+X586282Y362442D01*

+X586390Y362180D01*

+X586538Y361938D01*

+X586723Y361723D01*

+X586938Y361538D01*

+X587180Y361390D01*

+X587442Y361282D01*

+X587717Y361216D01*

+X587997Y361194D01*

+Y360806D01*

+G37*

+G36*

+Y323500D02*X586750D01*

+X586720Y324010D01*

+X586600Y324507D01*

+X586405Y324980D01*

+X586137Y325416D01*

+X586000Y325577D01*

+Y335318D01*

+X587997Y337315D01*

+Y323500D01*

+G37*

+G36*

+X651500Y268000D02*X701500D01*

+Y250000D01*

+X675500D01*

+X666500Y241000D01*

+X651500D01*

+Y268000D01*

+G37*

+G36*

+X610500D02*Y241000D01*

+X595500D01*

+X586500Y250000D01*

+X494000D01*

+Y268000D01*

+X610500D01*

+G37*

+G36*

+X701500Y249000D02*X701000Y230000D01*

+X683000Y212000D01*

+X494000D01*

+Y249000D01*

+X586000D01*

+X595000Y240000D01*

+X618500D01*

+Y232500D01*

+X619500Y231500D01*

+X622500D01*

+X623500Y232500D01*

+Y236000D01*

+X641500D01*

+X645500Y240000D01*

+X667000D01*

+X676000Y249000D01*

+X701500D01*

+G37*

+G36*

+X611500Y256000D02*X626000D01*

+Y244500D01*

+X627000Y243500D01*

+X630000D01*

+X631000Y244500D01*

+Y256000D01*

+X645500D01*

+Y241500D01*

+X641000Y237000D01*

+X623500D01*

+Y240000D01*

+X622500Y241000D01*

+X611500D01*

+Y256000D01*

+G37*

+G54D12*X593500Y277500D02*Y272854D01*

+G54D13*X621000Y234000D02*X629366D01*

+X631000Y232366D01*

+X621000Y238500D02*X628866D01*

+X631000Y240634D01*

+G54D12*X628500Y250646D02*Y246000D01*

+X653500Y277500D02*Y272854D01*

+X648500Y250646D02*Y246000D01*

+G54D13*X663957Y245500D02*X662500Y244043D01*

+X406500Y258000D02*X214500D01*

+X217500Y251500D02*X420000D01*

+X413000Y254500D02*X216000D01*

+X426500Y248000D02*X219500D01*

+X214500Y258000D02*X200000Y243500D01*

+X210000Y244000D02*X217500Y251500D01*

+X205000Y243500D02*X216000Y254500D01*

+X219500Y248000D02*X215000Y243500D01*

+X200000D02*Y231000D01*

+X210000D02*Y244000D01*

+X443500Y230000D02*X238500D01*

+X437000Y226500D02*X224500D01*

+X220000Y231000D01*

+X238500Y230000D02*X225000Y243500D01*

+X436000Y277500D02*X413000Y254500D01*

+X571000Y270000D02*X491000D01*

+X506000Y277000D02*X509500Y273500D01*

+X570500D01*

+X546059Y277000D02*X551441D01*

+X491000Y270000D02*X485000Y264000D01*

+X464500D01*

+X486000Y277000D02*X479000Y270000D01*

+X465500D01*

+X486000Y277000D02*X506000D01*

+X489500Y236441D02*X506441D01*

+X507500Y237500D01*

+X489500Y251059D02*X496059D01*

+X489500Y241559D02*Y245941D01*

+X496059Y251059D02*X498000Y253000D01*

+Y257000D01*

+G54D14*X450000Y294500D02*X455500Y289000D01*

+X450000Y299000D02*Y294500D01*

+X461012Y302512D02*Y299000D01*

+X456000Y311500D02*X455000Y312500D01*

+X456000Y311500D02*X462500D01*

+X445457Y309500D02*X452000D01*

+X455000Y312500D02*X452000Y309500D01*

+X461012Y302512D02*X467500Y309000D01*

+G54D13*X449400Y313600D02*X449500Y313500D01*

+X449400Y316800D02*Y313600D01*

+G54D14*X455000Y320000D02*Y312500D01*

+G54D13*X446000Y217500D02*X437000Y226500D01*

+X456000Y217500D02*X443500Y230000D01*

+X456000Y277500D02*X426500Y248000D01*

+X446000Y277500D02*X420000Y251500D01*

+X426000Y277500D02*X406500Y258000D01*

+X418500Y283500D02*X415500Y286500D01*

+G54D14*X455500Y289000D02*X482500D01*

+X476500Y299100D02*Y294000D01*

+X471000Y296100D02*Y294000D01*

+Y296100D02*X474000Y299100D01*

+X473000Y304941D02*Y299100D01*

+G54D13*X498500Y283500D02*X418500D01*

+G54D14*X490200Y299100D02*X491000Y299900D01*

+X485000Y294000D02*X492500D01*

+X486500Y306543D02*X486043Y307000D01*

+X486500Y306543D02*Y288900D01*

+X478500Y306543D02*Y299000D01*

+X478957Y307000D02*X478500Y306543D01*

+X474030Y299100D02*X482800D01*

+G54D13*X490200Y288900D02*X492100D01*

+X494500Y286500D01*

+X505700Y290700D02*X498500Y283500D01*

+X505700Y309900D02*Y290700D01*

+G54D14*X491000Y310500D02*Y299900D01*

+X474941Y312000D02*X489500D01*

+X474941D02*X473000Y310059D01*

+X491000Y310500D02*X489500Y312000D01*

+X495957Y315500D02*X491500Y319957D01*

+X483370Y315500D02*X491000D01*

+X496500Y310000D01*

+X483087Y327043D02*X499398D01*

+X478500Y334500D02*X491000D01*

+X496000Y332000D02*Y327086D01*

+X496043Y327043D01*

+X476500Y322370D02*Y332500D01*

+X478500Y334500D01*

+X474000Y336000D02*Y362500D01*

+X476500Y365000D01*

+X470500Y337000D02*Y361000D01*

+X466500Y365000D01*

+X482000Y328130D02*X483087Y327043D01*

+X483370Y315500D02*X476500Y322370D01*

+X483000Y323000D02*Y327000D01*

+X483065Y327065D01*

+X492000Y365000D02*Y358500D01*

+X501512Y348988D01*

+Y340000D01*

+X502000Y313500D02*X500000Y315500D01*

+X495957D01*

+X496500Y310000D02*X498000D01*

+X499441Y327000D02*Y321241D01*

+X504559Y327000D02*Y321241D01*

+X505700Y320100D01*

+X499441Y321241D02*X498300Y320100D01*

+X504559Y327000D02*X508000Y330441D01*

+Y332000D01*

+Y337559D02*X507941Y337500D01*

+X502000D01*

+X508000Y332000D02*X513500D01*

+X502000Y315500D02*Y309900D01*

+G54D15*X576000Y325154D02*Y322500D01*

+X574425Y325154D02*Y323925D01*

+G54D16*X572063Y325154D02*X570154D01*

+X568500Y323500D01*

+G54D15*X574425Y323925D02*X573500Y323000D01*

+Y320500D01*

+G54D13*X562000Y316000D02*X564059D01*

+G54D15*X577575Y325154D02*Y323925D01*

+G54D16*X579937Y325154D02*X581846D01*

+X583000Y328500D02*X569000D01*

+G54D15*X577575Y323925D02*X578500Y323000D01*

+Y320500D01*

+G54D16*X596000Y320000D02*X592059D01*

+X586941D02*Y320059D01*

+X581846Y325154D02*X586941Y320059D01*

+G54D13*X578500Y320500D02*Y318000D01*

+X573500Y320500D02*Y315500D01*

+X578500Y318000D02*X583500Y313000D01*

+G54D16*X579937Y331846D02*X582500Y334409D01*

+Y336000D01*

+G54D14*X583500D01*

+X586500Y339000D01*

+Y348500D01*

+G54D13*X582500Y341559D02*Y344500D01*

+G54D14*X586500Y348500D02*X588000Y350000D01*

+Y354500D01*

+X585000Y357500D01*

+X561000D01*

+X569110Y352346D02*Y374000D01*

+G54D13*X571000Y346000D02*X573500Y348500D01*

+G54D14*X554500Y351000D02*X561000Y357500D01*

+X554500Y351000D02*X540000D01*

+X535500Y346500D01*

+G54D13*X575500Y295059D02*Y299441D01*

+X556559Y290441D02*X548000Y299000D01*

+X575500Y285000D02*Y289941D01*

+X583500Y282500D02*X571000Y270000D01*

+X579500Y282500D02*X570500Y273500D01*

+X540941Y277000D02*X532500Y285441D01*

+Y288000D01*

+X556559Y277000D02*Y290441D01*

+X564059Y316000D02*X575500Y304559D01*

+X548000Y299000D02*Y329780D01*

+X573500Y315500D02*X579500Y309500D01*

+Y282500D01*

+X583500Y313000D02*Y282500D01*

+G54D14*X528500Y329780D02*X554500D01*

+X569000Y328500D02*X566059D01*

+X565559Y328000D01*

+G54D16*X568654Y331846D02*X568000Y332500D01*

+X572063Y331846D02*X568654D01*

+G54D14*X560441Y328000D02*Y331441D01*

+X563500Y334500D01*

+X568000Y332500D02*X566000Y334500D01*

+X563500D01*

+X559000Y339000D02*X563500Y334500D01*

+X535500Y346500D02*Y329780D01*

+X554500Y339000D02*X559000D01*

+G54D15*X577575Y331846D02*Y335866D01*

+X577000Y336441D01*

+G54D13*Y341559D02*Y345000D01*

+G54D15*X576000Y331846D02*Y328500D01*

+G54D13*X577000Y345000D02*X573500Y348500D01*

+X582500Y344500D02*X578000Y349000D01*

+G54D15*X574425Y331846D02*Y333016D01*

+X571000Y336441D01*

+G54D13*Y341559D02*Y346000D01*

+G54D14*X459200Y324200D02*X455000Y320000D01*

+X459600Y316800D02*X464000Y321200D01*

+X474500Y312000D02*Y313059D01*

+X472559Y318500D01*

+G54D13*X376500Y320441D02*Y315059D01*

+X372280Y329780D02*X376500Y325559D01*

+Y309941D02*Y306500D01*

+X354500Y329780D02*X372280D01*

+X321500Y328441D02*X316559Y323500D01*

+X313500D01*

+G54D14*X442000Y326000D02*Y320043D01*

+X445457Y309500D02*X442000Y312957D01*

+Y320043D02*X442457Y320500D01*

+X449500D01*

+X449400Y324200D02*X447870Y325730D01*

+Y333000D01*

+X447012D01*

+X440512Y339500D01*

+X429488D02*Y342488D01*

+X436000Y349000D01*

+X445500D01*

+X448500Y346000D01*

+Y341000D01*

+X453559D02*X458441D01*

+X466000Y345500D02*X459500D01*

+X458500Y344500D01*

+Y341500D01*

+X467000Y344500D02*X466000Y345500D01*

+X467000Y338000D02*Y344500D01*

+X463559Y341000D02*Y339559D01*

+X459130Y335130D01*

+X451000Y365000D02*Y353500D01*

+X459000Y345500D01*

+X441000Y365000D02*Y349000D01*

+X464000Y321200D02*Y335000D01*

+X467000Y338000D01*

+X467500Y309000D02*Y334000D01*

+X470500Y337000D01*

+X472559Y334559D02*X474000Y336000D01*

+X472559Y318500D02*Y334559D01*

+X459130Y324130D02*Y335130D01*

+G54D13*X339000Y365000D02*Y361059D01*

+X321500Y343559D01*

+Y333559D02*Y338441D01*

+G54D16*X275000Y383500D02*X310500D01*

+X329000Y365000D02*X310500Y383500D01*

+X218000Y365000D02*Y351500D01*

+X205000Y338500D01*

+X260000Y356000D02*X231000D01*

+X213500Y338500D01*

+X231500Y351000D02*X221000Y340500D01*

+X231500Y351000D02*X262000D01*

+X221000Y340500D02*Y314000D01*

+X213500Y338500D02*Y314000D01*

+X205000Y338500D02*Y314000D01*

+X260000Y356000D02*X266500Y362500D01*

+X262000Y351000D02*X273500Y362500D01*

+Y365000D01*

+X266500Y362500D02*Y375000D01*

+X275000Y383500D01*

+G54D13*X278500Y310000D02*Y380000D01*

+X246000Y277500D02*X278500Y310000D01*

+G54D17*X157500Y226370D02*X158210Y227080D01*

+X160340D01*

+X161050Y226370D01*

+Y224950D01*

+X157500Y221400D02*X161050Y224950D01*

+X157500Y221400D02*X161050D01*

+X162754Y222110D02*X163464Y221400D01*

+X162754Y226370D02*Y222110D01*

+Y226370D02*X163464Y227080D01*

+X164884D01*

+X165594Y226370D01*

+Y222110D01*

+X164884Y221400D02*X165594Y222110D01*

+X163464Y221400D02*X164884D01*

+X162754Y222820D02*X165594Y225660D01*

+X167298Y225944D02*X168434Y227080D01*

+Y221400D01*

+X167298D02*X169428D01*

+X171842D02*X173972Y224240D01*

+Y226370D02*Y224240D01*

+X173262Y227080D02*X173972Y226370D01*

+X171842Y227080D02*X173262D01*

+X171132Y226370D02*X171842Y227080D01*

+X171132Y226370D02*Y224950D01*

+X171842Y224240D01*

+X173972D01*

+X175676Y222110D02*X176386Y221400D01*

+X175676Y226370D02*Y222110D01*

+Y226370D02*X176386Y227080D01*

+X177806D01*

+X178516Y226370D01*

+Y222110D01*

+X177806Y221400D02*X178516Y222110D01*

+X176386Y221400D02*X177806D01*

+X175676Y222820D02*X178516Y225660D01*

+X180220Y225944D02*X181356Y227080D01*

+Y221400D01*

+X180220D02*X182350D01*

+X184054Y225944D02*X185190Y227080D01*

+Y221400D01*

+X184054D02*X186184D01*

+X187888Y227080D02*X190728D01*

+X187888D02*Y224240D01*

+X188598Y224950D01*

+X190018D01*

+X190728Y224240D01*

+Y222110D01*

+X190018Y221400D02*X190728Y222110D01*

+X188598Y221400D02*X190018D01*

+X187888Y222110D02*X188598Y221400D01*

+G54D11*G36*

+X646250Y368250D02*Y361750D01*

+X652750D01*

+Y368250D01*

+X646250D01*

+G37*

+G54D18*X639500Y365000D03*

+G54D19*X666110Y374000D03*

+X679890D03*

+X666110Y352346D03*

+X679890D03*

+G54D18*X629500Y365000D03*

+X619500D03*

+G54D20*X701500Y380000D03*

+G54D21*X631000Y290500D03*

+Y286760D03*

+Y294240D03*

+X636709Y290500D03*

+X625291D03*

+G54D20*X701500Y212000D03*

+G54D18*X609500Y365000D03*

+G54D11*G36*

+X525250Y368250D02*Y361750D01*

+X531750D01*

+Y368250D01*

+X525250D01*

+G37*

+G54D18*X518500Y365000D03*

+G54D11*G36*

+X550750Y368250D02*Y361750D01*

+X557250D01*

+Y368250D01*

+X550750D01*

+G37*

+G54D18*X544000Y365000D03*

+X599500D03*

+G54D19*X569110Y374000D03*

+X582890D03*

+Y352346D03*

+X569110D03*

+G54D22*X554500Y329780D03*

+Y312063D03*

+X528500D03*

+X554500Y302220D03*

+G54D23*X543831Y290134D03*

+G54D22*X528500Y302220D03*

+G54D23*X517831Y290134D03*

+G54D22*X554500Y319937D03*

+G54D23*X543831Y341866D03*

+G54D22*X528500Y329780D03*

+Y319937D03*

+G54D23*X517831Y341866D03*

+G54D11*G36*

+X243000Y220500D02*Y214500D01*

+X249000D01*

+Y220500D01*

+X243000D01*

+G37*

+G54D24*X256000Y217500D03*

+X266000D03*

+X276000D03*

+X286000D03*

+X296000D03*

+X306000D03*

+X316000D03*

+X326000D03*

+X336000D03*

+X346000D03*

+X356000D03*

+X366000D03*

+X376000D03*

+X386000D03*

+X396000D03*

+X406000D03*

+X416000D03*

+X406000Y277500D03*

+X396000D03*

+X386000D03*

+X376000D03*

+X366000D03*

+X356000D03*

+X346000D03*

+X336000D03*

+X326000D03*

+X316000D03*

+X306000D03*

+X296000D03*

+X286000D03*

+X276000D03*

+X266000D03*

+X256000D03*

+X246000D03*

+X426000Y217500D03*

+X436000D03*

+X446000D03*

+X456000D03*

+X466000D03*

+X476000D03*

+Y277500D03*

+X466000D03*

+X456000D03*

+X446000D03*

+X436000D03*

+X426000D03*

+X416000D03*

+G54D22*X410000Y329780D03*

+G54D23*X399331Y341866D03*

+G54D22*X410000Y319937D03*

+Y312063D03*

+Y302220D03*

+G54D23*X399331Y290134D03*

+G54D11*G36*

+X447750Y368250D02*Y361750D01*

+X454250D01*

+Y368250D01*

+X447750D01*

+G37*

+G54D18*X441000Y365000D03*

+G54D11*G36*

+X421250Y368250D02*Y361750D01*

+X427750D01*

+Y368250D01*

+X421250D01*

+G37*

+G54D18*X414500Y365000D03*

+G54D11*G36*

+X473250Y368250D02*Y361750D01*

+X479750D01*

+Y368250D01*

+X473250D01*

+G37*

+G54D18*X466500Y365000D03*

+G54D11*G36*

+X498750Y368250D02*Y361750D01*

+X505250D01*

+Y368250D01*

+X498750D01*

+G37*

+G54D18*X492000Y365000D03*

+X404500D03*

+X394500D03*

+X384500D03*

+G54D11*G36*

+X365750Y368250D02*Y361750D01*

+X372250D01*

+Y368250D01*

+X365750D01*

+G37*

+G54D18*X359000Y365000D03*

+X349000D03*

+X339000D03*

+X329000D03*

+G54D22*X354500Y329780D03*

+G54D23*X343831Y341866D03*

+G54D11*G36*

+X310250Y368250D02*Y361750D01*

+X316750D01*

+Y368250D01*

+X310250D01*

+G37*

+G54D18*X303500Y365000D03*

+X293500D03*

+X283500D03*

+X273500D03*

+G54D11*G36*

+X254750Y368250D02*Y361750D01*

+X261250D01*

+Y368250D01*

+X254750D01*

+G37*

+G54D18*X248000Y365000D03*

+X238000D03*

+X228000D03*

+X218000D03*

+G54D11*G36*

+X199250Y368250D02*Y361750D01*

+X205750D01*

+Y368250D01*

+X199250D01*

+G37*

+G54D18*X192500Y365000D03*

+X182500D03*

+X172500D03*

+X162500D03*

+G54D20*X141000Y380000D03*

+G54D22*X354500Y319937D03*

+X299000D03*

+Y312063D03*

+Y302220D03*

+G54D23*X288331Y290134D03*

+G54D22*X354500Y312063D03*

+Y302220D03*

+G54D23*X343831Y290134D03*

+G54D22*X299000Y329780D03*

+G54D23*X288331Y341866D03*

+G54D22*X243500Y329780D03*

+Y319937D03*

+Y312063D03*

+Y302220D03*

+X188000D03*

+G54D23*X232831Y341866D03*

+G54D22*X188000Y329780D03*

+Y319937D03*

+Y312063D03*

+G54D23*X177331Y341866D03*

+X232831Y290134D03*

+X177331D03*

+G54D20*X141000Y212000D03*

+G54D25*X593500Y264476D02*Y249791D01*

+G54D26*Y251051D02*Y250035D01*

+G54D25*X598500Y264476D02*Y249791D01*

+G54D26*Y251051D02*Y250035D01*

+G54D27*X594823Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D25*X603500Y264476D02*Y249791D01*

+G54D26*Y251051D02*Y250035D01*

+G54D25*X608500Y264476D02*Y249791D01*

+G54D26*Y251051D02*Y250035D01*

+G54D28*X599681Y258295D02*X602319D01*

+G54D27*X598941Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+X603059Y256803D02*Y254646D01*

+G54D25*X628500Y273709D02*Y259024D01*

+G54D26*Y273465D02*Y272449D01*

+G54D25*X623500Y273709D02*Y259024D01*

+G54D26*Y273465D02*Y272449D01*

+G54D25*X618500Y273709D02*Y259024D01*

+G54D26*Y273465D02*Y272449D01*

+G54D25*X613500Y273709D02*Y259024D01*

+G54D27*X614823Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X627177Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D28*X619681Y265205D02*X622319D01*

+G54D27*X623059Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X618941Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D26*X613500Y273465D02*Y272449D01*

+G54D25*X608500Y273752D02*Y271146D01*

+G54D27*X603059Y263276D02*Y261118D01*

+X607177Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D29*X544500Y262492D02*Y256193D01*

+X576000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+G54D30*X607107Y244043D02*X607893D01*

+X607107Y236957D02*X607893D01*

+X599107Y244043D02*X599893D01*

+X599107Y236957D02*X599893D01*

+G54D29*X513000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+X544500Y242807D02*Y236508D01*

+G54D31*X489008Y245941D02*X489992D01*

+X489008Y251059D02*X489992D01*

+X489008Y241559D02*X489992D01*

+X489008Y236441D02*X489992D01*

+G54D32*X498300Y310700D02*Y309100D01*

+X502000Y310700D02*Y309100D01*

+X505700Y310700D02*Y309100D01*

+G54D33*X429488Y344421D02*Y334579D01*

+G54D30*X441607Y312957D02*X442393D01*

+X441607Y320043D02*X442393D01*

+G54D32*X448600Y316800D02*X450200D01*

+X448600Y324200D02*X450200D01*

+X448600Y320500D02*X450200D01*

+X458800Y316800D02*X460400D01*

+X458800Y324200D02*X460400D01*

+G54D34*X481094Y316870D02*X482906D01*

+G54D31*X467441Y315492D02*Y314508D01*

+X472559Y315492D02*Y314508D01*

+G54D32*X505700Y320900D02*Y319300D01*

+X498300Y320900D02*Y319300D01*

+G54D30*X491107Y319957D02*X491893D01*

+G54D31*X448441Y341492D02*Y340508D01*

+G54D34*X447870Y333906D02*Y332094D01*

+G54D33*X449988Y303921D02*Y294079D01*

+X440512Y344421D02*Y334579D01*

+G54D31*X453559Y341492D02*Y340508D01*

+X458441Y341492D02*Y340508D01*

+X463559Y341492D02*Y340508D01*

+G54D34*X459130Y333906D02*Y332094D01*

+G54D33*X461012Y303921D02*Y294079D01*

+G54D34*X473094Y287870D02*X474906D01*

+X473094Y299130D02*X474906D01*

+G54D31*X472508Y310059D02*X473492D01*

+G54D34*X481094Y328130D02*X482906D01*

+G54D31*X472508Y304941D02*X473492D01*

+G54D30*X478957Y307393D02*Y306607D01*

+X486043Y307393D02*Y306607D01*

+G54D32*X482800Y289700D02*Y288100D01*

+X486500Y289700D02*Y288100D01*

+X490200Y289700D02*Y288100D01*

+Y299900D02*Y298300D01*

+X482800Y299900D02*Y298300D01*

+G54D33*X490488Y344921D02*Y335079D01*

+X501512Y344921D02*Y335079D01*

+G54D31*X504559Y327492D02*Y326508D01*

+X499441Y327492D02*Y326508D01*

+X507508Y337559D02*X508492D01*

+X507508Y332441D02*X508492D01*

+G54D30*X491107Y327043D02*X491893D01*

+G54D35*X572850Y328500D02*X579150D01*

+G54D31*X560441Y328492D02*Y327508D01*

+X565559Y328492D02*Y327508D01*

+X586941Y320492D02*Y319508D01*

+X592059Y320492D02*Y319508D01*

+X582008Y336441D02*X582992D01*

+X582008Y341559D02*X582992D01*

+X570508Y336441D02*X571492D01*

+X570508Y341559D02*X571492D01*

+X576508Y336441D02*X577492D01*

+X576508Y341559D02*X577492D01*

+X376008Y315059D02*X376992D01*

+X376008Y309941D02*X376992D01*

+X376008Y320441D02*X376992D01*

+X376008Y325559D02*X376992D01*

+X321008Y333559D02*X321992D01*

+X321008Y338441D02*X321992D01*

+X321008Y328441D02*X321992D01*

+X321008Y343559D02*X321992D01*

+G54D25*X593500Y273752D02*Y271146D01*

+G54D36*Y273858D02*Y271850D01*

+G54D25*X598500Y273752D02*Y271146D01*

+G54D36*Y273858D02*Y271850D01*

+G54D25*X603500Y273752D02*Y271146D01*

+G54D36*Y273858D02*Y271850D01*

+X608500Y273858D02*Y271850D01*

+G54D31*X546059Y277492D02*Y276508D01*

+X551441Y277492D02*Y276508D01*

+X556559Y277492D02*Y276508D01*

+X540941Y277492D02*Y276508D01*

+G54D37*X625882Y240634D02*X636118D01*

+X625882Y232366D02*X636118D01*

+G54D25*X628500Y252354D02*Y249748D01*

+G54D36*Y251650D02*Y249642D01*

+G54D25*X638500Y252354D02*Y249748D01*

+G54D36*Y251650D02*Y249642D01*

+G54D25*X633500Y252354D02*Y249748D01*

+G54D36*Y251650D02*Y249642D01*

+G54D25*X623500Y252354D02*Y249748D01*

+G54D36*Y251650D02*Y249642D01*

+G54D25*X618500Y252354D02*Y249748D01*

+G54D36*Y251650D02*Y249642D01*

+G54D25*X613500Y252354D02*Y249748D01*

+G54D36*Y251650D02*Y249642D01*

+G54D25*X658500Y264476D02*Y249791D01*

+G54D27*X658941Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D25*X668500Y264476D02*Y249791D01*

+G54D26*Y251051D02*Y250035D01*

+G54D28*X659681Y258295D02*X662319D01*

+G54D27*X654823Y263276D02*Y261118D01*

+X663059Y263276D02*Y261118D01*

+X667177Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D25*X653500Y264476D02*Y249791D01*

+G54D26*Y251051D02*Y250035D01*

+G54D27*X654823Y256803D02*Y254646D01*

+G54D30*X654107Y244043D02*X654893D01*

+X654107Y236957D02*X654893D01*

+G54D26*X658500Y251051D02*Y250035D01*

+G54D25*X663500Y264476D02*Y249791D01*

+G54D26*Y251051D02*Y250035D01*

+G54D27*X663059Y256803D02*Y254646D01*

+G54D30*X662107Y244043D02*X662893D01*

+X662107Y236957D02*X662893D01*

+G54D25*X648500Y252354D02*Y249748D01*

+G54D36*Y251650D02*Y249642D01*

+G54D25*X643500Y252354D02*Y249748D01*

+G54D36*Y251650D02*Y249642D01*

+G54D25*X653500Y273752D02*Y271146D01*

+G54D36*Y273858D02*Y271850D01*

+G54D25*X658500Y273752D02*Y271146D01*

+G54D36*Y273858D02*Y271850D01*

+G54D25*X663500Y273752D02*Y271146D01*

+G54D36*Y273858D02*Y271850D01*

+G54D25*X668500Y273752D02*Y271146D01*

+G54D36*Y273858D02*Y271850D01*

+G54D25*X648500Y273709D02*Y259024D01*

+G54D27*X647177Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D25*X638500Y273709D02*Y259024D01*

+G54D26*Y273465D02*Y272449D01*

+G54D25*X633500Y273709D02*Y259024D01*

+G54D26*Y273465D02*Y272449D01*

+G54D27*X634823Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D28*X639681Y265205D02*X642319D01*

+G54D27*X643059Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X638941Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D26*X648500Y273465D02*Y272449D01*

+G54D25*X643500Y273709D02*Y259024D01*

+G54D26*Y273465D02*Y272449D01*

+G54D29*X686000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+G54D38*X610331Y310984D02*Y309016D01*

+G54D31*X575008Y295059D02*X575992D01*

+X575008Y289941D02*X575992D01*

+X575008Y299441D02*X575992D01*

+X575008Y304559D02*X575992D01*

+G54D38*X651669Y310984D02*Y309016D01*

+G54D39*X571768Y325154D02*X572358D01*

+G54D40*X574425Y325646D02*Y324661D01*

+X576000Y325646D02*Y324661D01*

+X577575Y325646D02*Y324661D01*

+G54D39*X579642Y325154D02*X580232D01*

+X579642Y331846D02*X580232D01*

+G54D40*X577575Y332339D02*Y331354D01*

+X576000Y332339D02*Y331354D01*

+X574425Y332339D02*Y331354D01*

+G54D39*X571768Y331846D02*X572358D01*

+G54D41*X628500Y246000D03*

+X653500Y277500D03*

+X648500Y246000D03*

+X658000Y278000D03*

+X649000Y277500D03*

+X668000Y245500D03*

+X680500Y244000D03*

+Y237500D03*

+X662500Y232000D03*

+X655000D03*

+X599500D03*

+X607500D03*

+X691500Y237500D03*

+Y244000D03*

+X686000Y231000D03*

+X598000Y293500D03*

+X569000Y297500D03*

+X575500Y285000D03*

+X621000Y234000D03*

+Y238500D03*

+X594000Y245500D03*

+G54D42*X587000Y264500D03*

+Y254500D03*

+X583000Y259500D03*

+G54D41*X562000Y316000D03*

+X532500Y288000D03*

+X593500Y277500D03*

+X627000Y278000D03*

+X616500Y280500D03*

+Y290500D03*

+X625000Y303000D03*

+X622500Y306500D03*

+X647500Y285500D03*

+X637500Y303000D03*

+X622500Y311000D03*

+Y320000D03*

+X627000Y325500D03*

+G54D42*X596000Y320000D03*

+G54D41*Y312500D03*

+X570500Y244000D03*

+X581500Y237500D03*

+Y244000D03*

+X576000Y231000D03*

+X570500Y237500D03*

+X539000Y244000D03*

+Y237500D03*

+X518500D03*

+Y244000D03*

+X513000Y231000D03*

+X507500Y237500D03*

+X550000D03*

+X544500Y231000D03*

+X550000Y244000D03*

+X507500D03*

+X449500Y313500D03*

+G54D24*X462500Y311500D03*

+X442000Y326000D03*

+G54D42*X496000Y332000D03*

+X246000Y338500D03*

+X274000D03*

+X263000D03*

+G54D41*X422500Y331500D03*

+X416000Y373500D03*

+X313500Y323500D03*

+G54D24*X513500Y332000D03*

+G54D41*X569000Y328500D03*

+G54D43*X576000Y322500D03*

+G54D42*X568500Y323500D03*

+G54D24*X563500Y334500D03*

+X554500Y339000D03*

+G54D41*X583000Y328500D03*

+G54D42*X583500Y323500D03*

+X596500Y333500D03*

+X589000D03*

+Y326000D03*

+X596500D03*

+G54D41*X573500Y348500D03*

+X564500D03*

+X578000Y349000D03*

+G54D43*X591500Y350000D03*

+G54D41*X646500Y351500D03*

+X595000Y352000D03*

+G54D43*X588000Y363000D03*

+Y359000D03*

+G54D24*X606000Y381500D03*

+X600500Y386500D03*

+X595000Y381500D03*

+X589500Y386500D03*

+G54D41*X360500Y373500D03*

+X305000D03*

+X249500D03*

+X194000D03*

+X278500Y380000D03*

+X271000Y268000D03*

+X281000D03*

+X291000D03*

+X301000D03*

+G54D42*X492500Y294000D03*

+X485000D03*

+X476500D03*

+X471000D03*

+G54D41*X494500Y286500D03*

+X415500D03*

+G54D42*X483000Y323000D03*

+G54D24*X502000Y315000D03*

+X498000Y257000D03*

+G54D41*X246000Y261500D03*

+X429000Y254500D03*

+G54D24*X498000Y264000D03*

+G54D41*X463500Y243500D03*

+X489500Y274000D03*

+X464500Y264000D03*

+X465500Y270000D03*

+X449500Y240000D03*

+X455000Y250000D03*

+G54D42*X191500Y258000D03*

+Y237000D03*

+X205000Y314000D03*

+X213500D03*

+X221000D03*

+G54D41*X386000Y233500D03*

+X376500Y306500D03*

+X225000Y243500D03*

+X215000D03*

+X205000D03*

+X220000Y231000D03*

+X210000D03*

+X200000D03*

+X329500Y240500D03*

+X339000Y234500D03*

+X337000Y242000D03*

+X343500Y245000D03*

+G54D44*G54D14*G54D44*G54D14*G54D44*G54D12*G54D14*G54D44*G54D12*G54D44*G54D45*G54D14*G54D12*G54D44*G54D14*G54D44*G54D45*G54D44*G54D45*G54D12*G54D44*G54D14*G54D44*G54D14*G54D12*G54D44*G54D12*G54D44*G54D14*G54D44*G54D46*G54D47*G54D46*G54D48*G54D49*G54D48*G54D46*G54D47*G54D50*G54D51*G54D50*G54D51*G54D50*G54D51*G54D50*G54D51*G54D52*G54D50*G54D51*G54D50*G54D51*G54D46*G54D50*G54D51*G54D46*G54D48*G54D50*G54D51*G54D50*G54D51*G54D50*G54D51*G54D50*G54D51*G54D50*G54D51*G54D48*M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.topmask.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.topmask.gbr
new file mode 100644
index 0000000..28eed04
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.topmask.gbr
@@ -0,0 +1,444 @@
+G04 start of page 8 for group -4063 idx -4063 *

+G04 Title: uart, componentmask *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNTOPMASK*%

+%ADD169R,0.0138X0.0138*%

+%ADD168R,0.0236X0.0236*%

+%ADD167R,0.1772X0.1772*%

+%ADD166R,0.0650X0.0650*%

+%ADD165R,0.0221X0.0221*%

+%ADD164R,0.0402X0.0402*%

+%ADD163R,0.0614X0.0614*%

+%ADD162R,0.0551X0.0551*%

+%ADD161R,0.0380X0.0380*%

+%ADD160R,0.0355X0.0355*%

+%ADD159R,0.0572X0.0572*%

+%ADD158R,0.0748X0.0748*%

+%ADD157R,0.1516X0.1516*%

+%ADD156R,0.0294X0.0294*%

+%ADD155R,0.0200X0.0200*%

+%ADD154R,0.0280X0.0280*%

+%ADD153C,0.0660*%

+%ADD152C,0.1161*%

+%ADD151C,0.0650*%

+%ADD150C,0.1850*%

+%ADD149C,0.0728*%

+%ADD148C,0.0710*%

+%ADD147C,0.0001*%

+G54D147*G36*

+X645950Y368550D02*Y361450D01*

+X653050D01*

+Y368550D01*

+X645950D01*

+G37*

+G54D148*X639500Y365000D03*

+G54D149*X666110Y374000D03*

+X679890D03*

+X666110Y352346D03*

+X679890D03*

+G54D148*X629500Y365000D03*

+X619500D03*

+G54D150*X701500Y380000D03*

+Y212000D03*

+G54D148*X609500Y365000D03*

+G54D147*G36*

+X524950Y368550D02*Y361450D01*

+X532050D01*

+Y368550D01*

+X524950D01*

+G37*

+G54D148*X518500Y365000D03*

+G54D147*G36*

+X550450Y368550D02*Y361450D01*

+X557550D01*

+Y368550D01*

+X550450D01*

+G37*

+G54D148*X544000Y365000D03*

+X599500D03*

+G54D149*X569110Y374000D03*

+X582890D03*

+Y352346D03*

+X569110D03*

+G54D151*X554500Y329780D03*

+Y312063D03*

+X528500D03*

+X554500Y302220D03*

+G54D152*X543831Y290134D03*

+G54D151*X528500Y302220D03*

+G54D152*X517831Y290134D03*

+G54D151*X554500Y319937D03*

+G54D152*X543831Y341866D03*

+G54D151*X528500Y329780D03*

+Y319937D03*

+G54D152*X517831Y341866D03*

+G54D147*G36*

+X242700Y220800D02*Y214200D01*

+X249300D01*

+Y220800D01*

+X242700D01*

+G37*

+G54D153*X256000Y217500D03*

+X266000D03*

+X276000D03*

+X286000D03*

+X296000D03*

+X306000D03*

+X316000D03*

+X326000D03*

+X336000D03*

+X346000D03*

+X356000D03*

+X366000D03*

+X376000D03*

+X386000D03*

+X396000D03*

+X406000D03*

+X416000D03*

+X406000Y277500D03*

+X396000D03*

+X386000D03*

+X376000D03*

+X366000D03*

+X356000D03*

+X346000D03*

+X336000D03*

+X326000D03*

+X316000D03*

+X306000D03*

+X296000D03*

+X286000D03*

+X276000D03*

+X266000D03*

+X256000D03*

+X246000D03*

+X426000Y217500D03*

+X436000D03*

+X446000D03*

+X456000D03*

+X466000D03*

+X476000D03*

+Y277500D03*

+X466000D03*

+X456000D03*

+X446000D03*

+X436000D03*

+X426000D03*

+X416000D03*

+G54D151*X410000Y329780D03*

+G54D152*X399331Y341866D03*

+G54D151*X410000Y319937D03*

+Y312063D03*

+Y302220D03*

+G54D152*X399331Y290134D03*

+G54D147*G36*

+X447450Y368550D02*Y361450D01*

+X454550D01*

+Y368550D01*

+X447450D01*

+G37*

+G54D148*X441000Y365000D03*

+G54D147*G36*

+X420950Y368550D02*Y361450D01*

+X428050D01*

+Y368550D01*

+X420950D01*

+G37*

+G54D148*X414500Y365000D03*

+G54D147*G36*

+X472950Y368550D02*Y361450D01*

+X480050D01*

+Y368550D01*

+X472950D01*

+G37*

+G54D148*X466500Y365000D03*

+G54D147*G36*

+X498450Y368550D02*Y361450D01*

+X505550D01*

+Y368550D01*

+X498450D01*

+G37*

+G54D148*X492000Y365000D03*

+X404500D03*

+X394500D03*

+X384500D03*

+G54D147*G36*

+X365450Y368550D02*Y361450D01*

+X372550D01*

+Y368550D01*

+X365450D01*

+G37*

+G54D148*X359000Y365000D03*

+X349000D03*

+X339000D03*

+X329000D03*

+G54D151*X354500Y329780D03*

+G54D152*X343831Y341866D03*

+G54D147*G36*

+X309950Y368550D02*Y361450D01*

+X317050D01*

+Y368550D01*

+X309950D01*

+G37*

+G54D148*X303500Y365000D03*

+X293500D03*

+X283500D03*

+X273500D03*

+G54D147*G36*

+X254450Y368550D02*Y361450D01*

+X261550D01*

+Y368550D01*

+X254450D01*

+G37*

+G54D148*X248000Y365000D03*

+X238000D03*

+X228000D03*

+X218000D03*

+G54D147*G36*

+X198950Y368550D02*Y361450D01*

+X206050D01*

+Y368550D01*

+X198950D01*

+G37*

+G54D148*X192500Y365000D03*

+X182500D03*

+X172500D03*

+X162500D03*

+G54D150*X141000Y380000D03*

+G54D151*X354500Y319937D03*

+X299000D03*

+Y312063D03*

+Y302220D03*

+G54D152*X288331Y290134D03*

+G54D151*X354500Y312063D03*

+Y302220D03*

+G54D152*X343831Y290134D03*

+G54D151*X299000Y329780D03*

+G54D152*X288331Y341866D03*

+G54D151*X243500Y329780D03*

+Y319937D03*

+Y312063D03*

+Y302220D03*

+X188000D03*

+G54D152*X232831Y341866D03*

+G54D151*X188000Y329780D03*

+Y319937D03*

+Y312063D03*

+G54D152*X177331Y341866D03*

+X232831Y290134D03*

+X177331D03*

+G54D150*X141000Y212000D03*

+G54D154*X593500Y264476D02*Y249791D01*

+G54D155*Y251051D02*Y250035D01*

+G54D154*X598500Y264476D02*Y249791D01*

+G54D155*Y251051D02*Y250035D01*

+G54D156*X594823Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D154*X603500Y264476D02*Y249791D01*

+G54D155*Y251051D02*Y250035D01*

+G54D154*X608500Y264476D02*Y249791D01*

+G54D155*Y251051D02*Y250035D01*

+G54D157*X599681Y258295D02*X602319D01*

+G54D156*X598941Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+X603059Y256803D02*Y254646D01*

+G54D154*X628500Y273709D02*Y259024D01*

+G54D155*Y273465D02*Y272449D01*

+G54D154*X623500Y273709D02*Y259024D01*

+G54D155*Y273465D02*Y272449D01*

+G54D154*X618500Y273709D02*Y259024D01*

+G54D155*Y273465D02*Y272449D01*

+G54D154*X613500Y273709D02*Y259024D01*

+G54D156*X614823Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X627177Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D157*X619681Y265205D02*X622319D01*

+G54D156*X623059Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X618941Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D155*X613500Y273465D02*Y272449D01*

+G54D154*X608500Y273752D02*Y271146D01*

+G54D156*X603059Y263276D02*Y261118D01*

+X607177Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D158*X544500Y262492D02*Y256193D01*

+X576000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+G54D159*X607107Y244043D02*X607893D01*

+X607107Y236957D02*X607893D01*

+X599107Y244043D02*X599893D01*

+X599107Y236957D02*X599893D01*

+G54D158*X513000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+X544500Y242807D02*Y236508D01*

+G54D160*X489008Y245941D02*X489992D01*

+X489008Y251059D02*X489992D01*

+X489008Y241559D02*X489992D01*

+X489008Y236441D02*X489992D01*

+G54D161*X498300Y310700D02*Y309100D01*

+X502000Y310700D02*Y309100D01*

+X505700Y310700D02*Y309100D01*

+G54D162*X429488Y344421D02*Y334579D01*

+G54D159*X441607Y312957D02*X442393D01*

+X441607Y320043D02*X442393D01*

+G54D161*X448600Y316800D02*X450200D01*

+X448600Y324200D02*X450200D01*

+X448600Y320500D02*X450200D01*

+X458800Y316800D02*X460400D01*

+X458800Y324200D02*X460400D01*

+G54D163*X481094Y316870D02*X482906D01*

+G54D160*X467441Y315492D02*Y314508D01*

+X472559Y315492D02*Y314508D01*

+G54D161*X505700Y320900D02*Y319300D01*

+X498300Y320900D02*Y319300D01*

+G54D159*X491107Y319957D02*X491893D01*

+G54D160*X448441Y341492D02*Y340508D01*

+G54D163*X447870Y333906D02*Y332094D01*

+G54D162*X449988Y303921D02*Y294079D01*

+X440512Y344421D02*Y334579D01*

+G54D160*X453559Y341492D02*Y340508D01*

+X458441Y341492D02*Y340508D01*

+X463559Y341492D02*Y340508D01*

+G54D163*X459130Y333906D02*Y332094D01*

+G54D162*X461012Y303921D02*Y294079D01*

+G54D163*X473094Y287870D02*X474906D01*

+X473094Y299130D02*X474906D01*

+G54D160*X472508Y310059D02*X473492D01*

+G54D163*X481094Y328130D02*X482906D01*

+G54D160*X472508Y304941D02*X473492D01*

+G54D159*X478957Y307393D02*Y306607D01*

+X486043Y307393D02*Y306607D01*

+G54D161*X482800Y289700D02*Y288100D01*

+X486500Y289700D02*Y288100D01*

+X490200Y289700D02*Y288100D01*

+Y299900D02*Y298300D01*

+X482800Y299900D02*Y298300D01*

+G54D162*X490488Y344921D02*Y335079D01*

+X501512Y344921D02*Y335079D01*

+G54D160*X504559Y327492D02*Y326508D01*

+X499441Y327492D02*Y326508D01*

+X507508Y337559D02*X508492D01*

+X507508Y332441D02*X508492D01*

+G54D159*X491107Y327043D02*X491893D01*

+G54D164*X572850Y328500D02*X579150D01*

+G54D160*X560441Y328492D02*Y327508D01*

+X565559Y328492D02*Y327508D01*

+X586941Y320492D02*Y319508D01*

+X592059Y320492D02*Y319508D01*

+X582008Y336441D02*X582992D01*

+X582008Y341559D02*X582992D01*

+X570508Y336441D02*X571492D01*

+X570508Y341559D02*X571492D01*

+X576508Y336441D02*X577492D01*

+X576508Y341559D02*X577492D01*

+X376008Y315059D02*X376992D01*

+X376008Y309941D02*X376992D01*

+X376008Y320441D02*X376992D01*

+X376008Y325559D02*X376992D01*

+X321008Y333559D02*X321992D01*

+X321008Y338441D02*X321992D01*

+X321008Y328441D02*X321992D01*

+X321008Y343559D02*X321992D01*

+G54D154*X593500Y273752D02*Y271146D01*

+G54D165*Y273858D02*Y271850D01*

+G54D154*X598500Y273752D02*Y271146D01*

+G54D165*Y273858D02*Y271850D01*

+G54D154*X603500Y273752D02*Y271146D01*

+G54D165*Y273858D02*Y271850D01*

+X608500Y273858D02*Y271850D01*

+G54D160*X546059Y277492D02*Y276508D01*

+X551441Y277492D02*Y276508D01*

+X556559Y277492D02*Y276508D01*

+X540941Y277492D02*Y276508D01*

+G54D166*X625882Y240634D02*X636118D01*

+X625882Y232366D02*X636118D01*

+G54D154*X628500Y252354D02*Y249748D01*

+G54D165*Y251650D02*Y249642D01*

+G54D154*X638500Y252354D02*Y249748D01*

+G54D165*Y251650D02*Y249642D01*

+G54D154*X633500Y252354D02*Y249748D01*

+G54D165*Y251650D02*Y249642D01*

+G54D154*X623500Y252354D02*Y249748D01*

+G54D165*Y251650D02*Y249642D01*

+G54D154*X618500Y252354D02*Y249748D01*

+G54D165*Y251650D02*Y249642D01*

+G54D154*X613500Y252354D02*Y249748D01*

+G54D165*Y251650D02*Y249642D01*

+G54D154*X658500Y264476D02*Y249791D01*

+G54D156*X658941Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D154*X668500Y264476D02*Y249791D01*

+G54D155*Y251051D02*Y250035D01*

+G54D157*X659681Y258295D02*X662319D01*

+G54D156*X654823Y263276D02*Y261118D01*

+X663059Y263276D02*Y261118D01*

+X667177Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D154*X653500Y264476D02*Y249791D01*

+G54D155*Y251051D02*Y250035D01*

+G54D156*X654823Y256803D02*Y254646D01*

+G54D159*X654107Y244043D02*X654893D01*

+X654107Y236957D02*X654893D01*

+G54D155*X658500Y251051D02*Y250035D01*

+G54D154*X663500Y264476D02*Y249791D01*

+G54D155*Y251051D02*Y250035D01*

+G54D156*X663059Y256803D02*Y254646D01*

+G54D159*X662107Y244043D02*X662893D01*

+X662107Y236957D02*X662893D01*

+G54D154*X648500Y252354D02*Y249748D01*

+G54D165*Y251650D02*Y249642D01*

+G54D154*X643500Y252354D02*Y249748D01*

+G54D165*Y251650D02*Y249642D01*

+G54D154*X653500Y273752D02*Y271146D01*

+G54D165*Y273858D02*Y271850D01*

+G54D154*X658500Y273752D02*Y271146D01*

+G54D165*Y273858D02*Y271850D01*

+G54D154*X663500Y273752D02*Y271146D01*

+G54D165*Y273858D02*Y271850D01*

+G54D154*X668500Y273752D02*Y271146D01*

+G54D165*Y273858D02*Y271850D01*

+G54D154*X648500Y273709D02*Y259024D01*

+G54D156*X647177Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D154*X638500Y273709D02*Y259024D01*

+G54D155*Y273465D02*Y272449D01*

+G54D154*X633500Y273709D02*Y259024D01*

+G54D155*Y273465D02*Y272449D01*

+G54D156*X634823Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D157*X639681Y265205D02*X642319D01*

+G54D156*X643059Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X638941Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D155*X648500Y273465D02*Y272449D01*

+G54D154*X643500Y273709D02*Y259024D01*

+G54D155*Y273465D02*Y272449D01*

+G54D158*X686000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+G54D167*X610331Y310984D02*Y309016D01*

+G54D160*X575008Y295059D02*X575992D01*

+X575008Y289941D02*X575992D01*

+X575008Y299441D02*X575992D01*

+X575008Y304559D02*X575992D01*

+G54D167*X651669Y310984D02*Y309016D01*

+G54D168*X571768Y325154D02*X572358D01*

+G54D169*X574425Y325646D02*Y324661D01*

+X576000Y325646D02*Y324661D01*

+X577575Y325646D02*Y324661D01*

+G54D168*X579642Y325154D02*X580232D01*

+X579642Y331846D02*X580232D01*

+G54D169*X577575Y332339D02*Y331354D01*

+X576000Y332339D02*Y331354D01*

+X574425Y332339D02*Y331354D01*

+G54D168*X571768Y331846D02*X572358D01*

+M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.toppaste.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.toppaste.gbr
new file mode 100644
index 0000000..b3241c7
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.toppaste.gbr
@@ -0,0 +1,196 @@
+G04 start of page 12 for group -4015 idx -4015 *

+G04 Title: uart, toppaste *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNTOPPASTE*%

+%ADD207R,0.0362X0.0362*%

+%ADD206R,0.0098X0.0098*%

+%ADD205R,0.0197X0.0197*%

+%ADD204R,0.0472X0.0472*%

+%ADD203R,0.0528X0.0528*%

+%ADD202R,0.0280X0.0280*%

+%ADD201R,0.0295X0.0295*%

+%ADD200R,0.0512X0.0512*%

+%ADD199R,0.0630X0.0630*%

+%ADD198R,0.1772X0.1772*%

+%ADD197R,0.0221X0.0221*%

+%ADD196R,0.0294X0.0294*%

+%ADD195R,0.0200X0.0200*%

+%ADD194R,0.0551X0.0551*%

+G54D194*X625882Y240634D02*X636118D01*

+X625882Y232366D02*X636118D01*

+G54D195*X628500Y273465D02*Y272449D01*

+X623500Y273465D02*Y272449D01*

+X618500Y273465D02*Y272449D01*

+X613500Y273465D02*Y272449D01*

+G54D196*X627177Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X623059Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X618941Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X614823Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D197*X628500Y251650D02*Y249642D01*

+X623500Y251650D02*Y249642D01*

+X618500Y251650D02*Y249642D01*

+X613500Y251650D02*Y249642D01*

+G54D195*X653500Y251051D02*Y250035D01*

+X658500Y251051D02*Y250035D01*

+X663500Y251051D02*Y250035D01*

+X668500Y251051D02*Y250035D01*

+G54D196*X654823Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+X658941Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+X663059Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+X667177Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D197*X653500Y273858D02*Y271850D01*

+X658500Y273858D02*Y271850D01*

+X663500Y273858D02*Y271850D01*

+X668500Y273858D02*Y271850D01*

+G54D195*X648500Y273465D02*Y272449D01*

+X643500Y273465D02*Y272449D01*

+X638500Y273465D02*Y272449D01*

+X633500Y273465D02*Y272449D01*

+G54D196*X647177Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X643059Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X638941Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+X634823Y268854D02*Y266697D01*

+Y262382D02*Y260224D01*

+G54D197*X648500Y251650D02*Y249642D01*

+X643500Y251650D02*Y249642D01*

+X638500Y251650D02*Y249642D01*

+X633500Y251650D02*Y249642D01*

+G54D195*X593500Y251051D02*Y250035D01*

+X598500Y251051D02*Y250035D01*

+X603500Y251051D02*Y250035D01*

+X608500Y251051D02*Y250035D01*

+G54D196*X594823Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+X598941Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+X603059Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+X607177Y256803D02*Y254646D01*

+Y263276D02*Y261118D01*

+G54D197*X593500Y273858D02*Y271850D01*

+X598500Y273858D02*Y271850D01*

+X603500Y273858D02*Y271850D01*

+X608500Y273858D02*Y271850D01*

+G54D198*X610331Y310984D02*Y309016D01*

+X651669Y310984D02*Y309016D01*

+G54D199*X513000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+X544500Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+X576000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+G54D200*X654107Y244043D02*X654893D01*

+X654107Y236957D02*X654893D01*

+X662107Y244043D02*X662893D01*

+X662107Y236957D02*X662893D01*

+G54D199*X686000Y262492D02*Y256193D01*

+Y242807D02*Y236508D01*

+G54D200*X607107Y244043D02*X607893D01*

+X607107Y236957D02*X607893D01*

+X599107Y244043D02*X599893D01*

+X599107Y236957D02*X599893D01*

+G54D201*X448441Y341492D02*Y340508D01*

+X453559Y341492D02*Y340508D01*

+X458441Y341492D02*Y340508D01*

+X463559Y341492D02*Y340508D01*

+G54D200*X441607Y312957D02*X442393D01*

+X441607Y320043D02*X442393D01*

+G54D202*X448600Y324200D02*X450200D01*

+X448600Y320500D02*X450200D01*

+X448600Y316800D02*X450200D01*

+X458800D02*X460400D01*

+X458800Y324200D02*X460400D01*

+G54D203*X447870Y333906D02*Y332094D01*

+X459130Y333906D02*Y332094D01*

+G54D204*X449988Y303921D02*Y294079D01*

+X461012Y303921D02*Y294079D01*

+X440512Y344421D02*Y334579D01*

+X429488Y344421D02*Y334579D01*

+G54D203*X473094Y287870D02*X474906D01*

+X473094Y299130D02*X474906D01*

+G54D201*X472508Y310059D02*X473492D01*

+X472508Y304941D02*X473492D01*

+G54D202*X482800Y289700D02*Y288100D01*

+X486500Y289700D02*Y288100D01*

+X490200Y289700D02*Y288100D01*

+Y299900D02*Y298300D01*

+X482800Y299900D02*Y298300D01*

+G54D200*X478957Y307393D02*Y306607D01*

+X486043Y307393D02*Y306607D01*

+G54D203*X481094Y316870D02*X482906D01*

+X481094Y328130D02*X482906D01*

+G54D202*X498300Y310700D02*Y309100D01*

+X502000Y310700D02*Y309100D01*

+X505700Y310700D02*Y309100D01*

+Y320900D02*Y319300D01*

+X498300Y320900D02*Y319300D01*

+G54D204*X490488Y344921D02*Y335079D01*

+X501512Y344921D02*Y335079D01*

+G54D201*X504559Y327492D02*Y326508D01*

+X499441Y327492D02*Y326508D01*

+X507508Y337559D02*X508492D01*

+X507508Y332441D02*X508492D01*

+X467441Y315492D02*Y314508D01*

+X472559Y315492D02*Y314508D01*

+G54D200*X491107Y327043D02*X491893D01*

+X491107Y319957D02*X491893D01*

+G54D201*X575008Y295059D02*X575992D01*

+X575008Y289941D02*X575992D01*

+X575008Y299441D02*X575992D01*

+X575008Y304559D02*X575992D01*

+G54D205*X571768Y325154D02*X572358D01*

+G54D206*X574425Y325646D02*Y324661D01*

+X576000Y325646D02*Y324661D01*

+X577575Y325646D02*Y324661D01*

+G54D205*X579642Y325154D02*X580232D01*

+X579642Y331846D02*X580232D01*

+G54D206*X577575Y332339D02*Y331354D01*

+X576000Y332339D02*Y331354D01*

+X574425Y332339D02*Y331354D01*

+G54D205*X571768Y331846D02*X572358D01*

+G54D207*X572850Y328500D02*X579150D01*

+G54D201*X582008Y336441D02*X582992D01*

+X582008Y341559D02*X582992D01*

+X560441Y328492D02*Y327508D01*

+X565559Y328492D02*Y327508D01*

+X586941Y320492D02*Y319508D01*

+X592059Y320492D02*Y319508D01*

+X570508Y336441D02*X571492D01*

+X570508Y341559D02*X571492D01*

+X576508Y336441D02*X577492D01*

+X576508Y341559D02*X577492D01*

+X546059Y277492D02*Y276508D01*

+X540941Y277492D02*Y276508D01*

+X551441Y277492D02*Y276508D01*

+X556559Y277492D02*Y276508D01*

+X376008Y315059D02*X376992D01*

+X376008Y309941D02*X376992D01*

+X376008Y320441D02*X376992D01*

+X376008Y325559D02*X376992D01*

+X489008Y245941D02*X489992D01*

+X489008Y251059D02*X489992D01*

+X489008Y241559D02*X489992D01*

+X489008Y236441D02*X489992D01*

+X321008Y333559D02*X321992D01*

+X321008Y328441D02*X321992D01*

+X321008Y338441D02*X321992D01*

+X321008Y343559D02*X321992D01*

+M02*

diff --git a/motors/uart_schematic/shipped_files/uart-20190115/uart.topsilk.gbr b/motors/uart_schematic/shipped_files/uart-20190115/uart.topsilk.gbr
new file mode 100644
index 0000000..854632e
--- /dev/null
+++ b/motors/uart_schematic/shipped_files/uart-20190115/uart.topsilk.gbr
@@ -0,0 +1,3347 @@
+G04 start of page 10 for group -4079 idx -4079 *

+G04 Title: uart, topsilk *

+G04 Creator: pcb 20140316 *

+G04 CreationDate: Wed 16 Jan 2019 07:50:34 AM GMT UTC *

+G04 For: brian *

+G04 Format: Gerber/RS-274X *

+G04 PCB-Dimensions (mil): 9000.00 5000.00 *

+G04 PCB-Coordinate-Origin: lower left *

+%MOIN*%

+%FSLAX25Y25*%

+%LNTOPSILK*%

+%ADD189C,0.0110*%

+%ADD188C,0.0098*%

+%ADD187C,0.0197*%

+%ADD186C,0.0080*%

+%ADD185C,0.0100*%

+G54D185*X441000Y330500D02*Y328500D01*

+X439000Y329500D02*X444000D01*

+X442000D02*X441000Y328500D01*

+X442000Y329500D02*X441000Y330500D01*

+X442500Y331000D02*Y328000D01*

+X469500Y307500D02*X470500D01*

+X490000Y308000D02*X490500D01*

+X491500Y307000D01*

+X470000Y318500D02*Y317500D01*

+X476000Y323500D02*Y320000D01*

+X491000Y316500D02*Y314500D01*

+X490500Y314000D01*

+X474500Y322500D02*X477500D01*

+X476000Y322000D02*X475000Y321000D01*

+X476000Y322000D02*X477000Y321000D01*

+X475000D02*X477000D01*

+X466000Y297500D02*X468000D01*

+X467000Y300500D02*Y295500D01*

+Y298500D02*X468000Y297500D01*

+X467000Y298500D02*X466000Y297500D01*

+X465500Y299000D02*X468500D01*

+X443500Y306000D02*X442500Y305000D01*

+X443500Y309000D02*Y306000D01*

+X494500Y252000D02*Y246500D01*

+X492500Y248500D02*X496500D01*

+X494500D02*X493000Y250000D01*

+X496000D01*

+X494500Y248500D01*

+X507500Y327000D02*X508500D01*

+X577000Y344500D02*Y347000D01*

+X576500Y347500D01*

+X570500Y305500D02*Y300000D01*

+X568500Y302000D02*X572500D01*

+X570500D02*X572000Y303500D01*

+X569000D01*

+X570500Y302000D01*

+X552000Y282000D02*X557500D01*

+X554000Y284000D02*Y280000D01*

+Y282000D02*X555500Y280500D01*

+Y283500D02*X554000Y282000D01*

+X555500Y283500D02*Y280500D01*

+X371500Y326500D02*Y321000D01*

+X369500Y323000D02*X373500D01*

+X371500D02*X373000Y324500D01*

+X370000D01*

+X371500Y323000D01*

+X316500Y344500D02*Y339000D01*

+X314500Y341000D02*X318500D01*

+X316500D02*X318000Y342500D01*

+X315000D01*

+X316500Y341000D01*

+G54D186*X590241Y305159D02*X589641Y304559D01*

+X590241Y306959D02*Y305159D01*

+X589641Y307559D02*X590241Y306959D01*

+X588441Y307559D02*X589641D01*

+X588441D02*X587841Y306959D01*

+Y305159D01*

+X587241Y304559D01*

+X586041D02*X587241D01*

+X585441Y305159D02*X586041Y304559D01*

+X585441Y306959D02*Y305159D01*

+X586041Y307559D02*X585441Y306959D01*

+Y302519D02*X590241D01*

+Y303119D02*Y300719D01*

+X589641Y300119D01*

+X588441D02*X589641D01*

+X587841Y300719D02*X588441Y300119D01*

+X587841Y302519D02*Y300719D01*

+X590241Y298679D02*Y297479D01*

+X585441Y298079D02*X590241D01*

+X585441Y298679D02*Y297479D01*

+X590241Y293879D02*Y291479D01*

+X587841Y293879D02*X590241D01*

+X587841D02*X588441Y293279D01*

+Y292079D01*

+X587841Y291479D01*

+X586041D02*X587841D01*

+X585441Y292079D02*X586041Y291479D01*

+X585441Y293279D02*Y292079D01*

+X586041Y293879D02*X585441Y293279D01*

+X590241Y290039D02*X585441Y288839D01*

+X590241Y287639D01*

+X365494Y330900D02*X367340D01*

+X364500Y331894D02*X365494Y330900D01*

+X364500Y335586D02*Y331894D01*

+Y335586D02*X365494Y336580D01*

+X367340D01*

+X369044Y335160D02*Y330900D01*

+Y335160D02*X370038Y336580D01*

+X371600D01*

+X372594Y335160D01*

+Y330900D01*

+X369044Y333740D02*X372594D01*

+X374298Y336580D02*Y330900D01*

+Y336580D02*X376428Y333740D01*

+X378558Y336580D01*

+Y330900D01*

+X382818Y336580D02*X385658D01*

+X382818D02*Y333740D01*

+X383528Y334450D01*

+X384948D01*

+X385658Y333740D01*

+Y331610D01*

+X384948Y330900D02*X385658Y331610D01*

+X383528Y330900D02*X384948D01*

+X382818Y331610D02*X383528Y330900D01*

+X387362Y336580D02*X388782Y330900D01*

+X390202Y336580D01*

+X308500Y336600D02*X311300D01*

+X308500D02*Y333800D01*

+X309200Y334500D01*

+X310600D01*

+X311300Y333800D01*

+Y331700D01*

+X310600Y331000D02*X311300Y331700D01*

+X309200Y331000D02*X310600D01*

+X308500Y331700D02*X309200Y331000D01*

+X312980Y336600D02*X314380Y331000D01*

+X315780Y336600D01*

+X511000Y279870D02*Y275610D01*

+Y279870D02*X511710Y280580D01*

+X513130D01*

+X513840Y279870D01*

+Y275610D01*

+X513130Y274900D02*X513840Y275610D01*

+X511710Y274900D02*X513130D01*

+X511000Y275610D02*X511710Y274900D01*

+X516254Y280580D02*Y274900D01*

+X518100Y280580D02*X519094Y279586D01*

+Y275894D01*

+X518100Y274900D02*X519094Y275894D01*

+X515544Y274900D02*X518100D01*

+X515544Y280580D02*X518100D01*

+X520798D02*X523638D01*

+X524348Y279870D01*

+Y278450D01*

+X523638Y277740D02*X524348Y278450D01*

+X521508Y277740D02*X523638D01*

+X521508Y280580D02*Y274900D01*

+X522644Y277740D02*X524348Y274900D01*

+X526052Y279870D02*Y275610D01*

+Y279870D02*X526762Y280580D01*

+X528182D01*

+X528892Y279870D01*

+Y275610D01*

+X528182Y274900D02*X528892Y275610D01*

+X526762Y274900D02*X528182D01*

+X526052Y275610D02*X526762Y274900D01*

+X530596Y280580D02*X532016D01*

+X531306D02*Y274900D01*

+X530596D02*X532016D01*

+X534430Y280580D02*Y274900D01*

+X536276Y280580D02*X537270Y279586D01*

+Y275894D01*

+X536276Y274900D02*X537270Y275894D01*

+X533720Y274900D02*X536276D01*

+X533720Y280580D02*X536276D01*

+X366000Y382875D02*X366375Y383250D01*

+X367125D01*

+X367500Y382875D01*

+X367125Y380250D02*X367500Y380625D01*

+X366375Y380250D02*X367125D01*

+X366000Y380625D02*X366375Y380250D01*

+Y381900D02*X367125D01*

+X367500Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X367125Y381900D01*

+X367500Y382275D02*X367125Y381900D01*

+X368400Y380250D02*X368775D01*

+X369675Y382875D02*X370050Y383250D01*

+X370800D01*

+X371175Y382875D01*

+X370800Y380250D02*X371175Y380625D01*

+X370050Y380250D02*X370800D01*

+X369675Y380625D02*X370050Y380250D01*

+Y381900D02*X370800D01*

+X371175Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X370800Y381900D01*

+X371175Y382275D02*X370800Y381900D01*

+X372075Y383250D02*X372825Y380250D01*

+X373575Y383250D01*

+X356500D02*X358000D01*

+X357250D02*Y380250D01*

+X358900D02*X360775Y383250D01*

+X358900D02*X360775Y380250D01*

+X347500Y383250D02*X349000D01*

+X349375Y382875D01*

+Y382125D01*

+X349000Y381750D02*X349375Y382125D01*

+X347875Y381750D02*X349000D01*

+X347875Y383250D02*Y380250D01*

+X348475Y381750D02*X349375Y380250D01*

+X350275D02*X352150Y383250D01*

+X350275D02*X352150Y380250D01*

+X337000Y383250D02*X338500D01*

+X337000D02*Y381750D01*

+X337375Y382125D01*

+X338125D01*

+X338500Y381750D01*

+Y380625D01*

+X338125Y380250D02*X338500Y380625D01*

+X337375Y380250D02*X338125D01*

+X337000Y380625D02*X337375Y380250D01*

+X339400Y383250D02*X340150Y380250D01*

+X340900Y383250D01*

+X325000D02*Y380250D01*

+X326500D01*

+X327400Y381900D02*X328525D01*

+X327400Y380250D02*X328900D01*

+X327400Y383250D02*Y380250D01*

+Y383250D02*X328900D01*

+X330175D02*Y380250D01*

+X331150Y383250D02*X331675Y382725D01*

+Y380775D01*

+X331150Y380250D02*X331675Y380775D01*

+X329800Y380250D02*X331150D01*

+X329800Y383250D02*X331150D01*

+X421500Y382875D02*X421875Y383250D01*

+X422625D01*

+X423000Y382875D01*

+X422625Y380250D02*X423000Y380625D01*

+X421875Y380250D02*X422625D01*

+X421500Y380625D02*X421875Y380250D01*

+Y381900D02*X422625D01*

+X423000Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X422625Y381900D01*

+X423000Y382275D02*X422625Y381900D01*

+X423900Y380250D02*X424275D01*

+X425175Y382875D02*X425550Y383250D01*

+X426300D01*

+X426675Y382875D01*

+X426300Y380250D02*X426675Y380625D01*

+X425550Y380250D02*X426300D01*

+X425175Y380625D02*X425550Y380250D01*

+Y381900D02*X426300D01*

+X426675Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X426300Y381900D01*

+X426675Y382275D02*X426300Y381900D01*

+X427575Y383250D02*X428325Y380250D01*

+X429075Y383250D01*

+X412000D02*X413500D01*

+X412750D02*Y380250D01*

+X414400D02*X416275Y383250D01*

+X414400D02*X416275Y380250D01*

+X438500Y381240D02*X441340D01*

+X403000Y383250D02*X404500D01*

+X404875Y382875D01*

+Y382125D01*

+X404500Y381750D02*X404875Y382125D01*

+X403375Y381750D02*X404500D01*

+X403375Y383250D02*Y380250D01*

+X403975Y381750D02*X404875Y380250D01*

+X405775D02*X407650Y383250D01*

+X405775D02*X407650Y380250D01*

+X392500Y383250D02*X394000D01*

+X392500D02*Y381750D01*

+X392875Y382125D01*

+X393625D01*

+X394000Y381750D01*

+Y380625D01*

+X393625Y380250D02*X394000Y380625D01*

+X392875Y380250D02*X393625D01*

+X392500Y380625D02*X392875Y380250D01*

+X394900Y383250D02*X395650Y380250D01*

+X396400Y383250D01*

+X380500D02*Y380250D01*

+X382000D01*

+X382900Y381900D02*X384025D01*

+X382900Y380250D02*X384400D01*

+X382900Y383250D02*Y380250D01*

+Y383250D02*X384400D01*

+X385675D02*Y380250D01*

+X386650Y383250D02*X387175Y382725D01*

+Y380775D01*

+X386650Y380250D02*X387175Y380775D01*

+X385300Y380250D02*X386650D01*

+X385300Y383250D02*X386650D01*

+X449000Y381740D02*X451840D01*

+X450420Y383160D02*Y380320D01*

+X464000Y381240D02*X466840D01*

+X474500Y381740D02*X477340D01*

+X475920Y383160D02*Y380320D01*

+X490000Y381240D02*X492840D01*

+X500500Y381740D02*X503340D01*

+X501920Y383160D02*Y380320D01*

+X470470Y384520D02*X470960Y384030D01*

+X469490Y384520D02*X470470D01*

+X469000Y384030D02*X469490Y384520D01*

+X469000Y384030D02*Y381090D01*

+X469490Y380600D01*

+X470470Y382756D02*X470960Y382266D01*

+X469000Y382756D02*X470470D01*

+X469490Y380600D02*X470470D01*

+X470960Y381090D01*

+Y382266D02*Y381090D01*

+X494990Y381600D02*X496950Y385520D01*

+X494500D02*X496950D01*

+X526500Y383250D02*X528000D01*

+X526500D02*Y381750D01*

+X526875Y382125D01*

+X527625D01*

+X528000Y381750D01*

+Y380625D01*

+X527625Y380250D02*X528000Y380625D01*

+X526875Y380250D02*X527625D01*

+X526500Y380625D02*X526875Y380250D01*

+X528900Y383250D02*X529650Y380250D01*

+X530400Y383250D01*

+X514500D02*Y380250D01*

+X516000D01*

+X516900Y381900D02*X518025D01*

+X516900Y380250D02*X518400D01*

+X516900Y383250D02*Y380250D01*

+Y383250D02*X518400D01*

+X519675D02*Y380250D01*

+X520650Y383250D02*X521175Y382725D01*

+Y380775D01*

+X520650Y380250D02*X521175Y380775D01*

+X519300Y380250D02*X520650D01*

+X519300Y383250D02*X520650D01*

+X581000D02*X581375Y382875D01*

+X579875Y383250D02*X581000D01*

+X579500Y382875D02*X579875Y383250D01*

+X579500Y382875D02*Y380625D01*

+X579875Y380250D01*

+X581000D01*

+X581375Y380625D01*

+Y381375D02*Y380625D01*

+X581000Y381750D02*X581375Y381375D01*

+X580250Y381750D02*X581000D01*

+X582275Y383250D02*Y380250D01*

+Y383250D02*X584150Y380250D01*

+Y383250D02*Y380250D01*

+X585425Y383250D02*Y380250D01*

+X586400Y383250D02*X586925Y382725D01*

+Y380775D01*

+X586400Y380250D02*X586925Y380775D01*

+X585050Y380250D02*X586400D01*

+X585050Y383250D02*X586400D01*

+X552000D02*X553500D01*

+X552000D02*Y381750D01*

+X552375Y382125D01*

+X553125D01*

+X553500Y381750D01*

+Y380625D01*

+X553125Y380250D02*X553500Y380625D01*

+X552375Y380250D02*X553125D01*

+X552000Y380625D02*X552375Y380250D01*

+X554400Y383250D02*X555150Y380250D01*

+X555900Y383250D01*

+X540000D02*Y380250D01*

+X541500D01*

+X542400Y381900D02*X543525D01*

+X542400Y380250D02*X543900D01*

+X542400Y383250D02*Y380250D01*

+Y383250D02*X543900D01*

+X545175D02*Y380250D01*

+X546150Y383250D02*X546675Y382725D01*

+Y380775D01*

+X546150Y380250D02*X546675Y380775D01*

+X544800Y380250D02*X546150D01*

+X544800Y383250D02*X546150D01*

+X562000Y383375D02*Y381125D01*

+Y383375D02*X562375Y383750D01*

+X563125D01*

+X563500Y383375D01*

+Y381125D01*

+X563125Y380750D02*X563500Y381125D01*

+X562375Y380750D02*X563125D01*

+X562000Y381125D02*X562375Y380750D01*

+X564775Y383750D02*Y380750D01*

+X565750Y383750D02*X566275Y383225D01*

+Y381275D01*

+X565750Y380750D02*X566275Y381275D01*

+X564400Y380750D02*X565750D01*

+X564400Y383750D02*X565750D01*

+X567175D02*X568675D01*

+X569050Y383375D01*

+Y382625D01*

+X568675Y382250D02*X569050Y382625D01*

+X567550Y382250D02*X568675D01*

+X567550Y383750D02*Y380750D01*

+X568150Y382250D02*X569050Y380750D01*

+X569950Y383375D02*Y381125D01*

+Y383375D02*X570325Y383750D01*

+X571075D01*

+X571450Y383375D01*

+Y381125D01*

+X571075Y380750D02*X571450Y381125D01*

+X570325Y380750D02*X571075D01*

+X569950Y381125D02*X570325Y380750D01*

+X572350Y383750D02*X573100D01*

+X572725D02*Y380750D01*

+X572350D02*X573100D01*

+X574375Y383750D02*Y380750D01*

+X575350Y383750D02*X575875Y383225D01*

+Y381275D01*

+X575350Y380750D02*X575875Y381275D01*

+X574000Y380750D02*X575350D01*

+X574000Y383750D02*X575350D01*

+X548375Y383250D02*X549500Y384750D01*

+Y385875D02*Y384750D01*

+X549125Y386250D02*X549500Y385875D01*

+X548375Y386250D02*X549125D01*

+X548000Y385875D02*X548375Y386250D01*

+X548000Y385875D02*Y385125D01*

+X548375Y384750D01*

+X549500D01*

+X523000Y383125D02*X523375Y382750D01*

+X523000Y383725D02*Y383125D01*

+Y383725D02*X523525Y384250D01*

+X523975D01*

+X524500Y383725D01*

+Y383125D01*

+X524125Y382750D02*X524500Y383125D01*

+X523375Y382750D02*X524125D01*

+X523000Y384775D02*X523525Y384250D01*

+X523000Y385375D02*Y384775D01*

+Y385375D02*X523375Y385750D01*

+X524125D01*

+X524500Y385375D01*

+Y384775D01*

+X523975Y384250D02*X524500Y384775D01*

+X677500Y383750D02*X677875Y383375D01*

+X676375Y383750D02*X677500D01*

+X676000Y383375D02*X676375Y383750D01*

+X676000Y383375D02*Y381125D01*

+X676375Y380750D01*

+X677500D01*

+X677875Y381125D01*

+Y381875D02*Y381125D01*

+X677500Y382250D02*X677875Y381875D01*

+X676750Y382250D02*X677500D01*

+X678775Y383750D02*Y380750D01*

+Y383750D02*X680650Y380750D01*

+Y383750D02*Y380750D01*

+X681925Y383750D02*Y380750D01*

+X682900Y383750D02*X683425Y383225D01*

+Y381275D01*

+X682900Y380750D02*X683425Y381275D01*

+X681550Y380750D02*X682900D01*

+X681550Y383750D02*X682900D01*

+X661000D02*X661750Y380750D01*

+X662500Y383750D01*

+X663400Y380750D02*X664900D01*

+X665275Y381125D01*

+Y382025D02*Y381125D01*

+X664900Y382400D02*X665275Y382025D01*

+X663775Y382400D02*X664900D01*

+X663775Y383750D02*Y380750D01*

+X663400Y383750D02*X664900D01*

+X665275Y383375D01*

+Y382775D01*

+X664900Y382400D02*X665275Y382775D01*

+X666175Y383000D02*Y380750D01*

+Y383000D02*X666700Y383750D01*

+X667525D01*

+X668050Y383000D01*

+Y380750D01*

+X666175Y382250D02*X668050D01*

+X668950Y383750D02*X670450D01*

+X669700D02*Y380750D01*

+X647500Y383750D02*X647875Y383375D01*

+X646375Y383750D02*X647500D01*

+X646000Y383375D02*X646375Y383750D01*

+X646000Y383375D02*Y381125D01*

+X646375Y380750D01*

+X647500D01*

+X647875Y381125D01*

+Y381875D02*Y381125D01*

+X647500Y382250D02*X647875Y381875D01*

+X646750Y382250D02*X647500D01*

+X648775Y383750D02*Y380750D01*

+Y383750D02*X650650Y380750D01*

+Y383750D02*Y380750D01*

+X651925Y383750D02*Y380750D01*

+X652900Y383750D02*X653425Y383225D01*

+Y381275D01*

+X652900Y380750D02*X653425Y381275D01*

+X651550Y380750D02*X652900D01*

+X651550Y383750D02*X652900D01*

+X598525Y380250D02*X599500D01*

+X598000Y380775D02*X598525Y380250D01*

+X598000Y382725D02*Y380775D01*

+Y382725D02*X598525Y383250D01*

+X599500D01*

+X601900D02*X602275Y382875D01*

+X600775Y383250D02*X601900D01*

+X600400Y382875D02*X600775Y383250D01*

+X600400Y382875D02*Y382125D01*

+X600775Y381750D01*

+X601900D01*

+X602275Y381375D01*

+Y380625D01*

+X601900Y380250D02*X602275Y380625D01*

+X600775Y380250D02*X601900D01*

+X600400Y380625D02*X600775Y380250D01*

+X604500Y383250D02*Y380250D01*

+Y383250D02*X605625Y381750D01*

+X606750Y383250D01*

+Y380250D01*

+X607650Y383250D02*X608400D01*

+X608025D02*Y380250D01*

+X607650D02*X608400D01*

+X610800Y383250D02*X611175Y382875D01*

+X609675Y383250D02*X610800D01*

+X609300Y382875D02*X609675Y383250D01*

+X609300Y382875D02*Y382125D01*

+X609675Y381750D01*

+X610800D01*

+X611175Y381375D01*

+Y380625D01*

+X610800Y380250D02*X611175Y380625D01*

+X609675Y380250D02*X610800D01*

+X609300Y380625D02*X609675Y380250D01*

+X612075Y382875D02*Y380625D01*

+Y382875D02*X612450Y383250D01*

+X613200D01*

+X613575Y382875D01*

+Y380625D01*

+X613200Y380250D02*X613575Y380625D01*

+X612450Y380250D02*X613200D01*

+X612075Y380625D02*X612450Y380250D01*

+X634875Y383750D02*Y380750D01*

+X634500Y383750D02*X636000D01*

+X636375Y383375D01*

+Y382625D01*

+X636000Y382250D02*X636375Y382625D01*

+X634875Y382250D02*X636000D01*

+X637275Y383750D02*Y382250D01*

+X637650Y380750D01*

+X638400Y382250D01*

+X639150Y380750D01*

+X639525Y382250D01*

+Y383750D02*Y382250D01*

+X640425Y383750D02*X641925D01*

+X642300Y383375D01*

+Y382625D01*

+X641925Y382250D02*X642300Y382625D01*

+X640800Y382250D02*X641925D01*

+X640800Y383750D02*Y380750D01*

+X641400Y382250D02*X642300Y380750D01*

+X627025D02*X628000D01*

+X626500Y381275D02*X627025Y380750D01*

+X626500Y383225D02*Y381275D01*

+Y383225D02*X627025Y383750D01*

+X628000D01*

+X628900D02*Y380750D01*

+X630400D01*

+X631300Y383750D02*Y380750D01*

+Y382250D02*X632800Y383750D01*

+X631300Y382250D02*X632800Y380750D01*

+X615000Y383250D02*Y380250D01*

+Y383250D02*X616125Y381750D01*

+X617250Y383250D01*

+Y380250D01*

+X618150Y382875D02*Y380625D01*

+Y382875D02*X618525Y383250D01*

+X619275D01*

+X619650Y382875D01*

+Y380625D01*

+X619275Y380250D02*X619650Y380625D01*

+X618525Y380250D02*X619275D01*

+X618150Y380625D02*X618525Y380250D01*

+X622050Y383250D02*X622425Y382875D01*

+X620925Y383250D02*X622050D01*

+X620550Y382875D02*X620925Y383250D01*

+X620550Y382875D02*Y382125D01*

+X620925Y381750D01*

+X622050D01*

+X622425Y381375D01*

+Y380625D01*

+X622050Y380250D02*X622425Y380625D01*

+X620925Y380250D02*X622050D01*

+X620550Y380625D02*X620925Y380250D01*

+X623325Y383250D02*X624075D01*

+X623700D02*Y380250D01*

+X623325D02*X624075D01*

+X153000Y268530D02*X153490Y269020D01*

+X154960D01*

+X155450Y268530D01*

+Y267550D01*

+X153000Y265100D02*X155450Y267550D01*

+X153000Y265100D02*X155450D01*

+X156626Y265590D02*X157116Y265100D01*

+X156626Y268530D02*Y265590D01*

+Y268530D02*X157116Y269020D01*

+X158096D01*

+X158586Y268530D01*

+Y265590D01*

+X158096Y265100D02*X158586Y265590D01*

+X157116Y265100D02*X158096D01*

+X156626Y266080D02*X158586Y268040D01*

+X159762Y268236D02*X160546Y269020D01*

+Y265100D01*

+X159762D02*X161232D01*

+X162898D02*X164368Y267060D01*

+Y268530D02*Y267060D01*

+X163878Y269020D02*X164368Y268530D01*

+X162898Y269020D02*X163878D01*

+X162408Y268530D02*X162898Y269020D01*

+X162408Y268530D02*Y267550D01*

+X162898Y267060D01*

+X164368D01*

+X165544Y265590D02*X166034Y265100D01*

+X165544Y268530D02*Y265590D01*

+Y268530D02*X166034Y269020D01*

+X167014D01*

+X167504Y268530D01*

+Y265590D01*

+X167014Y265100D02*X167504Y265590D01*

+X166034Y265100D02*X167014D01*

+X165544Y266080D02*X167504Y268040D01*

+X168680Y268236D02*X169464Y269020D01*

+Y265100D01*

+X168680D02*X170150D01*

+X171326Y268236D02*X172110Y269020D01*

+Y265100D01*

+X171326D02*X172796D01*

+X173972Y269020D02*X175932D01*

+X173972D02*Y267060D01*

+X174462Y267550D01*

+X175442D01*

+X175932Y267060D01*

+Y265590D01*

+X175442Y265100D02*X175932Y265590D01*

+X174462Y265100D02*X175442D01*

+X173972Y265590D02*X174462Y265100D01*

+X153500Y260520D02*Y256600D01*

+Y260520D02*X155460D01*

+X153500Y258756D02*X154970D01*

+X156636Y260520D02*X158596D01*

+X159086Y260030D01*

+Y259050D01*

+X158596Y258560D02*X159086Y259050D01*

+X157126Y258560D02*X158596D01*

+X157126Y260520D02*Y256600D01*

+X157910Y258560D02*X159086Y256600D01*

+X160948D02*X162222D01*

+X160262Y257286D02*X160948Y256600D01*

+X160262Y259834D02*Y257286D01*

+Y259834D02*X160948Y260520D01*

+X162222D01*

+X165652Y256600D02*X167122Y258560D01*

+Y260030D02*Y258560D01*

+X166632Y260520D02*X167122Y260030D01*

+X165652Y260520D02*X166632D01*

+X165162Y260030D02*X165652Y260520D01*

+X165162Y260030D02*Y259050D01*

+X165652Y258560D01*

+X167122D01*

+X168788Y256600D02*X170748Y260520D01*

+X168298D02*X170748D01*

+X171924Y259736D02*X172708Y260520D01*

+Y256600D01*

+X171924D02*X173394D01*

+X151460Y255020D02*X151950Y254530D01*

+X149990Y255020D02*X151460D01*

+X149500Y254530D02*X149990Y255020D01*

+X149500Y254530D02*Y253550D01*

+X149990Y253060D01*

+X151460D01*

+X151950Y252570D01*

+Y251590D01*

+X151460Y251100D02*X151950Y251590D01*

+X149990Y251100D02*X151460D01*

+X149500Y251590D02*X149990Y251100D01*

+X153616Y252570D02*Y249630D01*

+X153126Y253060D02*X153616Y252570D01*

+X154106Y253060D01*

+X155086D01*

+X155576Y252570D01*

+Y251590D01*

+X155086Y251100D02*X155576Y251590D01*

+X154106Y251100D02*X155086D01*

+X153616Y251590D02*X154106Y251100D01*

+X158222Y253060D02*X158712Y252570D01*

+X157242Y253060D02*X158222D01*

+X156752Y252570D02*X157242Y253060D01*

+X156752Y252570D02*Y251590D01*

+X157242Y251100D01*

+X158712Y253060D02*Y251590D01*

+X159202Y251100D01*

+X157242D02*X158222D01*

+X158712Y251590D01*

+X160868Y252570D02*Y251100D01*

+Y252570D02*X161358Y253060D01*

+X162338D01*

+X160378D02*X160868Y252570D01*

+X164004Y255020D02*Y251590D01*

+X164494Y251100D01*

+X163514Y253550D02*X164494D01*

+X166944Y253060D02*X167434Y252570D01*

+X165964Y253060D02*X166944D01*

+X165474Y252570D02*X165964Y253060D01*

+X165474Y252570D02*Y251590D01*

+X165964Y251100D01*

+X167434Y253060D02*Y251590D01*

+X167924Y251100D01*

+X165964D02*X166944D01*

+X167434Y251590D01*

+X169590Y252570D02*Y251100D01*

+Y252570D02*X170080Y253060D01*

+X170570D01*

+X171060Y252570D01*

+Y251100D01*

+X169100Y253060D02*X169590Y252570D01*

+X174000Y255020D02*X175960D01*

+X176450Y254530D01*

+Y253550D01*

+X175960Y253060D02*X176450Y253550D01*

+X174490Y253060D02*X175960D01*

+X174490Y255020D02*Y251100D01*

+X175274Y253060D02*X176450Y251100D01*

+X177626Y252570D02*Y251590D01*

+Y252570D02*X178116Y253060D01*

+X179096D01*

+X179586Y252570D01*

+Y251590D01*

+X179096Y251100D02*X179586Y251590D01*

+X178116Y251100D02*X179096D01*

+X177626Y251590D02*X178116Y251100D01*

+X180762Y255020D02*Y251100D01*

+Y251590D02*X181252Y251100D01*

+X182232D01*

+X182722Y251590D01*

+Y252570D02*Y251590D01*

+X182232Y253060D02*X182722Y252570D01*

+X181252Y253060D02*X182232D01*

+X180762Y252570D02*X181252Y253060D01*

+X183898Y252570D02*Y251590D01*

+Y252570D02*X184388Y253060D01*

+X185368D01*

+X185858Y252570D01*

+Y251590D01*

+X185368Y251100D02*X185858Y251590D01*

+X184388Y251100D02*X185368D01*

+X183898Y251590D02*X184388Y251100D01*

+X187524Y255020D02*Y251590D01*

+X188014Y251100D01*

+X187034Y253550D02*X188014D01*

+X188994Y254040D02*Y253942D01*

+Y252570D02*Y251100D01*

+X190464Y253060D02*X191934D01*

+X189974Y252570D02*X190464Y253060D01*

+X189974Y252570D02*Y251590D01*

+X190464Y251100D01*

+X191934D01*

+X193600D02*X195070D01*

+X195560Y251590D01*

+X195070Y252080D02*X195560Y251590D01*

+X193600Y252080D02*X195070D01*

+X193110Y252570D02*X193600Y252080D01*

+X193110Y252570D02*X193600Y253060D01*

+X195070D01*

+X195560Y252570D01*

+X193110Y251590D02*X193600Y251100D01*

+X147000Y245520D02*Y242090D01*

+X147490Y241600D01*

+X148470D01*

+X148960Y242090D01*

+Y245520D02*Y242090D01*

+X150136Y244540D02*Y241600D01*

+Y244540D02*X150822Y245520D01*

+X151900D01*

+X152586Y244540D01*

+Y241600D01*

+X150136Y243560D02*X152586D01*

+X153762Y245520D02*X155722D01*

+X156212Y245030D01*

+Y244050D01*

+X155722Y243560D02*X156212Y244050D01*

+X154252Y243560D02*X155722D01*

+X154252Y245520D02*Y241600D01*

+X155036Y243560D02*X156212Y241600D01*

+X157388Y245520D02*X159348D01*

+X158368D02*Y241600D01*

+X162974D02*X164248D01*

+X162288Y242286D02*X162974Y241600D01*

+X162288Y244834D02*Y242286D01*

+Y244834D02*X162974Y245520D01*

+X164248D01*

+X166894Y243560D02*X167384Y243070D01*

+X165914Y243560D02*X166894D01*

+X165424Y243070D02*X165914Y243560D01*

+X165424Y243070D02*Y242090D01*

+X165914Y241600D01*

+X167384Y243560D02*Y242090D01*

+X167874Y241600D01*

+X165914D02*X166894D01*

+X167384Y242090D01*

+X169540Y243070D02*Y241600D01*

+Y243070D02*X170030Y243560D01*

+X170520D01*

+X171010Y243070D01*

+Y241600D01*

+Y243070D02*X171500Y243560D01*

+X171990D01*

+X172480Y243070D01*

+Y241600D01*

+X169050Y243560D02*X169540Y243070D01*

+X174146Y241600D02*X175616D01*

+X173656Y242090D02*X174146Y241600D01*

+X173656Y243070D02*Y242090D01*

+Y243070D02*X174146Y243560D01*

+X175126D01*

+X175616Y243070D01*

+X173656Y242580D02*X175616D01*

+Y243070D02*Y242580D01*

+X177282Y243070D02*Y241600D01*

+Y243070D02*X177772Y243560D01*

+X178752D01*

+X176792D02*X177282Y243070D01*

+X181398Y243560D02*X181888Y243070D01*

+X180418Y243560D02*X181398D01*

+X179928Y243070D02*X180418Y243560D01*

+X179928Y243070D02*Y242090D01*

+X180418Y241600D01*

+X181888Y243560D02*Y242090D01*

+X182378Y241600D01*

+X180418D02*X181398D01*

+X181888Y242090D01*

+X185318Y241600D02*X187278D01*

+X187768Y242090D01*

+Y243266D02*Y242090D01*

+X187278Y243756D02*X187768Y243266D01*

+X185808Y243756D02*X187278D01*

+X185808Y245520D02*Y241600D01*

+X185318Y245520D02*X187278D01*

+X187768Y245030D01*

+Y244246D01*

+X187278Y243756D02*X187768Y244246D01*

+X188944Y243070D02*Y242090D01*

+Y243070D02*X189434Y243560D01*

+X190414D01*

+X190904Y243070D01*

+Y242090D01*

+X190414Y241600D02*X190904Y242090D01*

+X189434Y241600D02*X190414D01*

+X188944Y242090D02*X189434Y241600D01*

+X193550Y243560D02*X194040Y243070D01*

+X192570Y243560D02*X193550D01*

+X192080Y243070D02*X192570Y243560D01*

+X192080Y243070D02*Y242090D01*

+X192570Y241600D01*

+X194040Y243560D02*Y242090D01*

+X194530Y241600D01*

+X192570D02*X193550D01*

+X194040Y242090D01*

+X196196Y243070D02*Y241600D01*

+Y243070D02*X196686Y243560D01*

+X197666D01*

+X195706D02*X196196Y243070D01*

+X200802Y245520D02*Y241600D01*

+X200312D02*X200802Y242090D01*

+X199332Y241600D02*X200312D01*

+X198842Y242090D02*X199332Y241600D01*

+X198842Y243070D02*Y242090D01*

+Y243070D02*X199332Y243560D01*

+X200312D01*

+X200802Y243070D01*

+X181000Y383250D02*X182500D01*

+X182875Y382875D01*

+Y382125D01*

+X182500Y381750D02*X182875Y382125D01*

+X181375Y381750D02*X182500D01*

+X181375Y383250D02*Y380250D01*

+X181975Y381750D02*X182875Y380250D01*

+X183775D02*X185650Y383250D01*

+X183775D02*X185650Y380250D01*

+X170500Y383250D02*X172000D01*

+X170500D02*Y381750D01*

+X170875Y382125D01*

+X171625D01*

+X172000Y381750D01*

+Y380625D01*

+X171625Y380250D02*X172000Y380625D01*

+X170875Y380250D02*X171625D01*

+X170500Y380625D02*X170875Y380250D01*

+X172900Y383250D02*X173650Y380250D01*

+X174400Y383250D01*

+X158500D02*Y380250D01*

+X160000D01*

+X160900Y381900D02*X162025D01*

+X160900Y380250D02*X162400D01*

+X160900Y383250D02*Y380250D01*

+Y383250D02*X162400D01*

+X163675D02*Y380250D01*

+X164650Y383250D02*X165175Y382725D01*

+Y380775D01*

+X164650Y380250D02*X165175Y380775D01*

+X163300Y380250D02*X164650D01*

+X163300Y383250D02*X164650D01*

+X199500Y382875D02*X199875Y383250D01*

+X200625D01*

+X201000Y382875D01*

+X200625Y380250D02*X201000Y380625D01*

+X199875Y380250D02*X200625D01*

+X199500Y380625D02*X199875Y380250D01*

+Y381900D02*X200625D01*

+X201000Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X200625Y381900D01*

+X201000Y382275D02*X200625Y381900D01*

+X201900Y380250D02*X202275D01*

+X203175Y382875D02*X203550Y383250D01*

+X204300D01*

+X204675Y382875D01*

+X204300Y380250D02*X204675Y380625D01*

+X203550Y380250D02*X204300D01*

+X203175Y380625D02*X203550Y380250D01*

+Y381900D02*X204300D01*

+X204675Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X204300Y381900D01*

+X204675Y382275D02*X204300Y381900D01*

+X205575Y383250D02*X206325Y380250D01*

+X207075Y383250D01*

+X245500D02*X247000D01*

+X246250D02*Y380250D01*

+X247900D02*X249775Y383250D01*

+X247900D02*X249775Y380250D01*

+X236500Y383250D02*X238000D01*

+X238375Y382875D01*

+Y382125D01*

+X238000Y381750D02*X238375Y382125D01*

+X236875Y381750D02*X238000D01*

+X236875Y383250D02*Y380250D01*

+X237475Y381750D02*X238375Y380250D01*

+X239275D02*X241150Y383250D01*

+X239275D02*X241150Y380250D01*

+X226000Y383250D02*X227500D01*

+X226000D02*Y381750D01*

+X226375Y382125D01*

+X227125D01*

+X227500Y381750D01*

+Y380625D01*

+X227125Y380250D02*X227500Y380625D01*

+X226375Y380250D02*X227125D01*

+X226000Y380625D02*X226375Y380250D01*

+X228400Y383250D02*X229150Y380250D01*

+X229900Y383250D01*

+X214000D02*Y380250D01*

+X215500D01*

+X216400Y381900D02*X217525D01*

+X216400Y380250D02*X217900D01*

+X216400Y383250D02*Y380250D01*

+Y383250D02*X217900D01*

+X219175D02*Y380250D01*

+X220150Y383250D02*X220675Y382725D01*

+Y380775D01*

+X220150Y380250D02*X220675Y380775D01*

+X218800Y380250D02*X220150D01*

+X218800Y383250D02*X220150D01*

+X190000D02*X191500D01*

+X190750D02*Y380250D01*

+X192400D02*X194275Y383250D01*

+X192400D02*X194275Y380250D01*

+X255000Y382875D02*X255375Y383250D01*

+X256125D01*

+X256500Y382875D01*

+X256125Y380250D02*X256500Y380625D01*

+X255375Y380250D02*X256125D01*

+X255000Y380625D02*X255375Y380250D01*

+Y381900D02*X256125D01*

+X256500Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X256125Y381900D01*

+X256500Y382275D02*X256125Y381900D01*

+X257400Y380250D02*X257775D01*

+X258675Y382875D02*X259050Y383250D01*

+X259800D01*

+X260175Y382875D01*

+X259800Y380250D02*X260175Y380625D01*

+X259050Y380250D02*X259800D01*

+X258675Y380625D02*X259050Y380250D01*

+Y381900D02*X259800D01*

+X260175Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X259800Y381900D01*

+X260175Y382275D02*X259800Y381900D01*

+X261075Y383250D02*X261825Y380250D01*

+X262575Y383250D01*

+X310500Y382875D02*X310875Y383250D01*

+X311625D01*

+X312000Y382875D01*

+X311625Y380250D02*X312000Y380625D01*

+X310875Y380250D02*X311625D01*

+X310500Y380625D02*X310875Y380250D01*

+Y381900D02*X311625D01*

+X312000Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X311625Y381900D01*

+X312000Y382275D02*X311625Y381900D01*

+X312900Y380250D02*X313275D01*

+X314175Y382875D02*X314550Y383250D01*

+X315300D01*

+X315675Y382875D01*

+X315300Y380250D02*X315675Y380625D01*

+X314550Y380250D02*X315300D01*

+X314175Y380625D02*X314550Y380250D01*

+Y381900D02*X315300D01*

+X315675Y382875D02*Y382275D01*

+Y381525D02*Y380625D01*

+Y381525D02*X315300Y381900D01*

+X315675Y382275D02*X315300Y381900D01*

+X316575Y383250D02*X317325Y380250D01*

+X318075Y383250D01*

+X301000D02*X302500D01*

+X301750D02*Y380250D01*

+X303400D02*X305275Y383250D01*

+X303400D02*X305275Y380250D01*

+X292000Y383250D02*X293500D01*

+X293875Y382875D01*

+Y382125D01*

+X293500Y381750D02*X293875Y382125D01*

+X292375Y381750D02*X293500D01*

+X292375Y383250D02*Y380250D01*

+X292975Y381750D02*X293875Y380250D01*

+X294775D02*X296650Y383250D01*

+X294775D02*X296650Y380250D01*

+X281500Y383250D02*X283000D01*

+X281500D02*Y381750D01*

+X281875Y382125D01*

+X282625D01*

+X283000Y381750D01*

+Y380625D01*

+X282625Y380250D02*X283000Y380625D01*

+X281875Y380250D02*X282625D01*

+X281500Y380625D02*X281875Y380250D01*

+X283900Y383250D02*X284650Y380250D01*

+X285400Y383250D01*

+X269500D02*Y380250D01*

+X271000D01*

+X271900Y381900D02*X273025D01*

+X271900Y380250D02*X273400D01*

+X271900Y383250D02*Y380250D01*

+Y383250D02*X273400D01*

+X274675D02*Y380250D01*

+X275650Y383250D02*X276175Y382725D01*

+Y380775D01*

+X275650Y380250D02*X276175Y380775D01*

+X274300Y380250D02*X275650D01*

+X274300Y383250D02*X275650D01*

+X194186Y385100D02*X195460D01*

+X193500Y385786D02*X194186Y385100D01*

+X193500Y388334D02*Y385786D01*

+Y388334D02*X194186Y389020D01*

+X195460D01*

+X196636Y388040D02*Y385100D01*

+Y388040D02*X197322Y389020D01*

+X198400D01*

+X199086Y388040D01*

+Y385100D01*

+X196636Y387060D02*X199086D01*

+X200262Y389020D02*Y385100D01*

+Y389020D02*X201732Y387060D01*

+X203202Y389020D01*

+Y385100D01*

+X204378Y385590D02*X204868Y385100D01*

+X204378Y388530D02*Y385590D01*

+Y388530D02*X204868Y389020D01*

+X205848D01*

+X206338Y388530D01*

+Y385590D01*

+X205848Y385100D02*X206338Y385590D01*

+X204868Y385100D02*X205848D01*

+X204378Y386080D02*X206338Y388040D01*

+X250686Y385600D02*X251960D01*

+X250000Y386286D02*X250686Y385600D01*

+X250000Y388834D02*Y386286D01*

+Y388834D02*X250686Y389520D01*

+X251960D01*

+X253136Y388540D02*Y385600D01*

+Y388540D02*X253822Y389520D01*

+X254900D01*

+X255586Y388540D01*

+Y385600D01*

+X253136Y387560D02*X255586D01*

+X256762Y389520D02*Y385600D01*

+Y389520D02*X258232Y387560D01*

+X259702Y389520D01*

+Y385600D01*

+X260878Y388736D02*X261662Y389520D01*

+Y385600D01*

+X260878D02*X262348D01*

+X302686Y385100D02*X303960D01*

+X302000Y385786D02*X302686Y385100D01*

+X302000Y388334D02*Y385786D01*

+Y388334D02*X302686Y389020D01*

+X303960D01*

+X305136Y388040D02*Y385100D01*

+Y388040D02*X305822Y389020D01*

+X306900D01*

+X307586Y388040D01*

+Y385100D01*

+X305136Y387060D02*X307586D01*

+X308762Y389020D02*Y385100D01*

+Y389020D02*X310232Y387060D01*

+X311702Y389020D01*

+Y385100D01*

+X312878Y388530D02*X313368Y389020D01*

+X314838D01*

+X315328Y388530D01*

+Y387550D01*

+X312878Y385100D02*X315328Y387550D01*

+X312878Y385100D02*X315328D01*

+X358686D02*X359960D01*

+X358000Y385786D02*X358686Y385100D01*

+X358000Y388334D02*Y385786D01*

+Y388334D02*X358686Y389020D01*

+X359960D01*

+X361136Y388040D02*Y385100D01*

+Y388040D02*X361822Y389020D01*

+X362900D01*

+X363586Y388040D01*

+Y385100D01*

+X361136Y387060D02*X363586D01*

+X364762Y389020D02*Y385100D01*

+Y389020D02*X366232Y387060D01*

+X367702Y389020D01*

+Y385100D01*

+X368878Y388530D02*X369368Y389020D01*

+X370348D01*

+X370838Y388530D01*

+X370348Y385100D02*X370838Y385590D01*

+X369368Y385100D02*X370348D01*

+X368878Y385590D02*X369368Y385100D01*

+Y387256D02*X370348D01*

+X370838Y388530D02*Y387746D01*

+Y386766D02*Y385590D01*

+Y386766D02*X370348Y387256D01*

+X370838Y387746D02*X370348Y387256D01*

+X414686Y385100D02*X415960D01*

+X414000Y385786D02*X414686Y385100D01*

+X414000Y388334D02*Y385786D01*

+Y388334D02*X414686Y389020D01*

+X415960D01*

+X417136Y388040D02*Y385100D01*

+Y388040D02*X417822Y389020D01*

+X418900D01*

+X419586Y388040D01*

+Y385100D01*

+X417136Y387060D02*X419586D01*

+X420762Y389020D02*Y385100D01*

+Y389020D02*X422232Y387060D01*

+X423702Y389020D01*

+Y385100D01*

+X424878Y386570D02*X426838Y389020D01*

+X424878Y386570D02*X427328D01*

+X426838Y389020D02*Y385100D01*

+X443500Y386020D02*X445460D01*

+X443500D02*Y384060D01*

+X443990Y384550D01*

+X444970D01*

+X445460Y384060D01*

+Y382590D01*

+X444970Y382100D02*X445460Y382590D01*

+X443990Y382100D02*X444970D01*

+X443500Y382590D02*X443990Y382100D01*

+G54D187*X518906Y235524D02*X527567D01*

+X498433D02*X507094D01*

+G54D188*X528059Y259244D02*Y237689D01*

+X497941Y259244D02*Y237689D01*

+Y259244D02*X502665Y263969D01*

+X528059Y259244D02*X523335Y263969D01*

+X502665D02*X507094D01*

+X518906D02*X523335D01*

+G54D187*X550406Y235524D02*X559067D01*

+X529933D02*X538594D01*

+G54D188*X559559Y259244D02*Y237689D01*

+X529441Y259244D02*Y237689D01*

+Y259244D02*X534165Y263969D01*

+X559559Y259244D02*X554835Y263969D01*

+X534165D02*X538594D01*

+X550406D02*X554835D01*

+G54D187*X581906Y235524D02*X590567D01*

+X561433D02*X570094D01*

+G54D188*X591059Y259244D02*Y237689D01*

+X560941Y259244D02*Y237689D01*

+Y259244D02*X565665Y263969D01*

+X591059Y259244D02*X586335Y263969D01*

+X565665D02*X570094D01*

+X581906D02*X586335D01*

+G54D186*X602255Y240893D02*Y240107D01*

+X596745Y240893D02*Y240107D01*

+G54D185*X241000Y272500D02*X481000D01*

+Y282500D02*X241000D01*

+Y272500D02*Y282500D01*

+X251000Y272500D02*Y282500D01*

+X261000Y272500D02*Y282500D01*

+X271000Y272500D02*Y282500D01*

+X281000Y272500D02*Y282500D01*

+X291000Y272500D02*Y282500D01*

+X301000Y272500D02*Y282500D01*

+X311000Y272500D02*Y282500D01*

+X321000Y272500D02*Y282500D01*

+X331000Y272500D02*Y282500D01*

+X341000Y272500D02*Y282500D01*

+X351000Y272500D02*Y282500D01*

+X361000Y272500D02*Y282500D01*

+X371000Y272500D02*Y282500D01*

+X381000Y272500D02*Y282500D01*

+X391000Y272500D02*Y282500D01*

+X401000Y272500D02*Y282500D01*

+X411000Y272500D02*Y282500D01*

+X421000Y272500D02*Y282500D01*

+X431000Y272500D02*Y282500D01*

+X441000Y272500D02*Y282500D01*

+X451000Y272500D02*Y282500D01*

+X461000Y272500D02*Y282500D01*

+X471000Y272500D02*Y282500D01*

+X481000Y272500D02*Y282500D01*

+X241000Y212500D02*X481000D01*

+Y222500D02*X241000D01*

+Y212500D02*Y222500D01*

+X251000Y212500D02*Y222500D01*

+X261000Y212500D02*Y222500D01*

+X271000Y212500D02*Y222500D01*

+X281000Y212500D02*Y222500D01*

+X291000Y212500D02*Y222500D01*

+X301000Y212500D02*Y222500D01*

+X311000Y212500D02*Y222500D01*

+X321000Y212500D02*Y222500D01*

+X331000Y212500D02*Y222500D01*

+X341000Y212500D02*Y222500D01*

+X351000Y212500D02*Y222500D01*

+X361000Y212500D02*Y222500D01*

+X371000Y212500D02*Y222500D01*

+X381000Y212500D02*Y222500D01*

+X391000Y212500D02*Y222500D01*

+X401000Y212500D02*Y222500D01*

+X411000Y212500D02*Y222500D01*

+X421000Y212500D02*Y222500D01*

+X431000Y212500D02*Y222500D01*

+X441000Y212500D02*Y222500D01*

+X451000Y212500D02*Y222500D01*

+X461000Y212500D02*Y222500D01*

+X471000Y212500D02*Y222500D01*

+X481000Y212500D02*Y222500D01*

+G54D186*X128500Y212000D02*G75*G03X128500Y212000I12500J0D01*G01*

+X534406Y344543D02*Y287457D01*

+X524563D02*X534406D01*

+X524563Y344543D02*X534406D01*

+X511886Y337654D02*Y294346D01*

+G54D185*X534700Y379300D02*Y350300D01*

+X512300Y379300D02*Y350300D01*

+X534700D01*

+X512300Y359300D02*X534700D01*

+X523500Y379300D02*Y359300D01*

+X512300Y379300D02*X534700D01*

+X482700D02*Y350300D01*

+X460300Y379300D02*Y350300D01*

+X482700D01*

+X460300Y359300D02*X482700D01*

+X471500Y379300D02*Y359300D01*

+X460300Y379300D02*X482700D01*

+X508200D02*Y350300D01*

+X485800Y379300D02*Y350300D01*

+X508200D01*

+X485800Y359300D02*X508200D01*

+X497000Y379300D02*Y359300D01*

+X485800Y379300D02*X508200D01*

+G54D186*X480400Y302300D02*Y285700D01*

+X492600D01*

+Y302300D02*Y285700D01*

+X480400Y302300D02*X492600D01*

+X482107Y309755D02*X482893D01*

+X482107Y304245D02*X482893D01*

+X495900Y323300D02*Y306700D01*

+X508100D01*

+Y323300D02*Y306700D01*

+X495900Y323300D02*X508100D01*

+X486528Y316004D02*Y328996D01*

+X477472Y316004D02*Y328996D01*

+G54D189*Y327618D03*

+X486528D03*

+G54D186*X487142Y348858D02*Y331142D01*

+Y348858D02*X504858D01*

+X487142Y331142D02*X504858D01*

+Y348858D02*Y331142D01*

+X494255Y323107D02*Y323893D01*

+X488745Y323107D02*Y323893D01*

+G54D185*X375200Y379300D02*Y350300D01*

+X322800Y379300D02*Y350300D01*

+X375200D01*

+X322800Y359300D02*X375200D01*

+X364000Y379300D02*Y359300D01*

+X354000Y379300D02*Y359300D01*

+X344000Y379300D02*Y359300D01*

+X334000Y379300D02*Y359300D01*

+X322800Y379300D02*X375200D01*

+X319700D02*Y350300D01*

+X267300Y379300D02*Y350300D01*

+X319700D01*

+X267300Y359300D02*X319700D01*

+X308500Y379300D02*Y359300D01*

+X298500Y379300D02*Y359300D01*

+X288500Y379300D02*Y359300D01*

+X278500Y379300D02*Y359300D01*

+X267300Y379300D02*X319700D01*

+X264200D02*Y350300D01*

+X211800Y379300D02*Y350300D01*

+X264200D01*

+X211800Y359300D02*X264200D01*

+X253000Y379300D02*Y359300D01*

+X243000Y379300D02*Y359300D01*

+X233000Y379300D02*Y359300D01*

+X223000Y379300D02*Y359300D01*

+X211800Y379300D02*X264200D01*

+X208700D02*Y350300D01*

+X156300Y379300D02*Y350300D01*

+X208700D01*

+X156300Y359300D02*X208700D01*

+X197500Y379300D02*Y359300D01*

+X187500Y379300D02*Y359300D01*

+X177500Y379300D02*Y359300D01*

+X167500Y379300D02*Y359300D01*

+X156300Y379300D02*X208700D01*

+G54D186*X128500Y380000D02*G75*G03X128500Y380000I12500J0D01*G01*

+X360406Y344543D02*Y287457D01*

+X350563D02*X360406D01*

+X350563Y344543D02*X360406D01*

+X337886Y337654D02*Y294346D01*

+X304906Y344543D02*Y287457D01*

+X295063D02*X304906D01*

+X295063Y344543D02*X304906D01*

+X282386Y337654D02*Y294346D01*

+X249406Y344543D02*Y287457D01*

+X239563D02*X249406D01*

+X239563Y344543D02*X249406D01*

+X226886Y337654D02*Y294346D01*

+X193906Y344543D02*Y287457D01*

+X184063D02*X193906D01*

+X184063Y344543D02*X193906D01*

+X171386Y337654D02*Y294346D01*

+G54D185*X457200Y379300D02*Y350300D01*

+X434800Y379300D02*Y350300D01*

+X457200D01*

+X434800Y359300D02*X457200D01*

+X446000Y379300D02*Y359300D01*

+X434800Y379300D02*X457200D01*

+X430700D02*Y350300D01*

+X378300Y379300D02*Y350300D01*

+X430700D01*

+X378300Y359300D02*X430700D01*

+X419500Y379300D02*Y359300D01*

+X409500Y379300D02*Y359300D01*

+X399500Y379300D02*Y359300D01*

+X389500Y379300D02*Y359300D01*

+X378300Y379300D02*X430700D01*

+G54D186*X443858Y348358D02*Y330642D01*

+X426142D02*X443858D01*

+X426142Y348358D02*X443858D01*

+X426142D02*Y330642D01*

+X415906Y344543D02*Y287457D01*

+X406063D02*X415906D01*

+X406063Y344543D02*X415906D01*

+X393386Y337654D02*Y294346D01*

+X439245Y316893D02*Y316107D01*

+X444755Y316893D02*Y316107D01*

+X446200Y326600D02*X462800D01*

+X446200D02*Y314400D01*

+X462800D01*

+Y326600D02*Y314400D01*

+X447004Y328472D02*X459996D01*

+X447004Y337528D02*X459996D01*

+G54D189*X458618D03*

+Y328472D03*

+G54D186*X446642Y307858D02*Y290142D01*

+Y307858D02*X464358D01*

+X446642Y290142D02*X464358D01*

+Y307858D02*Y290142D01*

+X478528Y299996D02*Y287004D01*

+X469472Y299996D02*Y287004D01*

+G54D189*Y298618D03*

+X478528D03*

+G54D186*X569996Y324465D02*Y332535D01*

+X582004Y324465D02*Y332535D01*

+X610255Y240893D02*Y240107D01*

+X604745Y240893D02*Y240107D01*

+X657255Y240893D02*Y240107D01*

+X651745Y240893D02*Y240107D01*

+X665255Y240893D02*Y240107D01*

+X659745Y240893D02*Y240107D01*

+G54D187*X691906Y235524D02*X700567D01*

+X671433D02*X680094D01*

+G54D188*X701059Y259244D02*Y237689D01*

+X670941Y259244D02*Y237689D01*

+Y259244D02*X675665Y263969D01*

+X701059Y259244D02*X696335Y263969D01*

+X675665D02*X680094D01*

+X691906D02*X696335D01*

+G54D186*X689000Y212000D02*G75*G03X689000Y212000I12500J0D01*G01*

+X601866Y325748D02*Y343071D01*

+Y294252D02*Y276929D01*

+X660134Y325748D02*Y343071D01*

+Y294252D02*Y276929D01*

+X601866D01*

+X660134Y343071D02*X601866D01*

+G54D185*X655700Y379300D02*Y350300D01*

+X593300Y379300D02*Y350300D01*

+X655700D01*

+X593300Y359300D02*X655700D01*

+X644500Y379300D02*Y359300D01*

+X634500Y379300D02*Y359300D01*

+X624500Y379300D02*Y359300D01*

+X614500Y379300D02*Y359300D01*

+X604500Y379300D02*Y359300D01*

+X593300Y379300D02*X655700D01*

+G54D186*X659811Y379512D02*X686189D01*

+X659811Y346835D02*X686189D01*

+X659811Y379512D02*Y346835D01*

+X686189Y379512D02*Y346835D01*

+X663354Y357071D02*X668866D01*

+Y362583D02*Y357071D01*

+X663354Y362583D02*X668866D01*

+X663354D02*Y357071D01*

+X677134D02*X682646D01*

+X677134Y362583D02*Y357071D01*

+Y362583D02*X682646D01*

+Y357071D01*

+X663354Y366913D02*G75*G03X663354Y366913I2756J0D01*G01*

+X677134D02*G75*G03X677134Y366913I2756J0D01*G01*

+X562811Y379512D02*X589189D01*

+X562811Y346835D02*X589189D01*

+X562811Y379512D02*Y346835D01*

+X589189Y379512D02*Y346835D01*

+X566354Y357071D02*X571866D01*

+Y362583D01*

+X566354D01*

+Y357071D01*

+X585646D02*X580134D01*

+Y362583D01*

+X585646D01*

+Y357071D01*

+X566354Y366913D02*G75*G03X566354Y366913I2756J0D01*G01*

+X580134D02*G75*G03X580134Y366913I2756J0D01*G01*

+X560406Y344543D02*Y287457D01*

+X550563D02*X560406D01*

+X550563Y344543D02*X560406D01*

+X537886Y337654D02*Y294346D01*

+G54D185*X560200Y379300D02*Y350300D01*

+X537800Y379300D02*Y350300D01*

+X560200D01*

+X537800Y359300D02*X560200D01*

+X549000Y379300D02*Y359300D01*

+X537800Y379300D02*X560200D01*

+G54D186*X689000Y380000D02*G75*G03X689000Y380000I12500J0D01*G01*

+X629000Y228000D02*X631000D01*

+X631500Y227500D01*

+Y226500D01*

+X631000Y226000D02*X631500Y226500D01*

+X629500Y226000D02*X631000D01*

+X629500Y228000D02*Y224000D01*

+X630300Y226000D02*X631500Y224000D01*

+X633200D02*X635200Y228000D01*

+X632700D02*X635200D01*

+X614500Y246845D02*Y244535D01*

+Y246845D02*X614885Y247230D01*

+X615655D01*

+X616040Y246845D01*

+Y244920D01*

+X615270Y244150D02*X616040Y244920D01*

+X614885Y244150D02*X615270D01*

+X614500Y244535D02*X614885Y244150D01*

+X615270Y245305D02*X616040Y244150D01*

+X616964Y245305D02*X618504Y247230D01*

+X616964Y245305D02*X618889D01*

+X618504Y247230D02*Y244150D01*

+X642500Y246345D02*Y244035D01*

+Y246345D02*X642885Y246730D01*

+X643655D01*

+X644040Y246345D01*

+Y244420D01*

+X643270Y243650D02*X644040Y244420D01*

+X642885Y243650D02*X643270D01*

+X642500Y244035D02*X642885Y243650D01*

+X643270Y244805D02*X644040Y243650D01*

+X644964Y246114D02*X645580Y246730D01*

+Y243650D01*

+X644964D02*X646119D01*

+X649050Y226650D02*X650350D01*

+X648350Y227350D02*X649050Y226650D01*

+X648350Y229950D02*Y227350D01*

+Y229950D02*X649050Y230650D01*

+X650350D01*

+X651550Y229850D02*X652350Y230650D01*

+Y226650D01*

+X651550D02*X653050D01*

+X654250Y230150D02*X654750Y230650D01*

+X656250D01*

+X656750Y230150D01*

+Y229150D01*

+X654250Y226650D02*X656750Y229150D01*

+X654250Y226650D02*X656750D01*

+X584000Y274500D02*Y271500D01*

+Y274500D02*X584500Y275000D01*

+X585500D01*

+X586000Y274500D01*

+Y272000D01*

+X585000Y271000D02*X586000Y272000D01*

+X584500Y271000D02*X585000D01*

+X584000Y271500D02*X584500Y271000D01*

+X585000Y272500D02*X586000Y271000D01*

+X587200Y274500D02*X587700Y275000D01*

+X589200D01*

+X589700Y274500D01*

+Y273500D01*

+X587200Y271000D02*X589700Y273500D01*

+X587200Y271000D02*X589700D01*

+X255000D02*X258500D01*

+X255000D02*X254500Y270500D01*

+Y269500D01*

+X255000Y269000D01*

+X258500D01*

+X257700Y267800D02*X258500Y267000D01*

+X254500D02*X258500D01*

+X254500Y267800D02*Y266300D01*

+X255000Y265100D02*X254500Y264600D01*

+X255000Y265100D02*X258000D01*

+X258500Y264600D01*

+Y263600D01*

+X258000Y263100D01*

+X255000D02*X258000D01*

+X254500Y263600D02*X255000Y263100D01*

+X254500Y264600D02*Y263600D01*

+X255500Y265100D02*X257500Y263100D01*

+X257700Y261900D02*X258500Y261100D01*

+X254500D02*X258500D01*

+X254500Y261900D02*Y260400D01*

+X535350Y272650D02*X537350D01*

+X537850Y272150D01*

+Y271150D01*

+X537350Y270650D02*X537850Y271150D01*

+X535850Y270650D02*X537350D01*

+X535850Y272650D02*Y268650D01*

+X536650Y270650D02*X537850Y268650D01*

+X539050Y272150D02*X539550Y272650D01*

+X540550D01*

+X541050Y272150D01*

+X540550Y268650D02*X541050Y269150D01*

+X539550Y268650D02*X540550D01*

+X539050Y269150D02*X539550Y268650D01*

+Y270850D02*X540550D01*

+X541050Y272150D02*Y271350D01*

+Y270350D02*Y269150D01*

+Y270350D02*X540550Y270850D01*

+X541050Y271350D02*X540550Y270850D01*

+X542250Y269150D02*X542750Y268650D01*

+X542250Y272150D02*Y269150D01*

+Y272150D02*X542750Y272650D01*

+X543750D01*

+X544250Y272150D01*

+Y269150D01*

+X543750Y268650D02*X544250Y269150D01*

+X542750Y268650D02*X543750D01*

+X542250Y269650D02*X544250Y271650D01*

+X545450Y272150D02*X545950Y272650D01*

+X547450D01*

+X547950Y272150D01*

+Y271150D01*

+X545450Y268650D02*X547950Y271150D01*

+X545450Y268650D02*X547950D01*

+X551850Y272650D02*Y268650D01*

+X553150Y272650D02*X553850Y271950D01*

+Y269350D01*

+X553150Y268650D02*X553850Y269350D01*

+X551350Y268650D02*X553150D01*

+X551350Y272650D02*X553150D01*

+X555050Y272150D02*X555550Y272650D01*

+X556550D01*

+X557050Y272150D01*

+X556550Y268650D02*X557050Y269150D01*

+X555550Y268650D02*X556550D01*

+X555050Y269150D02*X555550Y268650D01*

+Y270850D02*X556550D01*

+X557050Y272150D02*Y271350D01*

+Y270350D02*Y269150D01*

+Y270350D02*X556550Y270850D01*

+X557050Y271350D02*X556550Y270850D01*

+X558250Y269150D02*X558750Y268650D01*

+X558250Y272150D02*Y269150D01*

+Y272150D02*X558750Y272650D01*

+X559750D01*

+X560250Y272150D01*

+Y269150D01*

+X559750Y268650D02*X560250Y269150D01*

+X558750Y268650D02*X559750D01*

+X558250Y269650D02*X560250Y271650D01*

+X561450Y272150D02*X561950Y272650D01*

+X563450D01*

+X563950Y272150D01*

+Y271150D01*

+X561450Y268650D02*X563950Y271150D01*

+X561450Y268650D02*X563950D01*

+X503200Y226000D02*X504500D01*

+X502500Y226700D02*X503200Y226000D01*

+X502500Y229300D02*Y226700D01*

+Y229300D02*X503200Y230000D01*

+X504500D01*

+X506200Y226000D02*X508200Y230000D01*

+X505700D02*X508200D01*

+X482150Y250150D02*X486150D01*

+Y248850D02*X485450Y248150D01*

+X482850D02*X485450D01*

+X482150Y248850D02*X482850Y248150D01*

+X482150Y250650D02*Y248850D01*

+X486150Y250650D02*Y248850D01*

+Y246950D02*Y244950D01*

+X484150Y246950D02*X486150D01*

+X484150D02*X484650Y246450D01*

+Y245450D01*

+X484150Y244950D01*

+X482650D02*X484150D01*

+X482150Y245450D02*X482650Y244950D01*

+X482150Y246450D02*Y245450D01*

+X482650Y246950D02*X482150Y246450D01*

+X485650Y242650D02*Y240650D01*

+X485150Y240150D01*

+X484150D02*X485150D01*

+X483650Y240650D02*X484150Y240150D01*

+X483650Y242150D02*Y240650D01*

+X481650Y242150D02*X485650D01*

+X483650Y241350D02*X481650Y240150D01*

+X484850Y238950D02*X485650Y238150D01*

+X481650D02*X485650D01*

+X481650Y238950D02*Y237450D01*

+X485150Y236250D02*X485650Y235750D01*

+Y234250D01*

+X485150Y233750D01*

+X484150D02*X485150D01*

+X481650Y236250D02*X484150Y233750D01*

+X481650Y236250D02*Y233750D01*

+X532700Y227500D02*X534000D01*

+X532000Y228200D02*X532700Y227500D01*

+X532000Y230800D02*Y228200D01*

+Y230800D02*X532700Y231500D01*

+X534000D01*

+X536700D02*X537200Y231000D01*

+X535700Y231500D02*X536700D01*

+X535200Y231000D02*X535700Y231500D01*

+X535200Y231000D02*Y228000D01*

+X535700Y227500D01*

+X536700Y229700D02*X537200Y229200D01*

+X535200Y229700D02*X536700D01*

+X535700Y227500D02*X536700D01*

+X537200Y228000D01*

+Y229200D02*Y228000D01*

+X565200Y228500D02*X566500D01*

+X564500Y229200D02*X565200Y228500D01*

+X564500Y231800D02*Y229200D01*

+Y231800D02*X565200Y232500D01*

+X566500D01*

+X567700Y232000D02*X568200Y232500D01*

+X569200D01*

+X569700Y232000D01*

+X569200Y228500D02*X569700Y229000D01*

+X568200Y228500D02*X569200D01*

+X567700Y229000D02*X568200Y228500D01*

+Y230700D02*X569200D01*

+X569700Y232000D02*Y231200D01*

+Y230200D02*Y229000D01*

+Y230200D02*X569200Y230700D01*

+X569700Y231200D02*X569200Y230700D01*

+X605550Y224650D02*X606850D01*

+X604850Y225350D02*X605550Y224650D01*

+X604850Y227950D02*Y225350D01*

+Y227950D02*X605550Y228650D01*

+X606850D01*

+X608050Y228150D02*X608550Y228650D01*

+X610050D01*

+X610550Y228150D01*

+Y227150D01*

+X608050Y224650D02*X610550Y227150D01*

+X608050Y224650D02*X610550D01*

+X592050Y228650D02*X593350D01*

+X591350Y229350D02*X592050Y228650D01*

+X591350Y231950D02*Y229350D01*

+Y231950D02*X592050Y232650D01*

+X593350D01*

+X594550Y231850D02*X595350Y232650D01*

+Y228650D01*

+X594550D02*X596050D01*

+X516339Y386450D02*X517340D01*

+X515800Y386989D02*X516339Y386450D01*

+X515800Y388991D02*Y386989D01*

+Y388991D02*X516339Y389530D01*

+X517340D01*

+X518264Y389145D02*Y386835D01*

+Y389145D02*X518649Y389530D01*

+X519419D01*

+X519804Y389145D01*

+Y386835D01*

+X519419Y386450D02*X519804Y386835D01*

+X518649Y386450D02*X519419D01*

+X518264Y386835D02*X518649Y386450D01*

+X520728Y389530D02*Y386450D01*

+Y389530D02*X522653Y386450D01*

+Y389530D02*Y386450D01*

+X523577Y389530D02*Y386450D01*

+Y389530D02*X525502Y386450D01*

+Y389530D02*Y386450D01*

+X526426Y389145D02*X526811Y389530D01*

+X527581D01*

+X527966Y389145D01*

+X527581Y386450D02*X527966Y386835D01*

+X526811Y386450D02*X527581D01*

+X526426Y386835D02*X526811Y386450D01*

+Y388144D02*X527581D01*

+X527966Y389145D02*Y388529D01*

+Y387759D02*Y386835D01*

+Y387759D02*X527581Y388144D01*

+X527966Y388529D02*X527581Y388144D01*

+X528890Y386835D02*X529275Y386450D01*

+X528890Y389145D02*Y386835D01*

+Y389145D02*X529275Y389530D01*

+X530045D01*

+X530430Y389145D01*

+Y386835D01*

+X530045Y386450D02*X530430Y386835D01*

+X529275Y386450D02*X530045D01*

+X528890Y387220D02*X530430Y388760D01*

+X531354Y389145D02*X531739Y389530D01*

+X532509D01*

+X532894Y389145D01*

+X532509Y386450D02*X532894Y386835D01*

+X531739Y386450D02*X532509D01*

+X531354Y386835D02*X531739Y386450D01*

+Y388144D02*X532509D01*

+X532894Y389145D02*Y388529D01*

+Y387759D02*Y386835D01*

+Y387759D02*X532509Y388144D01*

+X532894Y388529D02*X532509Y388144D01*

+X464339Y386950D02*X465340D01*

+X463800Y387489D02*X464339Y386950D01*

+X463800Y389491D02*Y387489D01*

+Y389491D02*X464339Y390030D01*

+X465340D01*

+X466264Y389645D02*Y387335D01*

+Y389645D02*X466649Y390030D01*

+X467419D01*

+X467804Y389645D01*

+Y387335D01*

+X467419Y386950D02*X467804Y387335D01*

+X466649Y386950D02*X467419D01*

+X466264Y387335D02*X466649Y386950D01*

+X468728Y390030D02*Y386950D01*

+Y390030D02*X470653Y386950D01*

+Y390030D02*Y386950D01*

+X471577Y390030D02*Y386950D01*

+Y390030D02*X473502Y386950D01*

+Y390030D02*Y386950D01*

+X474426Y388105D02*X475966Y390030D01*

+X474426Y388105D02*X476351D01*

+X475966Y390030D02*Y386950D01*

+X477275Y387335D02*X477660Y386950D01*

+X477275Y389645D02*Y387335D01*

+Y389645D02*X477660Y390030D01*

+X478430D01*

+X478815Y389645D01*

+Y387335D01*

+X478430Y386950D02*X478815Y387335D01*

+X477660Y386950D02*X478430D01*

+X477275Y387720D02*X478815Y389260D01*

+X479739Y389645D02*X480124Y390030D01*

+X481279D01*

+X481664Y389645D01*

+Y388875D01*

+X479739Y386950D02*X481664Y388875D01*

+X479739Y386950D02*X481664D01*

+X488839D02*X489840D01*

+X488300Y387489D02*X488839Y386950D01*

+X488300Y389491D02*Y387489D01*

+Y389491D02*X488839Y390030D01*

+X489840D01*

+X490764Y389645D02*Y387335D01*

+Y389645D02*X491149Y390030D01*

+X491919D01*

+X492304Y389645D01*

+Y387335D01*

+X491919Y386950D02*X492304Y387335D01*

+X491149Y386950D02*X491919D01*

+X490764Y387335D02*X491149Y386950D01*

+X493228Y390030D02*Y386950D01*

+Y390030D02*X495153Y386950D01*

+Y390030D02*Y386950D01*

+X496077Y390030D02*Y386950D01*

+Y390030D02*X498002Y386950D01*

+Y390030D02*Y386950D01*

+X498926Y388105D02*X500466Y390030D01*

+X498926Y388105D02*X500851D01*

+X500466Y390030D02*Y386950D01*

+X501775Y387335D02*X502160Y386950D01*

+X501775Y389645D02*Y387335D01*

+Y389645D02*X502160Y390030D01*

+X502930D01*

+X503315Y389645D01*

+Y387335D01*

+X502930Y386950D02*X503315Y387335D01*

+X502160Y386950D02*X502930D01*

+X501775Y387720D02*X503315Y389260D01*

+X504239Y389414D02*X504855Y390030D01*

+Y386950D01*

+X504239D02*X505394D01*

+X435339D02*X436340D01*

+X434800Y387489D02*X435339Y386950D01*

+X434800Y389491D02*Y387489D01*

+Y389491D02*X435339Y390030D01*

+X436340D01*

+X437264Y389645D02*Y387335D01*

+Y389645D02*X437649Y390030D01*

+X438419D01*

+X438804Y389645D01*

+Y387335D01*

+X438419Y386950D02*X438804Y387335D01*

+X437649Y386950D02*X438419D01*

+X437264Y387335D02*X437649Y386950D01*

+X439728Y390030D02*Y386950D01*

+Y390030D02*X441653Y386950D01*

+Y390030D02*Y386950D01*

+X442577Y390030D02*Y386950D01*

+Y390030D02*X444502Y386950D01*

+Y390030D02*Y386950D01*

+X445426Y388105D02*X446966Y390030D01*

+X445426Y388105D02*X447351D01*

+X446966Y390030D02*Y386950D01*

+X448275Y387335D02*X448660Y386950D01*

+X448275Y389645D02*Y387335D01*

+Y389645D02*X448660Y390030D01*

+X449430D01*

+X449815Y389645D01*

+Y387335D01*

+X449430Y386950D02*X449815Y387335D01*

+X448660Y386950D02*X449430D01*

+X448275Y387720D02*X449815Y389260D01*

+X450739Y389645D02*X451124Y390030D01*

+X451894D01*

+X452279Y389645D01*

+X451894Y386950D02*X452279Y387335D01*

+X451124Y386950D02*X451894D01*

+X450739Y387335D02*X451124Y386950D01*

+Y388644D02*X451894D01*

+X452279Y389645D02*Y389029D01*

+Y388259D02*Y387335D01*

+Y388259D02*X451894Y388644D01*

+X452279Y389029D02*X451894Y388644D01*

+X387500Y385300D02*X388800D01*

+X386800Y386000D02*X387500Y385300D01*

+X386800Y388600D02*Y386000D01*

+Y388600D02*X387500Y389300D01*

+X388800D01*

+X390000Y388800D02*Y385800D01*

+Y388800D02*X390500Y389300D01*

+X391500D01*

+X392000Y388800D01*

+Y385800D01*

+X391500Y385300D02*X392000Y385800D01*

+X390500Y385300D02*X391500D01*

+X390000Y385800D02*X390500Y385300D01*

+X393200Y389300D02*Y385300D01*

+Y389300D02*X395700Y385300D01*

+Y389300D02*Y385300D01*

+X396900Y389300D02*Y385300D01*

+Y389300D02*X399400Y385300D01*

+Y389300D02*Y385300D01*

+X400600Y388800D02*X401100Y389300D01*

+X402100D01*

+X402600Y388800D01*

+X402100Y385300D02*X402600Y385800D01*

+X401100Y385300D02*X402100D01*

+X400600Y385800D02*X401100Y385300D01*

+Y387500D02*X402100D01*

+X402600Y388800D02*Y388000D01*

+Y387000D02*Y385800D01*

+Y387000D02*X402100Y387500D01*

+X402600Y388000D02*X402100Y387500D01*

+X403800Y385800D02*X404300Y385300D01*

+X403800Y388800D02*Y385800D01*

+Y388800D02*X404300Y389300D01*

+X405300D01*

+X405800Y388800D01*

+Y385800D01*

+X405300Y385300D02*X405800Y385800D01*

+X404300Y385300D02*X405300D01*

+X403800Y386300D02*X405800Y388300D01*

+X407500Y385300D02*X409500Y389300D01*

+X407000D02*X409500D01*

+X166000Y385300D02*X167300D01*

+X165300Y386000D02*X166000Y385300D01*

+X165300Y388600D02*Y386000D01*

+Y388600D02*X166000Y389300D01*

+X167300D01*

+X168500Y388800D02*Y385800D01*

+Y388800D02*X169000Y389300D01*

+X170000D01*

+X170500Y388800D01*

+Y385800D01*

+X170000Y385300D02*X170500Y385800D01*

+X169000Y385300D02*X170000D01*

+X168500Y385800D02*X169000Y385300D01*

+X171700Y389300D02*Y385300D01*

+Y389300D02*X174200Y385300D01*

+Y389300D02*Y385300D01*

+X175400Y389300D02*Y385300D01*

+Y389300D02*X177900Y385300D01*

+Y389300D02*Y385300D01*

+X179100Y388800D02*X179600Y389300D01*

+X180600D01*

+X181100Y388800D01*

+X180600Y385300D02*X181100Y385800D01*

+X179600Y385300D02*X180600D01*

+X179100Y385800D02*X179600Y385300D01*

+Y387500D02*X180600D01*

+X181100Y388800D02*Y388000D01*

+Y387000D02*Y385800D01*

+Y387000D02*X180600Y387500D01*

+X181100Y388000D02*X180600Y387500D01*

+X182300Y385800D02*X182800Y385300D01*

+X182300Y388800D02*Y385800D01*

+Y388800D02*X182800Y389300D01*

+X183800D01*

+X184300Y388800D01*

+Y385800D01*

+X183800Y385300D02*X184300Y385800D01*

+X182800Y385300D02*X183800D01*

+X182300Y386300D02*X184300Y388300D01*

+X185500Y388800D02*X186000Y389300D01*

+X187500D01*

+X188000Y388800D01*

+Y387800D01*

+X185500Y385300D02*X188000Y387800D01*

+X185500Y385300D02*X188000D01*

+X222500Y384800D02*X223800D01*

+X221800Y385500D02*X222500Y384800D01*

+X221800Y388100D02*Y385500D01*

+Y388100D02*X222500Y388800D01*

+X223800D01*

+X225000Y388300D02*Y385300D01*

+Y388300D02*X225500Y388800D01*

+X226500D01*

+X227000Y388300D01*

+Y385300D01*

+X226500Y384800D02*X227000Y385300D01*

+X225500Y384800D02*X226500D01*

+X225000Y385300D02*X225500Y384800D01*

+X228200Y388800D02*Y384800D01*

+Y388800D02*X230700Y384800D01*

+Y388800D02*Y384800D01*

+X231900Y388800D02*Y384800D01*

+Y388800D02*X234400Y384800D01*

+Y388800D02*Y384800D01*

+X235600Y388300D02*X236100Y388800D01*

+X237100D01*

+X237600Y388300D01*

+X237100Y384800D02*X237600Y385300D01*

+X236100Y384800D02*X237100D01*

+X235600Y385300D02*X236100Y384800D01*

+Y387000D02*X237100D01*

+X237600Y388300D02*Y387500D01*

+Y386500D02*Y385300D01*

+Y386500D02*X237100Y387000D01*

+X237600Y387500D02*X237100Y387000D01*

+X238800Y385300D02*X239300Y384800D01*

+X238800Y388300D02*Y385300D01*

+Y388300D02*X239300Y388800D01*

+X240300D01*

+X240800Y388300D01*

+Y385300D01*

+X240300Y384800D02*X240800Y385300D01*

+X239300Y384800D02*X240300D01*

+X238800Y385800D02*X240800Y387800D01*

+X242000Y386300D02*X244000Y388800D01*

+X242000Y386300D02*X244500D01*

+X244000Y388800D02*Y384800D01*

+X276500Y385300D02*X277800D01*

+X275800Y386000D02*X276500Y385300D01*

+X275800Y388600D02*Y386000D01*

+Y388600D02*X276500Y389300D01*

+X277800D01*

+X279000Y388800D02*Y385800D01*

+Y388800D02*X279500Y389300D01*

+X280500D01*

+X281000Y388800D01*

+Y385800D01*

+X280500Y385300D02*X281000Y385800D01*

+X279500Y385300D02*X280500D01*

+X279000Y385800D02*X279500Y385300D01*

+X282200Y389300D02*Y385300D01*

+Y389300D02*X284700Y385300D01*

+Y389300D02*Y385300D01*

+X285900Y389300D02*Y385300D01*

+Y389300D02*X288400Y385300D01*

+Y389300D02*Y385300D01*

+X289600Y388800D02*X290100Y389300D01*

+X291100D01*

+X291600Y388800D01*

+X291100Y385300D02*X291600Y385800D01*

+X290100Y385300D02*X291100D01*

+X289600Y385800D02*X290100Y385300D01*

+Y387500D02*X291100D01*

+X291600Y388800D02*Y388000D01*

+Y387000D02*Y385800D01*

+Y387000D02*X291100Y387500D01*

+X291600Y388000D02*X291100Y387500D01*

+X292800Y385800D02*X293300Y385300D01*

+X292800Y388800D02*Y385800D01*

+Y388800D02*X293300Y389300D01*

+X294300D01*

+X294800Y388800D01*

+Y385800D01*

+X294300Y385300D02*X294800Y385800D01*

+X293300Y385300D02*X294300D01*

+X292800Y386300D02*X294800Y388300D01*

+X296000Y389300D02*X298000D01*

+X296000D02*Y387300D01*

+X296500Y387800D01*

+X297500D01*

+X298000Y387300D01*

+Y385800D01*

+X297500Y385300D02*X298000Y385800D01*

+X296500Y385300D02*X297500D01*

+X296000Y385800D02*X296500Y385300D01*

+X330000D02*X331300D01*

+X329300Y386000D02*X330000Y385300D01*

+X329300Y388600D02*Y386000D01*

+Y388600D02*X330000Y389300D01*

+X331300D01*

+X332500Y388800D02*Y385800D01*

+Y388800D02*X333000Y389300D01*

+X334000D01*

+X334500Y388800D01*

+Y385800D01*

+X334000Y385300D02*X334500Y385800D01*

+X333000Y385300D02*X334000D01*

+X332500Y385800D02*X333000Y385300D01*

+X335700Y389300D02*Y385300D01*

+Y389300D02*X338200Y385300D01*

+Y389300D02*Y385300D01*

+X339400Y389300D02*Y385300D01*

+Y389300D02*X341900Y385300D01*

+Y389300D02*Y385300D01*

+X343100Y388800D02*X343600Y389300D01*

+X344600D01*

+X345100Y388800D01*

+X344600Y385300D02*X345100Y385800D01*

+X343600Y385300D02*X344600D01*

+X343100Y385800D02*X343600Y385300D01*

+Y387500D02*X344600D01*

+X345100Y388800D02*Y388000D01*

+Y387000D02*Y385800D01*

+Y387000D02*X344600Y387500D01*

+X345100Y388000D02*X344600Y387500D01*

+X346300Y385800D02*X346800Y385300D01*

+X346300Y388800D02*Y385800D01*

+Y388800D02*X346800Y389300D01*

+X347800D01*

+X348300Y388800D01*

+Y385800D01*

+X347800Y385300D02*X348300Y385800D01*

+X346800Y385300D02*X347800D01*

+X346300Y386300D02*X348300Y388300D01*

+X351000Y389300D02*X351500Y388800D01*

+X350000Y389300D02*X351000D01*

+X349500Y388800D02*X350000Y389300D01*

+X349500Y388800D02*Y385800D01*

+X350000Y385300D01*

+X351000Y387500D02*X351500Y387000D01*

+X349500Y387500D02*X351000D01*

+X350000Y385300D02*X351000D01*

+X351500Y385800D01*

+Y387000D02*Y385800D01*

+X211200Y276000D02*X212500D01*

+X210500Y276700D02*X211200Y276000D01*

+X210500Y279300D02*Y276700D01*

+Y279300D02*X211200Y280000D01*

+X212500D01*

+X213700Y279500D02*Y276500D01*

+Y279500D02*X214200Y280000D01*

+X215200D01*

+X215700Y279500D01*

+Y276500D01*

+X215200Y276000D02*X215700Y276500D01*

+X214200Y276000D02*X215200D01*

+X213700Y276500D02*X214200Y276000D01*

+X216900Y280000D02*Y276000D01*

+Y280000D02*X219400Y276000D01*

+Y280000D02*Y276000D01*

+X220600Y280000D02*Y276000D01*

+Y280000D02*X223100Y276000D01*

+Y280000D02*Y276000D01*

+X224300Y279500D02*X224800Y280000D01*

+X225800D01*

+X226300Y279500D01*

+X225800Y276000D02*X226300Y276500D01*

+X224800Y276000D02*X225800D01*

+X224300Y276500D02*X224800Y276000D01*

+Y278200D02*X225800D01*

+X226300Y279500D02*Y278700D01*

+Y277700D02*Y276500D01*

+Y277700D02*X225800Y278200D01*

+X226300Y278700D02*X225800Y278200D01*

+X227500Y276500D02*X228000Y276000D01*

+X227500Y279500D02*Y276500D01*

+Y279500D02*X228000Y280000D01*

+X229000D01*

+X229500Y279500D01*

+Y276500D01*

+X229000Y276000D02*X229500Y276500D01*

+X228000Y276000D02*X229000D01*

+X227500Y277000D02*X229500Y279000D01*

+X231200Y276000D02*X232700Y278000D01*

+Y279500D02*Y278000D01*

+X232200Y280000D02*X232700Y279500D01*

+X231200Y280000D02*X232200D01*

+X230700Y279500D02*X231200Y280000D01*

+X230700Y279500D02*Y278500D01*

+X231200Y278000D01*

+X232700D01*

+X169700Y275500D02*X171000D01*

+X169000Y276200D02*X169700Y275500D01*

+X169000Y278800D02*Y276200D01*

+Y278800D02*X169700Y279500D01*

+X171000D01*

+X172200Y279000D02*Y276000D01*

+Y279000D02*X172700Y279500D01*

+X173700D01*

+X174200Y279000D01*

+Y276000D01*

+X173700Y275500D02*X174200Y276000D01*

+X172700Y275500D02*X173700D01*

+X172200Y276000D02*X172700Y275500D01*

+X175400Y279500D02*Y275500D01*

+Y279500D02*X177900Y275500D01*

+Y279500D02*Y275500D01*

+X179100Y279500D02*Y275500D01*

+Y279500D02*X181600Y275500D01*

+Y279500D02*Y275500D01*

+X182800Y279000D02*X183300Y279500D01*

+X184300D01*

+X184800Y279000D01*

+X184300Y275500D02*X184800Y276000D01*

+X183300Y275500D02*X184300D01*

+X182800Y276000D02*X183300Y275500D01*

+Y277700D02*X184300D01*

+X184800Y279000D02*Y278200D01*

+Y277200D02*Y276000D01*

+Y277200D02*X184300Y277700D01*

+X184800Y278200D02*X184300Y277700D01*

+X186000Y276000D02*X186500Y275500D01*

+X186000Y279000D02*Y276000D01*

+Y279000D02*X186500Y279500D01*

+X187500D01*

+X188000Y279000D01*

+Y276000D01*

+X187500Y275500D02*X188000Y276000D01*

+X186500Y275500D02*X187500D01*

+X186000Y276500D02*X188000Y278500D01*

+X189200Y276000D02*X189700Y275500D01*

+X189200Y276800D02*Y276000D01*

+Y276800D02*X189900Y277500D01*

+X190500D01*

+X191200Y276800D01*

+Y276000D01*

+X190700Y275500D02*X191200Y276000D01*

+X189700Y275500D02*X190700D01*

+X189200Y278200D02*X189900Y277500D01*

+X189200Y279000D02*Y278200D01*

+Y279000D02*X189700Y279500D01*

+X190700D01*

+X191200Y279000D01*

+Y278200D01*

+X190500Y277500D02*X191200Y278200D01*

+X466350Y344880D02*X467890D01*

+X468275Y344495D01*

+Y343725D01*

+X467890Y343340D02*X468275Y343725D01*

+X466735Y343340D02*X467890D01*

+X466735Y344880D02*Y341800D01*

+X467351Y343340D02*X468275Y341800D01*

+X469199Y342955D02*X470739Y344880D01*

+X469199Y342955D02*X471124D01*

+X470739Y344880D02*Y341800D01*

+X472048Y342185D02*X472433Y341800D01*

+X472048Y344495D02*Y342185D01*

+Y344495D02*X472433Y344880D01*

+X473203D01*

+X473588Y344495D01*

+Y342185D01*

+X473203Y341800D02*X473588Y342185D01*

+X472433Y341800D02*X473203D01*

+X472048Y342570D02*X473588Y344110D01*

+X474512Y344495D02*X474897Y344880D01*

+X476052D01*

+X476437Y344495D01*

+Y343725D01*

+X474512Y341800D02*X476437Y343725D01*

+X474512Y341800D02*X476437D01*

+X463385Y334230D02*Y331150D01*

+X464386Y334230D02*X464925Y333691D01*

+Y331689D01*

+X464386Y331150D02*X464925Y331689D01*

+X463000Y331150D02*X464386D01*

+X463000Y334230D02*X464386D01*

+X465849Y332305D02*X467389Y334230D01*

+X465849Y332305D02*X467774D01*

+X467389Y334230D02*Y331150D01*

+X468698Y331535D02*X469083Y331150D01*

+X468698Y333845D02*Y331535D01*

+Y333845D02*X469083Y334230D01*

+X469853D01*

+X470238Y333845D01*

+Y331535D01*

+X469853Y331150D02*X470238Y331535D01*

+X469083Y331150D02*X469853D01*

+X468698Y331920D02*X470238Y333460D01*

+X471162Y333845D02*X471547Y334230D01*

+X472702D01*

+X473087Y333845D01*

+Y333075D01*

+X471162Y331150D02*X473087Y333075D01*

+X471162Y331150D02*X473087D01*

+X426500Y328740D02*Y325700D01*

+X428020D01*

+X428932Y326840D02*X430452Y328740D01*

+X428932Y326840D02*X430832D01*

+X430452Y328740D02*Y325700D01*

+X431744Y326080D02*X432124Y325700D01*

+X431744Y328360D02*Y326080D01*

+Y328360D02*X432124Y328740D01*

+X432884D01*

+X433264Y328360D01*

+Y326080D01*

+X432884Y325700D02*X433264Y326080D01*

+X432124Y325700D02*X432884D01*

+X431744Y326460D02*X433264Y327980D01*

+X434176Y328360D02*X434556Y328740D01*

+X435696D01*

+X436076Y328360D01*

+Y327600D01*

+X434176Y325700D02*X436076Y327600D01*

+X434176Y325700D02*X436076D01*

+X467385Y328730D02*Y325650D01*

+X468386Y328730D02*X468925Y328191D01*

+Y326189D01*

+X468386Y325650D02*X468925Y326189D01*

+X467000Y325650D02*X468386D01*

+X467000Y328730D02*X468386D01*

+X469849Y326805D02*X471389Y328730D01*

+X469849Y326805D02*X471774D01*

+X471389Y328730D02*Y325650D01*

+X472698Y326035D02*X473083Y325650D01*

+X472698Y328345D02*Y326035D01*

+Y328345D02*X473083Y328730D01*

+X473853D01*

+X474238Y328345D01*

+Y326035D01*

+X473853Y325650D02*X474238Y326035D01*

+X473083Y325650D02*X473853D01*

+X472698Y326420D02*X474238Y327960D01*

+X475162Y328114D02*X475778Y328730D01*

+Y325650D01*

+X475162D02*X476317D01*

+X464389Y319800D02*X465390D01*

+X463850Y320339D02*X464389Y319800D01*

+X463850Y322341D02*Y320339D01*

+Y322341D02*X464389Y322880D01*

+X465390D01*

+X466314Y320955D02*X467854Y322880D01*

+X466314Y320955D02*X468239D01*

+X467854Y322880D02*Y319800D01*

+X469163Y320185D02*X469548Y319800D01*

+X469163Y322495D02*Y320185D01*

+Y322495D02*X469548Y322880D01*

+X470318D01*

+X470703Y322495D01*

+Y320185D01*

+X470318Y319800D02*X470703Y320185D01*

+X469548Y319800D02*X470318D01*

+X469163Y320570D02*X470703Y322110D01*

+X471627Y322880D02*X473167D01*

+X471627D02*Y321340D01*

+X472012Y321725D01*

+X472782D01*

+X473167Y321340D01*

+Y320185D01*

+X472782Y319800D02*X473167Y320185D01*

+X472012Y319800D02*X472782D01*

+X471627Y320185D02*X472012Y319800D01*

+X477000Y337730D02*Y334650D01*

+X478540D01*

+X479464Y335805D02*X481004Y337730D01*

+X479464Y335805D02*X481389D01*

+X481004Y337730D02*Y334650D01*

+X482313Y335035D02*X482698Y334650D01*

+X482313Y337345D02*Y335035D01*

+Y337345D02*X482698Y337730D01*

+X483468D01*

+X483853Y337345D01*

+Y335035D01*

+X483468Y334650D02*X483853Y335035D01*

+X482698Y334650D02*X483468D01*

+X482313Y335420D02*X483853Y336960D01*

+X484777Y337114D02*X485393Y337730D01*

+Y334650D01*

+X484777D02*X485932D01*

+X443200Y295890D02*Y294889D01*

+X442661Y294350D02*X443200Y294889D01*

+X440659Y294350D02*X442661D01*

+X440659D02*X440120Y294889D01*

+Y295890D02*Y294889D01*

+X442045Y296814D02*X440120Y298354D01*

+X442045Y298739D02*Y296814D01*

+X440120Y298354D02*X443200D01*

+X442815Y299663D02*X443200Y300048D01*

+X440505Y299663D02*X442815D01*

+X440505D02*X440120Y300048D01*

+Y300818D02*Y300048D01*

+Y300818D02*X440505Y301203D01*

+X442815D01*

+X443200Y300818D02*X442815Y301203D01*

+X443200Y300818D02*Y300048D01*

+X442430Y299663D02*X440890Y301203D01*

+X440505Y302127D02*X440120Y302512D01*

+Y303667D02*Y302512D01*

+Y303667D02*X440505Y304052D01*

+X441275D01*

+X443200Y302127D02*X441275Y304052D01*

+X443200D02*Y302127D01*

+X450000Y313530D02*Y310835D01*

+X450385Y310450D01*

+X451155D01*

+X451540Y310835D01*

+Y313530D02*Y310835D01*

+X452464Y311605D02*X454004Y313530D01*

+X452464Y311605D02*X454389D01*

+X454004Y313530D02*Y310450D01*

+X455313Y310835D02*X455698Y310450D01*

+X455313Y313145D02*Y310835D01*

+Y313145D02*X455698Y313530D01*

+X456468D01*

+X456853Y313145D01*

+Y310835D01*

+X456468Y310450D02*X456853Y310835D01*

+X455698Y310450D02*X456468D01*

+X455313Y311220D02*X456853Y312760D01*

+X457777Y313145D02*X458162Y313530D01*

+X459317D01*

+X459702Y313145D01*

+Y312375D01*

+X457777Y310450D02*X459702Y312375D01*

+X457777Y310450D02*X459702D01*

+X441500Y289230D02*Y286150D01*

+X443040D01*

+X443964Y287305D02*X445504Y289230D01*

+X443964Y287305D02*X445889D01*

+X445504Y289230D02*Y286150D01*

+X446813Y286535D02*X447198Y286150D01*

+X446813Y288845D02*Y286535D01*

+Y288845D02*X447198Y289230D01*

+X447968D01*

+X448353Y288845D01*

+Y286535D01*

+X447968Y286150D02*X448353Y286535D01*

+X447198Y286150D02*X447968D01*

+X446813Y286920D02*X448353Y288460D01*

+X449277Y288845D02*X449662Y289230D01*

+X450432D01*

+X450817Y288845D01*

+X450432Y286150D02*X450817Y286535D01*

+X449662Y286150D02*X450432D01*

+X449277Y286535D02*X449662Y286150D01*

+Y287844D02*X450432D01*

+X450817Y288845D02*Y288229D01*

+Y287459D02*Y286535D01*

+Y287459D02*X450432Y287844D01*

+X450817Y288229D02*X450432Y287844D01*

+X491389Y302800D02*X492390D01*

+X490850Y303339D02*X491389Y302800D01*

+X490850Y305341D02*Y303339D01*

+Y305341D02*X491389Y305880D01*

+X492390D01*

+X493314Y303955D02*X494854Y305880D01*

+X493314Y303955D02*X495239D01*

+X494854Y305880D02*Y302800D01*

+X496163Y303185D02*X496548Y302800D01*

+X496163Y305495D02*Y303185D01*

+Y305495D02*X496548Y305880D01*

+X497318D01*

+X497703Y305495D01*

+Y303185D01*

+X497318Y302800D02*X497703Y303185D01*

+X496548Y302800D02*X497318D01*

+X496163Y303570D02*X497703Y305110D01*

+X499782Y305880D02*X500167Y305495D01*

+X499012Y305880D02*X499782D01*

+X498627Y305495D02*X499012Y305880D01*

+X498627Y305495D02*Y303185D01*

+X499012Y302800D01*

+X499782Y304494D02*X500167Y304109D01*

+X498627Y304494D02*X499782D01*

+X499012Y302800D02*X499782D01*

+X500167Y303185D01*

+Y304109D02*Y303185D01*

+X505335Y306000D02*X508030D01*

+X505335D02*X504950Y305615D01*

+Y304845D01*

+X505335Y304460D01*

+X508030D01*

+X506105Y303536D02*X508030Y301996D01*

+X506105Y303536D02*Y301611D01*

+X504950Y301996D02*X508030D01*

+X505335Y300687D02*X504950Y300302D01*

+X505335Y300687D02*X507645D01*

+X508030Y300302D01*

+Y299532D01*

+X507645Y299147D01*

+X505335D02*X507645D01*

+X504950Y299532D02*X505335Y299147D01*

+X504950Y300302D02*Y299532D01*

+X505720Y300687D02*X507260Y299147D01*

+X507414Y298223D02*X508030Y297607D01*

+X504950D02*X508030D01*

+X504950Y298223D02*Y297068D01*

+X511051Y330150D02*Y329070D01*

+X510781Y328800D01*

+X510241D02*X510781D01*

+X509971Y329070D02*X510241Y328800D01*

+X509971Y329880D02*Y329070D01*

+X508891Y329880D02*X511051D01*

+X509971Y329448D02*X508891Y328800D01*

+X509701Y328152D02*X511051Y327072D01*

+X509701Y328152D02*Y326802D01*

+X508891Y327072D02*X511051D01*

+X509161Y326154D02*X508891Y325884D01*

+X509161Y326154D02*X510781D01*

+X511051Y325884D01*

+Y325344D01*

+X510781Y325074D01*

+X509161D02*X510781D01*

+X508891Y325344D02*X509161Y325074D01*

+X508891Y325884D02*Y325344D01*

+X509431Y326154D02*X510511Y325074D01*

+X510619Y324426D02*X511051Y323994D01*

+X508891D02*X511051D01*

+X508891Y324426D02*Y323616D01*

+X506850Y348118D02*Y347130D01*

+X507382Y348650D02*X506850Y348118D01*

+X507382Y348650D02*X509358D01*

+X509890Y348118D01*

+Y347130D01*

+X507990Y346218D02*X509890Y344698D01*

+X507990Y346218D02*Y344318D01*

+X506850Y344698D02*X509890D01*

+X507230Y343406D02*X506850Y343026D01*

+X507230Y343406D02*X509510D01*

+X509890Y343026D01*

+Y342266D01*

+X509510Y341886D01*

+X507230D02*X509510D01*

+X506850Y342266D02*X507230Y341886D01*

+X506850Y343026D02*Y342266D01*

+X507610Y343406D02*X509130Y341886D01*

+X509282Y340974D02*X509890Y340366D01*

+X506850D02*X509890D01*

+X506850Y340974D02*Y339834D01*

+X459385Y286730D02*Y283650D01*

+X460386Y286730D02*X460925Y286191D01*

+Y284189D01*

+X460386Y283650D02*X460925Y284189D01*

+X459000Y283650D02*X460386D01*

+X459000Y286730D02*X460386D01*

+X461849Y284805D02*X463389Y286730D01*

+X461849Y284805D02*X463774D01*

+X463389Y286730D02*Y283650D01*

+X464698Y284035D02*X465083Y283650D01*

+X464698Y286345D02*Y284035D01*

+Y286345D02*X465083Y286730D01*

+X465853D01*

+X466238Y286345D01*

+Y284035D01*

+X465853Y283650D02*X466238Y284035D01*

+X465083Y283650D02*X465853D01*

+X464698Y284420D02*X466238Y285960D01*

+X467162Y286345D02*X467547Y286730D01*

+X468317D01*

+X468702Y286345D01*

+X468317Y283650D02*X468702Y284035D01*

+X467547Y283650D02*X468317D01*

+X467162Y284035D02*X467547Y283650D01*

+Y285344D02*X468317D01*

+X468702Y286345D02*Y285729D01*

+Y284959D02*Y284035D01*

+Y284959D02*X468317Y285344D01*

+X468702Y285729D02*X468317Y285344D01*

+X465620Y303390D02*Y301850D01*

+Y303390D02*X466005Y303775D01*

+X466775D01*

+X467160Y303390D02*X466775Y303775D01*

+X467160Y303390D02*Y302235D01*

+X465620D02*X468700D01*

+X467160Y302851D02*X468700Y303775D01*

+X467545Y304699D02*X465620Y306239D01*

+X467545Y306624D02*Y304699D01*

+X465620Y306239D02*X468700D01*

+X468315Y307548D02*X468700Y307933D01*

+X466005Y307548D02*X468315D01*

+X466005D02*X465620Y307933D01*

+Y308703D02*Y307933D01*

+Y308703D02*X466005Y309088D01*

+X468315D01*

+X468700Y308703D02*X468315Y309088D01*

+X468700Y308703D02*Y307933D01*

+X467930Y307548D02*X466390Y309088D01*

+X466005Y310012D02*X465620Y310397D01*

+Y311167D02*Y310397D01*

+Y311167D02*X466005Y311552D01*

+X468700Y311167D02*X468315Y311552D01*

+X468700Y311167D02*Y310397D01*

+X468315Y310012D02*X468700Y310397D01*

+X467006Y311167D02*Y310397D01*

+X466005Y311552D02*X466621D01*

+X467391D02*X468315D01*

+X467391D02*X467006Y311167D01*

+X466621Y311552D02*X467006Y311167D01*

+X486500Y283800D02*Y280300D01*

+X487000Y279800D01*

+X488000D01*

+X488500Y280300D01*

+Y283800D02*Y280300D01*

+X489700Y281300D02*X491700Y283800D01*

+X489700Y281300D02*X492200D01*

+X491700Y283800D02*Y279800D01*

+X493400Y280300D02*X493900Y279800D01*

+X493400Y283300D02*Y280300D01*

+Y283300D02*X493900Y283800D01*

+X494900D01*

+X495400Y283300D01*

+Y280300D01*

+X494900Y279800D02*X495400Y280300D01*

+X493900Y279800D02*X494900D01*

+X493400Y280800D02*X495400Y282800D01*

+X496600Y283300D02*X497100Y283800D01*

+X498100D01*

+X498600Y283300D01*

+X498100Y279800D02*X498600Y280300D01*

+X497100Y279800D02*X498100D01*

+X496600Y280300D02*X497100Y279800D01*

+Y282000D02*X498100D01*

+X498600Y283300D02*Y282500D01*

+Y281500D02*Y280300D01*

+Y281500D02*X498100Y282000D01*

+X498600Y282500D02*X498100Y282000D01*

+X487728Y311450D02*X488430D01*

+X487350Y311828D02*X487728Y311450D01*

+X487350Y313232D02*Y311828D01*

+Y313232D02*X487728Y313610D01*

+X488430D01*

+X489078Y312260D02*X490158Y313610D01*

+X489078Y312260D02*X490428D01*

+X490158Y313610D02*Y311450D01*

+X491076Y311720D02*X491346Y311450D01*

+X491076Y313340D02*Y311720D01*

+Y313340D02*X491346Y313610D01*

+X491886D01*

+X492156Y313340D01*

+Y311720D01*

+X491886Y311450D02*X492156Y311720D01*

+X491346Y311450D02*X491886D01*

+X491076Y311990D02*X492156Y313070D01*

+X492804Y312260D02*X493884Y313610D01*

+X492804Y312260D02*X494154D01*

+X493884Y313610D02*Y311450D01*

+X583650Y293650D02*Y291650D01*

+X583150Y291150D01*

+X582150D02*X583150D01*

+X581650Y291650D02*X582150Y291150D01*

+X581650Y293150D02*Y291650D01*

+X579650Y293150D02*X583650D01*

+X581650Y292350D02*X579650Y291150D01*

+X583150Y289950D02*X583650Y289450D01*

+Y287950D01*

+X583150Y287450D01*

+X582150D02*X583150D01*

+X579650Y289950D02*X582150Y287450D01*

+X579650Y289950D02*Y287450D01*

+X580150Y286250D02*X579650Y285750D01*

+X580150Y286250D02*X583150D01*

+X583650Y285750D01*

+Y284750D01*

+X583150Y284250D01*

+X580150D02*X583150D01*

+X579650Y284750D02*X580150Y284250D01*

+X579650Y285750D02*Y284750D01*

+X580650Y286250D02*X582650Y284250D01*

+X583150Y283050D02*X583650Y282550D01*

+Y281050D01*

+X583150Y280550D01*

+X582150D02*X583150D01*

+X579650Y283050D02*X582150Y280550D01*

+X579650Y283050D02*Y280550D01*

+X586650Y345450D02*Y344150D01*

+X587350Y346150D02*X586650Y345450D01*

+X587350Y346150D02*X589950D01*

+X590650Y345450D01*

+Y344150D01*

+X590150Y342950D02*X590650Y342450D01*

+Y341450D01*

+X590150Y340950D01*

+X586650Y341450D02*X587150Y340950D01*

+X586650Y342450D02*Y341450D01*

+X587150Y342950D02*X586650Y342450D01*

+X588850D02*Y341450D01*

+X589350Y340950D02*X590150D01*

+X587150D02*X588350D01*

+X588850Y341450D01*

+X589350Y340950D02*X588850Y341450D01*

+X587150Y339750D02*X586650Y339250D01*

+X587150Y339750D02*X590150D01*

+X590650Y339250D01*

+Y338250D01*

+X590150Y337750D01*

+X587150D02*X590150D01*

+X586650Y338250D02*X587150Y337750D01*

+X586650Y339250D02*Y338250D01*

+X587650Y339750D02*X589650Y337750D01*

+X590150Y336550D02*X590650Y336050D01*

+Y334550D01*

+X590150Y334050D01*

+X589150D02*X590150D01*

+X586650Y336550D02*X589150Y334050D01*

+X586650Y336550D02*Y334050D01*

+X584050Y312150D02*X585350D01*

+X583350Y312850D02*X584050Y312150D01*

+X583350Y315450D02*Y312850D01*

+Y315450D02*X584050Y316150D01*

+X585350D01*

+X586550Y315650D02*X587050Y316150D01*

+X588050D01*

+X588550Y315650D01*

+X588050Y312150D02*X588550Y312650D01*

+X587050Y312150D02*X588050D01*

+X586550Y312650D02*X587050Y312150D01*

+Y314350D02*X588050D01*

+X588550Y315650D02*Y314850D01*

+Y313850D02*Y312650D01*

+Y313850D02*X588050Y314350D01*

+X588550Y314850D02*X588050Y314350D01*

+X589750Y312650D02*X590250Y312150D01*

+X589750Y315650D02*Y312650D01*

+Y315650D02*X590250Y316150D01*

+X591250D01*

+X591750Y315650D01*

+Y312650D01*

+X591250Y312150D02*X591750Y312650D01*

+X590250Y312150D02*X591250D01*

+X589750Y313150D02*X591750Y315150D01*

+X592950Y313650D02*X594950Y316150D01*

+X592950Y313650D02*X595450D01*

+X594950Y316150D02*Y312150D01*

+X578800Y305765D02*X581880D01*

+Y304764D02*X581341Y304225D01*

+X579339D02*X581341D01*

+X578800Y304764D02*X579339Y304225D01*

+X578800Y306150D02*Y304764D01*

+X581880Y306150D02*Y304764D01*

+X581495Y303301D02*X581880Y302916D01*

+Y301761D01*

+X581495Y301376D01*

+X580725D02*X581495D01*

+X578800Y303301D02*X580725Y301376D01*

+X578800Y303301D02*Y301376D01*

+X579185Y300452D02*X578800Y300067D01*

+X579185Y300452D02*X581495D01*

+X581880Y300067D01*

+Y299297D01*

+X581495Y298912D01*

+X579185D02*X581495D01*

+X578800Y299297D02*X579185Y298912D01*

+X578800Y300067D02*Y299297D01*

+X579570Y300452D02*X581110Y298912D01*

+X581264Y297988D02*X581880Y297372D01*

+X578800D02*X581880D01*

+X578800Y297988D02*Y296833D01*

+X569500Y320000D02*Y316500D01*

+X570000Y316000D01*

+X571000D01*

+X571500Y316500D01*

+Y320000D02*Y316500D01*

+X572700Y319500D02*X573200Y320000D01*

+X574200D01*

+X574700Y319500D01*

+X574200Y316000D02*X574700Y316500D01*

+X573200Y316000D02*X574200D01*

+X572700Y316500D02*X573200Y316000D01*

+Y318200D02*X574200D01*

+X574700Y319500D02*Y318700D01*

+Y317700D02*Y316500D01*

+Y317700D02*X574200Y318200D01*

+X574700Y318700D02*X574200Y318200D01*

+X575900Y316500D02*X576400Y316000D01*

+X575900Y319500D02*Y316500D01*

+Y319500D02*X576400Y320000D01*

+X577400D01*

+X577900Y319500D01*

+Y316500D01*

+X577400Y316000D02*X577900Y316500D01*

+X576400Y316000D02*X577400D01*

+X575900Y317000D02*X577900Y319000D01*

+X579100Y319200D02*X579900Y320000D01*

+Y316000D01*

+X579100D02*X580600D01*

+X563300Y324111D02*Y323110D01*

+X563839Y324650D02*X563300Y324111D01*

+X563839Y324650D02*X565841D01*

+X566380Y324111D01*

+Y323110D01*

+X565995Y322186D02*X566380Y321801D01*

+Y321031D01*

+X565995Y320646D01*

+X563300Y321031D02*X563685Y320646D01*

+X563300Y321801D02*Y321031D01*

+X563685Y322186D02*X563300Y321801D01*

+X564994D02*Y321031D01*

+X565379Y320646D02*X565995D01*

+X563685D02*X564609D01*

+X564994Y321031D01*

+X565379Y320646D02*X564994Y321031D01*

+X563685Y319722D02*X563300Y319337D01*

+X563685Y319722D02*X565995D01*

+X566380Y319337D01*

+Y318567D01*

+X565995Y318182D01*

+X563685D02*X565995D01*

+X563300Y318567D02*X563685Y318182D01*

+X563300Y319337D02*Y318567D01*

+X564070Y319722D02*X565610Y318182D01*

+X565995Y317258D02*X566380Y316873D01*

+Y316103D01*

+X565995Y315718D01*

+X563300Y316103D02*X563685Y315718D01*

+X563300Y316873D02*Y316103D01*

+X563685Y317258D02*X563300Y316873D01*

+X564994D02*Y316103D01*

+X565379Y315718D02*X565995D01*

+X563685D02*X564609D01*

+X564994Y316103D01*

+X565379Y315718D02*X564994Y316103D01*

+X563650Y345950D02*Y344650D01*

+X564350Y346650D02*X563650Y345950D01*

+X564350Y346650D02*X566950D01*

+X567650Y345950D01*

+Y344650D01*

+X567150Y343450D02*X567650Y342950D01*

+Y341950D01*

+X567150Y341450D01*

+X563650Y341950D02*X564150Y341450D01*

+X563650Y342950D02*Y341950D01*

+X564150Y343450D02*X563650Y342950D01*

+X565850D02*Y341950D01*

+X566350Y341450D02*X567150D01*

+X564150D02*X565350D01*

+X565850Y341950D01*

+X566350Y341450D02*X565850Y341950D01*

+X564150Y340250D02*X563650Y339750D01*

+X564150Y340250D02*X567150D01*

+X567650Y339750D01*

+Y338750D01*

+X567150Y338250D01*

+X564150D02*X567150D01*

+X563650Y338750D02*X564150Y338250D01*

+X563650Y339750D02*Y338750D01*

+X564650Y340250D02*X566650Y338250D01*

+X566850Y337050D02*X567650Y336250D01*

+X563650D02*X567650D01*

+X563650Y337050D02*Y335550D01*

+X574150Y358950D02*Y357650D01*

+X574850Y359650D02*X574150Y358950D01*

+X574850Y359650D02*X577450D01*

+X578150Y358950D01*

+Y357650D01*

+X577650Y356450D02*X578150Y355950D01*

+Y354950D01*

+X577650Y354450D01*

+X574150Y354950D02*X574650Y354450D01*

+X574150Y355950D02*Y354950D01*

+X574650Y356450D02*X574150Y355950D01*

+X576350D02*Y354950D01*

+X576850Y354450D02*X577650D01*

+X574650D02*X575850D01*

+X576350Y354950D01*

+X576850Y354450D02*X576350Y354950D01*

+X574650Y353250D02*X574150Y352750D01*

+X574650Y353250D02*X577650D01*

+X578150Y352750D01*

+Y351750D01*

+X577650Y351250D01*

+X574650D02*X577650D01*

+X574150Y351750D02*X574650Y351250D01*

+X574150Y352750D02*Y351750D01*

+X575150Y353250D02*X577150Y351250D01*

+X578150Y350050D02*Y348050D01*

+X576150Y350050D02*X578150D01*

+X576150D02*X576650Y349550D01*

+Y348550D01*

+X576150Y348050D01*

+X574650D02*X576150D01*

+X574150Y348550D02*X574650Y348050D01*

+X574150Y349550D02*Y348550D01*

+X574650Y350050D02*X574150Y349550D01*

+X362000Y312800D02*Y311500D01*

+X362700Y313500D02*X362000Y312800D01*

+X362700Y313500D02*X365300D01*

+X366000Y312800D01*

+Y311500D01*

+X362500Y310300D02*X365500D01*

+X366000Y309800D01*

+Y308800D01*

+X365500Y308300D01*

+X362500D02*X365500D01*

+X362000Y308800D02*X362500Y308300D01*

+X362000Y309800D02*Y308800D01*

+X362500Y310300D02*X362000Y309800D01*

+Y307100D02*X366000D01*

+X362000Y304600D01*

+X366000D01*

+X362000Y303400D02*X366000D01*

+X362000Y300900D01*

+X366000D01*

+X365500Y299700D02*X366000Y299200D01*

+Y298200D01*

+X365500Y297700D01*

+X362000Y298200D02*X362500Y297700D01*

+X362000Y299200D02*Y298200D01*

+X362500Y299700D02*X362000Y299200D01*

+X364200D02*Y298200D01*

+X364700Y297700D02*X365500D01*

+X362500D02*X363700D01*

+X364200Y298200D01*

+X364700Y297700D02*X364200Y298200D01*

+X365200Y296500D02*X366000Y295700D01*

+X362000D02*X366000D01*

+X362000Y296500D02*Y295000D01*

+X365200Y293800D02*X366000Y293000D01*

+X362000D02*X366000D01*

+X362000Y293800D02*Y292300D01*

+X306000Y316300D02*Y315000D01*

+X306700Y317000D02*X306000Y316300D01*

+X306700Y317000D02*X309300D01*

+X310000Y316300D01*

+Y315000D01*

+X306500Y313800D02*X309500D01*

+X310000Y313300D01*

+Y312300D01*

+X309500Y311800D01*

+X306500D02*X309500D01*

+X306000Y312300D02*X306500Y311800D01*

+X306000Y313300D02*Y312300D01*

+X306500Y313800D02*X306000Y313300D01*

+Y310600D02*X310000D01*

+X306000Y308100D01*

+X310000D01*

+X306000Y306900D02*X310000D01*

+X306000Y304400D01*

+X310000D01*

+X309500Y303200D02*X310000Y302700D01*

+Y301700D01*

+X309500Y301200D01*

+X306000Y301700D02*X306500Y301200D01*

+X306000Y302700D02*Y301700D01*

+X306500Y303200D02*X306000Y302700D01*

+X308200D02*Y301700D01*

+X308700Y301200D02*X309500D01*

+X306500D02*X307700D01*

+X308200Y301700D01*

+X308700Y301200D02*X308200Y301700D01*

+X309200Y300000D02*X310000Y299200D01*

+X306000D02*X310000D01*

+X306000Y300000D02*Y298500D01*

+X306500Y297300D02*X306000Y296800D01*

+X306500Y297300D02*X309500D01*

+X310000Y296800D01*

+Y295800D01*

+X309500Y295300D01*

+X306500D02*X309500D01*

+X306000Y295800D02*X306500Y295300D01*

+X306000Y296800D02*Y295800D01*

+X307000Y297300D02*X309000Y295300D01*

+X384150Y315150D02*Y313150D01*

+X383650Y312650D01*

+X382650D02*X383650D01*

+X382150Y313150D02*X382650Y312650D01*

+X382150Y314650D02*Y313150D01*

+X380150Y314650D02*X384150D01*

+X382150Y313850D02*X380150Y312650D01*

+X383650Y311450D02*X384150Y310950D01*

+Y309950D01*

+X383650Y309450D01*

+X380150Y309950D02*X380650Y309450D01*

+X380150Y310950D02*Y309950D01*

+X380650Y311450D02*X380150Y310950D01*

+X382350D02*Y309950D01*

+X382850Y309450D02*X383650D01*

+X380650D02*X381850D01*

+X382350Y309950D01*

+X382850Y309450D02*X382350Y309950D01*

+X380650Y308250D02*X380150Y307750D01*

+X380650Y308250D02*X383650D01*

+X384150Y307750D01*

+Y306750D01*

+X383650Y306250D01*

+X380650D02*X383650D01*

+X380150Y306750D02*X380650Y306250D01*

+X380150Y307750D02*Y306750D01*

+X381150Y308250D02*X383150Y306250D01*

+X383350Y305050D02*X384150Y304250D01*

+X380150D02*X384150D01*

+X380150Y305050D02*Y303550D01*

+Y329150D02*X384150D01*

+Y327850D02*X383450Y327150D01*

+X380850D02*X383450D01*

+X380150Y327850D02*X380850Y327150D01*

+X380150Y329650D02*Y327850D01*

+X384150Y329650D02*Y327850D01*

+X383650Y325950D02*X384150Y325450D01*

+Y324450D01*

+X383650Y323950D01*

+X380150Y324450D02*X380650Y323950D01*

+X380150Y325450D02*Y324450D01*

+X380650Y325950D02*X380150Y325450D01*

+X382350D02*Y324450D01*

+X382850Y323950D02*X383650D01*

+X380650D02*X381850D01*

+X382350Y324450D01*

+X382850Y323950D02*X382350Y324450D01*

+X380650Y322750D02*X380150Y322250D01*

+X380650Y322750D02*X383650D01*

+X384150Y322250D01*

+Y321250D01*

+X383650Y320750D01*

+X380650D02*X383650D01*

+X380150Y321250D02*X380650Y320750D01*

+X380150Y322250D02*Y321250D01*

+X381150Y322750D02*X383150Y320750D01*

+X383350Y319550D02*X384150Y318750D01*

+X380150D02*X384150D01*

+X380150Y319550D02*Y318050D01*

+X329150Y333650D02*Y331650D01*

+X328650Y331150D01*

+X327650D02*X328650D01*

+X327150Y331650D02*X327650Y331150D01*

+X327150Y333150D02*Y331650D01*

+X325150Y333150D02*X329150D01*

+X327150Y332350D02*X325150Y331150D01*

+X328350Y329950D02*X329150Y329150D01*

+X325150D02*X329150D01*

+X325150Y329950D02*Y328450D01*

+X328350Y327250D02*X329150Y326450D01*

+X325150D02*X329150D01*

+X325150Y327250D02*Y325750D01*

+X324650Y343150D02*X328650D01*

+Y341850D02*X327950Y341150D01*

+X325350D02*X327950D01*

+X324650Y341850D02*X325350Y341150D01*

+X324650Y343650D02*Y341850D01*

+X328650Y343650D02*Y341850D01*

+X326150Y339950D02*X328650Y337950D01*

+X326150Y339950D02*Y337450D01*

+X324650Y337950D02*X328650D01*

+X666500Y281500D02*Y278500D01*

+Y281500D02*X667000Y282000D01*

+X668000D01*

+X668500Y281500D01*

+Y279000D01*

+X667500Y278000D02*X668500Y279000D01*

+X667000Y278000D02*X667500D01*

+X666500Y278500D02*X667000Y278000D01*

+X667500Y279500D02*X668500Y278000D01*

+X669700Y281500D02*X670200Y282000D01*

+X671200D01*

+X671700Y281500D01*

+X671200Y278000D02*X671700Y278500D01*

+X670200Y278000D02*X671200D01*

+X669700Y278500D02*X670200Y278000D01*

+Y280200D02*X671200D01*

+X671700Y281500D02*Y280700D01*

+Y279700D02*Y278500D01*

+Y279700D02*X671200Y280200D01*

+X671700Y280700D02*X671200Y280200D01*

+X662550Y227150D02*X663850D01*

+X661850Y227850D02*X662550Y227150D01*

+X661850Y230450D02*Y227850D01*

+Y230450D02*X662550Y231150D01*

+X663850D01*

+X665050Y228650D02*X667050Y231150D01*

+X665050Y228650D02*X667550D01*

+X667050Y231150D02*Y227150D01*

+X676200Y230000D02*X677500D01*

+X675500Y230700D02*X676200Y230000D01*

+X675500Y233300D02*Y230700D01*

+Y233300D02*X676200Y234000D01*

+X677500D01*

+X678700D02*X680700D01*

+X678700D02*Y232000D01*

+X679200Y232500D01*

+X680200D01*

+X680700Y232000D01*

+Y230500D01*

+X680200Y230000D02*X680700Y230500D01*

+X679200Y230000D02*X680200D01*

+X678700Y230500D02*X679200Y230000D01*

+X665500Y332500D02*Y328500D01*

+X667500D01*

+X668700Y331700D02*X669500Y332500D01*

+Y328500D01*

+X668700D02*X670200D01*

+X609500Y385300D02*X610800D01*

+X608800Y386000D02*X609500Y385300D01*

+X608800Y388600D02*Y386000D01*

+Y388600D02*X609500Y389300D01*

+X610800D01*

+X612000Y388800D02*Y385800D01*

+Y388800D02*X612500Y389300D01*

+X613500D01*

+X614000Y388800D01*

+Y385800D01*

+X613500Y385300D02*X614000Y385800D01*

+X612500Y385300D02*X613500D01*

+X612000Y385800D02*X612500Y385300D01*

+X615200Y389300D02*Y385300D01*

+Y389300D02*X617700Y385300D01*

+Y389300D02*Y385300D01*

+X618900Y389300D02*Y385300D01*

+Y389300D02*X621400Y385300D01*

+Y389300D02*Y385300D01*

+X622600Y388800D02*X623100Y389300D01*

+X624600D01*

+X625100Y388800D01*

+Y387800D01*

+X622600Y385300D02*X625100Y387800D01*

+X622600Y385300D02*X625100D01*

+X626300Y385800D02*X626800Y385300D01*

+X626300Y388800D02*Y385800D01*

+Y388800D02*X626800Y389300D01*

+X627800D01*

+X628300Y388800D01*

+Y385800D01*

+X627800Y385300D02*X628300Y385800D01*

+X626800Y385300D02*X627800D01*

+X626300Y386300D02*X628300Y388300D01*

+X629500Y388500D02*X630300Y389300D01*

+Y385300D01*

+X629500D02*X631000D01*

+X662200Y385500D02*X663500D01*

+X661500Y386200D02*X662200Y385500D01*

+X661500Y388800D02*Y386200D01*

+Y388800D02*X662200Y389500D01*

+X663500D01*

+X664700Y389000D02*Y386000D01*

+Y389000D02*X665200Y389500D01*

+X666200D01*

+X666700Y389000D01*

+Y386000D01*

+X666200Y385500D02*X666700Y386000D01*

+X665200Y385500D02*X666200D01*

+X664700Y386000D02*X665200Y385500D01*

+X667900Y389500D02*Y385500D01*

+Y389500D02*X670400Y385500D01*

+Y389500D02*Y385500D01*

+X671600Y389500D02*Y385500D01*

+Y389500D02*X674100Y385500D01*

+Y389500D02*Y385500D01*

+X675300Y389000D02*X675800Y389500D01*

+X676800D01*

+X677300Y389000D01*

+X676800Y385500D02*X677300Y386000D01*

+X675800Y385500D02*X676800D01*

+X675300Y386000D02*X675800Y385500D01*

+Y387700D02*X676800D01*

+X677300Y389000D02*Y388200D01*

+Y387200D02*Y386000D01*

+Y387200D02*X676800Y387700D01*

+X677300Y388200D02*X676800Y387700D01*

+X678500Y388700D02*X679300Y389500D01*

+Y385500D01*

+X678500D02*X680000D01*

+X681200Y389500D02*X683200D01*

+X681200D02*Y387500D01*

+X681700Y388000D01*

+X682700D01*

+X683200Y387500D01*

+Y386000D01*

+X682700Y385500D02*X683200Y386000D01*

+X681700Y385500D02*X682700D01*

+X681200Y386000D02*X681700Y385500D01*

+X566039Y385650D02*X567040D01*

+X565500Y386189D02*X566039Y385650D01*

+X565500Y388191D02*Y386189D01*

+Y388191D02*X566039Y388730D01*

+X567040D01*

+X567964Y388345D02*Y386035D01*

+Y388345D02*X568349Y388730D01*

+X569119D01*

+X569504Y388345D01*

+Y386035D01*

+X569119Y385650D02*X569504Y386035D01*

+X568349Y385650D02*X569119D01*

+X567964Y386035D02*X568349Y385650D01*

+X570428Y388730D02*Y385650D01*

+Y388730D02*X572353Y385650D01*

+Y388730D02*Y385650D01*

+X573277Y388730D02*Y385650D01*

+Y388730D02*X575202Y385650D01*

+Y388730D02*Y385650D01*

+X576126Y388345D02*X576511Y388730D01*

+X577281D01*

+X577666Y388345D01*

+X577281Y385650D02*X577666Y386035D01*

+X576511Y385650D02*X577281D01*

+X576126Y386035D02*X576511Y385650D01*

+Y387344D02*X577281D01*

+X577666Y388345D02*Y387729D01*

+Y386959D02*Y386035D01*

+Y386959D02*X577281Y387344D01*

+X577666Y387729D02*X577281Y387344D01*

+X578590Y388114D02*X579206Y388730D01*

+Y385650D01*

+X578590D02*X579745D01*

+X581824Y388730D02*X582209Y388345D01*

+X581054Y388730D02*X581824D01*

+X580669Y388345D02*X581054Y388730D01*

+X580669Y388345D02*Y386035D01*

+X581054Y385650D01*

+X581824Y387344D02*X582209Y386959D01*

+X580669Y387344D02*X581824D01*

+X581054Y385650D02*X581824D01*

+X582209Y386035D01*

+Y386959D02*Y386035D01*

+X542839Y386450D02*X543840D01*

+X542300Y386989D02*X542839Y386450D01*

+X542300Y388991D02*Y386989D01*

+Y388991D02*X542839Y389530D01*

+X543840D01*

+X544764Y389145D02*Y386835D01*

+Y389145D02*X545149Y389530D01*

+X545919D01*

+X546304Y389145D01*

+Y386835D01*

+X545919Y386450D02*X546304Y386835D01*

+X545149Y386450D02*X545919D01*

+X544764Y386835D02*X545149Y386450D01*

+X547228Y389530D02*Y386450D01*

+Y389530D02*X549153Y386450D01*

+Y389530D02*Y386450D01*

+X550077Y389530D02*Y386450D01*

+Y389530D02*X552002Y386450D01*

+Y389530D02*Y386450D01*

+X552926Y389145D02*X553311Y389530D01*

+X554081D01*

+X554466Y389145D01*

+X554081Y386450D02*X554466Y386835D01*

+X553311Y386450D02*X554081D01*

+X552926Y386835D02*X553311Y386450D01*

+Y388144D02*X554081D01*

+X554466Y389145D02*Y388529D01*

+Y387759D02*Y386835D01*

+Y387759D02*X554081Y388144D01*

+X554466Y388529D02*X554081Y388144D01*

+X555390Y386835D02*X555775Y386450D01*

+X555390Y389145D02*Y386835D01*

+Y389145D02*X555775Y389530D01*

+X556545D01*

+X556930Y389145D01*

+Y386835D01*

+X556545Y386450D02*X556930Y386835D01*

+X555775Y386450D02*X556545D01*

+X555390Y387220D02*X556930Y388760D01*

+X557854Y388914D02*X558470Y389530D01*

+Y386450D01*

+X557854D02*X559009D01*

+X561000Y311300D02*Y310000D01*

+X561700Y312000D02*X561000Y311300D01*

+X561700Y312000D02*X564300D01*

+X565000Y311300D01*

+Y310000D01*

+X561500Y308800D02*X564500D01*

+X565000Y308300D01*

+Y307300D01*

+X564500Y306800D01*

+X561500D02*X564500D01*

+X561000Y307300D02*X561500Y306800D01*

+X561000Y308300D02*Y307300D01*

+X561500Y308800D02*X561000Y308300D01*

+Y305600D02*X565000D01*

+X561000Y303100D01*

+X565000D01*

+X561000Y301900D02*X565000D01*

+X561000Y299400D01*

+X565000D01*

+X564500Y298200D02*X565000Y297700D01*

+Y296700D01*

+X564500Y296200D01*

+X561000Y296700D02*X561500Y296200D01*

+X561000Y297700D02*Y296700D01*

+X561500Y298200D02*X561000Y297700D01*

+X563200D02*Y296700D01*

+X563700Y296200D02*X564500D01*

+X561500D02*X562700D01*

+X563200Y296700D01*

+X563700Y296200D02*X563200Y296700D01*

+X564200Y295000D02*X565000Y294200D01*

+X561000D02*X565000D01*

+X561000Y295000D02*Y293500D01*

+X564500Y292300D02*X565000Y291800D01*

+Y290800D01*

+X564500Y290300D01*

+X561000Y290800D02*X561500Y290300D01*

+X561000Y291800D02*Y290800D01*

+X561500Y292300D02*X561000Y291800D01*

+X563200D02*Y290800D01*

+X563700Y290300D02*X564500D01*

+X561500D02*X562700D01*

+X563200Y290800D01*

+X563700Y290300D02*X563200Y290800D01*

+X508800Y295122D02*Y294420D01*

+X509178Y295500D02*X508800Y295122D01*

+X509178Y295500D02*X510582D01*

+X510960Y295122D01*

+Y294420D01*

+X509070Y293772D02*X510690D01*

+X510960Y293502D01*

+Y292962D01*

+X510690Y292692D01*

+X509070D02*X510690D01*

+X508800Y292962D02*X509070Y292692D01*

+X508800Y293502D02*Y292962D01*

+X509070Y293772D02*X508800Y293502D01*

+Y292044D02*X510960D01*

+X508800Y290694D01*

+X510960D01*

+X508800Y290046D02*X510960D01*

+X508800Y288696D01*

+X510960D01*

+X510690Y288048D02*X510960Y287778D01*

+Y287238D01*

+X510690Y286968D01*

+X508800Y287238D02*X509070Y286968D01*

+X508800Y287778D02*Y287238D01*

+X509070Y288048D02*X508800Y287778D01*

+X509988D02*Y287238D01*

+X510258Y286968D02*X510690D01*

+X509070D02*X509718D01*

+X509988Y287238D01*

+X510258Y286968D02*X509988Y287238D01*

+X510528Y286320D02*X510960Y285888D01*

+X508800D02*X510960D01*

+X508800Y286320D02*Y285510D01*

+X509610Y284862D02*X510960Y283782D01*

+X509610Y284862D02*Y283512D01*

+X508800Y283782D02*X510960D01*

+X418000Y314800D02*Y313500D01*

+X418700Y315500D02*X418000Y314800D01*

+X418700Y315500D02*X421300D01*

+X422000Y314800D01*

+Y313500D01*

+X418500Y312300D02*X421500D01*

+X422000Y311800D01*

+Y310800D01*

+X421500Y310300D01*

+X418500D02*X421500D01*

+X418000Y310800D02*X418500Y310300D01*

+X418000Y311800D02*Y310800D01*

+X418500Y312300D02*X418000Y311800D01*

+Y309100D02*X422000D01*

+X418000Y306600D01*

+X422000D01*

+X418000Y305400D02*X422000D01*

+X418000Y302900D01*

+X422000D01*

+X421500Y301700D02*X422000Y301200D01*

+Y300200D01*

+X421500Y299700D01*

+X418000Y300200D02*X418500Y299700D01*

+X418000Y301200D02*Y300200D01*

+X418500Y301700D02*X418000Y301200D01*

+X420200D02*Y300200D01*

+X420700Y299700D02*X421500D01*

+X418500D02*X419700D01*

+X420200Y300200D01*

+X420700Y299700D02*X420200Y300200D01*

+X421200Y298500D02*X422000Y297700D01*

+X418000D02*X422000D01*

+X418000Y298500D02*Y297000D01*

+X421500Y295800D02*X422000Y295300D01*

+Y293800D01*

+X421500Y293300D01*

+X420500D02*X421500D01*

+X418000Y295800D02*X420500Y293300D01*

+X418000Y295800D02*Y293300D01*

+X447389Y344300D02*X448390D01*

+X446850Y344839D02*X447389Y344300D01*

+X446850Y346841D02*Y344839D01*

+Y346841D02*X447389Y347380D01*

+X448390D01*

+X449314Y345455D02*X450854Y347380D01*

+X449314Y345455D02*X451239D01*

+X450854Y347380D02*Y344300D01*

+X452163Y344685D02*X452548Y344300D01*

+X452163Y346995D02*Y344685D01*

+Y346995D02*X452548Y347380D01*

+X453318D01*

+X453703Y346995D01*

+Y344685D01*

+X453318Y344300D02*X453703Y344685D01*

+X452548Y344300D02*X453318D01*

+X452163Y345070D02*X453703Y346610D01*

+X454627Y346995D02*X455012Y347380D01*

+X455782D01*

+X456167Y346995D01*

+X455782Y344300D02*X456167Y344685D01*

+X455012Y344300D02*X455782D01*

+X454627Y344685D02*X455012Y344300D01*

+Y345994D02*X455782D01*

+X456167Y346995D02*Y346379D01*

+Y345609D02*Y344685D01*

+Y345609D02*X455782Y345994D01*

+X456167Y346379D02*X455782Y345994D01*

+M02*

diff --git a/motors/uart_schematic/uart-5v.sch b/motors/uart_schematic/uart-5v.sch
new file mode 100644
index 0000000..408b206
--- /dev/null
+++ b/motors/uart_schematic/uart-5v.sch
@@ -0,0 +1,782 @@
+v 20130925 2
+C 51700 44200 1 0 0 LM34936.sym
+{
+T 52200 48700 5 10 1 1 0 0 1
+device=LM34936
+T 53500 48700 5 10 1 1 0 0 1
+refdes=U1
+T 57200 47500 5 10 0 1 0 0 1
+footprint=QFN28_4_5_EP
+T 51700 44200 5 10 0 0 0 0 1
+pn=LM34936RHFR
+}
+C 52700 54200 1 270 0 capacitor-1.sym
+{
+T 53400 54000 5 10 0 0 270 0 1
+device=CAPACITOR
+T 53600 54000 5 10 0 0 270 0 1
+symversion=0.1
+T 52700 54200 5 10 0 0 270 0 1
+footprint=0805
+T 52700 54200 5 10 0 0 270 0 1
+pn=GMK212BBJ106MG-T
+T 53200 54000 5 10 1 1 270 0 1
+refdes=C1
+T 52500 54000 5 10 1 1 270 0 1
+value=10 uF
+}
+N 52900 54200 52900 54400 4
+C 52800 52800 1 0 0 gnd-1.sym
+N 52900 53100 52900 53300 4
+C 54000 54200 1 270 0 capacitor-1.sym
+{
+T 54700 54000 5 10 0 0 270 0 1
+device=CAPACITOR
+T 54900 54000 5 10 0 0 270 0 1
+symversion=0.1
+T 54000 54200 5 10 0 0 270 0 1
+footprint=0805
+T 54000 54200 5 10 0 0 270 0 1
+pn=GMK212BBJ106MG-T
+T 54500 54000 5 10 1 1 270 0 1
+refdes=C2
+T 53800 54000 5 10 1 1 270 0 1
+value=10 uF
+}
+N 54200 54200 54200 54400 4
+C 54100 52800 1 0 0 gnd-1.sym
+N 54200 53100 54200 53300 4
+C 55300 54200 1 270 0 capacitor-2.sym
+{
+T 56000 54000 5 10 0 0 270 0 1
+device=POLARIZED_CAPACITOR
+T 56200 54000 5 10 0 0 270 0 1
+symversion=0.1
+T 55300 54200 5 10 0 0 0 0 1
+footprint=CAP_D
+T 55300 54200 5 10 0 0 0 0 1
+pn=HHXC250ARA680MF80G
+T 55800 54000 5 10 1 1 270 0 1
+refdes=C3
+T 55100 54000 5 10 1 1 270 0 1
+value=68 uF
+}
+C 55400 52800 1 0 0 gnd-1.sym
+N 55500 53100 55500 53300 4
+N 55500 54400 55500 54200 4
+C 61900 54200 1 270 0 capacitor-1.sym
+{
+T 62600 54000 5 10 0 0 270 0 1
+device=CAPACITOR
+T 62800 54000 5 10 0 0 270 0 1
+symversion=0.1
+T 61900 54200 5 10 0 0 270 0 1
+footprint=0805
+T 61900 54200 5 10 0 0 270 0 1
+pn=GMK212BBJ106MG-T
+T 62400 54000 5 10 1 1 270 0 1
+refdes=C4
+T 61700 54000 5 10 1 1 270 0 1
+value=10 uF
+}
+N 62100 54200 62100 54400 4
+C 62000 52800 1 0 0 gnd-1.sym
+N 62100 53100 62100 53300 4
+C 63200 54200 1 270 0 capacitor-2.sym
+{
+T 63900 54000 5 10 0 0 270 0 1
+device=POLARIZED_CAPACITOR
+T 64100 54000 5 10 0 0 270 0 1
+symversion=0.1
+T 63200 54200 5 10 0 0 0 0 1
+footprint=CAP_D
+T 63200 54200 5 10 0 0 0 0 1
+pn=16SVPG270MX
+T 63700 54000 5 10 1 1 270 0 1
+refdes=C5
+T 63000 54000 5 10 1 1 270 0 1
+value=270 uF
+}
+C 63300 52800 1 0 0 gnd-1.sym
+N 63400 53100 63400 53300 4
+N 63400 54400 63400 54200 4
+C 61900 54400 1 0 0 5V-plus-1.sym
+C 63200 54400 1 0 0 5V-plus-1.sym
+C 56600 54200 1 270 0 capacitor-2.sym
+{
+T 57300 54000 5 10 0 0 270 0 1
+device=POLARIZED_CAPACITOR
+T 57500 54000 5 10 0 0 270 0 1
+symversion=0.1
+T 56600 54200 5 10 0 0 0 0 1
+footprint=CAP_D
+T 56600 54200 5 10 0 0 0 0 1
+pn=HHXC250ARA680MF80G
+T 57100 54000 5 10 1 1 270 0 1
+refdes=C6
+T 56400 54000 5 10 1 1 270 0 1
+value=68 uF
+}
+C 56700 52800 1 0 0 gnd-1.sym
+N 56800 53100 56800 53300 4
+N 56800 54400 56800 54200 4
+C 57800 54200 1 270 0 capacitor-2.sym
+{
+T 58500 54000 5 10 0 0 270 0 1
+device=POLARIZED_CAPACITOR
+T 58700 54000 5 10 0 0 270 0 1
+symversion=0.1
+T 57800 54200 5 10 0 0 0 0 1
+footprint=CAP_D
+T 57800 54200 5 10 0 0 0 0 1
+pn=HHXC250ARA680MF80G
+T 58300 54000 5 10 1 1 270 0 1
+refdes=C7
+T 57600 54000 5 10 1 1 270 0 1
+value=68 uF
+}
+C 57900 52800 1 0 0 gnd-1.sym
+N 58000 53100 58000 53300 4
+N 58000 54400 58000 54200 4
+C 55700 56100 1 90 0 zener-4.sym
+{
+T 55100 56500 5 10 0 0 90 0 1
+device=DIODE
+T 55700 56100 5 10 0 0 90 0 1
+footprint=DO214AA
+T 55700 56100 5 10 0 0 90 0 1
+pn=SMBJ15D-M3/H
+T 55200 56400 5 10 1 1 90 0 1
+refdes=D1
+T 55900 56400 5 10 1 1 90 0 1
+standoff=15 V
+}
+C 55400 55600 1 0 0 gnd-1.sym
+C 55300 57200 1 0 0 vcc-1.sym
+N 55500 57200 55500 57000 4
+N 55500 56100 55500 55900 4
+C 54000 54400 1 0 0 vcc-1.sym
+C 52700 54400 1 0 0 vcc-1.sym
+C 55300 54400 1 0 0 vcc-1.sym
+C 56600 54400 1 0 0 vcc-1.sym
+C 57800 54400 1 0 0 vcc-1.sym
+C 53000 43700 1 0 0 gnd-1.sym
+N 53100 44000 53100 44200 4
+C 55000 44500 1 90 0 gnd-1.sym
+N 54700 44600 54500 44600 4
+C 55000 44800 1 90 0 gnd-1.sym
+N 54700 44900 54500 44900 4
+N 54500 45200 54700 45200 4
+C 54700 45400 1 270 0 vcc-1.sym
+N 54100 43700 54100 43900 4
+C 54000 42300 1 0 0 gnd-1.sym
+N 54100 42600 54100 42800 4
+C 53900 43900 1 0 0 vcc-1.sym
+C 55500 45300 1 270 0 capacitor-1.sym
+{
+T 56200 45100 5 10 0 0 270 0 1
+device=CAPACITOR
+T 56400 45100 5 10 0 0 270 0 1
+symversion=0.1
+T 55500 45300 5 10 0 0 270 0 1
+voltage=16 V
+T 55500 45300 5 10 0 0 270 0 1
+footprint=0603
+T 55500 45300 5 10 0 0 270 0 1
+pn=885012206047
+T 56000 45100 5 10 1 1 270 0 1
+refdes=C9
+T 55300 45100 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 55600 43900 1 0 0 gnd-1.sym
+N 55700 44200 55700 44400 4
+C 50200 48400 1 0 0 resistor-1.sym
+{
+T 50500 48800 5 10 0 0 0 0 1
+device=RESISTOR
+T 50200 48400 5 10 0 0 0 0 1
+footprint=0603
+T 50200 48400 5 10 0 0 90 0 1
+tolerance=1%
+T 50400 48700 5 10 1 1 0 0 1
+refdes=R1
+T 50400 48200 5 10 1 1 0 0 1
+value=93.1 k
+T 50200 48400 5 10 0 0 90 0 1
+pn=RC0603FR-0793K1L
+}
+N 51100 48500 51700 48500 4
+C 49700 48600 1 270 0 gnd-1.sym
+N 50000 48500 50200 48500 4
+C 51200 48300 1 270 0 gnd-1.sym
+N 51500 48200 51700 48200 4
+C 48900 48000 1 0 0 resistor-1.sym
+{
+T 49200 48400 5 10 0 0 0 0 1
+device=RESISTOR
+T 48900 48000 5 10 0 0 0 0 1
+footprint=0603
+T 48900 48000 5 10 0 0 90 0 1
+tolerance=1%
+T 49100 48300 5 10 1 1 0 0 1
+refdes=R2
+T 49100 47800 5 10 1 1 0 0 1
+value=23.7 k
+T 48900 48000 5 10 0 0 90 0 1
+pn=RMCF0603FT23K7
+}
+N 48700 48100 48900 48100 4
+C 48400 48200 1 270 0 gnd-1.sym
+C 47600 47400 1 0 0 capacitor-1.sym
+{
+T 47800 48100 5 10 0 0 0 0 1
+device=CAPACITOR
+T 47800 48300 5 10 0 0 0 0 1
+symversion=0.1
+T 47600 47400 5 10 0 0 0 0 1
+voltage=16 V
+T 47600 47400 5 10 0 0 0 0 1
+footprint=0603
+T 47600 47400 5 10 0 0 0 0 1
+pn=CL10C680JB8NNNC
+T 47800 47900 5 10 1 1 0 0 1
+refdes=C10
+T 47800 47200 5 10 1 1 0 0 1
+value=68 pF
+}
+N 51700 47900 50900 47900 4
+N 50900 47900 50900 48100 4
+N 50900 48100 49800 48100 4
+N 47400 47600 47600 47600 4
+C 47100 47700 1 270 0 gnd-1.sym
+N 48500 47600 51700 47600 4
+C 48900 46800 1 0 0 capacitor-1.sym
+{
+T 49100 47500 5 10 0 0 0 0 1
+device=CAPACITOR
+T 49100 47700 5 10 0 0 0 0 1
+symversion=0.1
+T 48900 46800 5 10 0 0 0 0 1
+voltage=16 V
+T 48900 46800 5 10 0 0 0 0 1
+footprint=0805
+T 48900 46800 5 10 0 0 0 0 1
+pn=CGA4J2C0G1H223J125AA
+T 49100 47300 5 10 1 1 0 0 1
+refdes=C11
+T 49100 46600 5 10 1 1 0 0 1
+value=22 nF
+}
+N 51700 47300 50000 47300 4
+N 50000 47000 50000 47300 4
+N 50000 47000 49800 47000 4
+N 48700 47000 48900 47000 4
+C 48400 47100 1 270 0 gnd-1.sym
+N 51700 47000 50200 47000 4
+N 50200 46500 50200 47000 4
+N 50200 46500 48500 46500 4
+N 51700 46700 50400 46700 4
+N 50400 46300 50400 46700 4
+N 45400 46300 50400 46300 4
+C 51500 46500 1 180 0 output-1.sym
+{
+T 51400 46200 5 10 0 0 180 0 1
+device=OUTPUT
+T 51300 46300 5 10 1 1 180 0 1
+net=5V_PGOOD:1
+}
+N 51500 46400 51700 46400 4
+C 60600 54200 1 270 0 capacitor-1.sym
+{
+T 61300 54000 5 10 0 0 270 0 1
+device=CAPACITOR
+T 61500 54000 5 10 0 0 270 0 1
+symversion=0.1
+T 60600 54200 5 10 0 0 270 0 1
+footprint=0805
+T 60600 54200 5 10 0 0 270 0 1
+pn=GMK212BBJ106MG-T
+T 61100 54000 5 10 1 1 270 0 1
+refdes=C12
+T 60400 54000 5 10 1 1 270 0 1
+value=10 uF
+}
+N 60800 54200 60800 54400 4
+C 60700 52800 1 0 0 gnd-1.sym
+N 60800 53100 60800 53300 4
+C 60600 54400 1 0 0 5V-plus-1.sym
+C 53900 43700 1 270 0 capacitor-1.sym
+{
+T 54600 43500 5 10 0 0 270 0 1
+device=CAPACITOR
+T 54800 43500 5 10 0 0 270 0 1
+symversion=0.1
+T 53900 43700 5 10 0 0 270 0 1
+voltage=16 V
+T 53900 43700 5 10 0 0 270 0 1
+footprint=0603
+T 53900 43700 5 10 0 0 270 0 1
+pn=885012206047
+T 54400 43500 5 10 1 1 270 0 1
+refdes=C8
+T 53700 43500 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 44700 45900 1 270 0 resistor-1.sym
+{
+T 45100 45600 5 10 0 0 270 0 1
+device=RESISTOR
+T 44700 45900 5 10 0 0 270 0 1
+footprint=0603
+T 44700 45900 5 10 0 0 0 0 1
+tolerance=1%
+T 45000 45700 5 10 1 1 270 0 1
+refdes=R3
+T 44500 45700 5 10 1 1 270 0 1
+value=118 k
+T 44700 45900 5 10 0 0 0 0 1
+pn=RC0603FR-07118KL
+}
+C 44700 49600 1 270 0 resistor-1.sym
+{
+T 45100 49300 5 10 0 0 270 0 1
+device=RESISTOR
+T 44700 49600 5 10 0 0 270 0 1
+footprint=0603
+T 44700 49600 5 10 0 0 0 0 1
+tolerance=1%
+T 45000 49400 5 10 1 1 270 0 1
+refdes=R4
+T 44500 49400 5 10 1 1 270 0 1
+value=20 k
+T 44700 49600 5 10 0 0 0 0 1
+pn=RC0603FR-0720KL
+}
+C 44700 47200 1 270 0 resistor-1.sym
+{
+T 45100 46900 5 10 0 0 270 0 1
+device=RESISTOR
+T 44700 47200 5 10 0 0 270 0 1
+footprint=0603
+T 44700 47200 5 10 0 0 0 0 1
+tolerance=1%
+T 45000 47000 5 10 1 1 270 0 1
+refdes=R5
+T 44500 47000 5 10 1 1 270 0 1
+value=280 k
+T 44700 47200 5 10 0 0 0 0 1
+pn=RMCF0603FT280K
+}
+C 44700 50900 1 270 0 resistor-1.sym
+{
+T 45100 50600 5 10 0 0 270 0 1
+device=RESISTOR
+T 44700 50900 5 10 0 0 270 0 1
+footprint=0603
+T 44700 50900 5 10 0 0 0 0 1
+tolerance=1%
+T 45000 50700 5 10 1 1 270 0 1
+refdes=R6
+T 44500 50700 5 10 1 1 270 0 1
+value=118 k
+T 44700 50900 5 10 0 0 0 0 1
+pn=RC0603FR-07118KL
+}
+N 44800 45900 44800 46300 4
+N 44800 47200 44800 47400 4
+C 44600 47400 1 0 0 vcc-1.sym
+C 44700 44500 1 0 0 gnd-1.sym
+N 44800 44800 44800 45000 4
+N 51700 46100 44800 46100 4
+N 51500 45800 51700 45800 4
+C 51200 45900 1 270 0 gnd-1.sym
+N 51500 45500 51700 45500 4
+C 51200 45600 1 270 0 gnd-1.sym
+C 62300 49100 1 0 0 gnd-1.sym
+N 62400 49400 62400 49600 4
+C 62200 50500 1 270 0 capacitor-1.sym
+{
+T 62900 50300 5 10 0 0 270 0 1
+device=CAPACITOR
+T 63100 50300 5 10 0 0 270 0 1
+symversion=0.1
+T 62200 50500 5 10 0 0 270 0 1
+voltage=16 V
+T 62200 50500 5 10 0 0 270 0 1
+footprint=0603
+T 62200 50500 5 10 0 0 270 0 1
+pn=EMK107B7105KA-T
+T 62700 50300 5 10 1 1 270 0 1
+refdes=C13
+T 62000 50300 5 10 1 1 270 0 1
+value=1 uF
+}
+N 51500 44600 51700 44600 4
+N 44800 50000 44800 49600 4
+C 44700 48200 1 0 0 gnd-1.sym
+N 44800 48500 44800 48700 4
+C 44600 51100 1 0 0 5V-plus-1.sym
+N 44800 51100 44800 50900 4
+N 45400 46300 45400 49800 4
+N 45400 49800 44800 49800 4
+C 60700 50500 1 270 0 diode-1.sym
+{
+T 61300 50100 5 10 0 0 270 0 1
+device=DIODE
+T 60700 50500 5 10 0 0 90 0 1
+pn=DB2W40100L
+T 60700 50500 5 10 0 0 90 0 1
+footprint=SOD123F
+T 61200 50200 5 10 1 1 270 0 1
+refdes=D3
+}
+C 56800 50500 1 270 0 diode-1.sym
+{
+T 57400 50100 5 10 0 0 270 0 1
+device=DIODE
+T 56800 50500 5 10 0 0 90 0 1
+pn=DB2W40100L
+T 56800 50500 5 10 0 0 90 0 1
+footprint=SOD123F
+T 57300 50200 5 10 1 1 270 0 1
+refdes=D2
+}
+C 56800 49200 1 270 0 capacitor-1.sym
+{
+T 57500 49000 5 10 0 0 270 0 1
+device=CAPACITOR
+T 57700 49000 5 10 0 0 270 0 1
+symversion=0.1
+T 56800 49200 5 10 0 0 270 0 1
+voltage=25 V
+T 56800 49200 5 10 0 0 270 0 1
+footprint=0603
+T 56800 49200 5 10 0 0 270 0 1
+pn=885012206071
+T 57300 49000 5 10 1 1 270 0 1
+refdes=C14
+T 56600 49000 5 10 1 1 270 0 1
+value=0.1 uF
+}
+C 60700 49200 1 270 0 capacitor-1.sym
+{
+T 61400 49000 5 10 0 0 270 0 1
+device=CAPACITOR
+T 61600 49000 5 10 0 0 270 0 1
+symversion=0.1
+T 60700 49200 5 10 0 0 270 0 1
+voltage=25 V
+T 60700 49200 5 10 0 0 270 0 1
+footprint=0603
+T 60700 49200 5 10 0 0 270 0 1
+pn=885012206071
+T 61200 49000 5 10 1 1 270 0 1
+refdes=C15
+T 60500 49000 5 10 1 1 270 0 1
+value=0.1 uF
+}
+N 60900 49200 60900 49600 4
+N 57000 49200 57000 49600 4
+N 54500 47300 55300 47300 4
+N 55300 47300 55300 49400 4
+N 55300 49400 57000 49400 4
+N 54500 46100 58700 46100 4
+N 58700 46100 58700 49400 4
+N 58700 49400 60900 49400 4
+N 60900 50500 60900 50700 4
+N 56300 50700 62400 50700 4
+N 57000 50500 57000 50700 4
+N 54500 45500 55700 45500 4
+N 55700 45500 55700 45300 4
+N 56300 42100 56300 50700 4
+N 51500 42100 56300 42100 4
+N 51500 42100 51500 44600 4
+N 62400 50700 62400 50500 4
+C 64700 47300 1 0 0 inductor-1.sym
+{
+T 64900 47800 5 10 0 0 0 0 1
+device=INDUCTOR
+T 64900 48000 5 10 0 0 0 0 1
+symversion=0.1
+T 64700 47300 5 10 0 1 0 0 1
+pn=7443551200
+T 64900 47600 5 10 1 1 0 0 1
+refdes=L1
+T 64800 47200 5 10 1 1 0 0 1
+value=2 uH
+T 64700 47300 5 10 0 0 0 0 1
+footprint=1365
+}
+C 63800 48000 1 0 0 mosfet-with-diode-1.sym
+{
+T 64700 48500 5 10 0 0 0 0 1
+device=NPN_TRANSISTOR
+T 63800 48000 5 10 0 0 0 0 1
+pn=CSD19502Q5B
+T 63800 48000 5 10 0 0 0 0 1
+footprint=8-PowerTDFN_5_6
+T 64700 48500 5 10 1 1 0 0 1
+refdes=Q2
+}
+C 66500 46000 1 0 1 mosfet-with-diode-1.sym
+{
+T 65600 46500 5 10 0 0 0 6 1
+device=NPN_TRANSISTOR
+T 66500 46000 5 10 0 0 0 6 1
+pn=CSD17577Q5A
+T 66500 46000 5 10 0 0 0 6 1
+footprint=8-PowerTDFN_5_6
+T 65600 46500 5 10 1 1 0 6 1
+refdes=Q1
+}
+C 66500 48000 1 0 1 mosfet-with-diode-1.sym
+{
+T 65600 48500 5 10 0 0 0 6 1
+device=NPN_TRANSISTOR
+T 66500 48000 5 10 0 0 0 6 1
+pn=CSD17556Q5B
+T 66500 48000 5 10 0 0 0 6 1
+footprint=8-PowerTDFN_5_6
+T 65600 48500 5 10 1 1 0 6 1
+refdes=Q3
+}
+C 63800 46000 1 0 0 mosfet-with-diode-1.sym
+{
+T 64700 46500 5 10 0 0 0 0 1
+device=NPN_TRANSISTOR
+T 63800 46000 5 10 0 0 0 0 1
+pn=CSD19502Q5B
+T 63800 46000 5 10 0 0 0 0 1
+footprint=8-PowerTDFN_5_6
+T 64700 46500 5 10 1 1 0 0 1
+refdes=Q4
+}
+N 64400 47000 64400 48000 4
+N 65900 47000 65900 48000 4
+N 64400 47400 64700 47400 4
+N 65600 47400 65900 47400 4
+N 64400 47200 57000 47200 4
+N 57000 47200 57000 48300 4
+N 54500 47900 57000 47900 4
+N 65900 47800 60900 47800 4
+N 60900 46700 60900 48300 4
+N 54500 46700 60900 46700 4
+N 54500 47600 60300 47600 4
+N 60300 47600 60300 48100 4
+N 60300 48100 62700 48100 4
+N 62700 48100 62700 48500 4
+N 62700 48500 63800 48500 4
+N 54500 47000 63200 47000 4
+N 63200 46500 63200 47000 4
+N 63200 46500 63800 46500 4
+N 54500 45800 66700 45800 4
+N 66700 45800 66700 46500 4
+N 66700 46500 66500 46500 4
+N 54500 46400 62500 46400 4
+N 62500 45600 62500 46400 4
+N 62500 45600 66900 45600 4
+N 66900 45600 66900 48500 4
+N 66900 48500 66500 48500 4
+N 64400 46000 64400 45400 4
+N 57600 45400 65900 45400 4
+N 65900 45400 65900 46000 4
+N 65100 45400 65100 45200 4
+C 65000 45200 1 270 0 resistor-1.sym
+{
+T 65400 44900 5 10 0 0 270 0 1
+device=RESISTOR
+T 65000 45200 5 10 0 0 270 0 1
+footprint=0612
+T 65000 45200 5 10 0 0 0 0 1
+tolerance=1%
+T 65300 45000 5 10 1 1 270 0 1
+refdes=R7
+T 64800 45000 5 10 1 1 270 0 1
+value=6 m
+T 65000 45200 5 10 0 0 0 0 1
+pn=PRL1632-R006-F-T1
+}
+N 65100 43900 65100 44300 4
+C 65000 43600 1 0 0 gnd-1.sym
+N 65100 44100 58100 44100 4
+N 58100 41700 58100 44100 4
+N 57600 41900 57600 45400 4
+C 64200 49200 1 0 0 vcc-1.sym
+C 65700 49200 1 0 0 5V-plus-1.sym
+N 64400 49200 64400 49000 4
+N 65900 49200 65900 49000 4
+C 54700 48700 1 270 0 vcc-1.sym
+C 54700 48400 1 270 0 5V-plus-1.sym
+N 54700 48500 54500 48500 4
+N 54700 48200 54500 48200 4
+C 50000 44100 1 0 0 capacitor-1.sym
+{
+T 50200 44800 5 10 0 0 0 0 1
+device=CAPACITOR
+T 50200 45000 5 10 0 0 0 0 1
+symversion=0.1
+T 50000 44100 5 10 0 0 0 0 1
+footprint=0603
+T 50000 44100 5 10 0 0 0 0 1
+pn=06035A470JAT2A
+T 50200 44600 5 10 1 1 0 0 1
+refdes=C16
+T 50200 43900 5 10 1 1 0 0 1
+value=47 pF
+}
+N 50900 44300 51100 44300 4
+N 50000 44300 49800 44300 4
+N 51700 44900 51100 44900 4
+N 51100 44900 51100 43800 4
+N 51700 45200 49800 45200 4
+N 49800 45200 49800 43800 4
+C 51000 43800 1 270 0 resistor-1.sym
+{
+T 51400 43500 5 10 0 0 270 0 1
+device=RESISTOR
+T 51000 43800 5 10 0 0 270 0 1
+footprint=0603
+T 51000 43800 5 10 0 0 0 0 1
+tolerance=1%
+T 51300 43600 5 10 1 1 270 0 1
+refdes=R8
+T 50800 43600 5 10 1 1 270 0 1
+value=100
+T 51000 43800 5 10 0 0 0 0 1
+pn=CRCW0603100RFKEA
+}
+C 49700 43800 1 270 0 resistor-1.sym
+{
+T 50100 43500 5 10 0 0 270 0 1
+device=RESISTOR
+T 49700 43800 5 10 0 0 270 0 1
+footprint=0603
+T 49700 43800 5 10 0 0 0 0 1
+tolerance=1%
+T 50000 43600 5 10 1 1 270 0 1
+refdes=R9
+T 49500 43600 5 10 1 1 270 0 1
+value=100
+T 49700 43800 5 10 0 0 0 0 1
+pn=CRCW0603100RFKEA
+}
+N 51100 41900 57600 41900 4
+N 51100 41900 51100 42900 4
+N 49800 41700 58100 41700 4
+N 49800 41700 49800 42900 4
+C 47200 43500 1 270 0 resistor-1.sym
+{
+T 47600 43200 5 10 0 0 270 0 1
+device=RESISTOR
+T 47200 43500 5 10 0 0 270 0 1
+footprint=0603
+T 47200 43500 5 10 0 0 0 0 1
+tolerance=1%
+T 47500 43300 5 10 1 1 270 0 1
+refdes=R10
+T 47000 43300 5 10 1 1 270 0 1
+value=5.49 k
+T 47200 43500 5 10 0 0 0 0 1
+pn=RMCF0603FT5K49
+}
+C 47100 44600 1 270 0 capacitor-1.sym
+{
+T 47800 44400 5 10 0 0 270 0 1
+device=CAPACITOR
+T 48000 44400 5 10 0 0 270 0 1
+symversion=0.1
+T 47100 44600 5 10 0 0 270 0 1
+footprint=0603
+T 47100 44600 5 10 0 0 270 0 1
+pn=GRM1885C1H103JA01D
+T 47600 44400 5 10 1 1 270 0 1
+refdes=C17
+T 46900 44400 5 10 1 1 270 0 1
+value=10 nF
+}
+C 48300 44600 1 270 0 capacitor-1.sym
+{
+T 49000 44400 5 10 0 0 270 0 1
+device=CAPACITOR
+T 49200 44400 5 10 0 0 270 0 1
+symversion=0.1
+T 48300 44600 5 10 0 0 270 0 1
+footprint=0603
+T 48300 44600 5 10 0 0 270 0 1
+pn=885012006059
+T 48800 44400 5 10 1 1 270 0 1
+refdes=C18
+T 48100 44400 5 10 1 1 270 0 1
+value=220 pF
+}
+N 47300 43500 47300 43700 4
+N 47300 44600 47300 44800 4
+N 47300 44800 48500 44800 4
+N 48500 44600 48500 46500 4
+C 47200 42100 1 0 0 gnd-1.sym
+N 47300 42400 47300 42600 4
+C 48400 43200 1 0 0 gnd-1.sym
+N 48500 43500 48500 43700 4
+C 48900 52300 1 0 0 gnd-1.sym
+N 49000 55000 49000 54800 4
+C 49200 53900 1 90 0 led-3.sym
+{
+T 48550 54850 5 10 0 0 90 0 1
+device=LED
+T 49200 53900 5 10 0 0 0 0 1
+color=green
+T 49200 53900 5 10 0 0 0 0 1
+pn=150060VS75000
+T 49200 53900 5 10 0 0 0 0 1
+footprint=0603
+T 48650 54350 5 10 1 1 90 0 1
+refdes=D4
+}
+C 48900 53700 1 270 0 resistor-1.sym
+{
+T 49300 53400 5 10 0 0 270 0 1
+device=RESISTOR
+T 48900 53700 5 10 0 0 270 0 1
+footprint=0603
+T 48900 53700 5 10 0 0 0 0 1
+pn=RC0603FR-073K16L
+T 49200 53500 5 10 1 1 270 0 1
+refdes=R11
+T 48700 53500 5 10 1 1 270 0 1
+value=3.16 k
+}
+N 49000 53900 49000 53700 4
+N 49000 52800 49000 52600 4
+C 48800 55000 1 0 0 5V-plus-1.sym
+C 50100 53700 1 270 0 resistor-1.sym
+{
+T 50500 53400 5 10 0 0 270 0 1
+device=RESISTOR
+T 50100 53700 5 10 0 0 270 0 1
+footprint=0603
+T 50100 53700 5 10 0 0 0 0 1
+pn=RMCF0603JG10K0
+T 50400 53500 5 10 1 1 270 0 1
+refdes=R12
+T 49900 53500 5 10 1 1 270 0 1
+value=10 k
+}
+C 50000 55000 1 0 0 vcc-1.sym
+C 50100 52300 1 0 0 gnd-1.sym
+N 50200 52800 50200 52600 4
+N 50200 55000 50200 54800 4
+C 50400 53900 1 90 0 led-3.sym
+{
+T 49750 54850 5 10 0 0 90 0 1
+device=LED
+T 50400 53900 5 10 0 0 0 0 1
+color=green
+T 50400 53900 5 10 0 0 0 0 1
+pn=150060VS75000
+T 50400 53900 5 10 0 0 0 0 1
+footprint=0603
+T 49850 54350 5 10 1 1 90 0 1
+refdes=D5
+}
+N 50200 53900 50200 53700 4
diff --git a/motors/uart_schematic/uart-beacon.sch b/motors/uart_schematic/uart-beacon.sch
new file mode 100644
index 0000000..a744b4a
--- /dev/null
+++ b/motors/uart_schematic/uart-beacon.sch
@@ -0,0 +1,394 @@
+v 20130925 2
+C 41200 67800 1 180 0 input-1.sym
+{
+T 41200 67500 5 10 0 0 180 0 1
+device=INPUT
+T 40600 67400 5 10 1 1 0 0 1
+net=LED0:1
+}
+C 41200 63100 1 180 0 input-1.sym
+{
+T 41200 62800 5 10 0 0 180 0 1
+device=INPUT
+T 40600 62700 5 10 1 1 0 0 1
+net=LED1:1
+}
+C 41200 59000 1 180 0 input-1.sym
+{
+T 41200 58700 5 10 0 0 180 0 1
+device=INPUT
+T 40600 58600 5 10 1 1 0 0 1
+net=LED2:1
+}
+C 41800 67300 1 0 0 resistor-1.sym
+{
+T 42100 67700 5 10 0 0 0 0 1
+device=RESISTOR
+T 41800 67300 5 10 0 0 0 0 1
+footprint=0603
+T 41800 67300 5 10 0 0 90 0 1
+pn=RUT1608FR300CS
+T 41800 67300 5 10 0 0 90 0 1
+power=.125 W
+T 41800 67300 5 10 0 0 0 0 1
+tolerance=1 %
+T 42000 67600 5 10 1 1 0 0 1
+refdes=R401
+T 42000 67100 5 10 1 1 0 0 1
+value=.3
+}
+C 38100 67200 1 0 0 AL8808.sym
+{
+T 36600 67200 5 10 0 1 0 0 1
+footprint=SOT23-5
+T 38100 67200 5 10 0 0 0 0 1
+pn=AL8808WT-7
+T 38500 68300 5 10 1 1 0 0 1
+device=AL8808
+T 39300 68300 5 10 1 1 0 0 1
+refdes=U401
+}
+C 37800 67000 1 0 0 gnd-1.sym
+N 37900 67300 37900 67500 4
+C 37700 68100 1 0 0 vcc-1.sym
+N 37900 67900 37900 68100 4
+N 38100 67900 37900 67900 4
+N 38100 67500 37900 67500 4
+C 42900 67600 1 270 0 vcc-1.sym
+N 40000 67400 41800 67400 4
+N 42700 67400 42900 67400 4
+C 40400 68500 1 90 0 diode-1.sym
+{
+T 39800 68900 5 10 0 0 90 0 1
+device=DIODE
+T 40400 68500 5 10 0 0 0 0 1
+pn=SS13FL
+T 40400 68500 5 10 0 0 0 0 1
+footprint=SOD123F
+T 39900 68800 5 10 1 1 90 0 1
+refdes=D401
+}
+N 40000 68000 43600 68000 4
+N 40200 68500 40200 68000 4
+C 40000 69600 1 0 0 vcc-1.sym
+N 40200 69400 40200 69600 4
+N 40400 67700 40000 67700 4
+C 43600 67900 1 0 0 inductor-1.sym
+{
+T 43800 68400 5 10 0 0 0 0 1
+device=INDUCTOR
+T 43800 68600 5 10 0 0 0 0 1
+symversion=0.1
+T 43600 67900 5 10 0 0 0 0 1
+pn=NRS4018T330MDGJ
+T 43600 67900 5 10 0 0 0 0 1
+footprint=NRS4018
+T 43800 68200 5 10 1 1 0 0 1
+refdes=L401
+T 43700 67700 5 10 1 1 0 0 1
+value=33 uH
+}
+N 44500 68000 46300 68000 4
+C 44800 67600 1 270 0 capacitor-1.sym
+{
+T 45500 67400 5 10 0 0 270 0 1
+device=CAPACITOR
+T 45700 67400 5 10 0 0 270 0 1
+symversion=0.1
+T 44800 67600 5 10 0 0 270 0 1
+footprint=0603
+T 44800 67600 5 10 0 0 0 0 1
+pn=TMK107BJ105KA-T
+T 44800 67600 5 10 0 0 0 0 1
+voltage=25 V
+T 45300 67400 5 10 1 1 270 0 1
+refdes=C401
+T 44600 67400 5 10 1 1 270 0 1
+value=1 uF
+}
+N 45000 66500 45000 66700 4
+N 45000 68000 45000 67600 4
+C 48000 68200 1 180 0 connector2-1.sym
+{
+T 47800 67200 5 10 0 0 180 0 1
+device=CONNECTOR_2
+T 48000 68200 5 10 0 0 0 0 1
+footprint=22-23-2021
+T 48000 67400 5 10 1 1 180 0 1
+refdes=CONN401
+T 48000 68200 5 10 0 0 0 0 1
+pn=22-23-2021
+}
+N 46300 67700 45900 67700 4
+N 45900 66500 45900 67700 4
+N 41500 66500 45900 66500 4
+N 41500 66500 41500 67400 4
+C 36600 68000 1 270 0 capacitor-1.sym
+{
+T 37300 67800 5 10 0 0 270 0 1
+device=CAPACITOR
+T 37500 67800 5 10 0 0 270 0 1
+symversion=0.1
+T 36600 68000 5 10 0 0 270 0 1
+footprint=0805
+T 36600 68000 5 10 0 0 0 0 1
+pn=CL21A475KAQNNNG
+T 36600 68000 5 10 0 0 0 0 1
+voltage=25 V
+T 37100 67800 5 10 1 1 270 0 1
+refdes=C402
+T 36400 67800 5 10 1 1 270 0 1
+value=4.7 uF
+}
+C 36700 66600 1 0 0 gnd-1.sym
+N 36800 66900 36800 67100 4
+C 36600 68200 1 0 0 vcc-1.sym
+N 36800 68200 36800 68000 4
+C 41800 62600 1 0 0 resistor-1.sym
+{
+T 42100 63000 5 10 0 0 0 0 1
+device=RESISTOR
+T 41800 62600 5 10 0 0 0 0 1
+footprint=0603
+T 41800 62600 5 10 0 0 90 0 1
+pn=RUT1608FR300CS
+T 41800 62600 5 10 0 0 90 0 1
+power=.125 W
+T 41800 62600 5 10 0 0 0 0 1
+tolerance=1 %
+T 42000 62900 5 10 1 1 0 0 1
+refdes=R402
+T 42000 62400 5 10 1 1 0 0 1
+value=.3
+}
+C 38100 62500 1 0 0 AL8808.sym
+{
+T 36600 62500 5 10 0 1 0 0 1
+footprint=SOT23-5
+T 38100 62500 5 10 0 0 0 0 1
+pn=AL8808WT-7
+T 38500 63600 5 10 1 1 0 0 1
+device=AL8808
+T 39300 63600 5 10 1 1 0 0 1
+refdes=U402
+}
+C 37800 62300 1 0 0 gnd-1.sym
+N 37900 62600 37900 62800 4
+C 37700 63400 1 0 0 vcc-1.sym
+N 37900 63200 37900 63400 4
+N 38100 63200 37900 63200 4
+N 38100 62800 37900 62800 4
+C 42900 62900 1 270 0 vcc-1.sym
+N 40000 62700 41800 62700 4
+N 42700 62700 42900 62700 4
+C 40400 63800 1 90 0 diode-1.sym
+{
+T 39800 64200 5 10 0 0 90 0 1
+device=DIODE
+T 40400 63800 5 10 0 0 0 0 1
+pn=SS13FL
+T 40400 63800 5 10 0 0 0 0 1
+footprint=SOD123F
+T 39900 64100 5 10 1 1 90 0 1
+refdes=D402
+}
+N 40000 63300 43600 63300 4
+N 40200 63800 40200 63300 4
+C 40000 64900 1 0 0 vcc-1.sym
+N 40200 64700 40200 64900 4
+N 40400 63000 40000 63000 4
+C 43600 63200 1 0 0 inductor-1.sym
+{
+T 43800 63700 5 10 0 0 0 0 1
+device=INDUCTOR
+T 43800 63900 5 10 0 0 0 0 1
+symversion=0.1
+T 43600 63200 5 10 0 0 0 0 1
+pn=NRS4018T330MDGJ
+T 43600 63200 5 10 0 0 0 0 1
+footprint=NRS4018
+T 43800 63500 5 10 1 1 0 0 1
+refdes=L402
+T 43700 63000 5 10 1 1 0 0 1
+value=33 uH
+}
+N 44500 63300 46300 63300 4
+C 44800 62900 1 270 0 capacitor-1.sym
+{
+T 45500 62700 5 10 0 0 270 0 1
+device=CAPACITOR
+T 45700 62700 5 10 0 0 270 0 1
+symversion=0.1
+T 44800 62900 5 10 0 0 270 0 1
+footprint=0603
+T 44800 62900 5 10 0 0 0 0 1
+pn=TMK107BJ105KA-T
+T 44800 62900 5 10 0 0 0 0 1
+voltage=25 V
+T 45300 62700 5 10 1 1 270 0 1
+refdes=C403
+T 44600 62700 5 10 1 1 270 0 1
+value=1 uF
+}
+N 45000 61800 45000 62000 4
+N 45000 63300 45000 62900 4
+C 48000 63500 1 180 0 connector2-1.sym
+{
+T 47800 62500 5 10 0 0 180 0 1
+device=CONNECTOR_2
+T 48000 63500 5 10 0 0 0 0 1
+footprint=22-23-2021
+T 48000 62700 5 10 1 1 180 0 1
+refdes=CONN403
+T 48000 63500 5 10 0 0 0 0 1
+pn=22-23-2021
+}
+N 46300 63000 45900 63000 4
+N 45900 61800 45900 63000 4
+N 41500 61800 45900 61800 4
+N 41500 61800 41500 62700 4
+C 36600 63300 1 270 0 capacitor-1.sym
+{
+T 37300 63100 5 10 0 0 270 0 1
+device=CAPACITOR
+T 37500 63100 5 10 0 0 270 0 1
+symversion=0.1
+T 36600 63300 5 10 0 0 270 0 1
+footprint=0805
+T 36600 63300 5 10 0 0 0 0 1
+pn=CL21A475KAQNNNG
+T 36600 63300 5 10 0 0 0 0 1
+voltage=25 V
+T 37100 63100 5 10 1 1 270 0 1
+refdes=C404
+T 36400 63100 5 10 1 1 270 0 1
+value=4.7 uF
+}
+C 36700 61900 1 0 0 gnd-1.sym
+N 36800 62200 36800 62400 4
+C 36600 63500 1 0 0 vcc-1.sym
+N 36800 63500 36800 63300 4
+C 41800 58500 1 0 0 resistor-1.sym
+{
+T 42100 58900 5 10 0 0 0 0 1
+device=RESISTOR
+T 41800 58500 5 10 0 0 0 0 1
+footprint=0603
+T 41800 58500 5 10 0 0 90 0 1
+pn=RUT1608FR300CS
+T 41800 58500 5 10 0 0 90 0 1
+power=.125 W
+T 41800 58500 5 10 0 0 0 0 1
+tolerance=1 %
+T 42000 58800 5 10 1 1 0 0 1
+refdes=R403
+T 42000 58300 5 10 1 1 0 0 1
+value=.3
+}
+C 38100 58400 1 0 0 AL8808.sym
+{
+T 36600 58400 5 10 0 1 0 0 1
+footprint=SOT23-5
+T 38100 58400 5 10 0 0 0 0 1
+pn=AL8808WT-7
+T 38500 59500 5 10 1 1 0 0 1
+device=AL8808
+T 39300 59500 5 10 1 1 0 0 1
+refdes=U403
+}
+C 37800 58200 1 0 0 gnd-1.sym
+N 37900 58500 37900 58700 4
+C 37700 59300 1 0 0 vcc-1.sym
+N 37900 59100 37900 59300 4
+N 38100 59100 37900 59100 4
+N 38100 58700 37900 58700 4
+C 42900 58800 1 270 0 vcc-1.sym
+N 40000 58600 41800 58600 4
+N 42700 58600 42900 58600 4
+C 40400 59700 1 90 0 diode-1.sym
+{
+T 39800 60100 5 10 0 0 90 0 1
+device=DIODE
+T 40400 59700 5 10 0 0 0 0 1
+pn=SS13FL
+T 40400 59700 5 10 0 0 0 0 1
+footprint=SOD123F
+T 39900 60000 5 10 1 1 90 0 1
+refdes=D403
+}
+N 40000 59200 43600 59200 4
+N 40200 59700 40200 59200 4
+C 40000 60800 1 0 0 vcc-1.sym
+N 40200 60600 40200 60800 4
+N 40400 58900 40000 58900 4
+C 43600 59100 1 0 0 inductor-1.sym
+{
+T 43800 59600 5 10 0 0 0 0 1
+device=INDUCTOR
+T 43800 59800 5 10 0 0 0 0 1
+symversion=0.1
+T 43600 59100 5 10 0 0 0 0 1
+pn=NRS4018T330MDGJ
+T 43600 59100 5 10 0 0 0 0 1
+footprint=NRS4018
+T 43800 59400 5 10 1 1 0 0 1
+refdes=L403
+T 43700 58900 5 10 1 1 0 0 1
+value=33 uH
+}
+N 44500 59200 46300 59200 4
+C 44800 58800 1 270 0 capacitor-1.sym
+{
+T 45500 58600 5 10 0 0 270 0 1
+device=CAPACITOR
+T 45700 58600 5 10 0 0 270 0 1
+symversion=0.1
+T 44800 58800 5 10 0 0 270 0 1
+footprint=0603
+T 44800 58800 5 10 0 0 0 0 1
+pn=TMK107BJ105KA-T
+T 44800 58800 5 10 0 0 0 0 1
+voltage=25 V
+T 45300 58600 5 10 1 1 270 0 1
+refdes=C405
+T 44600 58600 5 10 1 1 270 0 1
+value=1 uF
+}
+N 45000 57700 45000 57900 4
+N 45000 59200 45000 58800 4
+C 48000 59400 1 180 0 connector2-1.sym
+{
+T 47800 58400 5 10 0 0 180 0 1
+device=CONNECTOR_2
+T 48000 59400 5 10 0 0 0 0 1
+footprint=22-23-2021
+T 48000 58600 5 10 1 1 180 0 1
+refdes=CONN402
+T 48000 59400 5 10 0 0 0 0 1
+pn=22-23-2021
+}
+N 46300 58900 45900 58900 4
+N 45900 57700 45900 58900 4
+N 41500 57700 45900 57700 4
+N 41500 57700 41500 58600 4
+C 36600 59200 1 270 0 capacitor-1.sym
+{
+T 37300 59000 5 10 0 0 270 0 1
+device=CAPACITOR
+T 37500 59000 5 10 0 0 270 0 1
+symversion=0.1
+T 36600 59200 5 10 0 0 270 0 1
+footprint=0805
+T 36600 59200 5 10 0 0 0 0 1
+pn=CL21A475KAQNNNG
+T 36600 59200 5 10 0 0 0 0 1
+voltage=25 V
+T 37100 59000 5 10 1 1 270 0 1
+refdes=C406
+T 36400 59000 5 10 1 1 270 0 1
+value=4.7 uF
+}
+C 36700 57800 1 0 0 gnd-1.sym
+N 36800 58100 36800 58300 4
+C 36600 59400 1 0 0 vcc-1.sym
+N 36800 59400 36800 59200 4
diff --git a/motors/uart_schematic/uart-main.sch b/motors/uart_schematic/uart-main.sch
new file mode 100644
index 0000000..c5f41b1
--- /dev/null
+++ b/motors/uart_schematic/uart-main.sch
@@ -0,0 +1,475 @@
+v 20130925 2
+C 58600 62600 1 0 0 teensy3.5.sym
+{
+T 58800 64200 5 10 0 1 0 0 1
+device=TEENSY3.5
+T 59400 64100 5 10 0 1 0 0 1
+footprint=teensy3.5
+T 60100 70100 5 10 1 1 0 0 1
+refdes=U101
+}
+C 60800 70000 1 270 0 5V-plus-1.sym
+C 56500 69900 1 270 0 gnd-1.sym
+N 58700 69800 56800 69800 4
+N 60600 69800 60800 69800 4
+C 61100 65500 1 90 0 gnd-1.sym
+N 60600 65600 60800 65600 4
+C 58900 70600 1 0 0 gnd-1.sym
+N 59000 72200 59000 72000 4
+N 59000 71100 59000 70900 4
+C 58800 72000 1 270 0 capacitor-1.sym
+{
+T 59500 71800 5 10 0 0 270 0 1
+device=CAPACITOR
+T 59700 71800 5 10 0 0 270 0 1
+symversion=0.1
+T 58800 72000 5 10 0 0 270 0 1
+voltage=16 V
+T 58800 72000 5 10 0 0 270 0 1
+footprint=0603
+T 58800 72000 5 10 0 0 270 0 1
+pn=885012206047
+T 59300 71800 5 10 1 1 270 0 1
+refdes=C101
+T 58600 71800 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 58800 72200 1 0 0 5V-plus-1.sym
+C 60800 68500 1 0 0 output-1.sym
+{
+T 60900 68800 5 10 0 0 0 0 1
+device=OUTPUT
+T 61000 68700 5 10 1 1 0 0 1
+net=LED0:1
+}
+N 60800 68600 60600 68600 4
+C 62500 68800 1 0 0 output-1.sym
+{
+T 62600 69100 5 10 0 0 0 0 1
+device=OUTPUT
+T 62700 69000 5 10 1 1 0 0 1
+net=LED1:1
+}
+N 62500 68900 60600 68900 4
+N 56800 68000 58700 68000 4
+C 56800 68100 1 180 0 output-1.sym
+{
+T 56700 67800 5 10 0 0 180 0 1
+device=OUTPUT
+T 56600 67900 5 10 1 1 180 0 1
+net=LED2:1
+}
+C 60800 67900 1 0 0 output-1.sym
+{
+T 60900 68200 5 10 0 0 0 0 1
+device=OUTPUT
+T 61000 68100 5 10 1 1 0 0 1
+net=LED3:1
+}
+N 60800 68000 60600 68000 4
+N 56800 63800 58700 63800 4
+C 56800 63900 1 180 0 output-1.sym
+{
+T 56700 63600 5 10 0 0 180 0 1
+device=OUTPUT
+T 56600 63700 5 10 1 1 180 0 1
+net=LED5:1
+}
+C 58500 63600 1 180 0 output-1.sym
+{
+T 58400 63300 5 10 0 0 180 0 1
+device=OUTPUT
+T 58300 63400 5 10 1 1 180 0 1
+net=LED4:1
+}
+N 58500 63500 58700 63500 4
+N 62500 63500 60600 63500 4
+C 62500 63400 1 0 0 output-1.sym
+{
+T 62600 63700 5 10 0 0 0 0 1
+device=OUTPUT
+T 62700 63600 5 10 1 1 0 0 1
+net=LED6:1
+}
+C 60800 63700 1 0 0 output-1.sym
+{
+T 60900 64000 5 10 0 0 0 0 1
+device=OUTPUT
+T 61000 63900 5 10 1 1 0 0 1
+net=LED7:1
+}
+N 60800 63800 60600 63800 4
+C 60800 64300 1 0 0 output-1.sym
+{
+T 60900 64600 5 10 0 0 0 0 1
+device=OUTPUT
+T 61000 64500 5 10 1 1 0 0 1
+net=LED9:1
+}
+N 60800 64400 60600 64400 4
+N 62500 64100 60600 64100 4
+C 62500 64000 1 0 0 output-1.sym
+{
+T 62600 64300 5 10 0 0 0 0 1
+device=OUTPUT
+T 62700 64200 5 10 1 1 0 0 1
+net=LED8:1
+}
+C 57700 68800 1 0 0 input-1.sym
+{
+T 57700 69100 5 10 0 0 0 0 1
+device=INPUT
+T 58200 68800 5 10 1 1 180 0 1
+net=SPI_CS:1
+}
+N 58700 68900 58500 68900 4
+N 56800 66200 58700 66200 4
+C 56800 66300 1 180 0 output-1.sym
+{
+T 56700 66000 5 10 0 0 180 0 1
+device=OUTPUT
+T 56600 66100 5 10 1 1 180 0 1
+net=SPI_MISO:1
+}
+C 57700 65800 1 0 0 input-1.sym
+{
+T 57700 66100 5 10 0 0 0 0 1
+device=INPUT
+T 58200 65800 5 10 1 1 180 0 1
+net=SPI_MOSI:1
+}
+N 58700 65900 58500 65900 4
+C 60200 70600 1 0 0 gnd-1.sym
+N 60300 72200 60300 72000 4
+N 60300 71100 60300 70900 4
+C 60100 72000 1 270 0 capacitor-1.sym
+{
+T 60800 71800 5 10 0 0 270 0 1
+device=CAPACITOR
+T 61000 71800 5 10 0 0 270 0 1
+symversion=0.1
+T 60100 72000 5 10 0 0 270 0 1
+voltage=16 V
+T 60100 72000 5 10 0 0 270 0 1
+footprint=0603
+T 60100 72000 5 10 0 0 270 0 1
+pn=885012206047
+T 60600 71800 5 10 1 1 270 0 1
+refdes=C102
+T 59900 71800 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 60100 72200 1 0 0 3.3V-plus-1.sym
+C 56800 65400 1 90 0 3.3V-plus-1.sym
+N 56800 65600 58700 65600 4
+N 60800 66200 60600 66200 4
+C 61600 66300 1 180 0 input-1.sym
+{
+T 61600 66000 5 10 0 0 180 0 1
+device=INPUT
+T 61100 66300 5 10 1 1 0 0 1
+net=SPI_CLK:1
+}
+C 56000 67300 1 0 0 input-1.sym
+{
+T 56000 67600 5 10 0 0 0 0 1
+device=INPUT
+T 56500 67300 5 10 1 1 180 0 1
+net=UART2_RX:1
+}
+C 58500 67200 1 180 0 output-1.sym
+{
+T 58400 66900 5 10 0 0 180 0 1
+device=OUTPUT
+T 58300 67000 5 10 1 1 180 0 1
+net=UART2_TX:1
+}
+N 58700 67400 56800 67400 4
+N 58500 67100 58700 67100 4
+N 58500 66500 58700 66500 4
+N 58700 66800 56800 66800 4
+C 58500 66600 1 180 0 output-1.sym
+{
+T 58400 66300 5 10 0 0 180 0 1
+device=OUTPUT
+T 58300 66400 5 10 1 1 180 0 1
+net=UART0_TX:1
+}
+C 56000 66700 1 0 0 input-1.sym
+{
+T 56000 67000 5 10 0 0 0 0 1
+device=INPUT
+T 56500 66700 5 10 1 1 180 0 1
+net=UART0_RX:1
+}
+N 58500 64700 58700 64700 4
+N 58700 64400 56800 64400 4
+C 58500 64800 1 180 0 output-1.sym
+{
+T 58400 64500 5 10 0 0 180 0 1
+device=OUTPUT
+T 58300 64600 5 10 1 1 180 0 1
+net=UART1_TX:1
+}
+C 56000 64300 1 0 0 input-1.sym
+{
+T 56000 64600 5 10 0 0 0 0 1
+device=INPUT
+T 56500 64300 5 10 1 1 180 0 1
+net=UART1_RX:1
+}
+N 58700 63200 56800 63200 4
+N 58500 62900 58700 62900 4
+C 56000 63100 1 0 0 input-1.sym
+{
+T 56000 63400 5 10 0 0 0 0 1
+device=INPUT
+T 56500 63100 5 10 1 1 180 0 1
+net=UART3_RX:1
+}
+C 58500 63000 1 180 0 output-1.sym
+{
+T 58400 62700 5 10 0 0 180 0 1
+device=OUTPUT
+T 58300 62800 5 10 1 1 180 0 1
+net=UART3_TX:1
+}
+N 60800 63200 60600 63200 4
+N 60600 62900 62500 62900 4
+C 61600 63300 1 180 0 input-1.sym
+{
+T 61600 63000 5 10 0 0 180 0 1
+device=INPUT
+T 61100 63300 5 10 1 1 0 0 1
+net=UART4_RX:1
+}
+C 62500 62800 1 0 0 output-1.sym
+{
+T 62600 63100 5 10 0 0 0 0 1
+device=OUTPUT
+T 62700 63000 5 10 1 1 0 0 1
+net=UART4_TX:1
+}
+C 63300 68400 1 180 0 input-1.sym
+{
+T 63300 68100 5 10 0 0 180 0 1
+device=INPUT
+T 62800 68400 5 10 1 1 0 0 1
+net=5V_PGOOD:1
+}
+N 60600 68300 62500 68300 4
+N 60600 66500 62500 66500 4
+C 60800 66700 1 0 0 output-1.sym
+{
+T 60900 67000 5 10 0 0 0 0 1
+device=OUTPUT
+T 61000 66900 5 10 1 1 0 0 1
+net=CAM_EN:1
+}
+N 60800 66800 60600 66800 4
+C 62500 66400 1 0 0 output-1.sym
+{
+T 62600 66700 5 10 0 0 0 0 1
+device=OUTPUT
+T 62700 66600 5 10 1 1 0 0 1
+net=ODROID_EN:1
+}
+C 73300 71100 1 180 0 input-1.sym
+{
+T 73300 70800 5 10 0 0 180 0 1
+device=INPUT
+T 72800 71100 5 10 1 1 0 0 1
+net=UART0_RX_RAW:1
+}
+C 70500 70600 1 0 0 output-1.sym
+{
+T 70600 70900 5 10 0 0 0 0 1
+device=OUTPUT
+T 70700 70800 5 10 1 1 0 0 1
+net=UART0_TX_RAW:1
+}
+C 68400 70900 1 0 0 input-1.sym
+{
+T 68400 71200 5 10 0 0 0 0 1
+device=INPUT
+T 68900 70900 5 10 1 1 180 0 1
+net=UART0_TX:1
+}
+C 67600 70800 1 180 0 output-1.sym
+{
+T 67500 70500 5 10 0 0 180 0 1
+device=OUTPUT
+T 67400 70600 5 10 1 1 180 0 1
+net=UART0_RX:1
+}
+C 69400 70000 1 0 0 resistor-x4.sym
+{
+T 69700 71300 5 10 0 0 0 0 1
+device=RESISTOR_x4
+T 69400 70000 5 10 0 0 0 0 1
+footprint=0603_4
+T 69400 70000 5 10 0 0 0 0 1
+pn=RAVF164DJT100R
+T 69600 71200 5 10 1 1 0 0 1
+refdes=R101
+T 69700 69800 5 10 1 1 0 0 1
+value=100
+}
+C 69400 68200 1 0 0 resistor-x4.sym
+{
+T 69700 69500 5 10 0 0 0 0 1
+device=RESISTOR_x4
+T 69400 68200 5 10 0 0 0 0 1
+footprint=0603_4
+T 69400 68200 5 10 0 0 0 0 1
+pn=RAVF164DJT100R
+T 69600 69400 5 10 1 1 0 0 1
+refdes=R102
+T 69700 68000 5 10 1 1 0 0 1
+value=100
+}
+C 69400 66400 1 0 0 resistor-x4.sym
+{
+T 69700 67700 5 10 0 0 0 0 1
+device=RESISTOR_x4
+T 69400 66400 5 10 0 0 0 0 1
+footprint=0603_4
+T 69400 66400 5 10 0 0 0 0 1
+pn=RAVF164DJT100R
+T 69600 67600 5 10 1 1 0 0 1
+refdes=R103
+T 69700 66200 5 10 1 1 0 0 1
+value=100
+}
+N 69200 71000 69400 71000 4
+N 67600 70700 69400 70700 4
+N 70500 70700 70300 70700 4
+N 72500 71000 70300 71000 4
+C 68400 70300 1 0 0 input-1.sym
+{
+T 68400 70600 5 10 0 0 0 0 1
+device=INPUT
+T 68900 70300 5 10 1 1 180 0 1
+net=UART1_TX:1
+}
+N 69200 70400 69400 70400 4
+N 72500 70400 70300 70400 4
+C 73300 70500 1 180 0 input-1.sym
+{
+T 73300 70200 5 10 0 0 180 0 1
+device=INPUT
+T 72800 70500 5 10 1 1 0 0 1
+net=UART1_RX_RAW:1
+}
+C 70500 70000 1 0 0 output-1.sym
+{
+T 70600 70300 5 10 0 0 0 0 1
+device=OUTPUT
+T 70700 70200 5 10 1 1 0 0 1
+net=UART1_TX_RAW:1
+}
+N 70500 70100 70300 70100 4
+N 67600 70100 69400 70100 4
+C 67600 70200 1 180 0 output-1.sym
+{
+T 67500 69900 5 10 0 0 180 0 1
+device=OUTPUT
+T 67400 70000 5 10 1 1 180 0 1
+net=UART1_RX:1
+}
+C 68400 69100 1 0 0 input-1.sym
+{
+T 68400 69400 5 10 0 0 0 0 1
+device=INPUT
+T 68900 69100 5 10 1 1 180 0 1
+net=UART2_TX:1
+}
+N 69200 69200 69400 69200 4
+N 72500 69200 70300 69200 4
+C 73300 69300 1 180 0 input-1.sym
+{
+T 73300 69000 5 10 0 0 180 0 1
+device=INPUT
+T 72800 69300 5 10 1 1 0 0 1
+net=UART2_RX_RAW:1
+}
+C 70500 68800 1 0 0 output-1.sym
+{
+T 70600 69100 5 10 0 0 0 0 1
+device=OUTPUT
+T 70700 69000 5 10 1 1 0 0 1
+net=UART2_TX_RAW:1
+}
+N 70500 68900 70300 68900 4
+N 67600 68900 69400 68900 4
+C 67600 69000 1 180 0 output-1.sym
+{
+T 67500 68700 5 10 0 0 180 0 1
+device=OUTPUT
+T 67400 68800 5 10 1 1 180 0 1
+net=UART2_RX:1
+}
+C 68400 68500 1 0 0 input-1.sym
+{
+T 68400 68800 5 10 0 0 0 0 1
+device=INPUT
+T 68900 68500 5 10 1 1 180 0 1
+net=UART3_TX:1
+}
+N 69200 68600 69400 68600 4
+N 72500 68600 70300 68600 4
+C 73300 68700 1 180 0 input-1.sym
+{
+T 73300 68400 5 10 0 0 180 0 1
+device=INPUT
+T 72800 68700 5 10 1 1 0 0 1
+net=UART3_RX_RAW:1
+}
+C 70500 68200 1 0 0 output-1.sym
+{
+T 70600 68500 5 10 0 0 0 0 1
+device=OUTPUT
+T 70700 68400 5 10 1 1 0 0 1
+net=UART3_TX_RAW:1
+}
+N 70500 68300 70300 68300 4
+N 67600 68300 69400 68300 4
+C 67600 68400 1 180 0 output-1.sym
+{
+T 67500 68100 5 10 0 0 180 0 1
+device=OUTPUT
+T 67400 68200 5 10 1 1 180 0 1
+net=UART3_RX:1
+}
+C 68400 67300 1 0 0 input-1.sym
+{
+T 68400 67600 5 10 0 0 0 0 1
+device=INPUT
+T 68900 67300 5 10 1 1 180 0 1
+net=UART4_TX:1
+}
+N 69200 67400 69400 67400 4
+N 72500 67400 70300 67400 4
+C 73300 67500 1 180 0 input-1.sym
+{
+T 73300 67200 5 10 0 0 180 0 1
+device=INPUT
+T 72800 67500 5 10 1 1 0 0 1
+net=UART4_RX_RAW:1
+}
+C 70500 67000 1 0 0 output-1.sym
+{
+T 70600 67300 5 10 0 0 0 0 1
+device=OUTPUT
+T 70700 67200 5 10 1 1 0 0 1
+net=UART4_TX_RAW:1
+}
+N 70500 67100 70300 67100 4
+N 67600 67100 69400 67100 4
+C 67600 67200 1 180 0 output-1.sym
+{
+T 67500 66900 5 10 0 0 180 0 1
+device=OUTPUT
+T 67400 67000 5 10 1 1 180 0 1
+net=UART4_RX:1
+}
diff --git a/motors/uart_schematic/uart-outputs.sch b/motors/uart_schematic/uart-outputs.sch
new file mode 100644
index 0000000..6d24b51
--- /dev/null
+++ b/motors/uart_schematic/uart-outputs.sch
@@ -0,0 +1,996 @@
+v 20130925 2
+C 57000 62700 1 0 0 connector2-1.sym
+{
+T 57200 63700 5 10 0 0 0 0 1
+device=CONNECTOR_2
+T 57000 63500 5 10 1 1 0 0 1
+refdes=CONN301
+T 57000 62700 5 10 0 0 0 0 1
+pn=22-23-2021
+T 57000 62700 5 10 0 0 0 0 1
+footprint=22-23-2021
+}
+C 47000 63400 1 0 0 connector5-1.sym
+{
+T 48800 64900 5 10 0 0 0 0 1
+device=CONNECTOR_5
+T 47100 65100 5 10 1 1 0 0 1
+refdes=CONN302
+T 47000 63400 5 10 0 0 0 0 1
+pn=22-23-2051
+T 47000 63400 5 10 0 0 0 0 1
+footprint=22-23-2051
+}
+C 57000 64300 1 0 0 connector2-1.sym
+{
+T 57200 65300 5 10 0 0 0 0 1
+device=CONNECTOR_2
+T 57000 65100 5 10 1 1 0 0 1
+refdes=CONN316
+T 57000 64300 5 10 0 0 0 0 1
+pn=1825640000
+T 57000 64300 5 10 0 0 0 0 1
+footprint=1825640000
+}
+C 54000 64300 1 0 0 connector2-1.sym
+{
+T 54200 65300 5 10 0 0 0 0 1
+device=CONNECTOR_2
+T 54000 65100 5 10 1 1 0 0 1
+refdes=CONN315
+T 54000 64300 5 10 0 0 0 0 1
+pn=1825640000
+T 54000 64300 5 10 0 0 0 0 1
+footprint=1825640000
+}
+C 55700 65000 1 0 0 vcc-1.sym
+C 55800 64000 1 0 0 gnd-1.sym
+C 58800 64000 1 0 0 gnd-1.sym
+N 55700 64500 55900 64500 4
+N 55900 64500 55900 64300 4
+N 55700 64800 55900 64800 4
+N 55900 64800 55900 65000 4
+N 58700 64500 58900 64500 4
+N 58900 64500 58900 64300 4
+C 57000 60900 1 0 0 connector2-1.sym
+{
+T 57200 61900 5 10 0 0 0 0 1
+device=CONNECTOR_2
+T 57000 60900 5 10 0 0 0 0 1
+pn=22-23-2021
+T 57000 60900 5 10 0 0 0 0 1
+footprint=22-23-2021
+T 57000 61700 5 10 1 1 0 0 1
+refdes=CONN303
+}
+C 50400 64100 1 270 0 5V-plus-1.sym
+N 50400 63900 48700 63900 4
+C 48900 65000 1 270 0 3.3V-plus-1.sym
+N 48900 64800 48700 64800 4
+C 51200 64600 1 180 0 input-1.sym
+{
+T 51200 64300 5 10 0 0 180 0 1
+device=INPUT
+T 50700 64600 5 10 1 1 0 0 1
+net=UART0_TX_RAW:1
+}
+N 50400 64500 48700 64500 4
+C 49000 64100 1 0 0 output-1.sym
+{
+T 49100 64400 5 10 0 0 0 0 1
+device=OUTPUT
+T 49200 64300 5 10 1 1 0 0 1
+net=UART0_RX_RAW:1
+}
+N 49000 64200 48700 64200 4
+C 47000 61100 1 0 0 connector5-1.sym
+{
+T 48800 62600 5 10 0 0 0 0 1
+device=CONNECTOR_5
+T 47000 61100 5 10 0 0 0 0 1
+pn=22-23-2051
+T 47000 61100 5 10 0 0 0 0 1
+footprint=22-23-2051
+T 47100 62800 5 10 1 1 0 0 1
+refdes=CONN304
+}
+C 50400 61800 1 270 0 5V-plus-1.sym
+N 50400 61600 48700 61600 4
+C 48900 62700 1 270 0 3.3V-plus-1.sym
+N 48900 62500 48700 62500 4
+C 51200 62300 1 180 0 input-1.sym
+{
+T 51200 62000 5 10 0 0 180 0 1
+device=INPUT
+T 50700 62300 5 10 1 1 0 0 1
+net=UART1_TX_RAW:1
+}
+N 50400 62200 48700 62200 4
+C 49000 61800 1 0 0 output-1.sym
+{
+T 49100 62100 5 10 0 0 0 0 1
+device=OUTPUT
+T 49200 62000 5 10 1 1 0 0 1
+net=UART1_RX_RAW:1
+}
+N 49000 61900 48700 61900 4
+C 47000 58800 1 0 0 connector5-1.sym
+{
+T 48800 60300 5 10 0 0 0 0 1
+device=CONNECTOR_5
+T 47000 58800 5 10 0 0 0 0 1
+pn=22-23-2051
+T 47000 58800 5 10 0 0 0 0 1
+footprint=22-23-2051
+T 47100 60500 5 10 1 1 0 0 1
+refdes=CONN305
+}
+C 50400 59500 1 270 0 5V-plus-1.sym
+N 50400 59300 48700 59300 4
+C 48900 60400 1 270 0 3.3V-plus-1.sym
+N 48900 60200 48700 60200 4
+C 51200 60000 1 180 0 input-1.sym
+{
+T 51200 59700 5 10 0 0 180 0 1
+device=INPUT
+T 50700 60000 5 10 1 1 0 0 1
+net=UART2_TX_RAW:1
+}
+N 50400 59900 48700 59900 4
+C 49000 59500 1 0 0 output-1.sym
+{
+T 49100 59800 5 10 0 0 0 0 1
+device=OUTPUT
+T 49200 59700 5 10 1 1 0 0 1
+net=UART2_RX_RAW:1
+}
+N 49000 59600 48700 59600 4
+C 47000 56500 1 0 0 connector5-1.sym
+{
+T 48800 58000 5 10 0 0 0 0 1
+device=CONNECTOR_5
+T 47000 56500 5 10 0 0 0 0 1
+pn=22-23-2051
+T 47000 56500 5 10 0 0 0 0 1
+footprint=22-23-2051
+T 47100 58200 5 10 1 1 0 0 1
+refdes=CONN306
+}
+C 50400 57200 1 270 0 5V-plus-1.sym
+N 50400 57000 48700 57000 4
+C 48900 58100 1 270 0 3.3V-plus-1.sym
+N 48900 57900 48700 57900 4
+C 51200 57700 1 180 0 input-1.sym
+{
+T 51200 57400 5 10 0 0 180 0 1
+device=INPUT
+T 50700 57700 5 10 1 1 0 0 1
+net=UART3_TX_RAW:1
+}
+N 50400 57600 48700 57600 4
+C 49000 57200 1 0 0 output-1.sym
+{
+T 49100 57500 5 10 0 0 0 0 1
+device=OUTPUT
+T 49200 57400 5 10 1 1 0 0 1
+net=UART3_RX_RAW:1
+}
+N 49000 57300 48700 57300 4
+C 47000 54200 1 0 0 connector5-1.sym
+{
+T 48800 55700 5 10 0 0 0 0 1
+device=CONNECTOR_5
+T 47000 54200 5 10 0 0 0 0 1
+pn=22-23-2051
+T 47000 54200 5 10 0 0 0 0 1
+footprint=22-23-2051
+T 47100 55900 5 10 1 1 0 0 1
+refdes=CONN307
+}
+C 50400 54900 1 270 0 5V-plus-1.sym
+N 50400 54700 48700 54700 4
+C 48900 55800 1 270 0 3.3V-plus-1.sym
+N 48900 55600 48700 55600 4
+C 51200 55400 1 180 0 input-1.sym
+{
+T 51200 55100 5 10 0 0 180 0 1
+device=INPUT
+T 50700 55400 5 10 1 1 0 0 1
+net=UART4_TX_RAW:1
+}
+N 50400 55300 48700 55300 4
+C 49000 54900 1 0 0 output-1.sym
+{
+T 49100 55200 5 10 0 0 0 0 1
+device=OUTPUT
+T 49200 55100 5 10 1 1 0 0 1
+net=UART4_RX_RAW:1
+}
+N 49000 55000 48700 55000 4
+C 42300 64000 1 0 0 usb-a.sym
+{
+T 42700 65000 5 10 1 1 0 0 1
+device=USB
+T 43300 65000 5 10 1 1 0 0 1
+refdes=CONN308
+T 42300 64000 5 10 0 0 0 0 1
+footprint=UE27AEX4X0X
+T 42300 64000 5 10 0 0 0 0 1
+pn=UE27AE54100
+}
+C 41900 64300 1 270 0 gnd-1.sym
+C 41900 64600 1 270 0 gnd-1.sym
+N 42200 64500 42400 64500 4
+N 42200 64200 42400 64200 4
+C 42300 61700 1 0 0 usb-a.sym
+{
+T 42700 62700 5 10 1 1 0 0 1
+device=USB
+T 43300 62700 5 10 1 1 0 0 1
+refdes=CONN309
+T 42300 61700 5 10 0 0 0 0 1
+footprint=UE27AEX4X0X
+T 42300 61700 5 10 0 0 0 0 1
+pn=UE27AE54100
+}
+C 41900 62000 1 270 0 gnd-1.sym
+C 41900 62300 1 270 0 gnd-1.sym
+N 42200 62200 42400 62200 4
+N 42200 61900 42400 61900 4
+C 42300 59400 1 0 0 usb-a.sym
+{
+T 42700 60400 5 10 1 1 0 0 1
+device=USB
+T 43300 60400 5 10 1 1 0 0 1
+refdes=CONN310
+T 42300 59400 5 10 0 0 0 0 1
+footprint=UE27AEX4X0X
+T 42300 59400 5 10 0 0 0 0 1
+pn=UE27AE54100
+}
+C 41900 59700 1 270 0 gnd-1.sym
+C 41900 60000 1 270 0 gnd-1.sym
+N 42200 59900 42400 59900 4
+N 42200 59600 42400 59600 4
+C 42300 57100 1 0 0 usb-a.sym
+{
+T 42700 58100 5 10 1 1 0 0 1
+device=USB
+T 43300 58100 5 10 1 1 0 0 1
+refdes=CONN311
+T 42300 57100 5 10 0 0 0 0 1
+footprint=UE27AEX4X0X
+T 42300 57100 5 10 0 0 0 0 1
+pn=UE27AE54100
+}
+C 41900 57400 1 270 0 gnd-1.sym
+C 41900 57700 1 270 0 gnd-1.sym
+N 42200 57600 42400 57600 4
+N 42200 57300 42400 57300 4
+C 42300 54800 1 0 0 usb-a.sym
+{
+T 42700 55800 5 10 1 1 0 0 1
+device=USB
+T 43300 55800 5 10 1 1 0 0 1
+refdes=CONN312
+T 42300 54800 5 10 0 0 0 0 1
+footprint=UE27AEX4X0X
+T 42300 54800 5 10 0 0 0 0 1
+pn=UE27AE54100
+}
+C 41900 55100 1 270 0 gnd-1.sym
+C 41900 55400 1 270 0 gnd-1.sym
+N 42200 55300 42400 55300 4
+N 42200 55000 42400 55000 4
+N 42400 55600 41500 55600 4
+N 41500 55600 41500 65000 4
+N 42400 64800 41500 64800 4
+N 42400 62500 41500 62500 4
+N 42400 60200 41500 60200 4
+N 42400 57900 41500 57900 4
+N 48700 63600 52400 63600 4
+N 52400 63600 52400 67000 4
+N 48700 61300 52600 61300 4
+N 52600 61300 52600 67400 4
+N 48700 59000 52800 59000 4
+N 52800 59000 52800 68200 4
+N 48700 56700 53000 56700 4
+N 53000 56700 53000 67800 4
+N 48700 54400 53200 54400 4
+N 53200 54400 53200 68600 4
+N 58700 62900 59200 62900 4
+N 59200 62900 59200 69400 4
+N 58700 61100 59400 61100 4
+N 59400 61100 59400 69000 4
+C 60400 62300 1 0 0 usb-a.sym
+{
+T 60800 63300 5 10 1 1 0 0 1
+device=USB
+T 61400 63300 5 10 1 1 0 0 1
+refdes=CONN313
+T 60400 62300 5 10 0 0 0 0 1
+footprint=UE27AEX4X0X
+T 60400 62300 5 10 0 0 0 0 1
+pn=UE27AE54100
+}
+C 60000 62600 1 270 0 gnd-1.sym
+C 60000 62900 1 270 0 gnd-1.sym
+N 60300 62800 60500 62800 4
+N 60300 62500 60500 62500 4
+C 60400 60600 1 0 0 usb-a.sym
+{
+T 60800 61600 5 10 1 1 0 0 1
+device=USB
+T 61400 61600 5 10 1 1 0 0 1
+refdes=CONN314
+T 60400 60600 5 10 0 0 0 0 1
+footprint=UE27AEX4X0X
+T 60400 60600 5 10 0 0 0 0 1
+pn=UE27AE54100
+}
+C 60000 60900 1 270 0 gnd-1.sym
+C 60000 61200 1 270 0 gnd-1.sym
+N 60300 61100 60500 61100 4
+N 60300 60800 60500 60800 4
+C 58700 61600 1 0 0 5V-plus-1.sym
+N 58900 61400 58900 61600 4
+N 58700 61400 58900 61400 4
+C 58700 63400 1 0 0 5V-plus-1.sym
+N 58900 63200 58900 63400 4
+N 58700 63200 58900 63200 4
+N 60500 61400 59800 61400 4
+N 59800 61400 59800 64800 4
+N 60500 63100 59800 63100 4
+N 58700 64800 60000 64800 4
+C 39000 67700 1 0 0 AP22966.sym
+{
+T 39300 70500 5 10 0 1 0 0 1
+footprint=V-DFN3020-14
+T 39700 69600 5 10 1 1 0 0 1
+device=AP22966
+T 40700 69600 5 10 1 1 0 0 1
+refdes=U301
+T 39000 67700 5 10 0 0 0 0 1
+pn=AP22966DC8-7
+}
+C 40400 67200 1 0 0 gnd-1.sym
+N 40500 67500 40500 67700 4
+C 42000 69300 1 90 0 gnd-1.sym
+N 41700 69400 41500 69400 4
+C 44600 69200 1 180 0 input-1.sym
+{
+T 44600 68900 5 10 0 0 180 0 1
+device=INPUT
+T 44100 69200 5 10 1 1 0 0 1
+net=CAM_EN:1
+}
+C 42500 68900 1 180 0 input-1.sym
+{
+T 42500 68600 5 10 0 0 180 0 1
+device=INPUT
+T 42000 68900 5 10 1 1 0 0 1
+net=ODROID_EN:1
+}
+N 41700 68800 41500 68800 4
+N 43800 69100 41500 69100 4
+C 38900 69200 1 90 0 5V-plus-1.sym
+C 38200 68900 1 90 0 5V-plus-1.sym
+C 38900 68600 1 90 0 5V-plus-1.sym
+N 38900 69400 39300 69400 4
+N 38200 69100 39300 69100 4
+N 38900 68800 39300 68800 4
+N 37500 68500 39300 68500 4
+N 38900 68200 39300 68200 4
+C 41200 70200 1 0 0 gnd-1.sym
+N 41300 71800 41300 71600 4
+N 41300 70700 41300 70500 4
+C 41100 71800 1 0 0 5V-plus-1.sym
+C 40000 70200 1 0 0 gnd-1.sym
+N 40100 71800 40100 71600 4
+N 40100 70700 40100 70500 4
+C 39900 71600 1 270 0 capacitor-1.sym
+{
+T 40600 71400 5 10 0 0 270 0 1
+device=CAPACITOR
+T 40800 71400 5 10 0 0 270 0 1
+symversion=0.1
+T 39900 71600 5 10 0 0 270 0 1
+voltage=16 V
+T 39900 71600 5 10 0 0 270 0 1
+footprint=0603
+T 39900 71600 5 10 0 0 270 0 1
+pn=885012206047
+T 40400 71400 5 10 1 1 270 0 1
+refdes=C302
+T 39700 71400 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 41300 65000 1 0 0 generic-power.sym
+{
+T 41500 65250 5 10 1 1 0 3 1
+net=CAM_5V:1
+}
+C 38700 67500 1 90 0 generic-power.sym
+{
+T 38450 67700 5 10 1 1 90 3 1
+net=ODROID_5V:1
+}
+C 60000 65000 1 270 0 generic-power.sym
+{
+T 60250 64800 5 10 1 1 270 3 1
+net=ODROID_5V:1
+}
+C 37500 68300 1 90 0 generic-power.sym
+{
+T 37250 68500 5 10 1 1 90 3 1
+net=CAM_5V:1
+}
+N 38700 67700 38900 67700 4
+N 38900 67700 38900 68200 4
+C 38800 70200 1 0 0 gnd-1.sym
+N 38900 71800 38900 71600 4
+N 38900 70700 38900 70500 4
+C 38700 71600 1 270 0 capacitor-1.sym
+{
+T 39400 71400 5 10 0 0 270 0 1
+device=CAPACITOR
+T 39600 71400 5 10 0 0 270 0 1
+symversion=0.1
+T 38700 71600 5 10 0 0 270 0 1
+voltage=16 V
+T 38700 71600 5 10 0 0 270 0 1
+footprint=0603
+T 38700 71600 5 10 0 0 270 0 1
+pn=885012206047
+T 39200 71400 5 10 1 1 270 0 1
+refdes=C303
+T 38500 71400 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 38700 71800 1 0 0 generic-power.sym
+{
+T 38900 72050 5 10 1 1 0 3 1
+net=CAM_5V:1
+}
+C 39900 71800 1 0 0 generic-power.sym
+{
+T 40100 72050 5 10 1 1 0 3 1
+net=ODROID_5V:1
+}
+C 41100 71600 1 270 0 capacitor-1.sym
+{
+T 41800 71400 5 10 0 0 270 0 1
+device=CAPACITOR
+T 42000 71400 5 10 0 0 270 0 1
+symversion=0.1
+T 41100 71600 5 10 0 0 270 0 1
+footprint=0603
+T 41100 71600 5 10 0 0 0 0 1
+pn=TMK107BJ105KA-T
+T 41100 71600 5 10 0 0 0 0 1
+voltage=25 V
+T 41600 71400 5 10 1 1 270 0 1
+refdes=C304
+T 40900 71400 5 10 1 1 270 0 1
+value=1 uF
+}
+C 42700 68000 1 270 0 capacitor-1.sym
+{
+T 43400 67800 5 10 0 0 270 0 1
+device=CAPACITOR
+T 43600 67800 5 10 0 0 270 0 1
+symversion=0.1
+T 42700 68000 5 10 0 0 270 0 1
+footprint=0603
+T 42700 68000 5 10 0 0 0 0 1
+pn=885012006063
+T 42700 68000 5 10 0 0 0 0 1
+voltage=50 V
+T 43200 67800 5 10 1 1 270 0 1
+refdes=C301
+T 42500 67800 5 10 1 1 270 0 1
+value=1000 pF
+}
+C 41500 68000 1 270 0 capacitor-1.sym
+{
+T 42200 67800 5 10 0 0 270 0 1
+device=CAPACITOR
+T 42400 67800 5 10 0 0 270 0 1
+symversion=0.1
+T 41500 68000 5 10 0 0 270 0 1
+footprint=0603
+T 41500 68000 5 10 0 0 0 0 1
+pn=885012006063
+T 41500 68000 5 10 0 0 0 0 1
+voltage=50 V
+T 42000 67800 5 10 1 1 270 0 1
+refdes=C305
+T 41300 67800 5 10 1 1 270 0 1
+value=1000 pF
+}
+C 41600 66600 1 0 0 gnd-1.sym
+N 41700 66900 41700 67100 4
+C 42800 66600 1 0 0 gnd-1.sym
+N 42900 66900 42900 67100 4
+N 41500 68200 41700 68200 4
+N 41700 68200 41700 68000 4
+N 41500 68500 42900 68500 4
+N 42900 68500 42900 68000 4
+C 40100 63400 1 0 0 gnd-1.sym
+N 40200 65000 40200 64800 4
+N 40200 63900 40200 63700 4
+C 40000 64800 1 270 0 capacitor-1.sym
+{
+T 40700 64600 5 10 0 0 270 0 1
+device=CAPACITOR
+T 40900 64600 5 10 0 0 270 0 1
+symversion=0.1
+T 40000 64800 5 10 0 0 270 0 1
+voltage=16 V
+T 40000 64800 5 10 0 0 270 0 1
+footprint=0603
+T 40000 64800 5 10 0 0 270 0 1
+pn=885012206047
+T 40500 64600 5 10 1 1 270 0 1
+refdes=C306
+T 39800 64600 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 40000 65000 1 0 0 generic-power.sym
+{
+T 40200 65250 5 10 1 1 0 3 1
+net=CAM_5V:1
+}
+C 40100 60900 1 0 0 gnd-1.sym
+N 40200 62500 40200 62300 4
+N 40200 61400 40200 61200 4
+C 40000 62300 1 270 0 capacitor-1.sym
+{
+T 40700 62100 5 10 0 0 270 0 1
+device=CAPACITOR
+T 40900 62100 5 10 0 0 270 0 1
+symversion=0.1
+T 40000 62300 5 10 0 0 270 0 1
+voltage=16 V
+T 40000 62300 5 10 0 0 270 0 1
+footprint=0603
+T 40000 62300 5 10 0 0 270 0 1
+pn=885012206047
+T 40500 62100 5 10 1 1 270 0 1
+refdes=C307
+T 39800 62100 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 40000 62500 1 0 0 generic-power.sym
+{
+T 40200 62750 5 10 1 1 0 3 1
+net=CAM_5V:1
+}
+C 40100 58600 1 0 0 gnd-1.sym
+N 40200 60200 40200 60000 4
+N 40200 59100 40200 58900 4
+C 40000 60000 1 270 0 capacitor-1.sym
+{
+T 40700 59800 5 10 0 0 270 0 1
+device=CAPACITOR
+T 40900 59800 5 10 0 0 270 0 1
+symversion=0.1
+T 40000 60000 5 10 0 0 270 0 1
+voltage=16 V
+T 40000 60000 5 10 0 0 270 0 1
+footprint=0603
+T 40000 60000 5 10 0 0 270 0 1
+pn=885012206047
+T 40500 59800 5 10 1 1 270 0 1
+refdes=C308
+T 39800 59800 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 40000 60200 1 0 0 generic-power.sym
+{
+T 40200 60450 5 10 1 1 0 3 1
+net=CAM_5V:1
+}
+C 40100 56300 1 0 0 gnd-1.sym
+N 40200 57900 40200 57700 4
+N 40200 56800 40200 56600 4
+C 40000 57700 1 270 0 capacitor-1.sym
+{
+T 40700 57500 5 10 0 0 270 0 1
+device=CAPACITOR
+T 40900 57500 5 10 0 0 270 0 1
+symversion=0.1
+T 40000 57700 5 10 0 0 270 0 1
+voltage=16 V
+T 40000 57700 5 10 0 0 270 0 1
+footprint=0603
+T 40000 57700 5 10 0 0 270 0 1
+pn=885012206047
+T 40500 57500 5 10 1 1 270 0 1
+refdes=C309
+T 39800 57500 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 40000 57900 1 0 0 generic-power.sym
+{
+T 40200 58150 5 10 1 1 0 3 1
+net=CAM_5V:1
+}
+C 40100 54000 1 0 0 gnd-1.sym
+N 40200 55600 40200 55400 4
+N 40200 54500 40200 54300 4
+C 40000 55400 1 270 0 capacitor-1.sym
+{
+T 40700 55200 5 10 0 0 270 0 1
+device=CAPACITOR
+T 40900 55200 5 10 0 0 270 0 1
+symversion=0.1
+T 40000 55400 5 10 0 0 270 0 1
+voltage=16 V
+T 40000 55400 5 10 0 0 270 0 1
+footprint=0603
+T 40000 55400 5 10 0 0 270 0 1
+pn=885012206047
+T 40500 55200 5 10 1 1 270 0 1
+refdes=C310
+T 39800 55200 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 40000 55600 1 0 0 generic-power.sym
+{
+T 40200 55850 5 10 1 1 0 3 1
+net=CAM_5V:1
+}
+C 63500 60900 1 0 0 gnd-1.sym
+N 63600 62500 63600 62300 4
+N 63600 61400 63600 61200 4
+C 63400 62300 1 270 0 capacitor-1.sym
+{
+T 64100 62100 5 10 0 0 270 0 1
+device=CAPACITOR
+T 64300 62100 5 10 0 0 270 0 1
+symversion=0.1
+T 63400 62300 5 10 0 0 270 0 1
+voltage=16 V
+T 63400 62300 5 10 0 0 270 0 1
+footprint=0603
+T 63400 62300 5 10 0 0 270 0 1
+pn=885012206047
+T 63900 62100 5 10 1 1 270 0 1
+refdes=C311
+T 63200 62100 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 63400 62500 1 0 0 generic-power.sym
+{
+T 63600 62750 5 10 1 1 0 3 1
+net=ODROID_5V:1
+}
+C 65100 60900 1 0 0 gnd-1.sym
+N 65200 62500 65200 62300 4
+N 65200 61400 65200 61200 4
+C 65000 62300 1 270 0 capacitor-1.sym
+{
+T 65700 62100 5 10 0 0 270 0 1
+device=CAPACITOR
+T 65900 62100 5 10 0 0 270 0 1
+symversion=0.1
+T 65000 62300 5 10 0 0 270 0 1
+voltage=16 V
+T 65000 62300 5 10 0 0 270 0 1
+footprint=0603
+T 65000 62300 5 10 0 0 270 0 1
+pn=885012206047
+T 65500 62100 5 10 1 1 270 0 1
+refdes=C312
+T 64800 62100 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 65000 62500 1 0 0 generic-power.sym
+{
+T 65200 62750 5 10 1 1 0 3 1
+net=ODROID_5V:1
+}
+C 61500 63700 1 0 0 gnd-1.sym
+N 61600 65300 61600 65100 4
+N 61600 64200 61600 64000 4
+C 61400 65100 1 270 0 capacitor-1.sym
+{
+T 62100 64900 5 10 0 0 270 0 1
+device=CAPACITOR
+T 62300 64900 5 10 0 0 270 0 1
+symversion=0.1
+T 61400 65100 5 10 0 0 270 0 1
+voltage=16 V
+T 61400 65100 5 10 0 0 270 0 1
+footprint=0603
+T 61400 65100 5 10 0 0 270 0 1
+pn=885012206047
+T 61900 64900 5 10 1 1 270 0 1
+refdes=C313
+T 61200 64900 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 61400 65300 1 0 0 generic-power.sym
+{
+T 61600 65550 5 10 1 1 0 3 1
+net=ODROID_5V:1
+}
+C 63100 63700 1 0 0 gnd-1.sym
+N 63200 65300 63200 65100 4
+N 63200 64200 63200 64000 4
+C 63000 65300 1 0 0 generic-power.sym
+{
+T 63200 65550 5 10 1 1 0 3 1
+net=ODROID_5V:1
+}
+C 63000 65100 1 270 0 capacitor-1.sym
+{
+T 63700 64900 5 10 0 0 270 0 1
+device=CAPACITOR
+T 63900 64900 5 10 0 0 270 0 1
+symversion=0.1
+T 63000 65100 5 10 0 0 270 0 1
+footprint=0603
+T 63000 65100 5 10 0 0 0 0 1
+pn=TMK107BJ105KA-T
+T 63000 65100 5 10 0 0 0 0 1
+voltage=25 V
+T 63500 64900 5 10 1 1 270 0 1
+refdes=C314
+T 62800 64900 5 10 1 1 270 0 1
+value=1 uF
+}
+C 46200 63400 1 0 0 gnd-1.sym
+N 46300 65000 46300 64800 4
+N 46300 63900 46300 63700 4
+C 46100 64800 1 270 0 capacitor-1.sym
+{
+T 46800 64600 5 10 0 0 270 0 1
+device=CAPACITOR
+T 47000 64600 5 10 0 0 270 0 1
+symversion=0.1
+T 46100 64800 5 10 0 0 270 0 1
+voltage=16 V
+T 46100 64800 5 10 0 0 270 0 1
+footprint=0603
+T 46100 64800 5 10 0 0 270 0 1
+pn=885012206047
+T 46600 64600 5 10 1 1 270 0 1
+refdes=C315
+T 45900 64600 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 46100 65000 1 0 0 3.3V-plus-1.sym
+C 46200 61100 1 0 0 gnd-1.sym
+N 46300 62700 46300 62500 4
+N 46300 61600 46300 61400 4
+C 46100 62500 1 270 0 capacitor-1.sym
+{
+T 46800 62300 5 10 0 0 270 0 1
+device=CAPACITOR
+T 47000 62300 5 10 0 0 270 0 1
+symversion=0.1
+T 46100 62500 5 10 0 0 270 0 1
+voltage=16 V
+T 46100 62500 5 10 0 0 270 0 1
+footprint=0603
+T 46100 62500 5 10 0 0 270 0 1
+pn=885012206047
+T 46600 62300 5 10 1 1 270 0 1
+refdes=C316
+T 45900 62300 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 46100 62700 1 0 0 3.3V-plus-1.sym
+C 46200 58800 1 0 0 gnd-1.sym
+N 46300 60400 46300 60200 4
+N 46300 59300 46300 59100 4
+C 46100 60200 1 270 0 capacitor-1.sym
+{
+T 46800 60000 5 10 0 0 270 0 1
+device=CAPACITOR
+T 47000 60000 5 10 0 0 270 0 1
+symversion=0.1
+T 46100 60200 5 10 0 0 270 0 1
+voltage=16 V
+T 46100 60200 5 10 0 0 270 0 1
+footprint=0603
+T 46100 60200 5 10 0 0 270 0 1
+pn=885012206047
+T 46600 60000 5 10 1 1 270 0 1
+refdes=C317
+T 45900 60000 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 46100 60400 1 0 0 3.3V-plus-1.sym
+C 46200 56500 1 0 0 gnd-1.sym
+N 46300 58100 46300 57900 4
+N 46300 57000 46300 56800 4
+C 46100 57900 1 270 0 capacitor-1.sym
+{
+T 46800 57700 5 10 0 0 270 0 1
+device=CAPACITOR
+T 47000 57700 5 10 0 0 270 0 1
+symversion=0.1
+T 46100 57900 5 10 0 0 270 0 1
+voltage=16 V
+T 46100 57900 5 10 0 0 270 0 1
+footprint=0603
+T 46100 57900 5 10 0 0 270 0 1
+pn=885012206047
+T 46600 57700 5 10 1 1 270 0 1
+refdes=C318
+T 45900 57700 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 46100 58100 1 0 0 3.3V-plus-1.sym
+C 46200 54200 1 0 0 gnd-1.sym
+N 46300 55800 46300 55600 4
+N 46300 54700 46300 54500 4
+C 46100 55600 1 270 0 capacitor-1.sym
+{
+T 46800 55400 5 10 0 0 270 0 1
+device=CAPACITOR
+T 47000 55400 5 10 0 0 270 0 1
+symversion=0.1
+T 46100 55600 5 10 0 0 270 0 1
+voltage=16 V
+T 46100 55600 5 10 0 0 270 0 1
+footprint=0603
+T 46100 55600 5 10 0 0 270 0 1
+pn=885012206047
+T 46600 55400 5 10 1 1 270 0 1
+refdes=C319
+T 45900 55400 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 46100 55800 1 0 0 3.3V-plus-1.sym
+C 48400 66400 1 0 0 ULN2003-1.sym
+{
+T 49950 70040 5 10 0 0 0 0 1
+device=ULN2003
+T 49950 69840 5 10 0 0 0 0 1
+footprint=SO16
+T 50100 69800 5 10 1 1 0 6 1
+refdes=U302
+T 48400 66400 5 10 0 0 0 0 1
+pn=ULQ2003ADR2G
+}
+C 47900 66700 1 270 0 gnd-1.sym
+N 48200 66600 48400 66600 4
+C 50900 66500 1 90 0 gnd-1.sym
+N 50600 66600 50400 66600 4
+C 47400 69300 1 0 0 input-1.sym
+{
+T 47400 69600 5 10 0 0 0 0 1
+device=INPUT
+T 48000 69700 5 10 1 1 180 0 1
+net=LED3:1
+}
+N 48200 69400 48400 69400 4
+N 47200 69000 48400 69000 4
+C 46400 68900 1 0 0 input-1.sym
+{
+T 46400 69200 5 10 0 0 0 0 1
+device=INPUT
+T 47000 69300 5 10 1 1 180 0 1
+net=LED4:1
+}
+C 47400 68500 1 0 0 input-1.sym
+{
+T 47400 68800 5 10 0 0 0 0 1
+device=INPUT
+T 48000 68900 5 10 1 1 180 0 1
+net=LED5:1
+}
+N 48200 68600 48400 68600 4
+N 47200 68200 48400 68200 4
+C 46400 68100 1 0 0 input-1.sym
+{
+T 46400 68400 5 10 0 0 0 0 1
+device=INPUT
+T 47000 68500 5 10 1 1 180 0 1
+net=LED6:1
+}
+C 47400 67700 1 0 0 input-1.sym
+{
+T 47400 68000 5 10 0 0 0 0 1
+device=INPUT
+T 48000 68100 5 10 1 1 180 0 1
+net=LED7:1
+}
+N 48200 67800 48400 67800 4
+N 47200 67400 48400 67400 4
+C 46400 67300 1 0 0 input-1.sym
+{
+T 46400 67600 5 10 0 0 0 0 1
+device=INPUT
+T 47000 67700 5 10 1 1 180 0 1
+net=LED8:1
+}
+C 47400 66900 1 0 0 input-1.sym
+{
+T 47400 67200 5 10 0 0 0 0 1
+device=INPUT
+T 48000 67300 5 10 1 1 180 0 1
+net=LED9:1
+}
+N 48200 67000 48400 67000 4
+N 52400 67000 50400 67000 4
+N 50400 67400 52600 67400 4
+N 50400 68200 52800 68200 4
+N 50400 67800 53000 67800 4
+N 50400 68600 53200 68600 4
+N 50400 69400 59200 69400 4
+N 50400 69000 59400 69000 4
+C 57700 56400 1 0 0 gnd-1.sym
+N 57800 59100 57800 58900 4
+C 58000 58000 1 90 0 led-3.sym
+{
+T 57350 58950 5 10 0 0 90 0 1
+device=LED
+T 58000 58000 5 10 0 0 0 0 1
+color=green
+T 58000 58000 5 10 0 0 0 0 1
+pn=150060VS75000
+T 58000 58000 5 10 0 0 0 0 1
+footprint=0603
+T 57450 58450 5 10 1 1 90 0 1
+refdes=D301
+}
+C 57700 57800 1 270 0 resistor-1.sym
+{
+T 58100 57500 5 10 0 0 270 0 1
+device=RESISTOR
+T 57700 57800 5 10 0 0 270 0 1
+footprint=0603
+T 57700 57800 5 10 0 0 0 0 1
+pn=RC0603FR-073K16L
+T 58000 57600 5 10 1 1 270 0 1
+refdes=R301
+T 57500 57600 5 10 1 1 270 0 1
+value=3.16 k
+}
+N 57800 58000 57800 57800 4
+N 57800 56900 57800 56700 4
+C 59500 56400 1 0 0 gnd-1.sym
+N 59600 59100 59600 58900 4
+C 59800 58000 1 90 0 led-3.sym
+{
+T 59150 58950 5 10 0 0 90 0 1
+device=LED
+T 59800 58000 5 10 0 0 0 0 1
+color=green
+T 59800 58000 5 10 0 0 0 0 1
+pn=150060VS75000
+T 59800 58000 5 10 0 0 0 0 1
+footprint=0603
+T 59250 58450 5 10 1 1 90 0 1
+refdes=D302
+}
+C 59500 57800 1 270 0 resistor-1.sym
+{
+T 59900 57500 5 10 0 0 270 0 1
+device=RESISTOR
+T 59500 57800 5 10 0 0 270 0 1
+footprint=0603
+T 59500 57800 5 10 0 0 0 0 1
+pn=RC0603FR-073K16L
+T 59800 57600 5 10 1 1 270 0 1
+refdes=R302
+T 59300 57600 5 10 1 1 270 0 1
+value=3.16 k
+}
+N 59600 58000 59600 57800 4
+N 59600 56900 59600 56700 4
+C 57600 59100 1 0 0 generic-power.sym
+{
+T 57800 59350 5 10 1 1 0 3 1
+net=CAM_5V:1
+}
+C 59400 59100 1 0 0 generic-power.sym
+{
+T 59600 59350 5 10 1 1 0 3 1
+net=ODROID_5V:1
+}
diff --git a/motors/uart_schematic/uart-spi.sch b/motors/uart_schematic/uart-spi.sch
new file mode 100644
index 0000000..c19457d
--- /dev/null
+++ b/motors/uart_schematic/uart-spi.sch
@@ -0,0 +1,292 @@
+v 20130925 2
+C 63100 57100 1 0 0 connector6-1.sym
+{
+T 64900 58900 5 10 0 0 0 0 1
+device=CONNECTOR_6
+T 63200 59100 5 10 1 1 0 0 1
+refdes=CONN201
+T 63100 57100 5 10 0 0 0 0 1
+pn=22-23-2061
+T 63100 57100 5 10 0 0 0 0 1
+footprint=22-23-2061
+}
+C 65000 59000 1 270 0 generic-power.sym
+{
+T 65250 58800 5 10 1 1 270 3 1
+net=SPI_GND:1
+}
+C 65600 58700 1 270 0 generic-power.sym
+{
+T 65850 58500 5 10 1 1 270 3 1
+net=SPI_5V:1
+}
+N 65000 58800 64800 58800 4
+N 65600 58500 64800 58500 4
+C 68200 58100 1 0 0 output-1.sym
+{
+T 68300 58400 5 10 0 0 0 0 1
+device=OUTPUT
+T 68400 58300 5 10 1 1 0 0 1
+net=RAW_SPI_CLK:1
+}
+C 70500 57800 1 0 0 output-1.sym
+{
+T 70600 58100 5 10 0 0 0 0 1
+device=OUTPUT
+T 70700 58000 5 10 1 1 0 0 1
+net=RAW_SPI_MOSI:1
+}
+C 68600 57700 1 180 0 input-1.sym
+{
+T 68600 57400 5 10 0 0 180 0 1
+device=INPUT
+T 68100 57700 5 10 1 1 0 0 1
+net=RAW_SPI_MISO:1
+}
+C 70500 57200 1 0 0 output-1.sym
+{
+T 70600 57500 5 10 0 0 0 0 1
+device=OUTPUT
+T 70700 57400 5 10 1 1 0 0 1
+net=RAW_SPI_CS:1
+}
+C 64400 51500 1 0 0 SI864x.sym
+{
+T 64900 53900 5 10 1 1 0 0 1
+device=SI864x
+T 65900 53900 5 10 1 1 0 0 1
+refdes=U201
+T 66100 54500 5 10 0 1 0 0 1
+footprint=SO16W
+T 64400 51500 5 10 0 0 0 0 1
+pn=SI8641BA-B-IUR
+}
+C 64200 53200 1 90 0 generic-power.sym
+{
+T 63950 53400 5 10 1 1 90 3 1
+net=SPI_GND:1
+}
+C 63200 52900 1 90 0 generic-power.sym
+{
+T 62950 53100 5 10 1 1 90 3 1
+net=SPI_GND:1
+}
+N 64200 53400 64400 53400 4
+N 63200 53100 64400 53100 4
+C 62300 53500 1 90 0 generic-power.sym
+{
+T 62050 53700 5 10 1 1 90 3 1
+net=SPI_5V:1
+}
+N 62300 53700 64400 53700 4
+C 66700 54700 1 0 0 gnd-1.sym
+N 66800 56300 66800 56100 4
+N 66800 55200 66800 55000 4
+C 66600 56100 1 270 0 capacitor-1.sym
+{
+T 67300 55900 5 10 0 0 270 0 1
+device=CAPACITOR
+T 67500 55900 5 10 0 0 270 0 1
+symversion=0.1
+T 66600 56100 5 10 0 0 270 0 1
+voltage=16 V
+T 66600 56100 5 10 0 0 270 0 1
+footprint=0603
+T 66600 56100 5 10 0 0 270 0 1
+pn=885012206047
+T 67100 55900 5 10 1 1 270 0 1
+refdes=C201
+T 66400 55900 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 66600 56300 1 0 0 3.3V-plus-1.sym
+N 65500 56300 65500 56100 4
+N 65500 55200 65500 55000 4
+C 65300 56100 1 270 0 capacitor-1.sym
+{
+T 66000 55900 5 10 0 0 270 0 1
+device=CAPACITOR
+T 66200 55900 5 10 0 0 270 0 1
+symversion=0.1
+T 65300 56100 5 10 0 0 270 0 1
+voltage=16 V
+T 65300 56100 5 10 0 0 270 0 1
+footprint=0603
+T 65300 56100 5 10 0 0 270 0 1
+pn=885012206047
+T 65800 55900 5 10 1 1 270 0 1
+refdes=C202
+T 65100 55900 5 10 1 1 270 0 1
+value=0.15 uF
+}
+C 65300 56300 1 0 0 generic-power.sym
+{
+T 65500 56550 5 10 1 1 0 3 1
+net=SPI_5V:1
+}
+C 65700 55000 1 180 0 generic-power.sym
+{
+T 65500 54750 5 10 1 1 180 3 1
+net=SPI_GND:1
+}
+C 68700 53900 1 270 0 3.3V-plus-1.sym
+C 66900 53000 1 270 0 3.3V-plus-1.sym
+C 69000 53000 1 90 0 gnd-1.sym
+C 67200 53300 1 90 0 gnd-1.sym
+N 68700 53700 66700 53700 4
+N 66900 53400 66700 53400 4
+N 68700 53100 66700 53100 4
+N 66900 52800 66700 52800 4
+C 63400 52400 1 0 0 input-1.sym
+{
+T 63400 52700 5 10 0 0 0 0 1
+device=INPUT
+T 63900 52400 5 10 1 1 180 0 1
+net=RAW_SPI_CLK:1
+}
+N 61000 52800 64400 52800 4
+N 64200 52500 64400 52500 4
+C 61500 52100 1 0 0 input-1.sym
+{
+T 61500 52400 5 10 0 0 0 0 1
+device=INPUT
+T 62000 52100 5 10 1 1 180 0 1
+net=RAW_SPI_MOSI:1
+}
+N 62300 52200 64400 52200 4
+C 63400 51800 1 0 0 input-1.sym
+{
+T 63400 52100 5 10 0 0 0 0 1
+device=INPUT
+T 63900 51800 5 10 1 1 180 0 1
+net=RAW_SPI_CS:1
+}
+N 64200 51900 64400 51900 4
+C 62300 51700 1 180 0 output-1.sym
+{
+T 62200 51400 5 10 0 0 180 0 1
+device=OUTPUT
+T 62100 51500 5 10 1 1 180 0 1
+net=RAW_SPI_MISO:1
+}
+N 62300 51600 64400 51600 4
+C 68700 52400 1 0 0 output-1.sym
+{
+T 68800 52700 5 10 0 0 0 0 1
+device=OUTPUT
+T 68900 52600 5 10 1 1 0 0 1
+net=SPI_CLK:1
+}
+N 68700 52500 66700 52500 4
+C 66900 52100 1 0 0 output-1.sym
+{
+T 67000 52400 5 10 0 0 0 0 1
+device=OUTPUT
+T 67100 52300 5 10 1 1 0 0 1
+net=SPI_MOSI:1
+}
+N 66900 52200 66700 52200 4
+C 68700 51800 1 0 0 output-1.sym
+{
+T 68800 52100 5 10 0 0 0 0 1
+device=OUTPUT
+T 68900 52000 5 10 1 1 0 0 1
+net=SPI_CS:1
+}
+N 68700 51900 66700 51900 4
+C 67700 51700 1 180 0 input-1.sym
+{
+T 67700 51400 5 10 0 0 180 0 1
+device=INPUT
+T 67200 51700 5 10 1 1 0 0 1
+net=SPI_MISO:1
+}
+N 66900 51600 66700 51600 4
+C 59400 52500 1 0 0 inverter.sym
+{
+T 60100 53300 5 10 0 0 0 0 1
+device=INVERTER
+T 60600 53100 5 10 1 1 0 0 1
+refdes=U202
+T 60100 55700 5 10 0 0 0 0 1
+footprint=SOT25
+T 59400 52500 5 10 0 0 0 0 1
+pn=74AHCT1G14SE-7
+}
+C 58300 52900 1 90 0 generic-power.sym
+{
+T 58050 53100 5 10 1 1 90 3 1
+net=SPI_5V:1
+}
+C 59100 52300 1 90 0 generic-power.sym
+{
+T 58850 52500 5 10 1 1 90 3 1
+net=SPI_GND:1
+}
+N 59100 52500 59800 52500 4
+N 58300 53100 59800 53100 4
+C 59000 54300 1 270 0 input-1.sym
+{
+T 59300 54300 5 10 0 0 270 0 1
+device=INPUT
+T 59000 53800 5 10 1 1 90 0 1
+net=RAW_SPI_CS:1
+}
+N 59800 52800 59100 52800 4
+N 59100 52800 59100 53500 4
+C 66400 57200 1 0 0 resistor-x4.sym
+{
+T 66700 58500 5 10 0 0 0 0 1
+device=RESISTOR_x4
+T 66400 57200 5 10 0 0 0 0 1
+footprint=0603_4
+T 66400 57200 5 10 0 0 0 0 1
+pn=RAVF164DJT100R
+T 66600 58400 5 10 1 1 0 0 1
+refdes=R201
+T 66700 57000 5 10 1 1 0 0 1
+value=100
+}
+N 64800 57300 66400 57300 4
+N 64800 57600 66400 57600 4
+N 64800 57900 66400 57900 4
+N 64800 58200 66400 58200 4
+N 67300 57300 70500 57300 4
+N 67800 57600 67300 57600 4
+N 67300 57900 70500 57900 4
+N 67300 58200 68200 58200 4
+C 72400 52300 1 0 0 gnd-1.sym
+N 72500 55000 72500 54800 4
+C 72700 53900 1 90 0 led-3.sym
+{
+T 72050 54850 5 10 0 0 90 0 1
+device=LED
+T 72700 53900 5 10 0 0 0 0 1
+color=green
+T 72700 53900 5 10 0 0 0 0 1
+pn=150060VS75000
+T 72700 53900 5 10 0 0 0 0 1
+footprint=0603
+T 72150 54350 5 10 1 1 90 0 1
+refdes=D201
+}
+C 72400 53700 1 270 0 resistor-1.sym
+{
+T 72800 53400 5 10 0 0 270 0 1
+device=RESISTOR
+T 72400 53700 5 10 0 0 270 0 1
+footprint=0603
+T 72400 53700 5 10 0 0 0 0 1
+pn=RC0603FR-073K16L
+T 72700 53500 5 10 1 1 270 0 1
+refdes=R202
+T 72200 53500 5 10 1 1 270 0 1
+value=3.16 k
+}
+N 72500 53900 72500 53700 4
+N 72500 52800 72500 52600 4
+C 72300 55000 1 0 0 generic-power.sym
+{
+T 72500 55250 5 10 1 1 0 3 1
+net=SPI_5V:1
+}
diff --git a/motors/uart_schematic/uart.gsch2pcb b/motors/uart_schematic/uart.gsch2pcb
new file mode 100644
index 0000000..1e0b139
--- /dev/null
+++ b/motors/uart_schematic/uart.gsch2pcb
@@ -0,0 +1,3 @@
+schematics uart-main.sch uart-5v.sch uart-spi.sch uart-outputs.sch uart-beacon.sch
+output-name uart
+use-files
diff --git a/motors/uart_schematic/uart.pcb b/motors/uart_schematic/uart.pcb
new file mode 100644
index 0000000..e78ec15
--- /dev/null
+++ b/motors/uart_schematic/uart.pcb
@@ -0,0 +1,4200 @@
+# release: pcb 20140316
+
+# To read pcb files, the pcb version (or the git source date) must be >= the file version
+FileVersion[20091103]
+
+PCB["uart" 9000.00mil 5000.00mil]
+
+Grid[500.000000 0.0000 0.0000 1]
+PolyArea[3100.006200]
+Thermal[0.500000]
+DRC[5.00mil 10.00mil 5.00mil 8.00mil 11.81mil 6.00mil]
+Flags("showdrc,rubberband,nameonpcb,clearnew,snappin,showmask")
+Groups("1,c:2:3:4,s:5")
+Styles["Signal,10.00mil,36.00mil,20.00mil,7.00mil:Power,25.00mil,60.00mil,35.00mil,10.00mil:Fat,15.00mil,45.00mil,25.00mil,10.00mil:Skinny,6.00mil,24.02mil,11.81mil,6.00mil"]
+
+Symbol[' ' 18.00mil]
+(
+)
+Symbol['!' 12.00mil]
+(
+	SymbolLine[0.0000 45.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 0.0000 35.00mil 8.00mil]
+)
+Symbol['"' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 20.00mil 8.00mil]
+	SymbolLine[10.00mil 10.00mil 10.00mil 20.00mil 8.00mil]
+)
+Symbol['#' 12.00mil]
+(
+	SymbolLine[0.0000 35.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[0.0000 25.00mil 20.00mil 25.00mil 8.00mil]
+	SymbolLine[15.00mil 20.00mil 15.00mil 40.00mil 8.00mil]
+	SymbolLine[5.00mil 20.00mil 5.00mil 40.00mil 8.00mil]
+)
+Symbol['$' 12.00mil]
+(
+	SymbolLine[15.00mil 15.00mil 20.00mil 20.00mil 8.00mil]
+	SymbolLine[5.00mil 15.00mil 15.00mil 15.00mil 8.00mil]
+	SymbolLine[0.0000 20.00mil 5.00mil 15.00mil 8.00mil]
+	SymbolLine[0.0000 20.00mil 0.0000 25.00mil 8.00mil]
+	SymbolLine[0.0000 25.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 20.00mil 40.00mil 8.00mil]
+	SymbolLine[15.00mil 45.00mil 20.00mil 40.00mil 8.00mil]
+	SymbolLine[5.00mil 45.00mil 15.00mil 45.00mil 8.00mil]
+	SymbolLine[0.0000 40.00mil 5.00mil 45.00mil 8.00mil]
+	SymbolLine[10.00mil 10.00mil 10.00mil 50.00mil 8.00mil]
+)
+Symbol['%' 12.00mil]
+(
+	SymbolLine[0.0000 15.00mil 0.0000 20.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 10.00mil 10.00mil 8.00mil]
+	SymbolLine[10.00mil 10.00mil 15.00mil 15.00mil 8.00mil]
+	SymbolLine[15.00mil 15.00mil 15.00mil 20.00mil 8.00mil]
+	SymbolLine[10.00mil 25.00mil 15.00mil 20.00mil 8.00mil]
+	SymbolLine[5.00mil 25.00mil 10.00mil 25.00mil 8.00mil]
+	SymbolLine[0.0000 20.00mil 5.00mil 25.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 40.00mil 10.00mil 8.00mil]
+	SymbolLine[35.00mil 50.00mil 40.00mil 45.00mil 8.00mil]
+	SymbolLine[40.00mil 40.00mil 40.00mil 45.00mil 8.00mil]
+	SymbolLine[35.00mil 35.00mil 40.00mil 40.00mil 8.00mil]
+	SymbolLine[30.00mil 35.00mil 35.00mil 35.00mil 8.00mil]
+	SymbolLine[25.00mil 40.00mil 30.00mil 35.00mil 8.00mil]
+	SymbolLine[25.00mil 40.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[25.00mil 45.00mil 30.00mil 50.00mil 8.00mil]
+	SymbolLine[30.00mil 50.00mil 35.00mil 50.00mil 8.00mil]
+)
+Symbol['&' 12.00mil]
+(
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 25.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 15.00mil 20.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[10.00mil 50.00mil 20.00mil 40.00mil 8.00mil]
+	SymbolLine[0.0000 25.00mil 25.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 10.00mil 10.00mil 8.00mil]
+	SymbolLine[10.00mil 10.00mil 15.00mil 15.00mil 8.00mil]
+	SymbolLine[15.00mil 15.00mil 15.00mil 20.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 0.0000 45.00mil 8.00mil]
+)
+Symbol[''' 12.00mil]
+(
+	SymbolLine[0.0000 20.00mil 10.00mil 10.00mil 8.00mil]
+)
+Symbol['(' 12.00mil]
+(
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 45.00mil 8.00mil]
+)
+Symbol[')' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 5.00mil 15.00mil 8.00mil]
+	SymbolLine[5.00mil 15.00mil 5.00mil 45.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 5.00mil 45.00mil 8.00mil]
+)
+Symbol['*' 12.00mil]
+(
+	SymbolLine[0.0000 20.00mil 20.00mil 40.00mil 8.00mil]
+	SymbolLine[0.0000 40.00mil 20.00mil 20.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[10.00mil 20.00mil 10.00mil 40.00mil 8.00mil]
+)
+Symbol['+' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[10.00mil 20.00mil 10.00mil 40.00mil 8.00mil]
+)
+Symbol[',' 12.00mil]
+(
+	SymbolLine[0.0000 60.00mil 10.00mil 50.00mil 8.00mil]
+)
+Symbol['-' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 20.00mil 30.00mil 8.00mil]
+)
+Symbol['.' 12.00mil]
+(
+	SymbolLine[0.0000 50.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['/' 12.00mil]
+(
+	SymbolLine[0.0000 45.00mil 30.00mil 15.00mil 8.00mil]
+)
+Symbol['0' 12.00mil]
+(
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[15.00mil 10.00mil 20.00mil 15.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 40.00mil 20.00mil 20.00mil 8.00mil]
+)
+Symbol['1' 12.00mil]
+(
+	SymbolLine[0.0000 18.00mil 8.00mil 10.00mil 8.00mil]
+	SymbolLine[8.00mil 10.00mil 8.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 15.00mil 50.00mil 8.00mil]
+)
+Symbol['2' 12.00mil]
+(
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[20.00mil 10.00mil 25.00mil 15.00mil 8.00mil]
+	SymbolLine[25.00mil 15.00mil 25.00mil 25.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 25.00mil 25.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 25.00mil 50.00mil 8.00mil]
+)
+Symbol['3' 12.00mil]
+(
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[15.00mil 10.00mil 20.00mil 15.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 28.00mil 15.00mil 28.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 20.00mil 23.00mil 8.00mil]
+	SymbolLine[20.00mil 33.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 33.00mil 15.00mil 28.00mil 8.00mil]
+	SymbolLine[20.00mil 23.00mil 15.00mil 28.00mil 8.00mil]
+)
+Symbol['4' 12.00mil]
+(
+	SymbolLine[0.0000 35.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 25.00mil 35.00mil 8.00mil]
+	SymbolLine[20.00mil 10.00mil 20.00mil 50.00mil 8.00mil]
+)
+Symbol['5' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 0.0000 30.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 5.00mil 25.00mil 8.00mil]
+	SymbolLine[5.00mil 25.00mil 15.00mil 25.00mil 8.00mil]
+	SymbolLine[15.00mil 25.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['6' 12.00mil]
+(
+	SymbolLine[15.00mil 10.00mil 20.00mil 15.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 28.00mil 20.00mil 33.00mil 8.00mil]
+	SymbolLine[0.0000 28.00mil 15.00mil 28.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 33.00mil 20.00mil 45.00mil 8.00mil]
+)
+Symbol['7' 12.00mil]
+(
+	SymbolLine[5.00mil 50.00mil 25.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 25.00mil 10.00mil 8.00mil]
+)
+Symbol['8' 12.00mil]
+(
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 37.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 37.00mil 7.00mil 30.00mil 8.00mil]
+	SymbolLine[7.00mil 30.00mil 13.00mil 30.00mil 8.00mil]
+	SymbolLine[13.00mil 30.00mil 20.00mil 37.00mil 8.00mil]
+	SymbolLine[20.00mil 37.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 23.00mil 7.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 23.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[15.00mil 10.00mil 20.00mil 15.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 20.00mil 23.00mil 8.00mil]
+	SymbolLine[13.00mil 30.00mil 20.00mil 23.00mil 8.00mil]
+)
+Symbol['9' 12.00mil]
+(
+	SymbolLine[5.00mil 50.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 10.00mil 20.00mil 15.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 25.00mil 8.00mil]
+	SymbolLine[0.0000 25.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+)
+Symbol[':' 12.00mil]
+(
+	SymbolLine[0.0000 25.00mil 5.00mil 25.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 35.00mil 8.00mil]
+)
+Symbol[';' 12.00mil]
+(
+	SymbolLine[0.0000 50.00mil 10.00mil 40.00mil 8.00mil]
+	SymbolLine[10.00mil 25.00mil 10.00mil 30.00mil 8.00mil]
+)
+Symbol['<' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 10.00mil 20.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 10.00mil 40.00mil 8.00mil]
+)
+Symbol['=' 12.00mil]
+(
+	SymbolLine[0.0000 25.00mil 20.00mil 25.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 20.00mil 35.00mil 8.00mil]
+)
+Symbol['>' 12.00mil]
+(
+	SymbolLine[0.0000 20.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 40.00mil 10.00mil 30.00mil 8.00mil]
+)
+Symbol['?' 12.00mil]
+(
+	SymbolLine[10.00mil 30.00mil 10.00mil 35.00mil 8.00mil]
+	SymbolLine[10.00mil 45.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 20.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[15.00mil 10.00mil 20.00mil 15.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 20.00mil 20.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 20.00mil 20.00mil 8.00mil]
+)
+Symbol['@' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 40.00mil 8.00mil]
+	SymbolLine[0.0000 40.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[10.00mil 50.00mil 40.00mil 50.00mil 8.00mil]
+	SymbolLine[50.00mil 35.00mil 50.00mil 10.00mil 8.00mil]
+	SymbolLine[50.00mil 10.00mil 40.00mil 0.0000 8.00mil]
+	SymbolLine[40.00mil 0.0000 10.00mil 0.0000 8.00mil]
+	SymbolLine[10.00mil 0.0000 0.0000 10.00mil 8.00mil]
+	SymbolLine[15.00mil 20.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 30.00mil 35.00mil 8.00mil]
+	SymbolLine[30.00mil 35.00mil 35.00mil 30.00mil 8.00mil]
+	SymbolLine[35.00mil 30.00mil 40.00mil 35.00mil 8.00mil]
+	SymbolLine[35.00mil 30.00mil 35.00mil 15.00mil 8.00mil]
+	SymbolLine[35.00mil 20.00mil 30.00mil 15.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 30.00mil 15.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 15.00mil 20.00mil 8.00mil]
+	SymbolLine[40.00mil 35.00mil 50.00mil 35.00mil 8.00mil]
+)
+Symbol['A' 12.00mil]
+(
+	SymbolLine[0.0000 20.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 20.00mil 7.00mil 10.00mil 8.00mil]
+	SymbolLine[7.00mil 10.00mil 18.00mil 10.00mil 8.00mil]
+	SymbolLine[18.00mil 10.00mil 25.00mil 20.00mil 8.00mil]
+	SymbolLine[25.00mil 20.00mil 25.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 25.00mil 30.00mil 8.00mil]
+)
+Symbol['B' 12.00mil]
+(
+	SymbolLine[0.0000 50.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[20.00mil 50.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[25.00mil 33.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 28.00mil 25.00mil 33.00mil 8.00mil]
+	SymbolLine[5.00mil 28.00mil 20.00mil 28.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[20.00mil 10.00mil 25.00mil 15.00mil 8.00mil]
+	SymbolLine[25.00mil 15.00mil 25.00mil 23.00mil 8.00mil]
+	SymbolLine[20.00mil 28.00mil 25.00mil 23.00mil 8.00mil]
+)
+Symbol['C' 12.00mil]
+(
+	SymbolLine[7.00mil 50.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 43.00mil 7.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 17.00mil 0.0000 43.00mil 8.00mil]
+	SymbolLine[0.0000 17.00mil 7.00mil 10.00mil 8.00mil]
+	SymbolLine[7.00mil 10.00mil 20.00mil 10.00mil 8.00mil]
+)
+Symbol['D' 12.00mil]
+(
+	SymbolLine[5.00mil 10.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[18.00mil 10.00mil 25.00mil 17.00mil 8.00mil]
+	SymbolLine[25.00mil 17.00mil 25.00mil 43.00mil 8.00mil]
+	SymbolLine[18.00mil 50.00mil 25.00mil 43.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 18.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 18.00mil 10.00mil 8.00mil]
+)
+Symbol['E' 12.00mil]
+(
+	SymbolLine[0.0000 28.00mil 15.00mil 28.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 20.00mil 10.00mil 8.00mil]
+)
+Symbol['F' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 28.00mil 15.00mil 28.00mil 8.00mil]
+)
+Symbol['G' 12.00mil]
+(
+	SymbolLine[20.00mil 10.00mil 25.00mil 15.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[20.00mil 50.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[25.00mil 35.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 25.00mil 35.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+)
+Symbol['H' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[25.00mil 10.00mil 25.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 25.00mil 30.00mil 8.00mil]
+)
+Symbol['I' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 10.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 10.00mil 50.00mil 8.00mil]
+)
+Symbol['J' 12.00mil]
+(
+	SymbolLine[7.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[15.00mil 10.00mil 15.00mil 45.00mil 8.00mil]
+	SymbolLine[10.00mil 50.00mil 15.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 0.0000 40.00mil 8.00mil]
+)
+Symbol['K' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 20.00mil 50.00mil 8.00mil]
+)
+Symbol['L' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 20.00mil 50.00mil 8.00mil]
+)
+Symbol['M' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 30.00mil 10.00mil 8.00mil]
+	SymbolLine[30.00mil 10.00mil 30.00mil 50.00mil 8.00mil]
+)
+Symbol['N' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 25.00mil 50.00mil 8.00mil]
+	SymbolLine[25.00mil 10.00mil 25.00mil 50.00mil 8.00mil]
+)
+Symbol['O' 12.00mil]
+(
+	SymbolLine[0.0000 15.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[15.00mil 10.00mil 20.00mil 15.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['P' 12.00mil]
+(
+	SymbolLine[5.00mil 10.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[20.00mil 10.00mil 25.00mil 15.00mil 8.00mil]
+	SymbolLine[25.00mil 15.00mil 25.00mil 25.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 25.00mil 25.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+)
+Symbol['Q' 12.00mil]
+(
+	SymbolLine[0.0000 15.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[15.00mil 10.00mil 20.00mil 15.00mil 8.00mil]
+	SymbolLine[20.00mil 15.00mil 20.00mil 40.00mil 8.00mil]
+	SymbolLine[10.00mil 50.00mil 20.00mil 40.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[10.00mil 35.00mil 20.00mil 50.00mil 8.00mil]
+)
+Symbol['R' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[20.00mil 10.00mil 25.00mil 15.00mil 8.00mil]
+	SymbolLine[25.00mil 15.00mil 25.00mil 25.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 25.00mil 25.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[13.00mil 30.00mil 25.00mil 50.00mil 8.00mil]
+)
+Symbol['S' 12.00mil]
+(
+	SymbolLine[20.00mil 10.00mil 25.00mil 15.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 15.00mil 0.0000 25.00mil 8.00mil]
+	SymbolLine[0.0000 25.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 25.00mil 35.00mil 8.00mil]
+	SymbolLine[25.00mil 35.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 50.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['T' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[10.00mil 10.00mil 10.00mil 50.00mil 8.00mil]
+)
+Symbol['U' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 10.00mil 20.00mil 45.00mil 8.00mil]
+)
+Symbol['V' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[10.00mil 50.00mil 20.00mil 10.00mil 8.00mil]
+)
+Symbol['W' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 30.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 25.00mil 50.00mil 8.00mil]
+	SymbolLine[25.00mil 50.00mil 30.00mil 30.00mil 8.00mil]
+	SymbolLine[30.00mil 30.00mil 30.00mil 10.00mil 8.00mil]
+)
+Symbol['X' 12.00mil]
+(
+	SymbolLine[0.0000 50.00mil 25.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 25.00mil 50.00mil 8.00mil]
+)
+Symbol['Y' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 20.00mil 10.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 10.00mil 50.00mil 8.00mil]
+)
+Symbol['Z' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 25.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 25.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 25.00mil 50.00mil 8.00mil]
+)
+Symbol['[' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['\' 12.00mil]
+(
+	SymbolLine[0.0000 15.00mil 30.00mil 45.00mil 8.00mil]
+)
+Symbol[']' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['^' 12.00mil]
+(
+	SymbolLine[0.0000 15.00mil 5.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 10.00mil 10.00mil 15.00mil 8.00mil]
+)
+Symbol['_' 12.00mil]
+(
+	SymbolLine[0.0000 50.00mil 20.00mil 50.00mil 8.00mil]
+)
+Symbol['a' 12.00mil]
+(
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 45.00mil 25.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+)
+Symbol['b' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+)
+Symbol['c' 12.00mil]
+(
+	SymbolLine[5.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 20.00mil 50.00mil 8.00mil]
+)
+Symbol['d' 12.00mil]
+(
+	SymbolLine[20.00mil 10.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+)
+Symbol['e' 12.00mil]
+(
+	SymbolLine[5.00mil 50.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[0.0000 40.00mil 20.00mil 40.00mil 8.00mil]
+	SymbolLine[20.00mil 40.00mil 20.00mil 35.00mil 8.00mil]
+)
+Symbol['f' 10.00mil]
+(
+	SymbolLine[5.00mil 15.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 15.00mil 10.00mil 10.00mil 8.00mil]
+	SymbolLine[10.00mil 10.00mil 15.00mil 10.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 10.00mil 30.00mil 8.00mil]
+)
+Symbol['g' 12.00mil]
+(
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[0.0000 60.00mil 5.00mil 65.00mil 8.00mil]
+	SymbolLine[5.00mil 65.00mil 15.00mil 65.00mil 8.00mil]
+	SymbolLine[15.00mil 65.00mil 20.00mil 60.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 20.00mil 60.00mil 8.00mil]
+)
+Symbol['h' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 20.00mil 50.00mil 8.00mil]
+)
+Symbol['i' 10.00mil]
+(
+	SymbolLine[0.0000 20.00mil 0.0000 21.00mil 10.00mil]
+	SymbolLine[0.0000 35.00mil 0.0000 50.00mil 8.00mil]
+)
+Symbol['j' 10.00mil]
+(
+	SymbolLine[5.00mil 20.00mil 5.00mil 21.00mil 10.00mil]
+	SymbolLine[5.00mil 35.00mil 5.00mil 60.00mil 8.00mil]
+	SymbolLine[0.0000 65.00mil 5.00mil 60.00mil 8.00mil]
+)
+Symbol['k' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 10.00mil 25.00mil 8.00mil]
+)
+Symbol['l' 10.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['m' 12.00mil]
+(
+	SymbolLine[5.00mil 35.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 35.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 25.00mil 30.00mil 8.00mil]
+	SymbolLine[25.00mil 30.00mil 30.00mil 30.00mil 8.00mil]
+	SymbolLine[30.00mil 30.00mil 35.00mil 35.00mil 8.00mil]
+	SymbolLine[35.00mil 35.00mil 35.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 5.00mil 35.00mil 8.00mil]
+)
+Symbol['n' 12.00mil]
+(
+	SymbolLine[5.00mil 35.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 35.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 5.00mil 35.00mil 8.00mil]
+)
+Symbol['o' 12.00mil]
+(
+	SymbolLine[0.0000 35.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['p' 12.00mil]
+(
+	SymbolLine[5.00mil 35.00mil 5.00mil 65.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 5.00mil 35.00mil 8.00mil]
+	SymbolLine[5.00mil 35.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 25.00mil 35.00mil 8.00mil]
+	SymbolLine[25.00mil 35.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 50.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[10.00mil 50.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 45.00mil 10.00mil 50.00mil 8.00mil]
+)
+Symbol['q' 12.00mil]
+(
+	SymbolLine[20.00mil 35.00mil 20.00mil 65.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 15.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+)
+Symbol['r' 12.00mil]
+(
+	SymbolLine[5.00mil 35.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 35.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 5.00mil 35.00mil 8.00mil]
+)
+Symbol['s' 12.00mil]
+(
+	SymbolLine[5.00mil 50.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[20.00mil 50.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 40.00mil 25.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 40.00mil 20.00mil 40.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 40.00mil 8.00mil]
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 25.00mil 35.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+)
+Symbol['t' 10.00mil]
+(
+	SymbolLine[5.00mil 10.00mil 5.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 45.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 25.00mil 10.00mil 25.00mil 8.00mil]
+)
+Symbol['u' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 20.00mil 45.00mil 8.00mil]
+)
+Symbol['v' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 10.00mil 50.00mil 8.00mil]
+)
+Symbol['w' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 10.00mil 50.00mil 8.00mil]
+	SymbolLine[10.00mil 50.00mil 15.00mil 45.00mil 8.00mil]
+	SymbolLine[15.00mil 30.00mil 15.00mil 45.00mil 8.00mil]
+	SymbolLine[15.00mil 45.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[20.00mil 50.00mil 25.00mil 50.00mil 8.00mil]
+	SymbolLine[25.00mil 50.00mil 30.00mil 45.00mil 8.00mil]
+	SymbolLine[30.00mil 30.00mil 30.00mil 45.00mil 8.00mil]
+)
+Symbol['x' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 20.00mil 50.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 20.00mil 30.00mil 8.00mil]
+)
+Symbol['y' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 0.0000 45.00mil 8.00mil]
+	SymbolLine[0.0000 45.00mil 5.00mil 50.00mil 8.00mil]
+	SymbolLine[20.00mil 30.00mil 20.00mil 60.00mil 8.00mil]
+	SymbolLine[15.00mil 65.00mil 20.00mil 60.00mil 8.00mil]
+	SymbolLine[5.00mil 65.00mil 15.00mil 65.00mil 8.00mil]
+	SymbolLine[0.0000 60.00mil 5.00mil 65.00mil 8.00mil]
+	SymbolLine[5.00mil 50.00mil 15.00mil 50.00mil 8.00mil]
+	SymbolLine[15.00mil 50.00mil 20.00mil 45.00mil 8.00mil]
+)
+Symbol['z' 12.00mil]
+(
+	SymbolLine[0.0000 30.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 20.00mil 30.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 20.00mil 50.00mil 8.00mil]
+)
+Symbol['{' 12.00mil]
+(
+	SymbolLine[5.00mil 15.00mil 10.00mil 10.00mil 8.00mil]
+	SymbolLine[5.00mil 15.00mil 5.00mil 25.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 5.00mil 25.00mil 8.00mil]
+	SymbolLine[0.0000 30.00mil 5.00mil 35.00mil 8.00mil]
+	SymbolLine[5.00mil 35.00mil 5.00mil 45.00mil 8.00mil]
+	SymbolLine[5.00mil 45.00mil 10.00mil 50.00mil 8.00mil]
+)
+Symbol['|' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 0.0000 50.00mil 8.00mil]
+)
+Symbol['}' 12.00mil]
+(
+	SymbolLine[0.0000 10.00mil 5.00mil 15.00mil 8.00mil]
+	SymbolLine[5.00mil 15.00mil 5.00mil 25.00mil 8.00mil]
+	SymbolLine[5.00mil 25.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 35.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 35.00mil 5.00mil 45.00mil 8.00mil]
+	SymbolLine[0.0000 50.00mil 5.00mil 45.00mil 8.00mil]
+)
+Symbol['~' 12.00mil]
+(
+	SymbolLine[0.0000 35.00mil 5.00mil 30.00mil 8.00mil]
+	SymbolLine[5.00mil 30.00mil 10.00mil 30.00mil 8.00mil]
+	SymbolLine[10.00mil 30.00mil 15.00mil 35.00mil 8.00mil]
+	SymbolLine[15.00mil 35.00mil 20.00mil 35.00mil 8.00mil]
+	SymbolLine[20.00mil 35.00mil 25.00mil 30.00mil 8.00mil]
+)
+Attribute("PCB::grid::unit" "mil")
+Attribute("PCB::grid::size" "5.00mil")
+Via[6285.00mil 2540.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6535.00mil 2225.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[5935.00mil 2225.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6485.00mil 2540.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6270.00mil 2220.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6580.00mil 2220.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6165.00mil 2195.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6165.00mil 2095.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[5980.00mil 2065.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6490.00mil 2225.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6475.00mil 2145.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6210.00mil 2660.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6210.00mil 2615.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6375.00mil 1970.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6250.00mil 1970.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6225.00mil 1935.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6225.00mil 1890.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6225.00mil 1800.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6270.00mil 1745.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[5940.00mil 2545.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6680.00mil 2545.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4495.00mil 1865.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4625.00mil 1885.00mil 60.00mil 20.00mil 0.0000 35.00mil "" ""]
+Via[4420.00mil 1740.00mil 60.00mil 20.00mil 0.0000 35.00mil "" "thermal(1S)"]
+Via[4925.00mil 2060.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[4850.00mil 2060.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(1S)"]
+Via[4765.00mil 2060.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[4710.00mil 2060.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[5135.00mil 1680.00mil 60.00mil 20.00mil 0.0000 35.00mil "" ""]
+Via[4830.00mil 1770.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[4960.00mil 1680.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[5705.00mil 2560.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5815.00mil 2625.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5815.00mil 2560.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5760.00mil 2690.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5705.00mil 2625.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5390.00mil 2560.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5500.00mil 2625.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5500.00mil 2560.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5445.00mil 2690.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5390.00mil 2625.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5075.00mil 2560.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5185.00mil 2625.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5185.00mil 2560.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5130.00mil 2690.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5075.00mil 2625.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[6805.00mil 2560.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[6915.00mil 2625.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[6915.00mil 2560.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[6860.00mil 2690.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[6805.00mil 2625.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[6625.00mil 2680.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[6550.00mil 2680.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5995.00mil 2680.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[6075.00mil 2680.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5870.00mil 2355.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(2S)"]
+Via[5870.00mil 2455.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(2S)"]
+Via[5830.00mil 2405.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(2S)"]
+Via[5690.00mil 1715.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5830.00mil 1715.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5760.00mil 1775.00mil 24.02mil 12.00mil 0.0000 11.81mil "" "thermal(2S)"]
+Via[5835.00mil 1765.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(2S)"]
+Via[5685.00mil 1765.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(2S)"]
+Via[5965.00mil 1665.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(0S,2S)"]
+Via[5890.00mil 1665.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(0S,2S)"]
+Via[5890.00mil 1740.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(0S,2S)"]
+Via[5965.00mil 1740.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(0S,2S)"]
+Via[5960.00mil 1800.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(1S)"]
+Via[5735.00mil 1515.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5780.00mil 1510.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5915.00mil 1500.00mil 24.02mil 12.00mil 0.0000 11.81mil "" ""]
+Via[6465.00mil 1485.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[5950.00mil 1480.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[5880.00mil 1370.00mil 24.02mil 12.00mil 0.0000 11.81mil "" ""]
+Via[5880.00mil 1410.00mil 24.02mil 12.00mil 0.0000 11.81mil "" ""]
+Via[5645.00mil 1515.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[6060.00mil 1185.00mil 60.00mil 20.00mil 0.0000 35.00mil "" "thermal(0S)"]
+Via[6005.00mil 1135.00mil 60.00mil 20.00mil 0.0000 35.00mil "" "thermal(0S)"]
+Via[5950.00mil 1185.00mil 60.00mil 20.00mil 0.0000 35.00mil "" "thermal(0S)"]
+Via[5895.00mil 1135.00mil 60.00mil 20.00mil 0.0000 35.00mil "" "thermal(0S)"]
+Via[5960.00mil 1875.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5690.00mil 2025.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5755.00mil 2150.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[5620.00mil 1840.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[5635.00mil 1655.00mil 60.00mil 20.00mil 0.0000 35.00mil "" ""]
+Via[5545.00mil 1610.00mil 60.00mil 20.00mil 0.0000 35.00mil "" ""]
+Via[4160.00mil 1265.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[3605.00mil 1265.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[3050.00mil 1265.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[2495.00mil 1265.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[1940.00mil 1265.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[1915.00mil 2420.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(1S)"]
+Via[1915.00mil 2630.00mil 45.00mil 20.00mil 0.0000 25.00mil "" "thermal(1S)"]
+Via[2460.00mil 1615.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[2740.00mil 1615.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[2630.00mil 1615.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[4980.00mil 2360.00mil 60.00mil 20.00mil 0.0000 35.00mil "" ""]
+Via[4980.00mil 2430.00mil 60.00mil 20.00mil 0.0000 35.00mil "" ""]
+Via[3860.00mil 2665.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[2460.00mil 2385.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[2785.00mil 1200.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2250.00mil 2565.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2200.00mil 2690.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2150.00mil 2565.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2100.00mil 2690.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2050.00mil 2565.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2000.00mil 2690.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4945.00mil 2135.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4635.00mil 2565.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4495.00mil 2600.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4550.00mil 2500.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4895.00mil 2260.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4290.00mil 2455.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4645.00mil 2360.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4655.00mil 2300.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4225.00mil 1685.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[4155.00mil 2135.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[5325.00mil 2120.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[3765.00mil 1935.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[3135.00mil 1765.00mil 36.00mil 14.00mil 0.0000 20.00mil "" "thermal(1S)"]
+Via[2050.00mil 1860.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[2135.00mil 1860.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[2210.00mil 1860.00mil 45.00mil 20.00mil 0.0000 25.00mil "" ""]
+Via[3295.00mil 2595.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[3390.00mil 2655.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2710.00mil 2320.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2810.00mil 2320.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[3370.00mil 2580.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[3435.00mil 2550.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[2910.00mil 2320.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[3010.00mil 2320.00mil 36.00mil 14.00mil 0.0000 20.00mil "" ""]
+Via[5020.00mil 1850.00mil 60.00mil 20.00mil 0.0000 35.00mil "" "thermal(1S)"]
+
+Element["onsolder" "0603" "R5" "280_k" 6145.00mil 2030.00mil 6.50mil 96.50mil 3 77 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "R3" "118_k" 6085.00mil 1975.00mil -23.50mil 26.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C8" "0.15_uF" 6160.00mil 1950.00mil -11.50mil -23.50mil 0 77 "auto"]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "0612" "R7" "6_m" 6310.00mil 2635.00mil -20.00mil 75.00mil 0 100 ""]
+(
+	Pad[-1.3000mm -1.0500mm 1.3000mm -1.0500mm 1.4000mm 20.00mil 1.6500mm "1" "1" "square"]
+	Pad[-1.3000mm 1.0500mm 1.3000mm 1.0500mm 1.4000mm 20.00mil 1.6500mm "2" "2" "square"]
+
+	)
+
+Element["" "8-PowerTDFN_5_6" "Q4" "unknown" 6210.00mil 2385.00mil -65.00mil 135.00mil 0 77 ""]
+(
+	Pad[75.00mil -3.1010mm 75.00mil 0.6290mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,nopaste"]
+	Pad[75.00mil -3.0390mm 75.00mil -2.7810mm 20.00mil 20.00mil 20.00mil "D" "D" "square"]
+	Pad[25.00mil -3.1010mm 25.00mil 0.6290mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,nopaste"]
+	Pad[25.00mil -3.0390mm 25.00mil -2.7810mm 20.00mil 20.00mil 20.00mil "D" "D" "square"]
+	Pad[-25.00mil -3.1010mm -25.00mil 0.6290mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,nopaste"]
+	Pad[-25.00mil -3.0390mm -25.00mil -2.7810mm 20.00mil 20.00mil 20.00mil "D" "D" "square"]
+	Pad[-75.00mil -3.1010mm -75.00mil 0.6290mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,nopaste"]
+	Pad[-75.00mil -3.0390mm -75.00mil -2.7810mm 20.00mil 20.00mil 20.00mil "D" "D" "square"]
+	Pad[-0.3350mm -0.9410mm 0.3350mm -0.9410mm 4.0500mm 20.00mil 3.8500mm "D" "D" "square,nopaste"]
+	Pad[1.5690mm -1.8680mm 1.5690mm -1.3200mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[1.5690mm -0.2240mm 1.5690mm 0.3240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[0.5230mm -1.8680mm 0.5230mm -1.3200mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[0.5230mm -0.2240mm 0.5230mm 0.3240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[-0.5230mm -1.8680mm -0.5230mm -1.3200mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[-0.5230mm -0.2240mm -0.5230mm 0.3240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[-1.5690mm -1.8680mm -1.5690mm -1.3200mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[-1.5690mm -0.2240mm -1.5690mm 0.3240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[75.00mil 2.3230mm 75.00mil 2.9850mm 0.9100mm 20.00mil 0.7100mm "G" "G" "square,edge2,nopaste"]
+	Pad[75.00mil 2.5020mm 75.00mil 3.0120mm 0.5620mm 20.00mil 0.5620mm "G" "G" "square,edge2"]
+	Pad[25.00mil 2.3230mm 25.00mil 2.9850mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,edge2,nopaste"]
+	Pad[25.00mil 2.5020mm 25.00mil 3.0120mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square,edge2"]
+	Pad[-25.00mil 2.3230mm -25.00mil 2.9850mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,edge2,nopaste"]
+	Pad[-25.00mil 2.5020mm -25.00mil 3.0120mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square,edge2"]
+	Pad[-75.00mil 2.3230mm -75.00mil 2.9850mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,edge2,nopaste"]
+	Pad[-75.00mil 2.5020mm -75.00mil 3.0120mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square,edge2"]
+
+	)
+
+Element["" "8-PowerTDFN_5_6" "Q3" "unknown" 6610.00mil 2380.00mil 55.00mil -210.00mil 0 100 ""]
+(
+	Pad[-75.00mil -0.6290mm -75.00mil 3.1010mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,edge2,nopaste"]
+	Pad[-75.00mil 2.7810mm -75.00mil 3.0390mm 20.00mil 20.00mil 20.00mil "D" "D" "square,edge2"]
+	Pad[-25.00mil -0.6290mm -25.00mil 3.1010mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,edge2,nopaste"]
+	Pad[-25.00mil 2.7810mm -25.00mil 3.0390mm 20.00mil 20.00mil 20.00mil "D" "D" "square,edge2"]
+	Pad[25.00mil -0.6290mm 25.00mil 3.1010mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,edge2,nopaste"]
+	Pad[25.00mil 2.7810mm 25.00mil 3.0390mm 20.00mil 20.00mil 20.00mil "D" "D" "square,edge2"]
+	Pad[75.00mil -0.6290mm 75.00mil 3.1010mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,edge2,nopaste"]
+	Pad[75.00mil 2.7810mm 75.00mil 3.0390mm 20.00mil 20.00mil 20.00mil "D" "D" "square,edge2"]
+	Pad[-0.3350mm 0.9410mm 0.3350mm 0.9410mm 4.0500mm 20.00mil 3.8500mm "D" "D" "square,nopaste"]
+	Pad[-1.5690mm 1.3200mm -1.5690mm 1.8680mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[-1.5690mm -0.3240mm -1.5690mm 0.2240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[-0.5230mm 1.3200mm -0.5230mm 1.8680mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[-0.5230mm -0.3240mm -0.5230mm 0.2240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[0.5230mm 1.3200mm 0.5230mm 1.8680mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[0.5230mm -0.3240mm 0.5230mm 0.2240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[1.5690mm 1.3200mm 1.5690mm 1.8680mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[1.5690mm -0.3240mm 1.5690mm 0.2240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[-75.00mil -2.9850mm -75.00mil -2.3230mm 0.9100mm 20.00mil 0.7100mm "G" "G" "square,nopaste"]
+	Pad[-75.00mil -3.0120mm -75.00mil -2.5020mm 0.5620mm 20.00mil 0.5620mm "G" "G" "square"]
+	Pad[-25.00mil -2.9850mm -25.00mil -2.3230mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,nopaste"]
+	Pad[-25.00mil -3.0120mm -25.00mil -2.5020mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square"]
+	Pad[25.00mil -2.9850mm 25.00mil -2.3230mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,nopaste"]
+	Pad[25.00mil -3.0120mm 25.00mil -2.5020mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square"]
+	Pad[75.00mil -2.9850mm 75.00mil -2.3230mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,nopaste"]
+	Pad[75.00mil -3.0120mm 75.00mil -2.5020mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square"]
+
+	)
+
+Element["" "8-PowerTDFN_5_6" "Q1" "unknown" 6410.00mil 2385.00mil 15.00mil 140.00mil 0 77 ""]
+(
+	Pad[75.00mil -3.1010mm 75.00mil 0.6290mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,nopaste"]
+	Pad[75.00mil -3.0390mm 75.00mil -2.7810mm 20.00mil 20.00mil 20.00mil "D" "D" "square"]
+	Pad[25.00mil -3.1010mm 25.00mil 0.6290mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,nopaste"]
+	Pad[25.00mil -3.0390mm 25.00mil -2.7810mm 20.00mil 20.00mil 20.00mil "D" "D" "square"]
+	Pad[-25.00mil -3.1010mm -25.00mil 0.6290mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,nopaste"]
+	Pad[-25.00mil -3.0390mm -25.00mil -2.7810mm 20.00mil 20.00mil 20.00mil "D" "D" "square"]
+	Pad[-75.00mil -3.1010mm -75.00mil 0.6290mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,nopaste"]
+	Pad[-75.00mil -3.0390mm -75.00mil -2.7810mm 20.00mil 20.00mil 20.00mil "D" "D" "square"]
+	Pad[-0.3350mm -0.9410mm 0.3350mm -0.9410mm 4.0500mm 20.00mil 3.8500mm "D" "D" "square,nopaste"]
+	Pad[1.5690mm -1.8680mm 1.5690mm -1.3200mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[1.5690mm -0.2240mm 1.5690mm 0.3240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[0.5230mm -1.8680mm 0.5230mm -1.3200mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[0.5230mm -0.2240mm 0.5230mm 0.3240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[-0.5230mm -1.8680mm -0.5230mm -1.3200mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[-0.5230mm -0.2240mm -0.5230mm 0.3240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[-1.5690mm -1.8680mm -1.5690mm -1.3200mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[-1.5690mm -0.2240mm -1.5690mm 0.3240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[75.00mil 2.3230mm 75.00mil 2.9850mm 0.9100mm 20.00mil 0.7100mm "G" "G" "square,edge2,nopaste"]
+	Pad[75.00mil 2.5020mm 75.00mil 3.0120mm 0.5620mm 20.00mil 0.5620mm "G" "G" "square,edge2"]
+	Pad[25.00mil 2.3230mm 25.00mil 2.9850mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,edge2,nopaste"]
+	Pad[25.00mil 2.5020mm 25.00mil 3.0120mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square,edge2"]
+	Pad[-25.00mil 2.3230mm -25.00mil 2.9850mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,edge2,nopaste"]
+	Pad[-25.00mil 2.5020mm -25.00mil 3.0120mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square,edge2"]
+	Pad[-75.00mil 2.3230mm -75.00mil 2.9850mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,edge2,nopaste"]
+	Pad[-75.00mil 2.5020mm -75.00mil 3.0120mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square,edge2"]
+
+	)
+
+Element["" "8-PowerTDFN_5_6" "Q2" "unknown" 6010.00mil 2380.00mil -170.00mil -140.00mil 0 100 ""]
+(
+	Pad[-75.00mil -0.6290mm -75.00mil 3.1010mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,edge2,nopaste"]
+	Pad[-75.00mil 2.7810mm -75.00mil 3.0390mm 20.00mil 20.00mil 20.00mil "D" "D" "square,edge2"]
+	Pad[-25.00mil -0.6290mm -25.00mil 3.1010mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,edge2,nopaste"]
+	Pad[-25.00mil 2.7810mm -25.00mil 3.0390mm 20.00mil 20.00mil 20.00mil "D" "D" "square,edge2"]
+	Pad[25.00mil -0.6290mm 25.00mil 3.1010mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,edge2,nopaste"]
+	Pad[25.00mil 2.7810mm 25.00mil 3.0390mm 20.00mil 20.00mil 20.00mil "D" "D" "square,edge2"]
+	Pad[75.00mil -0.6290mm 75.00mil 3.1010mm 0.9100mm 20.00mil 0.7100mm "D" "D" "square,edge2,nopaste"]
+	Pad[75.00mil 2.7810mm 75.00mil 3.0390mm 20.00mil 20.00mil 20.00mil "D" "D" "square,edge2"]
+	Pad[-0.3350mm 0.9410mm 0.3350mm 0.9410mm 4.0500mm 20.00mil 3.8500mm "D" "D" "square,nopaste"]
+	Pad[-1.5690mm 1.3200mm -1.5690mm 1.8680mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[-1.5690mm -0.3240mm -1.5690mm 0.2240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[-0.5230mm 1.3200mm -0.5230mm 1.8680mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[-0.5230mm -0.3240mm -0.5230mm 0.2240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[0.5230mm 1.3200mm 0.5230mm 1.8680mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[0.5230mm -0.3240mm 0.5230mm 0.2240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[1.5690mm 1.3200mm 1.5690mm 1.8680mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square,edge2"]
+	Pad[1.5690mm -0.3240mm 1.5690mm 0.2240mm 0.7460mm 20.00mil 0.7460mm "D" "D" "square"]
+	Pad[-75.00mil -2.9850mm -75.00mil -2.3230mm 0.9100mm 20.00mil 0.7100mm "G" "G" "square,nopaste"]
+	Pad[-75.00mil -3.0120mm -75.00mil -2.5020mm 0.5620mm 20.00mil 0.5620mm "G" "G" "square"]
+	Pad[-25.00mil -2.9850mm -25.00mil -2.3230mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,nopaste"]
+	Pad[-25.00mil -3.0120mm -25.00mil -2.5020mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square"]
+	Pad[25.00mil -2.9850mm 25.00mil -2.3230mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,nopaste"]
+	Pad[25.00mil -3.0120mm 25.00mil -2.5020mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square"]
+	Pad[75.00mil -2.9850mm 75.00mil -2.3230mm 0.9100mm 20.00mil 0.7100mm "S" "S" "square,nopaste"]
+	Pad[75.00mil -3.0120mm 75.00mil -2.5020mm 0.5620mm 20.00mil 0.5620mm "S" "S" "square"]
+
+	)
+
+Element["" "1365" "L1" "2_uH" 6310.00mil 1900.00mil 345.00mil -235.00mil 0 100 ""]
+(
+	Pad[-5.2500mm -0.2500mm -5.2500mm 0.2500mm 4.8000mm 20.00mil 4.5000mm "1" "1" "square"]
+	Pad[5.2500mm -0.2500mm 5.2500mm 0.2500mm 4.8000mm 20.00mil 4.5000mm "2" "2" "square"]
+	ElementLine [-7.4000mm -4.0000mm -7.4000mm -8.4000mm 8.00mil]
+	ElementLine [-7.4000mm 4.0000mm -7.4000mm 8.4000mm 8.00mil]
+	ElementLine [7.4000mm -4.0000mm 7.4000mm -8.4000mm 8.00mil]
+	ElementLine [7.4000mm 4.0000mm 7.4000mm 8.4000mm 8.00mil]
+	ElementLine [7.4000mm 8.4000mm -7.4000mm 8.4000mm 8.00mil]
+	ElementLine [7.4000mm -8.4000mm -7.4000mm -8.4000mm 8.00mil]
+
+	)
+
+Element["" "CAP_D" "C7" "68_uF" 5130.00mil 2505.00mil -105.00mil 185.00mil 0 100 ""]
+(
+	Pad[0.0000 -3.3000mm 0.0000 -1.7000mm 1.6000mm 20.00mil 1.9000mm "+" "1" "square"]
+	Pad[0.0000 1.7000mm 0.0000 3.3000mm 1.6000mm 20.00mil 1.9000mm "-" "2" "square,edge2"]
+	ElementLine [1.5000mm 3.5500mm 3.7000mm 3.5500mm 0.5000mm]
+	ElementLine [-3.7000mm 3.5500mm -1.5000mm 3.5500mm 0.5000mm]
+	ElementLine [3.8250mm -2.4750mm 3.8250mm 3.0000mm 0.2500mm]
+	ElementLine [-3.8250mm -2.4750mm -3.8250mm 3.0000mm 0.2500mm]
+	ElementLine [-3.8250mm -2.4750mm -2.6250mm -3.6750mm 0.2500mm]
+	ElementLine [3.8250mm -2.4750mm 2.6250mm -3.6750mm 0.2500mm]
+	ElementLine [-2.6250mm -3.6750mm -1.5000mm -3.6750mm 0.2500mm]
+	ElementLine [1.5000mm -3.6750mm 2.6250mm -3.6750mm 0.2500mm]
+
+	)
+
+Element["" "CAP_D" "C6" "68_uF" 5445.00mil 2505.00mil -125.00mil 170.00mil 0 100 ""]
+(
+	Pad[0.0000 -3.3000mm 0.0000 -1.7000mm 1.6000mm 20.00mil 1.9000mm "+" "1" "square"]
+	Pad[0.0000 1.7000mm 0.0000 3.3000mm 1.6000mm 20.00mil 1.9000mm "-" "2" "square,edge2"]
+	ElementLine [1.5000mm 3.5500mm 3.7000mm 3.5500mm 0.5000mm]
+	ElementLine [-3.7000mm 3.5500mm -1.5000mm 3.5500mm 0.5000mm]
+	ElementLine [3.8250mm -2.4750mm 3.8250mm 3.0000mm 0.2500mm]
+	ElementLine [-3.8250mm -2.4750mm -3.8250mm 3.0000mm 0.2500mm]
+	ElementLine [-3.8250mm -2.4750mm -2.6250mm -3.6750mm 0.2500mm]
+	ElementLine [3.8250mm -2.4750mm 2.6250mm -3.6750mm 0.2500mm]
+	ElementLine [-2.6250mm -3.6750mm -1.5000mm -3.6750mm 0.2500mm]
+	ElementLine [1.5000mm -3.6750mm 2.6250mm -3.6750mm 0.2500mm]
+
+	)
+
+Element["" "CAP_D" "C3" "68_uF" 5760.00mil 2505.00mil -115.00mil 160.00mil 0 100 ""]
+(
+	Pad[0.0000 -3.3000mm 0.0000 -1.7000mm 1.6000mm 20.00mil 1.9000mm "+" "1" "square"]
+	Pad[0.0000 1.7000mm 0.0000 3.3000mm 1.6000mm 20.00mil 1.9000mm "-" "2" "square,edge2"]
+	ElementLine [1.5000mm 3.5500mm 3.7000mm 3.5500mm 0.5000mm]
+	ElementLine [-3.7000mm 3.5500mm -1.5000mm 3.5500mm 0.5000mm]
+	ElementLine [3.8250mm -2.4750mm 3.8250mm 3.0000mm 0.2500mm]
+	ElementLine [-3.8250mm -2.4750mm -3.8250mm 3.0000mm 0.2500mm]
+	ElementLine [-3.8250mm -2.4750mm -2.6250mm -3.6750mm 0.2500mm]
+	ElementLine [3.8250mm -2.4750mm 2.6250mm -3.6750mm 0.2500mm]
+	ElementLine [-2.6250mm -3.6750mm -1.5000mm -3.6750mm 0.2500mm]
+	ElementLine [1.5000mm -3.6750mm 2.6250mm -3.6750mm 0.2500mm]
+
+	)
+
+Element["" "0805" "C12" "10_uF" 6545.00mil 2595.00mil -61.50mil 88.50mil 0 100 ""]
+(
+	Pad[-3.93mil -35.43mil 3.93mil -35.43mil 51.18mil 20.00mil 57.18mil "1" "1" "square"]
+	Pad[-3.93mil 35.43mil 3.93mil 35.43mil 51.18mil 20.00mil 57.18mil "2" "2" "square"]
+	ElementLine [27.55mil -3.93mil 27.55mil 3.93mil 8.00mil]
+	ElementLine [-27.55mil -3.93mil -27.55mil 3.93mil 8.00mil]
+
+	)
+
+Element["" "0805" "C4" "10_uF" 6625.00mil 2595.00mil -6.50mil 83.50mil 0 100 ""]
+(
+	Pad[-3.93mil -35.43mil 3.93mil -35.43mil 51.18mil 20.00mil 57.18mil "1" "1" "square"]
+	Pad[-3.93mil 35.43mil 3.93mil 35.43mil 51.18mil 20.00mil 57.18mil "2" "2" "square"]
+	ElementLine [27.55mil -3.93mil 27.55mil 3.93mil 8.00mil]
+	ElementLine [-27.55mil -3.93mil -27.55mil 3.93mil 8.00mil]
+
+	)
+
+Element["" "CAP_D" "C5" "270_uF" 6860.00mil 2505.00mil -105.00mil 145.00mil 0 100 ""]
+(
+	Pad[0.0000 -3.3000mm 0.0000 -1.7000mm 1.6000mm 20.00mil 1.9000mm "+" "1" "square"]
+	Pad[0.0000 1.7000mm 0.0000 3.3000mm 1.6000mm 20.00mil 1.9000mm "-" "2" "square,edge2"]
+	ElementLine [1.5000mm 3.5500mm 3.7000mm 3.5500mm 0.5000mm]
+	ElementLine [-3.7000mm 3.5500mm -1.5000mm 3.5500mm 0.5000mm]
+	ElementLine [3.8250mm -2.4750mm 3.8250mm 3.0000mm 0.2500mm]
+	ElementLine [-3.8250mm -2.4750mm -3.8250mm 3.0000mm 0.2500mm]
+	ElementLine [-3.8250mm -2.4750mm -2.6250mm -3.6750mm 0.2500mm]
+	ElementLine [3.8250mm -2.4750mm 2.6250mm -3.6750mm 0.2500mm]
+	ElementLine [-2.6250mm -3.6750mm -1.5000mm -3.6750mm 0.2500mm]
+	ElementLine [1.5000mm -3.6750mm 2.6250mm -3.6750mm 0.2500mm]
+
+	)
+
+Element["onsolder" "0603" "C14" "0.1_uF" 6125.00mil 2175.00mil 21.50mil 146.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "SOD123F" "D2" "unknown" 6050.00mil 2115.00mil -55.00mil 50.00mil 3 100 "auto"]
+(
+	Pad[-0.2300mm -1.4300mm 0.2300mm -1.4300mm 1.3400mm 20.00mil 1.5600mm "1" "1" "onsolder,square"]
+	Pad[-0.2300mm 1.4300mm 0.2300mm 1.4300mm 1.3400mm 20.00mil 1.5600mm "2" "2" "onsolder,square"]
+	ElementLine [1.1500mm -1.6500mm 1.1500mm 1.6500mm 8.00mil]
+	ElementLine [-1.1500mm -1.6500mm -1.1500mm 1.6500mm 8.00mil]
+	ElementLine [-1.1500mm 1.3000mm -1.1500mm 1.3000mm 11.00mil]
+	ElementLine [1.1500mm 1.3000mm 1.1500mm 1.3000mm 11.00mil]
+
+	)
+
+Element["onsolder" "0603" "C15" "0.1_uF" 6445.00mil 2275.00mil 26.50mil 136.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "SOD123F" "D3" "unknown" 6585.00mil 2220.00mil 70.00mil 45.00mil 0 100 "auto"]
+(
+	Pad[-0.2300mm -1.4300mm 0.2300mm -1.4300mm 1.3400mm 20.00mil 1.5600mm "1" "1" "onsolder,square"]
+	Pad[-0.2300mm 1.4300mm 0.2300mm 1.4300mm 1.3400mm 20.00mil 1.5600mm "2" "2" "onsolder,square"]
+	ElementLine [1.1500mm -1.6500mm 1.1500mm 1.6500mm 8.00mil]
+	ElementLine [-1.1500mm -1.6500mm -1.1500mm 1.6500mm 8.00mil]
+	ElementLine [-1.1500mm 1.3000mm -1.1500mm 1.3000mm 11.00mil]
+	ElementLine [1.1500mm 1.3000mm 1.1500mm 1.3000mm 11.00mil]
+
+	)
+
+Element["onsolder" "QFN28_4_5_EP" "U1" "unknown" 6310.00mil 2095.00mil 5.00mil 75.00mil 0 100 "auto"]
+(
+	Pin[0.0000 0.0000 0.6500mm 20.00mil 0.0000 0.3000mm "PAD_GND" "29" "edge2,thermal(1S)"]
+	Pin[0.0000 0.9500mm 0.6500mm 20.00mil 0.0000 0.3000mm "PAD_GND" "29" "edge2,thermal(1S)"]
+	Pin[0.0000 -0.9500mm 0.6500mm 20.00mil 0.0000 0.3000mm "PAD_GND" "29" "edge2,thermal(1S)"]
+	Pin[1.4500mm 0.0000 0.6500mm 20.00mil 0.0000 0.3000mm "PAD_GND" "29" "edge2,thermal(1S)"]
+	Pin[-1.4500mm 0.0000 0.6500mm 20.00mil 0.0000 0.3000mm "PAD_GND" "29" "edge2,thermal(1S)"]
+	Pad[-68.90mil -81.88mil -68.90mil -67.72mil 9.45mil 20.00mil 13.25mil "MODE" "1" "onsolder,square"]
+	Pad[-49.21mil -81.88mil -49.21mil -67.72mil 9.45mil 20.00mil 13.25mil "DITH" "2" "onsolder,square"]
+	Pad[-29.53mil -81.88mil -29.53mil -67.72mil 9.45mil 20.00mil 13.25mil "RT/SYNC" "3" "onsolder,square"]
+	Pad[-9.84mil -81.88mil -9.84mil -67.72mil 9.45mil 20.00mil 13.25mil "SLOPE" "4" "onsolder,square"]
+	Pad[9.84mil -81.88mil 9.84mil -67.72mil 9.45mil 20.00mil 13.25mil "SS" "5" "onsolder,square"]
+	Pad[29.53mil -81.88mil 29.53mil -67.72mil 9.45mil 20.00mil 13.25mil "COMP" "6" "onsolder,square"]
+	Pad[49.21mil -81.88mil 49.21mil -67.72mil 9.45mil 20.00mil 13.25mil "AGND" "7" "onsolder,square"]
+	Pad[68.90mil -81.88mil 68.90mil -67.72mil 9.45mil 20.00mil 13.25mil "FB" "8" "onsolder,square"]
+	Pad[87.40mil -49.21mil 101.57mil -49.21mil 9.45mil 20.00mil 13.25mil "VOSNS" "9" "onsolder,square,octagon,edge2"]
+	Pad[87.40mil -29.53mil 101.57mil -29.53mil 9.45mil 20.00mil 13.25mil "ISNS(-)" "10" "onsolder,square,octagon,edge2"]
+	Pad[87.40mil -9.84mil 101.57mil -9.84mil 9.45mil 20.00mil 13.25mil "ISNS(+)" "11" "onsolder,square,octagon,edge2"]
+	Pad[87.40mil 9.84mil 101.57mil 9.84mil 9.45mil 20.00mil 13.25mil "CSG" "12" "onsolder,square,octagon,edge2"]
+	Pad[87.40mil 29.53mil 101.57mil 29.53mil 9.45mil 20.00mil 13.25mil "CS" "13" "onsolder,square,octagon,edge2"]
+	Pad[87.40mil 49.21mil 101.57mil 49.21mil 9.45mil 20.00mil 13.25mil "PGOOD" "14" "onsolder,square,octagon,edge2"]
+	Pad[68.90mil 67.72mil 68.90mil 81.88mil 9.45mil 20.00mil 13.25mil "SW2" "15" "onsolder,square,edge2"]
+	Pad[49.21mil 67.72mil 49.21mil 81.88mil 9.45mil 20.00mil 13.25mil "HDRV2" "16" "onsolder,square,edge2"]
+	Pad[29.53mil 67.72mil 29.53mil 81.88mil 9.45mil 20.00mil 13.25mil "BOOT2" "17" "onsolder,square,edge2"]
+	Pad[9.84mil 67.72mil 9.84mil 81.88mil 9.45mil 20.00mil 13.25mil "LDRV2" "18" "onsolder,square,edge2"]
+	Pad[-9.84mil 67.72mil -9.84mil 81.88mil 9.45mil 20.00mil 13.25mil "PGND" "19" "onsolder,square,edge2"]
+	Pad[-29.53mil 67.72mil -29.53mil 81.88mil 9.45mil 20.00mil 13.25mil "VCC" "20" "onsolder,square,edge2"]
+	Pad[-49.21mil 67.72mil -49.21mil 81.88mil 9.45mil 20.00mil 13.25mil "BIAS" "21" "onsolder,square,edge2"]
+	Pad[-68.90mil 67.72mil -68.90mil 81.88mil 9.45mil 20.00mil 13.25mil "LDRV1" "22" "onsolder,square,edge2"]
+	Pad[-101.57mil 49.21mil -87.40mil 49.21mil 9.45mil 20.00mil 13.25mil "BOOT1" "23" "onsolder,square,octagon"]
+	Pad[-101.57mil 29.53mil -87.40mil 29.53mil 9.45mil 20.00mil 13.25mil "HDRV1" "24" "onsolder,square,octagon"]
+	Pad[-101.57mil 9.84mil -87.40mil 9.84mil 9.45mil 20.00mil 13.25mil "SW1" "25" "onsolder,square,octagon"]
+	Pad[-101.57mil -9.84mil -87.40mil -9.84mil 9.45mil 20.00mil 13.25mil "EN/UVLO" "26" "onsolder,square,octagon"]
+	Pad[-101.57mil -29.53mil -87.40mil -29.53mil 9.45mil 20.00mil 13.25mil "VIN" "27" "onsolder,square,octagon"]
+	Pad[-101.57mil -49.21mil -87.40mil -49.21mil 9.45mil 20.00mil 13.25mil "VISNS" "28" "onsolder,square,octagon"]
+	Pad[-19.68mil 0.0000 19.69mil 0.0000 100.39mil 0.0000 104.19mil "PAD_GND" "29" "onsolder,square,edge2"]
+	ElementLine [-3.0038mm 98.57mil 3.0038mm 98.57mil 10.00mil]
+	ElementLine [-3.0038mm -98.57mil -3.0038mm 98.57mil 10.00mil]
+	ElementLine [-3.0038mm -98.57mil 3.0038mm -98.57mil 10.00mil]
+	ElementLine [3.0038mm -98.57mil 3.0038mm 98.57mil 10.00mil]
+	ElementLine [-3.0038mm -98.59mil -3.3848mm -113.59mil 10.00mil]
+
+	)
+
+Element["onsolder" "0603" "C9" "0.15_uF" 6230.00mil 2285.00mil 21.50mil 111.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C13" "1_uF" 6285.00mil 2285.00mil 31.50mil 141.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "0805" "C2" "10_uF" 6075.00mil 2595.00mil -26.50mil 108.50mil 0 100 ""]
+(
+	Pad[-3.93mil -35.43mil 3.93mil -35.43mil 51.18mil 20.00mil 57.18mil "1" "1" "square"]
+	Pad[-3.93mil 35.43mil 3.93mil 35.43mil 51.18mil 20.00mil 57.18mil "2" "2" "square"]
+	ElementLine [27.55mil -3.93mil 27.55mil 3.93mil 8.00mil]
+	ElementLine [-27.55mil -3.93mil -27.55mil 3.93mil 8.00mil]
+
+	)
+
+Element["" "0805" "C1" "10_uF" 5995.00mil 2595.00mil -81.50mil 68.50mil 0 100 ""]
+(
+	Pad[-3.93mil -35.43mil 3.93mil -35.43mil 51.18mil 20.00mil 57.18mil "1" "1" "square"]
+	Pad[-3.93mil 35.43mil 3.93mil 35.43mil 51.18mil 20.00mil 57.18mil "2" "2" "square"]
+	ElementLine [27.55mil -3.93mil 27.55mil 3.93mil 8.00mil]
+	ElementLine [-27.55mil -3.93mil -27.55mil 3.93mil 8.00mil]
+
+	)
+
+Element["onsolder" "0603" "R2" "23.7_k" 6195.00mil 1845.00mil -111.50mil 21.50mil 0 77 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "R1" "93.1_k" 6195.00mil 1760.00mil -106.50mil 26.50mil 0 100 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "R9" "100" 6540.00mil 2025.00mil 63.50mil 26.50mil 0 100 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "R8" "100" 6540.00mil 2080.00mil 58.50mil 31.50mil 0 100 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C16" "47_pF" 6465.00mil 2060.00mil 71.50mil 171.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "R6" "118_k" 6485.00mil 1970.00mil 58.50mil 11.50mil 0 100 "auto"]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0805" "C11" "22_nF" 6365.00mil 1765.00mil 73.50mil 21.50mil 0 100 "auto"]
+(
+	Pad[35.43mil -3.93mil 35.43mil 3.93mil 51.18mil 20.00mil 57.18mil "1" "1" "onsolder,square"]
+	Pad[-35.43mil -3.93mil -35.43mil 3.93mil 51.18mil 20.00mil 57.18mil "2" "2" "onsolder,square"]
+	ElementLine [-3.93mil -27.55mil 3.93mil -27.55mil 8.00mil]
+	ElementLine [-3.93mil 27.55mil 3.93mil 27.55mil 8.00mil]
+
+	)
+
+Element["onsolder" "0603" "C10" "68_pF" 6270.00mil 1805.00mil 26.50mil -83.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "R4" "20_k" 6450.00mil 1895.00mil 76.50mil 16.50mil 3 76 "auto"]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C18" "220_pF" 6375.00mil 1925.00mil -111.50mil 21.50mil 0 76 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C17" "10_nF" 6340.00mil 1850.00mil -96.50mil 56.50mil 0 77 "auto"]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "R10" "5.49_k" 6400.00mil 1850.00mil 53.50mil -8.50mil 0 77 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "22-23-2061" "CONN201" "unknown" 6245.00mil 1350.00mil -157.00mil -253.00mil 0 100 ""]
+(
+	Pin[250.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square,edge2"]
+	Pin[150.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" "edge2"]
+	Pin[50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "3" "3" "edge2"]
+	Pin[-50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "4" "4" "edge2"]
+	Pin[-150.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "5" "5" "edge2"]
+	Pin[-250.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "6" "6" "edge2"]
+	ElementLine [312.00mil -143.00mil 312.00mil 147.00mil 10.00mil]
+	ElementLine [-312.00mil -143.00mil -312.00mil 147.00mil 10.00mil]
+	ElementLine [-312.00mil 147.00mil 312.00mil 147.00mil 10.00mil]
+	ElementLine [-312.00mil 57.00mil 312.00mil 57.00mil 10.00mil]
+	ElementLine [200.00mil -143.00mil 200.00mil 57.00mil 10.00mil]
+	ElementLine [100.00mil -143.00mil 100.00mil 57.00mil 10.00mil]
+	ElementLine [0.0000 -143.00mil 0.0000 57.00mil 10.00mil]
+	ElementLine [-100.00mil -143.00mil -100.00mil 57.00mil 10.00mil]
+	ElementLine [-200.00mil -143.00mil -200.00mil 57.00mil 10.00mil]
+	ElementLine [-312.00mil -143.00mil 312.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["" "teensy3.5" "U101" "unknown" 3610.00mil 2225.00mil -1015.00mil 65.00mil 3 100 ""]
+(
+	Pin[-1150.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "GND" "1" "square,edge2,thermal(1X)"]
+	Pin[-1050.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P0" "2" "edge2"]
+	Pin[-950.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P1" "3" "edge2"]
+	Pin[-850.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P2" "4" "edge2"]
+	Pin[-750.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P3" "5" "edge2"]
+	Pin[-650.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P4" "6" "edge2"]
+	Pin[-550.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P5" "7" "edge2"]
+	Pin[-450.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P6" "8" "edge2"]
+	Pin[-350.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P7" "9" "edge2"]
+	Pin[-250.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P8" "10" "edge2"]
+	Pin[-150.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P9" "11" "edge2"]
+	Pin[-50.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P10" "12" "edge2"]
+	Pin[50.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P11" "13" "edge2"]
+	Pin[150.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P12" "14" "edge2"]
+	Pin[250.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "V3.3" "15" "edge2"]
+	Pin[350.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P24" "16" "edge2"]
+	Pin[450.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P25" "17" "edge2"]
+	Pin[550.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P26" "18" "edge2"]
+	Pin[650.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P27" "19" "edge2"]
+	Pin[750.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P28" "20" "edge2"]
+	Pin[850.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P29" "21" "edge2"]
+	Pin[950.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P30" "22" "edge2"]
+	Pin[1050.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P31" "23" "edge2"]
+	Pin[1150.00mil 600.00mil 60.00mil 30.00mil 66.00mil 38.00mil "P32" "24" "edge2"]
+	Pin[1150.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P33" "25" "edge2"]
+	Pin[1050.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P34" "26" "edge2"]
+	Pin[950.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P35" "27" "edge2"]
+	Pin[850.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P36" "28" "edge2"]
+	Pin[750.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P37" "29" "edge2"]
+	Pin[650.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P38" "30" "edge2"]
+	Pin[550.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P39" "31" "edge2"]
+	Pin[450.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "A21" "32" "edge2"]
+	Pin[350.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "A22" "33" "edge2"]
+	Pin[250.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "GND" "34" "edge2,thermal(1X)"]
+	Pin[150.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P13" "35" "edge2"]
+	Pin[50.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P14" "36" "edge2"]
+	Pin[-50.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P15" "37" "edge2"]
+	Pin[-150.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P16" "38" "edge2"]
+	Pin[-250.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P17" "39" "edge2"]
+	Pin[-350.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P18" "40" "edge2"]
+	Pin[-450.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P19" "41" "edge2"]
+	Pin[-550.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P20" "42" "edge2"]
+	Pin[-650.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P21" "43" "edge2"]
+	Pin[-750.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P22" "44" "edge2"]
+	Pin[-850.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "P23" "45" "edge2"]
+	Pin[-950.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "3V3" "46" "edge2"]
+	Pin[-1050.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "AGND" "47" "edge2"]
+	Pin[-1150.00mil 0.0000 60.00mil 30.00mil 66.00mil 38.00mil "VIN" "48" "edge2"]
+	ElementLine [-1200.00mil 50.00mil 1200.00mil 50.00mil 10.00mil]
+	ElementLine [1200.00mil -50.00mil -1200.00mil -50.00mil 10.00mil]
+	ElementLine [-1200.00mil 50.00mil -1200.00mil -50.00mil 10.00mil]
+	ElementLine [-1100.00mil 50.00mil -1100.00mil -50.00mil 10.00mil]
+	ElementLine [-1000.00mil 50.00mil -1000.00mil -50.00mil 10.00mil]
+	ElementLine [-900.00mil 50.00mil -900.00mil -50.00mil 10.00mil]
+	ElementLine [-800.00mil 50.00mil -800.00mil -50.00mil 10.00mil]
+	ElementLine [-700.00mil 50.00mil -700.00mil -50.00mil 10.00mil]
+	ElementLine [-600.00mil 50.00mil -600.00mil -50.00mil 10.00mil]
+	ElementLine [-500.00mil 50.00mil -500.00mil -50.00mil 10.00mil]
+	ElementLine [-400.00mil 50.00mil -400.00mil -50.00mil 10.00mil]
+	ElementLine [-300.00mil 50.00mil -300.00mil -50.00mil 10.00mil]
+	ElementLine [-200.00mil 50.00mil -200.00mil -50.00mil 10.00mil]
+	ElementLine [-100.00mil 50.00mil -100.00mil -50.00mil 10.00mil]
+	ElementLine [0.0000 50.00mil 0.0000 -50.00mil 10.00mil]
+	ElementLine [100.00mil 50.00mil 100.00mil -50.00mil 10.00mil]
+	ElementLine [200.00mil 50.00mil 200.00mil -50.00mil 10.00mil]
+	ElementLine [300.00mil 50.00mil 300.00mil -50.00mil 10.00mil]
+	ElementLine [400.00mil 50.00mil 400.00mil -50.00mil 10.00mil]
+	ElementLine [500.00mil 50.00mil 500.00mil -50.00mil 10.00mil]
+	ElementLine [600.00mil 50.00mil 600.00mil -50.00mil 10.00mil]
+	ElementLine [700.00mil 50.00mil 700.00mil -50.00mil 10.00mil]
+	ElementLine [800.00mil 50.00mil 800.00mil -50.00mil 10.00mil]
+	ElementLine [900.00mil 50.00mil 900.00mil -50.00mil 10.00mil]
+	ElementLine [1000.00mil 50.00mil 1000.00mil -50.00mil 10.00mil]
+	ElementLine [1100.00mil 50.00mil 1100.00mil -50.00mil 10.00mil]
+	ElementLine [1200.00mil 50.00mil 1200.00mil -50.00mil 10.00mil]
+	ElementLine [-1200.00mil 650.00mil 1200.00mil 650.00mil 10.00mil]
+	ElementLine [1200.00mil 550.00mil -1200.00mil 550.00mil 10.00mil]
+	ElementLine [-1200.00mil 650.00mil -1200.00mil 550.00mil 10.00mil]
+	ElementLine [-1100.00mil 650.00mil -1100.00mil 550.00mil 10.00mil]
+	ElementLine [-1000.00mil 650.00mil -1000.00mil 550.00mil 10.00mil]
+	ElementLine [-900.00mil 650.00mil -900.00mil 550.00mil 10.00mil]
+	ElementLine [-800.00mil 650.00mil -800.00mil 550.00mil 10.00mil]
+	ElementLine [-700.00mil 650.00mil -700.00mil 550.00mil 10.00mil]
+	ElementLine [-600.00mil 650.00mil -600.00mil 550.00mil 10.00mil]
+	ElementLine [-500.00mil 650.00mil -500.00mil 550.00mil 10.00mil]
+	ElementLine [-400.00mil 650.00mil -400.00mil 550.00mil 10.00mil]
+	ElementLine [-300.00mil 650.00mil -300.00mil 550.00mil 10.00mil]
+	ElementLine [-200.00mil 650.00mil -200.00mil 550.00mil 10.00mil]
+	ElementLine [-100.00mil 650.00mil -100.00mil 550.00mil 10.00mil]
+	ElementLine [0.0000 650.00mil 0.0000 550.00mil 10.00mil]
+	ElementLine [100.00mil 650.00mil 100.00mil 550.00mil 10.00mil]
+	ElementLine [200.00mil 650.00mil 200.00mil 550.00mil 10.00mil]
+	ElementLine [300.00mil 650.00mil 300.00mil 550.00mil 10.00mil]
+	ElementLine [400.00mil 650.00mil 400.00mil 550.00mil 10.00mil]
+	ElementLine [500.00mil 650.00mil 500.00mil 550.00mil 10.00mil]
+	ElementLine [600.00mil 650.00mil 600.00mil 550.00mil 10.00mil]
+	ElementLine [700.00mil 650.00mil 700.00mil 550.00mil 10.00mil]
+	ElementLine [800.00mil 650.00mil 800.00mil 550.00mil 10.00mil]
+	ElementLine [900.00mil 650.00mil 900.00mil 550.00mil 10.00mil]
+	ElementLine [1000.00mil 650.00mil 1000.00mil 550.00mil 10.00mil]
+	ElementLine [1100.00mil 650.00mil 1100.00mil 550.00mil 10.00mil]
+	ElementLine [1200.00mil 650.00mil 1200.00mil 550.00mil 10.00mil]
+
+	)
+
+Element["onsolder" "0603" "C102" "0.15_uF" 3860.00mil 2725.00mil 91.50mil 36.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C101" "0.15_uF" 2460.00mil 2325.00mil 86.50mil 56.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "DO214AA" "D1" "unknown" 6730.00mil 1620.00mil -20.00mil 145.00mil 0 100 "auto"]
+(
+	Pad[-75.00mil -13.00mil -75.00mil 13.00mil 70.00mil 20.00mil 84.00mil "2" "2" "onsolder,square"]
+	Pad[75.00mil -13.00mil 75.00mil 13.00mil 70.00mil 20.00mil 84.00mil "1" "1" "onsolder,square"]
+	ElementLine [-90.00mil -77.50mil 90.00mil -77.50mil 8.00mil]
+	ElementLine [-90.00mil 77.50mil 90.00mil 77.50mil 8.00mil]
+	ElementLine [-75.00mil -65.00mil -75.00mil -72.50mil 15.00mil]
+	ElementLine [-65.00mil -65.00mil -65.00mil -72.50mil 15.00mil]
+	ElementLine [-75.00mil -65.00mil -65.00mil -65.00mil 15.00mil]
+	ElementLine [-75.00mil 72.50mil -75.00mil 65.00mil 15.00mil]
+	ElementLine [-65.00mil 72.50mil -65.00mil 65.00mil 15.00mil]
+	ElementLine [-75.00mil 65.00mil -65.00mil 65.00mil 15.00mil]
+
+	)
+
+Element["" "1825640000" "CONN315" "unknown" 6730.00mil 1260.00mil -115.00mil -165.00mil 0 100 ""]
+(
+	Pin[-1.7500mm 0.0000 1.6000mm 20.00mil 1.8500mm 1.1000mm "1" "1" "thermal(2S)"]
+	Pin[1.7500mm 0.0000 1.6000mm 20.00mil 1.8500mm 1.1000mm "2" "2" "thermal(1S)"]
+	Pin[-1.7500mm 5.5000mm 1.6000mm 20.00mil 1.8500mm 1.1000mm "1" "1" "thermal(2S)"]
+	Pin[1.7500mm 5.5000mm 1.6000mm 20.00mil 1.8500mm 1.1000mm "2" "2" "thermal(1S)"]
+	ElementLine [-3.3500mm -1.4000mm 3.3500mm -1.4000mm 8.00mil]
+	ElementLine [-3.3500mm 6.9000mm 3.3500mm 6.9000mm 8.00mil]
+	ElementLine [-3.3500mm -1.4000mm -3.3500mm 6.9000mm 8.00mil]
+	ElementLine [3.3500mm -1.4000mm 3.3500mm 6.9000mm 8.00mil]
+	ElementLine [-2.4500mm 4.3000mm -1.0500mm 4.3000mm 8.00mil]
+	ElementLine [-1.0500mm 2.9000mm -1.0500mm 4.3000mm 8.00mil]
+	ElementLine [-2.4500mm 2.9000mm -1.0500mm 2.9000mm 8.00mil]
+	ElementLine [-2.4500mm 2.9000mm -2.4500mm 4.3000mm 8.00mil]
+	ElementLine [1.0500mm 4.3000mm 2.4500mm 4.3000mm 8.00mil]
+	ElementLine [1.0500mm 2.9000mm 1.0500mm 4.3000mm 8.00mil]
+	ElementLine [1.0500mm 2.9000mm 2.4500mm 2.9000mm 8.00mil]
+	ElementLine [2.4500mm 2.9000mm 2.4500mm 4.3000mm 8.00mil]
+	ElementArc [-1.7500mm 1.8000mm 0.7000mm 0.7000mm 0 360 8.00mil]
+	ElementArc [1.7500mm 1.8000mm 0.7000mm 0.7000mm 0 360 8.00mil]
+
+	)
+
+Element["onsolder" "SOT25" "U202" "unknown" 5925.00mil 1330.00mil -40.00mil -20.00mil 0 100 "auto"]
+(
+	Pad[-8.00mil 0.0000 8.00mil 0.0000 24.00mil 30.00mil 30.00mil "1" "1" "onsolder,square,edge2"]
+	Pad[-8.00mil 78.00mil 8.00mil 78.00mil 24.00mil 30.00mil 30.00mil "A" "2" "onsolder,square,edge2"]
+	Pad[-90.00mil 78.00mil -74.00mil 78.00mil 24.00mil 30.00mil 30.00mil "GND" "3" "onsolder,square"]
+	Pad[-90.00mil 39.00mil -74.00mil 39.00mil 24.00mil 30.00mil 30.00mil "Y" "4" "onsolder,square"]
+	Pad[-90.00mil 0.0000 -74.00mil 0.0000 24.00mil 30.00mil 30.00mil "VCC" "5" "onsolder,square"]
+	ElementLine [-110.00mil -20.00mil 29.00mil -20.00mil 10.00mil]
+	ElementLine [29.00mil -20.00mil 29.00mil 98.00mil 10.00mil]
+	ElementLine [-110.00mil 98.00mil 29.00mil 98.00mil 10.00mil]
+	ElementLine [-110.00mil -20.00mil -110.00mil 98.00mil 10.00mil]
+
+	)
+
+Element["onsolder" "0603" "C202" "0.15_uF" 6445.00mil 1435.00mil -136.50mil 86.50mil 0 100 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "SO16W" "U201" "unknown" 5785.00mil 1755.00mil 225.00mil -55.00mil 0 100 "auto"]
+(
+	Pad[-175.00mil -210.00mil -175.00mil -150.00mil 20.00mil 10.00mil 30.00mil "VDD1" "1" "onsolder,square"]
+	Pad[-125.00mil -210.00mil -125.00mil -150.00mil 20.00mil 10.00mil 30.00mil "GND1-1" "2" "onsolder,square"]
+	Pad[-75.00mil -210.00mil -75.00mil -150.00mil 20.00mil 10.00mil 30.00mil "A1" "3" "onsolder,square"]
+	Pad[-25.00mil -210.00mil -25.00mil -150.00mil 20.00mil 10.00mil 30.00mil "A2" "4" "onsolder,square"]
+	Pad[25.00mil -210.00mil 25.00mil -150.00mil 20.00mil 10.00mil 30.00mil "A3" "5" "onsolder,square"]
+	Pad[75.00mil -210.00mil 75.00mil -150.00mil 20.00mil 10.00mil 30.00mil "A4" "6" "onsolder,square"]
+	Pad[125.00mil -210.00mil 125.00mil -150.00mil 20.00mil 10.00mil 30.00mil "EN1" "7" "onsolder,square"]
+	Pad[175.00mil -210.00mil 175.00mil -150.00mil 20.00mil 10.00mil 30.00mil "GND1-2" "8" "onsolder,square"]
+	Pad[175.00mil 150.00mil 175.00mil 210.00mil 20.00mil 10.00mil 30.00mil "GND2-2" "9" "onsolder,square,edge2"]
+	Pad[125.00mil 150.00mil 125.00mil 210.00mil 20.00mil 10.00mil 30.00mil "EN2" "10" "onsolder,square,edge2"]
+	Pad[75.00mil 150.00mil 75.00mil 210.00mil 20.00mil 10.00mil 30.00mil "B4" "11" "onsolder,square,edge2"]
+	Pad[25.00mil 150.00mil 25.00mil 210.00mil 20.00mil 10.00mil 30.00mil "B3" "12" "onsolder,square,edge2"]
+	Pad[-25.00mil 150.00mil -25.00mil 210.00mil 20.00mil 10.00mil 30.00mil "B2" "13" "onsolder,square,edge2"]
+	Pad[-75.00mil 150.00mil -75.00mil 210.00mil 20.00mil 10.00mil 30.00mil "B1" "14" "onsolder,square,edge2"]
+	Pad[-125.00mil 150.00mil -125.00mil 210.00mil 20.00mil 10.00mil 30.00mil "GND2-1" "15" "onsolder,square,edge2"]
+	Pad[-175.00mil 150.00mil -175.00mil 210.00mil 20.00mil 10.00mil 30.00mil "VDD2" "16" "onsolder,square,edge2"]
+	ElementLine [-195.00mil -230.00mil 195.00mil -230.00mil 10.00mil]
+	ElementLine [195.00mil -230.00mil 195.00mil 230.00mil 10.00mil]
+	ElementLine [-195.00mil 230.00mil 195.00mil 230.00mil 10.00mil]
+	ElementLine [-195.00mil -230.00mil -195.00mil -25.00mil 10.00mil]
+	ElementLine [-195.00mil 25.00mil -195.00mil 230.00mil 10.00mil]
+	ElementArc [-195.00mil 0.0000 25.00mil 25.00mil 90 180 10.00mil]
+
+	)
+
+Element["" "1825640000" "CONN316" "unknown" 5760.00mil 1260.00mil -105.00mil -155.00mil 0 77 ""]
+(
+	Pin[-1.7500mm 0.0000 1.6000mm 20.00mil 1.8500mm 1.1000mm "1" "1" ""]
+	Pin[1.7500mm 0.0000 1.6000mm 20.00mil 1.8500mm 1.1000mm "2" "2" "thermal(1X)"]
+	Pin[-1.7500mm 5.5000mm 1.6000mm 20.00mil 1.8500mm 1.1000mm "1" "1" ""]
+	Pin[1.7500mm 5.5000mm 1.6000mm 20.00mil 1.8500mm 1.1000mm "2" "2" "thermal(1X)"]
+	ElementLine [-3.3500mm -1.4000mm 3.3500mm -1.4000mm 8.00mil]
+	ElementLine [-3.3500mm 6.9000mm 3.3500mm 6.9000mm 8.00mil]
+	ElementLine [-3.3500mm -1.4000mm -3.3500mm 6.9000mm 8.00mil]
+	ElementLine [3.3500mm -1.4000mm 3.3500mm 6.9000mm 8.00mil]
+	ElementLine [-2.4500mm 4.3000mm -1.0500mm 4.3000mm 8.00mil]
+	ElementLine [-1.0500mm 4.3000mm -1.0500mm 2.9000mm 8.00mil]
+	ElementLine [-1.0500mm 2.9000mm -2.4500mm 2.9000mm 8.00mil]
+	ElementLine [-2.4500mm 2.9000mm -2.4500mm 4.3000mm 8.00mil]
+	ElementLine [2.4500mm 4.3000mm 1.0500mm 4.3000mm 8.00mil]
+	ElementLine [1.0500mm 4.3000mm 1.0500mm 2.9000mm 8.00mil]
+	ElementLine [1.0500mm 2.9000mm 2.4500mm 2.9000mm 8.00mil]
+	ElementLine [2.4500mm 2.9000mm 2.4500mm 4.3000mm 8.00mil]
+	ElementArc [-1.7500mm 1.8000mm 0.7000mm 0.7000mm 0 360 8.00mil]
+	ElementArc [1.7500mm 1.8000mm 0.7000mm 0.7000mm 0 360 8.00mil]
+
+	)
+
+Element["" "UE27AEX4X0X" "CONN313" "unknown" 5545.00mil 1840.00mil 115.00mil 40.00mil 3 100 ""]
+(
+	Pin[0.0000 -3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "VBUS" "1" ""]
+	Pin[0.0000 -1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D-" "2" ""]
+	Pin[0.0000 1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D+" "3" ""]
+	Pin[0.0000 3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "GND" "4" "thermal(1X)"]
+	Pin[-2.7100mm -6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	Pin[-2.7100mm 6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	ElementLine [1.5000mm -7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm 7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm -7.2500mm 1.5000mm -7.2500mm 8.00mil]
+	ElementLine [-4.2200mm -5.5000mm -4.2200mm 5.5000mm 8.00mil]
+
+	)
+
+Element["" "UE27AEX4X0X" "CONN314" "unknown" 5285.00mil 1840.00mil -170.00mil 205.00mil 3 54 ""]
+(
+	Pin[0.0000 -3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "VBUS" "1" ""]
+	Pin[0.0000 -1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D-" "2" ""]
+	Pin[0.0000 1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D+" "3" ""]
+	Pin[0.0000 3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "GND" "4" "thermal(1X)"]
+	Pin[-2.7100mm -6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	Pin[-2.7100mm 6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	ElementLine [1.5000mm -7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm 7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm -7.2500mm 1.5000mm -7.2500mm 8.00mil]
+	ElementLine [-4.2200mm -5.5000mm -4.2200mm 5.5000mm 8.00mil]
+
+	)
+
+Element["" "22-23-2021" "CONN303" "unknown" 5235.00mil 1350.00mil -77.00mil -253.00mil 0 77 ""]
+(
+	Pin[50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square"]
+	Pin[-50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" ""]
+	ElementLine [112.00mil -143.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil -112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 147.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 57.00mil 112.00mil 57.00mil 10.00mil]
+	ElementLine [0.0000 -143.00mil 0.0000 57.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil 112.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["" "22-23-2021" "CONN301" "unknown" 5490.00mil 1350.00mil -67.00mil -253.00mil 0 77 ""]
+(
+	Pin[50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square"]
+	Pin[-50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" ""]
+	ElementLine [112.00mil -143.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil -112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 147.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 57.00mil 112.00mil 57.00mil 10.00mil]
+	ElementLine [0.0000 -143.00mil 0.0000 57.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil 112.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["" "22-23-2021" "CONN403" "unknown" 4460.00mil 1350.00mil -112.00mil -258.00mil 0 77 ""]
+(
+	Pin[50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square"]
+	Pin[-50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" ""]
+	ElementLine [112.00mil -143.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil -112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 147.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 57.00mil 112.00mil 57.00mil 10.00mil]
+	ElementLine [0.0000 -143.00mil 0.0000 57.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil 112.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["" "22-23-2021" "CONN402" "unknown" 4715.00mil 1350.00mil -77.00mil -258.00mil 0 77 ""]
+(
+	Pin[50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square"]
+	Pin[-50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" ""]
+	ElementLine [112.00mil -143.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil -112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 147.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 57.00mil 112.00mil 57.00mil 10.00mil]
+	ElementLine [0.0000 -143.00mil 0.0000 57.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil 112.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["" "22-23-2021" "CONN401" "unknown" 4970.00mil 1350.00mil -87.00mil -258.00mil 0 77 ""]
+(
+	Pin[50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square"]
+	Pin[-50.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" ""]
+	ElementLine [112.00mil -143.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil -112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 147.00mil 112.00mil 147.00mil 10.00mil]
+	ElementLine [-112.00mil 57.00mil 112.00mil 57.00mil 10.00mil]
+	ElementLine [0.0000 -143.00mil 0.0000 57.00mil 10.00mil]
+	ElementLine [-112.00mil -143.00mil 112.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["" "UE27AEX4X0X" "CONN312" "unknown" 4100.00mil 1840.00mil 130.00mil 5.00mil 3 100 ""]
+(
+	Pin[0.0000 -3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "VBUS" "1" ""]
+	Pin[0.0000 -1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D-" "2" ""]
+	Pin[0.0000 1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D+" "3" ""]
+	Pin[0.0000 3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "GND" "4" "thermal(1X)"]
+	Pin[-2.7100mm -6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	Pin[-2.7100mm 6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	ElementLine [1.5000mm -7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm 7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm -7.2500mm 1.5000mm -7.2500mm 8.00mil]
+	ElementLine [-4.2200mm -5.5000mm -4.2200mm 5.5000mm 8.00mil]
+
+	)
+
+Element["" "22-23-2051" "CONN307" "unknown" 4045.00mil 1350.00mil -177.00mil -253.00mil 0 100 ""]
+(
+	Pin[200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square,edge2"]
+	Pin[100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" "edge2"]
+	Pin[0.0000 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "3" "3" "edge2"]
+	Pin[-100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "4" "4" "edge2"]
+	Pin[-200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "5" "5" "edge2"]
+	ElementLine [262.00mil -143.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil -262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 147.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 57.00mil 262.00mil 57.00mil 10.00mil]
+	ElementLine [150.00mil -143.00mil 150.00mil 57.00mil 10.00mil]
+	ElementLine [50.00mil -143.00mil 50.00mil 57.00mil 10.00mil]
+	ElementLine [-50.00mil -143.00mil -50.00mil 57.00mil 10.00mil]
+	ElementLine [-150.00mil -143.00mil -150.00mil 57.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil 262.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["" "22-23-2051" "CONN306" "unknown" 3490.00mil 1350.00mil -197.00mil -253.00mil 0 100 ""]
+(
+	Pin[200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square,edge2"]
+	Pin[100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" "edge2"]
+	Pin[0.0000 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "3" "3" "edge2"]
+	Pin[-100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "4" "4" "edge2"]
+	Pin[-200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "5" "5" "edge2"]
+	ElementLine [262.00mil -143.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil -262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 147.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 57.00mil 262.00mil 57.00mil 10.00mil]
+	ElementLine [150.00mil -143.00mil 150.00mil 57.00mil 10.00mil]
+	ElementLine [50.00mil -143.00mil 50.00mil 57.00mil 10.00mil]
+	ElementLine [-50.00mil -143.00mil -50.00mil 57.00mil 10.00mil]
+	ElementLine [-150.00mil -143.00mil -150.00mil 57.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil 262.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["onsolder" "SO16" "U302" "unknown" 2125.00mil 2525.00mil 220.00mil 65.00mil 0 100 "auto"]
+(
+	Pad[175.00mil 70.00mil 175.00mil 135.00mil 20.00mil 10.00mil 30.00mil "1B" "1" "onsolder,square,edge2"]
+	Pad[125.00mil 70.00mil 125.00mil 135.00mil 20.00mil 10.00mil 30.00mil "2B" "2" "onsolder,square,edge2"]
+	Pad[75.00mil 70.00mil 75.00mil 135.00mil 20.00mil 10.00mil 30.00mil "3B" "3" "onsolder,square,edge2"]
+	Pad[25.00mil 70.00mil 25.00mil 135.00mil 20.00mil 10.00mil 30.00mil "4B" "4" "onsolder,square,edge2"]
+	Pad[-25.00mil 70.00mil -25.00mil 135.00mil 20.00mil 10.00mil 30.00mil "5B" "5" "onsolder,square,edge2"]
+	Pad[-75.00mil 70.00mil -75.00mil 135.00mil 20.00mil 10.00mil 30.00mil "6B" "6" "onsolder,square,edge2"]
+	Pad[-125.00mil 70.00mil -125.00mil 135.00mil 20.00mil 10.00mil 30.00mil "7B" "7" "onsolder,square,edge2"]
+	Pad[-175.00mil 70.00mil -175.00mil 135.00mil 20.00mil 10.00mil 30.00mil "E" "8" "onsolder,square,edge2"]
+	Pad[-175.00mil -135.00mil -175.00mil -70.00mil 20.00mil 10.00mil 30.00mil "COM" "9" "onsolder,square"]
+	Pad[-125.00mil -135.00mil -125.00mil -70.00mil 20.00mil 10.00mil 30.00mil "7C" "10" "onsolder,square"]
+	Pad[-75.00mil -135.00mil -75.00mil -70.00mil 20.00mil 10.00mil 30.00mil "6C" "11" "onsolder,square"]
+	Pad[-25.00mil -135.00mil -25.00mil -70.00mil 20.00mil 10.00mil 30.00mil "5C" "12" "onsolder,square"]
+	Pad[25.00mil -135.00mil 25.00mil -70.00mil 20.00mil 10.00mil 30.00mil "4C" "13" "onsolder,square"]
+	Pad[75.00mil -135.00mil 75.00mil -70.00mil 20.00mil 10.00mil 30.00mil "3C" "14" "onsolder,square"]
+	Pad[125.00mil -135.00mil 125.00mil -70.00mil 20.00mil 10.00mil 30.00mil "2C" "15" "onsolder,square"]
+	Pad[175.00mil -135.00mil 175.00mil -70.00mil 20.00mil 10.00mil 30.00mil "1C" "16" "onsolder,square"]
+	ElementLine [-195.00mil 155.00mil 195.00mil 155.00mil 10.00mil]
+	ElementLine [-195.00mil -155.00mil -195.00mil 155.00mil 10.00mil]
+	ElementLine [-195.00mil -155.00mil 195.00mil -155.00mil 10.00mil]
+	ElementLine [195.00mil 25.00mil 195.00mil 155.00mil 10.00mil]
+	ElementLine [195.00mil -155.00mil 195.00mil -25.00mil 10.00mil]
+	ElementArc [195.00mil 0.0000 25.00mil 25.00mil 270 180 10.00mil]
+
+	)
+
+Element["onsolder" "0603" "C319" "0.15_uF" 4220.00mil 1265.00mil -51.50mil -33.50mil 0 100 "auto"]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C318" "0.15_uF" 3665.00mil 1265.00mil -61.50mil -33.50mil 0 100 "auto"]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C310" "0.15_uF" 4035.00mil 1840.00mil -38.50mil 56.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603_4" "R103" "100" 4140.00mil 1520.00mil -65.00mil 120.00mil 0 100 "auto"]
+(
+	Pad[-1.2000mm 0.6250mm -1.2000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "1" "1" "onsolder,square,edge2"]
+	Pad[-1.2000mm -1.0750mm -1.2000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "2" "2" "onsolder,square"]
+	Pad[-0.4000mm 0.6250mm -0.4000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "3" "3" "onsolder,square,edge2"]
+	Pad[-0.4000mm -1.0750mm -0.4000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "4" "4" "onsolder,square"]
+	Pad[0.4000mm 0.6250mm 0.4000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "5" "5" "onsolder,square,edge2"]
+	Pad[0.4000mm -1.0750mm 0.4000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "6" "6" "onsolder,square"]
+	Pad[1.2000mm 0.6250mm 1.2000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "7" "7" "onsolder,square,edge2"]
+	Pad[1.2000mm -1.0750mm 1.2000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "8" "8" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603_4" "R102" "100" 3215.00mil 1500.00mil -75.00mil 130.00mil 0 100 "auto"]
+(
+	Pad[-1.2000mm 0.6250mm -1.2000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "1" "1" "onsolder,square,edge2"]
+	Pad[-1.2000mm -1.0750mm -1.2000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "2" "2" "onsolder,square"]
+	Pad[-0.4000mm 0.6250mm -0.4000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "3" "3" "onsolder,square,edge2"]
+	Pad[-0.4000mm -1.0750mm -0.4000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "4" "4" "onsolder,square"]
+	Pad[0.4000mm 0.6250mm 0.4000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "5" "5" "onsolder,square,edge2"]
+	Pad[0.4000mm -1.0750mm 0.4000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "6" "6" "onsolder,square"]
+	Pad[1.2000mm 0.6250mm 1.2000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "7" "7" "onsolder,square,edge2"]
+	Pad[1.2000mm -1.0750mm 1.2000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "8" "8" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603_4" "R101" "100" 2105.00mil 1500.00mil -60.00mil 120.00mil 0 100 "auto"]
+(
+	Pad[-1.2000mm 0.6250mm -1.2000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "1" "1" "onsolder,square,edge2"]
+	Pad[-1.2000mm -1.0750mm -1.2000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "2" "2" "onsolder,square"]
+	Pad[-0.4000mm 0.6250mm -0.4000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "3" "3" "onsolder,square,edge2"]
+	Pad[-0.4000mm -1.0750mm -0.4000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "4" "4" "onsolder,square"]
+	Pad[0.4000mm 0.6250mm 0.4000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "5" "5" "onsolder,square,edge2"]
+	Pad[0.4000mm -1.0750mm 0.4000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "6" "6" "onsolder,square"]
+	Pad[1.2000mm 0.6250mm 1.2000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "7" "7" "onsolder,square,edge2"]
+	Pad[1.2000mm -1.0750mm 1.2000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "8" "8" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603_4" "R201" "100" 6145.00mil 1460.00mil -55.00mil 125.00mil 0 100 "auto"]
+(
+	Pad[1.2000mm -1.0750mm 1.2000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "1" "1" "onsolder,square"]
+	Pad[1.2000mm 0.6250mm 1.2000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "2" "2" "onsolder,square,edge2"]
+	Pad[0.4000mm -1.0750mm 0.4000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "3" "3" "onsolder,square"]
+	Pad[0.4000mm 0.6250mm 0.4000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "4" "4" "onsolder,square,edge2"]
+	Pad[-0.4000mm -1.0750mm -0.4000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "5" "5" "onsolder,square"]
+	Pad[-0.4000mm 0.6250mm -0.4000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "6" "6" "onsolder,square,edge2"]
+	Pad[-1.2000mm -1.0750mm -1.2000mm -0.6250mm 0.4500mm 20.00mil 0.6600mm "7" "7" "onsolder,square"]
+	Pad[-1.2000mm 0.6250mm -1.2000mm 1.0750mm 0.4500mm 20.00mil 0.6600mm "8" "8" "onsolder,square,edge2"]
+
+	)
+
+Element["onsolder" "0603" "C314" "1_uF" 5760.00mil 1335.00mil -171.50mil 31.50mil 0 100 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C313" "0.15_uF" 5760.00mil 1410.00mil -166.50mil 26.50mil 0 100 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C312" "0.15_uF" 5220.00mil 1840.00mil -28.50mil 51.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["onsolder" "0603" "C311" "0.15_uF" 5480.00mil 1840.00mil -28.50mil 51.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "22-23-2051" "CONN305" "unknown" 2935.00mil 1350.00mil -177.00mil -253.00mil 0 100 ""]
+(
+	Pin[200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square,edge2"]
+	Pin[100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" "edge2"]
+	Pin[0.0000 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "3" "3" "edge2"]
+	Pin[-100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "4" "4" "edge2"]
+	Pin[-200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "5" "5" "edge2"]
+	ElementLine [262.00mil -143.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil -262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 147.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 57.00mil 262.00mil 57.00mil 10.00mil]
+	ElementLine [150.00mil -143.00mil 150.00mil 57.00mil 10.00mil]
+	ElementLine [50.00mil -143.00mil 50.00mil 57.00mil 10.00mil]
+	ElementLine [-50.00mil -143.00mil -50.00mil 57.00mil 10.00mil]
+	ElementLine [-150.00mil -143.00mil -150.00mil 57.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil 262.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["onsolder" "0603" "C317" "0.15_uF" 3111.00mil 1264.00mil -58.50mil -31.50mil 0 100 "auto"]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "22-23-2051" "CONN304" "unknown" 2380.00mil 1350.00mil -162.00mil -248.00mil 0 100 ""]
+(
+	Pin[200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square,edge2"]
+	Pin[100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" "edge2"]
+	Pin[0.0000 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "3" "3" "edge2"]
+	Pin[-100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "4" "4" "edge2"]
+	Pin[-200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "5" "5" "edge2"]
+	ElementLine [262.00mil -143.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil -262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 147.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 57.00mil 262.00mil 57.00mil 10.00mil]
+	ElementLine [150.00mil -143.00mil 150.00mil 57.00mil 10.00mil]
+	ElementLine [50.00mil -143.00mil 50.00mil 57.00mil 10.00mil]
+	ElementLine [-50.00mil -143.00mil -50.00mil 57.00mil 10.00mil]
+	ElementLine [-150.00mil -143.00mil -150.00mil 57.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil 262.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["onsolder" "0603" "C316" "0.15_uF" 2555.00mil 1265.00mil -56.50mil -33.50mil 0 100 "auto"]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "22-23-2051" "CONN302" "unknown" 1825.00mil 1350.00mil -172.00mil -253.00mil 0 100 ""]
+(
+	Pin[200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "1" "1" "square,edge2"]
+	Pin[100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "2" "2" "edge2"]
+	Pin[0.0000 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "3" "3" "edge2"]
+	Pin[-100.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "4" "4" "edge2"]
+	Pin[-200.00mil 0.0000 65.00mil 30.00mil 71.00mil 40.00mil "5" "5" "edge2"]
+	ElementLine [262.00mil -143.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil -262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 147.00mil 262.00mil 147.00mil 10.00mil]
+	ElementLine [-262.00mil 57.00mil 262.00mil 57.00mil 10.00mil]
+	ElementLine [150.00mil -143.00mil 150.00mil 57.00mil 10.00mil]
+	ElementLine [50.00mil -143.00mil 50.00mil 57.00mil 10.00mil]
+	ElementLine [-50.00mil -143.00mil -50.00mil 57.00mil 10.00mil]
+	ElementLine [-150.00mil -143.00mil -150.00mil 57.00mil 10.00mil]
+	ElementLine [-262.00mil -143.00mil 262.00mil -143.00mil 10.00mil]
+
+	)
+
+Element["onsolder" "0603" "C315" "0.15_uF" 2000.00mil 1265.00mil -71.50mil -33.50mil 0 100 "auto"]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "UE27AEX4X0X" "CONN311" "unknown" 3545.00mil 1840.00mil 125.00mil 25.00mil 3 100 ""]
+(
+	Pin[0.0000 -3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "VBUS" "1" ""]
+	Pin[0.0000 -1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D-" "2" ""]
+	Pin[0.0000 1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D+" "3" ""]
+	Pin[0.0000 3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "GND" "4" "thermal(1X)"]
+	Pin[-2.7100mm -6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	Pin[-2.7100mm 6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	ElementLine [1.5000mm -7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm 7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm -7.2500mm 1.5000mm -7.2500mm 8.00mil]
+	ElementLine [-4.2200mm -5.5000mm -4.2200mm 5.5000mm 8.00mil]
+
+	)
+
+Element["onsolder" "0603" "C309" "0.15_uF" 3480.00mil 1840.00mil -33.50mil 51.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "UE27AEX4X0X" "CONN310" "unknown" 2990.00mil 1840.00mil 120.00mil -10.00mil 3 100 ""]
+(
+	Pin[0.0000 -3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "VBUS" "1" ""]
+	Pin[0.0000 -1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D-" "2" ""]
+	Pin[0.0000 1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D+" "3" ""]
+	Pin[0.0000 3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "GND" "4" "thermal(1X)"]
+	Pin[-2.7100mm -6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	Pin[-2.7100mm 6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	ElementLine [1.5000mm -7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm 7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm -7.2500mm 1.5000mm -7.2500mm 8.00mil]
+	ElementLine [-4.2200mm -5.5000mm -4.2200mm 5.5000mm 8.00mil]
+
+	)
+
+Element["onsolder" "0603" "C308" "0.15_uF" 2925.00mil 1840.00mil -28.50mil 51.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "UE27AEX4X0X" "CONN309" "unknown" 2435.00mil 1840.00mil -330.00mil 350.00mil 0 100 ""]
+(
+	Pin[0.0000 -3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "VBUS" "1" ""]
+	Pin[0.0000 -1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D-" "2" ""]
+	Pin[0.0000 1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D+" "3" ""]
+	Pin[0.0000 3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "GND" "4" "thermal(1X)"]
+	Pin[-2.7100mm -6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	Pin[-2.7100mm 6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	ElementLine [1.5000mm -7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm 7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm -7.2500mm 1.5000mm -7.2500mm 8.00mil]
+	ElementLine [-4.2200mm -5.5000mm -4.2200mm 5.5000mm 8.00mil]
+
+	)
+
+Element["onsolder" "0603" "C307" "0.15_uF" 2370.00mil 1840.00mil -28.50mil 46.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "UE27AEX4X0X" "CONN308" "unknown" 1880.00mil 1840.00mil -190.00mil 355.00mil 0 100 ""]
+(
+	Pin[0.0000 -3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "VBUS" "1" ""]
+	Pin[0.0000 -1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D-" "2" ""]
+	Pin[0.0000 1.0000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "D+" "3" ""]
+	Pin[0.0000 3.5000mm 1.4000mm 20.00mil 1.6500mm 0.9000mm "GND" "4" "thermal(1X)"]
+	Pin[-2.7100mm -6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	Pin[-2.7100mm 6.5700mm 2.7000mm 20.00mil 2.9500mm 2.3000mm "SHIELD" "5" "thermal(1X)"]
+	ElementLine [1.5000mm -7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm 7.2500mm 1.5000mm 7.2500mm 8.00mil]
+	ElementLine [-1.0000mm -7.2500mm 1.5000mm -7.2500mm 8.00mil]
+	ElementLine [-4.2200mm -5.5000mm -4.2200mm 5.5000mm 8.00mil]
+
+	)
+
+Element["onsolder" "0603" "C306" "0.15_uF" 1815.00mil 1840.00mil -28.50mil 51.50mil 3 100 "auto"]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "0603" "C403" "1_uF" 4510.00mil 1590.00mil -41.50mil -71.50mil 0 77 ""]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "R402" ".3" 4610.00mil 1590.00mil 53.50mil -46.50mil 0 77 ""]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0805" "C402" "4.7_uF" 4420.00mil 1835.00mil -26.50mil 221.50mil 1 77 ""]
+(
+	Pad[-3.93mil 35.43mil 3.93mil 35.43mil 51.18mil 20.00mil 57.18mil "1" "1" "square"]
+	Pad[-3.93mil -35.43mil 3.93mil -35.43mil 51.18mil 20.00mil 57.18mil "2" "2" "square"]
+	ElementLine [-27.55mil -3.93mil -27.55mil 3.93mil 8.00mil]
+	ElementLine [27.55mil -3.93mil 27.55mil 3.93mil 8.00mil]
+
+	)
+
+Element["" "SOT23-5" "U402" "unknown" 4545.00mil 1795.00mil -45.00mil 62.00mil 0 77 ""]
+(
+	Pad[-59.00mil -37.00mil -43.00mil -37.00mil 28.00mil 20.00mil 38.00mil "SW" "1" "square"]
+	Pad[-59.00mil 0.0000 -43.00mil 0.0000 28.00mil 20.00mil 38.00mil "GND" "2" "square"]
+	Pad[-59.00mil 37.00mil -43.00mil 37.00mil 28.00mil 20.00mil 38.00mil "CTRL" "3" "square"]
+	Pad[43.00mil 37.00mil 59.00mil 37.00mil 28.00mil 20.00mil 38.00mil "SET" "4" "square,edge2"]
+	Pad[43.00mil -37.00mil 59.00mil -37.00mil 28.00mil 20.00mil 38.00mil "VCC" "5" "square,edge2"]
+	ElementLine [-83.00mil -61.00mil 83.00mil -61.00mil 8.00mil]
+	ElementLine [-83.00mil -61.00mil -83.00mil 61.00mil 8.00mil]
+	ElementLine [-83.00mil 61.00mil 83.00mil 61.00mil 8.00mil]
+	ElementLine [83.00mil -61.00mil 83.00mil 61.00mil 8.00mil]
+
+	)
+
+Element["" "SOD123F" "D402" "unknown" 4535.00mil 1670.00mil 95.00mil -20.00mil 0 77 ""]
+(
+	Pad[-1.4300mm -0.2300mm -1.4300mm 0.2300mm 1.3400mm 20.00mil 1.5600mm "1" "1" "square"]
+	Pad[1.4300mm -0.2300mm 1.4300mm 0.2300mm 1.3400mm 20.00mil 1.5600mm "2" "2" "square"]
+	ElementLine [-1.6500mm 1.1500mm 1.6500mm 1.1500mm 8.00mil]
+	ElementLine [-1.6500mm -1.1500mm 1.6500mm -1.1500mm 8.00mil]
+	ElementLine [1.3000mm -1.1500mm 1.3000mm -1.1500mm 11.00mil]
+	ElementLine [1.3000mm 1.1500mm 1.3000mm 1.1500mm 11.00mil]
+
+	)
+
+Element["" "NRS4018" "L403" "33_uH" 4555.00mil 2010.00mil -140.00mil 90.00mil 0 77 ""]
+(
+	Pad[-1.4000mm -1.2500mm -1.4000mm 1.2500mm 1.2000mm 20.00mil 1.4000mm "1" "1" "square"]
+	Pad[1.4000mm -1.2500mm 1.4000mm 1.2500mm 1.2000mm 20.00mil 1.4000mm "2" "2" "square"]
+	ElementLine [-2.2500mm -2.2500mm -2.2500mm 2.2500mm 8.00mil]
+	ElementLine [-2.2500mm -2.2500mm 2.2500mm -2.2500mm 8.00mil]
+	ElementLine [-2.2500mm 2.2500mm 2.2500mm 2.2500mm 8.00mil]
+	ElementLine [2.2500mm -2.2500mm 2.2500mm 2.2500mm 8.00mil]
+
+	)
+
+Element["" "NRS4018" "L402" "33_uH" 4350.00mil 1605.00mil -85.00mil 100.00mil 0 76 ""]
+(
+	Pad[1.4000mm -1.2500mm 1.4000mm 1.2500mm 1.2000mm 20.00mil 1.4000mm "1" "1" "square"]
+	Pad[-1.4000mm -1.2500mm -1.4000mm 1.2500mm 1.2000mm 20.00mil 1.4000mm "2" "2" "square"]
+	ElementLine [2.2500mm -2.2500mm 2.2500mm 2.2500mm 8.00mil]
+	ElementLine [-2.2500mm 2.2500mm 2.2500mm 2.2500mm 8.00mil]
+	ElementLine [-2.2500mm -2.2500mm 2.2500mm -2.2500mm 8.00mil]
+	ElementLine [-2.2500mm -2.2500mm -2.2500mm 2.2500mm 8.00mil]
+
+	)
+
+Element["" "SOD123F" "D403" "unknown" 4740.00mil 2065.00mil -150.00mil 60.00mil 0 77 ""]
+(
+	Pad[-0.2300mm 1.4300mm 0.2300mm 1.4300mm 1.3400mm 20.00mil 1.5600mm "1" "1" "square"]
+	Pad[-0.2300mm -1.4300mm 0.2300mm -1.4300mm 1.3400mm 20.00mil 1.5600mm "2" "2" "square"]
+	ElementLine [1.1500mm -1.6500mm 1.1500mm 1.6500mm 8.00mil]
+	ElementLine [-1.1500mm -1.6500mm -1.1500mm 1.6500mm 8.00mil]
+	ElementLine [-1.1500mm -1.3000mm -1.1500mm -1.3000mm 11.00mil]
+	ElementLine [1.1500mm -1.3000mm 1.1500mm -1.3000mm 11.00mil]
+
+	)
+
+Element["" "0603" "R403" ".3" 4730.00mil 1925.00mil -81.50mil 56.50mil 1 77 ""]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "SOT23-5" "U403" "unknown" 4865.00mil 2060.00mil 0.0000 92.00mil 0 100 ""]
+(
+	Pad[-37.00mil 43.00mil -37.00mil 59.00mil 28.00mil 20.00mil 38.00mil "SW" "1" "square,edge2"]
+	Pad[0.0000 43.00mil 0.0000 59.00mil 28.00mil 20.00mil 38.00mil "GND" "2" "square,edge2"]
+	Pad[37.00mil 43.00mil 37.00mil 59.00mil 28.00mil 20.00mil 38.00mil "CTRL" "3" "square,edge2"]
+	Pad[37.00mil -59.00mil 37.00mil -43.00mil 28.00mil 20.00mil 38.00mil "SET" "4" "square"]
+	Pad[-37.00mil -59.00mil -37.00mil -43.00mil 28.00mil 20.00mil 38.00mil "VCC" "5" "square"]
+	ElementLine [-61.00mil -83.00mil -61.00mil 83.00mil 8.00mil]
+	ElementLine [-61.00mil 83.00mil 61.00mil 83.00mil 8.00mil]
+	ElementLine [61.00mil -83.00mil 61.00mil 83.00mil 8.00mil]
+	ElementLine [-61.00mil -83.00mil 61.00mil -83.00mil 8.00mil]
+
+	)
+
+Element["" "0805" "C406" "4.7_uF" 4825.00mil 1930.00mil 83.50mil 3.50mil 0 77 ""]
+(
+	Pad[-35.43mil -3.93mil -35.43mil 3.93mil 51.18mil 20.00mil 57.18mil "1" "1" "square"]
+	Pad[35.43mil -3.93mil 35.43mil 3.93mil 51.18mil 20.00mil 57.18mil "2" "2" "square"]
+	ElementLine [-3.93mil -27.55mil 3.93mil -27.55mil 8.00mil]
+	ElementLine [-3.93mil 27.55mil 3.93mil 27.55mil 8.00mil]
+
+	)
+
+Element["" "SOD123F" "D401" "unknown" 4820.00mil 1775.00mil -150.00mil -70.00mil 0 77 ""]
+(
+	Pad[-0.2300mm 1.4300mm 0.2300mm 1.4300mm 1.3400mm 20.00mil 1.5600mm "1" "1" "square"]
+	Pad[-0.2300mm -1.4300mm 0.2300mm -1.4300mm 1.3400mm 20.00mil 1.5600mm "2" "2" "square"]
+	ElementLine [1.1500mm 1.6500mm 1.1500mm -1.6500mm 8.00mil]
+	ElementLine [-1.1500mm 1.6500mm -1.1500mm -1.6500mm 8.00mil]
+	ElementLine [-1.1500mm -1.3000mm -1.1500mm -1.3000mm 11.00mil]
+	ElementLine [1.1500mm -1.3000mm 1.1500mm -1.3000mm 11.00mil]
+
+	)
+
+Element["" "SOT23-5" "U401" "unknown" 5020.00mil 1850.00mil 68.00mil 90.00mil 3 77 ""]
+(
+	Pad[-37.00mil 43.00mil -37.00mil 59.00mil 28.00mil 20.00mil 38.00mil "SW" "1" "square,edge2"]
+	Pad[0.0000 43.00mil 0.0000 59.00mil 28.00mil 20.00mil 38.00mil "GND" "2" "square,edge2"]
+	Pad[37.00mil 43.00mil 37.00mil 59.00mil 28.00mil 20.00mil 38.00mil "CTRL" "3" "square,edge2"]
+	Pad[37.00mil -59.00mil 37.00mil -43.00mil 28.00mil 20.00mil 38.00mil "SET" "4" "square"]
+	Pad[-37.00mil -59.00mil -37.00mil -43.00mil 28.00mil 20.00mil 38.00mil "VCC" "5" "square"]
+	ElementLine [-61.00mil -83.00mil -61.00mil 83.00mil 8.00mil]
+	ElementLine [-61.00mil 83.00mil 61.00mil 83.00mil 8.00mil]
+	ElementLine [61.00mil -83.00mil 61.00mil 83.00mil 8.00mil]
+	ElementLine [-61.00mil -83.00mil 61.00mil -83.00mil 8.00mil]
+
+	)
+
+Element["" "NRS4018" "L401" "33_uH" 4960.00mil 1600.00mil -190.00mil 15.00mil 0 77 ""]
+(
+	Pad[-1.4000mm -1.2500mm -1.4000mm 1.2500mm 1.2000mm 20.00mil 1.4000mm "1" "1" "square"]
+	Pad[1.4000mm -1.2500mm 1.4000mm 1.2500mm 1.2000mm 20.00mil 1.4000mm "2" "2" "square"]
+	ElementLine [-2.2500mm -2.2500mm -2.2500mm 2.2500mm 8.00mil]
+	ElementLine [-2.2500mm -2.2500mm 2.2500mm -2.2500mm 8.00mil]
+	ElementLine [-2.2500mm 2.2500mm 2.2500mm 2.2500mm 8.00mil]
+	ElementLine [2.2500mm -2.2500mm 2.2500mm 2.2500mm 8.00mil]
+
+	)
+
+Element["" "0603" "R401" ".3" 5020.00mil 1730.00mil 95.91mil -31.50mil 3 54 ""]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "C401" "1_uF" 5080.00mil 1650.00mil 26.50mil -136.50mil 3 76 ""]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "C405" "1_uF" 4700.00mil 1850.00mil -61.50mil -86.50mil 0 77 ""]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "#4 bolt" "" "" 7015.00mil 1200.00mil 0.0000 0.0000 0 100 ""]
+(
+	Pin[0.0000 0.0000 180.00mil 20.00mil 185.00mil 128.50mil "1" "1" ""]
+	ElementArc [0.0000 0.0000 125.00mil 125.00mil 0 360 8.00mil]
+
+	)
+
+Element["" "0805" "C404" "4.7_uF" 4915.00mil 1765.00mil -41.50mil 93.50mil 0 54 ""]
+(
+	Pad[-3.93mil -35.43mil 3.93mil -35.43mil 51.18mil 20.00mil 57.18mil "1" "1" "square"]
+	Pad[-3.93mil 35.43mil 3.93mil 35.43mil 51.18mil 20.00mil 57.18mil "2" "2" "square"]
+	ElementLine [27.55mil 3.93mil 27.55mil -3.93mil 8.00mil]
+	ElementLine [-27.55mil 3.93mil -27.55mil -3.93mil 8.00mil]
+
+	)
+
+Element["" "0603" "R202" "3.16_k" 5755.00mil 2075.00mil 91.50mil -11.50mil 3 100 ""]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "D201" "unknown" 5755.00mil 1980.00mil 71.50mil -41.50mil 3 77 ""]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "CATHODE" "1" "square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "ANODE" "2" "square"]
+
+	)
+
+Element["" "V-DFN3020-14" "U301" "unknown" 5760.00mil 1715.00mil -65.00mil 75.00mil 0 100 ""]
+(
+	Pad[-1.0750mm 0.8500mm -0.9250mm 0.8500mm 0.5000mm 20.00mil 0.6000mm "VIN1" "1_2" "square"]
+	Pad[-0.4000mm 0.7250mm -0.4000mm 0.9750mm 0.2500mm 20.00mil 0.3500mm "EN1" "3" "square,edge2"]
+	Pad[0.0000 0.7250mm 0.0000 0.9750mm 0.2500mm 20.00mil 0.3500mm "VBIAS" "4" "square,edge2"]
+	Pad[0.4000mm 0.7250mm 0.4000mm 0.9750mm 0.2500mm 20.00mil 0.3500mm "EN2" "5" "square,edge2"]
+	Pad[0.9250mm 0.8500mm 1.0750mm 0.8500mm 0.5000mm 20.00mil 0.6000mm "VIN2" "6_7" "square,edge2"]
+	Pad[0.9250mm -0.8500mm 1.0750mm -0.8500mm 0.5000mm 20.00mil 0.6000mm "VOUT2" "8_9" "square,edge2"]
+	Pad[0.4000mm -0.9750mm 0.4000mm -0.7250mm 0.2500mm 20.00mil 0.3500mm "SS2" "10" "square"]
+	Pad[0.0000 -0.9750mm 0.0000 -0.7250mm 0.2500mm 20.00mil 0.3500mm "GND" "11" "square"]
+	Pad[-0.4000mm -0.9750mm -0.4000mm -0.7250mm 0.2500mm 20.00mil 0.3500mm "SS1" "12" "square"]
+	Pad[-1.0750mm -0.8500mm -0.9250mm -0.8500mm 0.5000mm 20.00mil 0.6000mm "VOUT1" "13_14" "square"]
+	Pad[-0.8000mm 0.0000 0.8000mm 0.0000 0.9200mm 20.00mil 1.0200mm "PAD" "15" "square"]
+	ElementLine [-1.5250mm 1.0250mm -1.5250mm -1.0250mm 8.00mil]
+	ElementLine [1.5250mm 1.0250mm 1.5250mm -1.0250mm 8.00mil]
+
+	)
+
+Element["" "0603" "C302" "0.15_uF" 5825.00mil 1610.00mil 91.50mil -71.50mil 3 100 ""]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "C303" "0.15_uF" 5630.00mil 1720.00mil 41.50mil 33.50mil 3 77 ""]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "C304" "1_uF" 5895.00mil 1800.00mil -61.50mil 28.50mil 0 100 ""]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "C301" "1000_pF" 5710.00mil 1610.00mil -23.50mil -76.50mil 3 100 ""]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "C305" "1000_pF" 5770.00mil 1610.00mil 21.50mil -206.50mil 3 100 ""]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["onsolder" "0603" "C201" "0.15_uF" 5635.00mil 2025.00mil -61.50mil 86.50mil 0 100 "auto"]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "onsolder,square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "onsolder,square"]
+
+	)
+
+Element["" "0603" "R302" "3.16_k" 5435.00mil 2230.00mil -81.50mil 33.50mil 0 100 ""]
+(
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "D302" "unknown" 5540.00mil 2230.00mil -26.50mil 33.50mil 0 100 ""]
+(
+	Pad[-25.59mil -4.92mil -25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "CATHODE" "1" "square"]
+	Pad[25.59mil -4.92mil 25.59mil 4.92mil 29.52mil 20.00mil 35.52mil "ANODE" "2" "square"]
+
+	)
+
+Element["" "0603" "R301" "3.16_k" 3765.00mil 1875.00mil 86.50mil -26.50mil 3 100 ""]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "D301" "unknown" 3765.00mil 1770.00mil 86.50mil -66.50mil 3 100 ""]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "CATHODE" "1" "square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "ANODE" "2" "square"]
+
+	)
+
+Element["" "0603" "D5" "unknown" 4895.00mil 2515.00mil -23.50mil -21.50mil 3 100 ""]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "CATHODE" "1" "square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "ANODE" "2" "square"]
+
+	)
+
+Element["" "0603" "R12" "10_k" 4895.00mil 2610.00mil -28.50mil -36.50mil 3 100 ""]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "R11" "3.16_k" 3215.00mil 1690.00mil 86.50mil -26.50mil 3 100 ""]
+(
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "1" "1" "square"]
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "2" "2" "square"]
+
+	)
+
+Element["" "0603" "D4" "unknown" 3215.00mil 1590.00mil 81.50mil -26.50mil 3 100 ""]
+(
+	Pad[-4.92mil 25.59mil 4.92mil 25.59mil 29.52mil 20.00mil 35.52mil "CATHODE" "1" "square"]
+	Pad[-4.92mil -25.59mil 4.92mil -25.59mil 29.52mil 20.00mil 35.52mil "ANODE" "2" "square"]
+
+	)
+
+Element["" "#4 bolt" "" "" 1410.00mil 1200.00mil 0.0000 0.0000 0 100 ""]
+(
+	Pin[0.0000 0.0000 180.00mil 20.00mil 185.00mil 128.50mil "1" "1" ""]
+	ElementArc [0.0000 0.0000 125.00mil 125.00mil 0 360 8.00mil]
+
+	)
+
+Element["" "#4 bolt" "" "" 7015.00mil 2880.00mil 0.0000 0.0000 0 100 ""]
+(
+	Pin[0.0000 0.0000 180.00mil 20.00mil 185.00mil 128.50mil "1" "1" ""]
+	ElementArc [0.0000 0.0000 125.00mil 125.00mil 0 360 8.00mil]
+
+	)
+
+Element["" "#4 bolt" "" "" 1410.00mil 2880.00mil 0.0000 0.0000 0 100 ""]
+(
+	Pin[0.0000 0.0000 180.00mil 20.00mil 185.00mil 128.50mil "1" "1" ""]
+	ElementArc [0.0000 0.0000 125.00mil 125.00mil 0 360 8.00mil]
+
+	)
+Layer(1 "top")
+(
+	Line[6285.00mil 63.3360mm 6285.00mil 2540.00mil 35.00mil 20.00mil "clearline"]
+	Line[6535.00mil 2225.00mil 6535.00mil 57.6950mm 35.00mil 20.00mil "clearline"]
+	Line[5935.00mil 2225.00mil 5935.00mil 57.6950mm 35.00mil 20.00mil "clearline"]
+	Line[6485.00mil 63.3360mm 6485.00mil 2540.00mil 35.00mil 20.00mil "clearline"]
+	Line[6210.00mil 2660.00mil 159.8590mm 2660.00mil 10.00mil 14.00mil "clearline"]
+	Line[159.8590mm 2660.00mil 6310.00mil 67.9790mm 10.00mil 14.00mil "clearline"]
+	Line[6210.00mil 2615.00mil 159.7320mm 2615.00mil 10.00mil 14.00mil "clearline"]
+	Line[159.7320mm 2615.00mil 6310.00mil 65.8790mm 10.00mil 14.00mil "clearline"]
+	Line[168.6451mm 2545.00mil 6625.00mil 65.0131mm 10.00mil 14.00mil "clearline"]
+	Line[4500.00mil 2055.00mil 4555.00mil 2110.00mil 25.00mil 20.00mil "clearline"]
+	Line[4420.00mil 1740.00mil 4420.00mil 45.7091mm 25.00mil 20.00mil "clearline"]
+	Line[4560.00mil 1885.00mil 4550.00mil 1875.00mil 25.00mil 20.00mil "clearline"]
+	Line[4560.00mil 1885.00mil 4625.00mil 1885.00mil 25.00mil 20.00mil "clearline"]
+	Line[4494.00mil 1864.00mil 4495.00mil 1865.00mil 10.00mil 14.00mil "clearline"]
+	Line[4494.00mil 1832.00mil 4494.00mil 1864.00mil 10.00mil 14.00mil "clearline"]
+	Line[113.1461mm 1905.00mil 4420.00mil 47.5089mm 25.00mil 20.00mil "clearline"]
+	Line[113.1461mm 1905.00mil 4520.00mil 1905.00mil 25.00mil 20.00mil "clearline"]
+	Line[4550.00mil 1875.00mil 4520.00mil 1905.00mil 25.00mil 20.00mil "clearline"]
+	Line[4550.00mil 1800.00mil 4550.00mil 1875.00mil 25.00mil 20.00mil "clearline"]
+	Line[4592.00mil 1758.00mil 4550.00mil 1800.00mil 25.00mil 20.00mil "clearline"]
+	Line[112.3841mm 1795.00mil 4495.00mil 1795.00mil 25.00mil 20.00mil "clearline"]
+	Line[4420.00mil 45.7091mm 112.3841mm 1795.00mil 25.00mil 20.00mil "clearline"]
+	Line[4596.00mil 1832.00mil 4640.00mil 1788.00mil 25.00mil 20.00mil "clearline"]
+	Line[4500.00mil 2010.00mil 4500.00mil 2055.00mil 25.00mil 20.00mil "clearline"]
+	Line[117.0970mm 50.1620mm 117.0970mm 2010.00mil 25.00mil 20.00mil "clearline"]
+	Line[117.0970mm 50.1620mm 4675.00mil 1910.00mil 25.00mil 20.00mil "clearline"]
+	Line[4555.00mil 2110.00mil 4825.00mil 2110.00mil 25.00mil 20.00mil "clearline"]
+	Line[4865.00mil 49.1381mm 123.4549mm 1930.00mil 25.00mil 20.00mil "clearline"]
+	Line[4865.00mil 49.1381mm 4865.00mil 2111.00mil 25.00mil 20.00mil "clearline"]
+	Line[4785.00mil 49.1381mm 4785.00mil 2010.00mil 25.00mil 20.00mil "clearline"]
+	Line[121.6551mm 1930.00mil 4785.00mil 49.1381mm 25.00mil 20.00mil "clearline"]
+	Line[4740.30mil 2009.00mil 4828.00mil 2009.00mil 25.00mil 20.00mil "clearline"]
+	Line[4902.00mil 2009.00mil 4910.00mil 2001.00mil 25.00mil 20.00mil "clearline"]
+	Line[4910.00mil 1895.00mil 4910.00mil 2001.00mil 25.00mil 20.00mil "clearline"]
+	Line[4910.00mil 1895.00mil 4895.00mil 1880.00mil 25.00mil 20.00mil "clearline"]
+	Line[4765.00mil 2009.00mil 4765.00mil 2060.00mil 25.00mil 20.00mil "clearline"]
+	Line[4850.00mil 2060.00mil 4925.00mil 2060.00mil 25.00mil 20.00mil "clearline"]
+	Line[4710.00mil 2039.00mil 4710.00mil 2060.00mil 25.00mil 20.00mil "clearline"]
+	Line[4710.00mil 2039.00mil 4740.00mil 2009.00mil 25.00mil 20.00mil "clearline"]
+	Line[4730.00mil 49.5450mm 4730.00mil 2009.00mil 25.00mil 20.00mil "clearline"]
+	Line[120.6350mm 1880.00mil 4895.00mil 1880.00mil 25.00mil 20.00mil "clearline"]
+	Line[120.6350mm 1880.00mil 4730.00mil 48.2450mm 25.00mil 20.00mil "clearline"]
+	Line[5020.00mil 1865.00mil 5000.00mil 1845.00mil 25.00mil 20.00mil "clearline"]
+	Line[5000.00mil 1845.00mil 125.9731mm 1845.00mil 25.00mil 20.00mil "clearline"]
+	Line[125.9731mm 1845.00mil 4915.00mil 45.7309mm 25.00mil 20.00mil "clearline"]
+	Line[4833.70mil 1845.00mil 4910.00mil 1845.00mil 25.00mil 20.00mil "clearline"]
+	Line[4910.00mil 1845.00mil 4965.00mil 1900.00mil 25.00mil 20.00mil "clearline"]
+	Line[4965.00mil 1900.00mil 4980.00mil 1900.00mil 25.00mil 20.00mil "clearline"]
+	Line[126.8580mm 1730.00mil 126.8580mm 45.4048mm 25.00mil 20.00mil "clearline"]
+	Line[126.8580mm 45.4048mm 4983.00mil 1799.00mil 25.00mil 20.00mil "clearline"]
+	Line[128.1580mm 1730.00mil 128.1580mm 45.4048mm 25.00mil 20.00mil "clearline"]
+	Line[128.1580mm 45.4048mm 5057.00mil 1799.00mil 25.00mil 20.00mil "clearline"]
+	Line[4820.00mil 43.6550mm 122.7041mm 43.9311mm 25.00mil 20.00mil "clearline"]
+	Line[122.7041mm 43.9311mm 126.8471mm 43.9311mm 25.00mil 20.00mil "clearline"]
+	Line[4833.70mil 1845.00mil 4765.00mil 45.1180mm 25.00mil 20.00mil "clearline"]
+	Line[4765.00mil 45.1180mm 4765.00mil 1675.00mil 25.00mil 20.00mil "clearline"]
+	Line[4765.00mil 1675.00mil 4785.00mil 1655.00mil 25.00mil 20.00mil "clearline"]
+	Line[4785.00mil 1655.00mil 4910.00mil 1655.00mil 25.00mil 20.00mil "clearline"]
+	Line[128.1580mm 1730.00mil 5080.00mil 43.0680mm 25.00mil 20.00mil "clearline"]
+	Line[5080.00mil 43.0680mm 5080.00mil 1680.00mil 25.00mil 20.00mil "clearline"]
+	Line[5080.00mil 41.2600mm 129.0170mm 1625.00mil 25.00mil 20.00mil "clearline"]
+	Line[129.0170mm 1625.00mil 5020.00mil 1625.00mil 25.00mil 20.00mil "clearline"]
+	Line[5080.00mil 1680.00mil 5135.00mil 1680.00mil 25.00mil 20.00mil "clearline"]
+	Line[4960.00mil 1680.00mil 4960.00mil 43.9202mm 25.00mil 20.00mil "clearline"]
+	Line[4960.00mil 43.9202mm 125.9949mm 43.9311mm 25.00mil 20.00mil "clearline"]
+	Line[4830.00mil 1770.00mil 4830.00mil 1730.00mil 25.00mil 20.00mil "clearline"]
+	Line[4830.00mil 1730.00mil 122.6985mm 43.9255mm 25.00mil 20.00mil "clearline"]
+	Line[4920.00mil 1350.00mil 4920.00mil 1415.00mil 25.00mil 20.00mil "clearline"]
+	Line[4920.00mil 1415.00mil 127.3840mm 38.3570mm 25.00mil 20.00mil "clearline"]
+	Line[127.3840mm 38.3570mm 127.3840mm 1600.00mil 25.00mil 20.00mil "clearline"]
+	Line[5020.00mil 1845.00mil 5020.00mil 1901.00mil 25.00mil 20.00mil "clearline"]
+	Line[5760.00mil 44.4110mm 5760.00mil 1775.00mil 6.00mil 12.00mil "clearline"]
+	Line[145.9040mm 44.4110mm 145.9040mm 44.7230mm 6.00mil 12.00mil "clearline"]
+	Line[145.9040mm 44.7230mm 5735.00mil 1770.00mil 6.00mil 12.00mil "clearline"]
+	Line[146.7040mm 44.4110mm 146.7040mm 44.7230mm 6.00mil 12.00mil "clearline"]
+	Line[146.7040mm 44.7230mm 5785.00mil 1770.00mil 6.00mil 12.00mil "clearline"]
+	Line[5735.00mil 1770.00mil 5735.00mil 1795.00mil 6.00mil 12.00mil "clearline"]
+	Line[5785.00mil 1770.00mil 5785.00mil 1795.00mil 6.00mil 12.00mil "clearline"]
+	Line[145.3040mm 44.4110mm 144.8190mm 44.4110mm 15.00mil 20.00mil "clearline"]
+	Line[144.8190mm 44.4110mm 5685.00mil 1765.00mil 15.00mil 20.00mil "clearline"]
+	Line[147.3040mm 44.4110mm 147.7890mm 44.4110mm 15.00mil 20.00mil "clearline"]
+	Line[5960.00mil 1800.00mil 150.3830mm 1800.00mil 15.00mil 20.00mil "clearline"]
+	Line[149.0830mm 1800.00mil 149.0830mm 45.7050mm 15.00mil 20.00mil "clearline"]
+	Line[147.7890mm 44.4110mm 149.0830mm 45.7050mm 15.00mil 20.00mil "clearline"]
+	Line[5830.00mil 1715.00mil 5690.00mil 1715.00mil 15.00mil 20.00mil "clearline"]
+	Line[147.3040mm 42.7110mm 5825.00mil 42.0600mm 15.00mil 20.00mil "clearline"]
+	Line[5825.00mil 42.0600mm 5825.00mil 1640.00mil 15.00mil 20.00mil "clearline"]
+	Line[146.7040mm 42.7110mm 146.7040mm 41.6900mm 6.00mil 12.00mil "clearline"]
+	Line[146.7040mm 41.6900mm 5770.00mil 41.5440mm 6.00mil 12.00mil "clearline"]
+	Line[145.9040mm 42.7110mm 145.9040mm 42.4140mm 6.00mil 12.00mil "clearline"]
+	Line[145.9040mm 42.4140mm 5710.00mil 41.5440mm 6.00mil 12.00mil "clearline"]
+	Line[5825.00mil 1640.00mil 5835.00mil 1640.00mil 25.00mil 20.00mil "clearline"]
+	Line[5835.00mil 1640.00mil 5865.00mil 1610.00mil 25.00mil 20.00mil "clearline"]
+	Line[5865.00mil 1610.00mil 5865.00mil 1515.00mil 25.00mil 20.00mil "clearline"]
+	Line[5865.00mil 1515.00mil 5880.00mil 1500.00mil 25.00mil 20.00mil "clearline"]
+	Line[5880.00mil 1500.00mil 5880.00mil 1455.00mil 25.00mil 20.00mil "clearline"]
+	Line[5880.00mil 1455.00mil 5850.00mil 1425.00mil 25.00mil 20.00mil "clearline"]
+	Line[5691.10mil 37.5040mm 5691.10mil 1260.00mil 25.00mil 20.00mil "clearline"]
+	Line[5850.00mil 1425.00mil 5610.00mil 1425.00mil 25.00mil 20.00mil "clearline"]
+	Line[5710.00mil 40.2440mm 5710.00mil 1540.00mil 10.00mil 14.00mil "clearline"]
+	Line[5710.00mil 1540.00mil 5735.00mil 1515.00mil 10.00mil 14.00mil "clearline"]
+	Line[5770.00mil 40.2440mm 5770.00mil 1550.00mil 10.00mil 14.00mil "clearline"]
+	Line[5770.00mil 1550.00mil 5735.00mil 1515.00mil 10.00mil 14.00mil "clearline"]
+	Line[5825.00mil 40.2440mm 5825.00mil 1555.00mil 10.00mil 14.00mil "clearline"]
+	Line[5825.00mil 1555.00mil 5780.00mil 1510.00mil 10.00mil 14.00mil "clearline"]
+	Line[5285.00mil 43.2360mm 5545.00mil 43.2360mm 25.00mil 20.00mil "clearline"]
+	Line[5545.00mil 1490.00mil 5610.00mil 1425.00mil 25.00mil 20.00mil "clearline"]
+	Line[5755.00mil 52.0550mm 5755.00mil 50.9420mm 10.00mil 14.00mil "clearline"]
+	Line[5755.00mil 2150.00mil 5755.00mil 53.3550mm 10.00mil 14.00mil "clearline"]
+	Line[5620.00mil 1840.00mil 143.2710mm 1840.00mil 10.00mil 14.00mil "clearline"]
+	Line[143.2710mm 1840.00mil 5755.00mil 49.6420mm 10.00mil 14.00mil "clearline"]
+	Line[5690.00mil 1715.00mil 143.7790mm 1715.00mil 25.00mil 20.00mil "clearline"]
+	Line[143.7790mm 1715.00mil 143.6520mm 1720.00mil 25.00mil 20.00mil "clearline"]
+	Line[142.3520mm 1720.00mil 142.3520mm 42.8140mm 25.00mil 20.00mil "clearline"]
+	Line[142.3520mm 42.8140mm 5635.00mil 1655.00mil 25.00mil 20.00mil "clearline"]
+	Line[145.3040mm 42.7110mm 144.4380mm 42.7110mm 15.00mil 20.00mil "clearline"]
+	Line[144.4380mm 42.7110mm 5680.00mil 1675.00mil 15.00mil 20.00mil "clearline"]
+	Line[5680.00mil 1675.00mil 5660.00mil 1655.00mil 25.00mil 20.00mil "clearline"]
+	Line[5660.00mil 1655.00mil 5635.00mil 1655.00mil 25.00mil 20.00mil "clearline"]
+	Line[5545.00mil 1490.00mil 5400.00mil 1490.00mil 25.00mil 20.00mil "clearline"]
+	Line[5400.00mil 1490.00mil 5355.00mil 1535.00mil 25.00mil 20.00mil "clearline"]
+	Line[5355.00mil 1535.00mil 5355.00mil 43.2360mm 25.00mil 20.00mil "clearline"]
+	Line[5545.00mil 1610.00mil 5590.00mil 1610.00mil 25.00mil 20.00mil "clearline"]
+	Line[5590.00mil 1610.00mil 5635.00mil 1655.00mil 25.00mil 20.00mil "clearline"]
+	Line[4494.00mil 1758.00mil 4478.70mil 1742.70mil 25.00mil 20.00mil "clearline"]
+	Line[4478.70mil 1742.70mil 4478.70mil 1670.00mil 25.00mil 20.00mil "clearline"]
+	Line[4478.70mil 1670.00mil 113.5410mm 1670.00mil 25.00mil 20.00mil "clearline"]
+	Line[113.5410mm 1670.00mil 111.8900mm 1605.00mil 25.00mil 20.00mil "clearline"]
+	Line[115.2040mm 1590.00mil 116.4440mm 1590.00mil 25.00mil 20.00mil "clearline"]
+	Line[109.0900mm 1605.00mil 109.0900mm 40.0080mm 25.00mil 20.00mil "clearline"]
+	Line[109.0900mm 40.0080mm 4360.00mil 1510.00mil 25.00mil 20.00mil "clearline"]
+	Line[4360.00mil 1510.00mil 4455.00mil 1510.00mil 25.00mil 20.00mil "clearline"]
+	Line[4455.00mil 1510.00mil 4485.00mil 1540.00mil 25.00mil 20.00mil "clearline"]
+	Line[4485.00mil 1540.00mil 4485.00mil 1590.00mil 25.00mil 20.00mil "clearline"]
+	Line[4745.00mil 1880.00mil 4745.00mil 47.4830mm 25.00mil 20.00mil "clearline"]
+	Line[4745.00mil 47.4830mm 120.0300mm 1815.00mil 25.00mil 20.00mil "clearline"]
+	Line[4640.00mil 1788.00mil 4640.00mil 1650.00mil 25.00mil 20.00mil "clearline"]
+	Line[4640.00mil 1650.00mil 4670.00mil 1620.00mil 25.00mil 20.00mil "clearline"]
+	Line[4670.00mil 1620.00mil 4670.00mil 1555.00mil 25.00mil 20.00mil "clearline"]
+	Line[4670.00mil 1555.00mil 4660.00mil 1545.00mil 25.00mil 20.00mil "clearline"]
+	Line[4660.00mil 1545.00mil 4595.00mil 1545.00mil 25.00mil 20.00mil "clearline"]
+	Line[4595.00mil 1545.00mil 4585.00mil 1555.00mil 25.00mil 20.00mil "clearline"]
+	Line[4585.00mil 1555.00mil 4585.00mil 1585.00mil 25.00mil 20.00mil "clearline"]
+	Line[4675.00mil 1910.00mil 4675.00mil 1660.00mil 25.00mil 20.00mil "clearline"]
+	Line[4675.00mil 1660.00mil 4705.00mil 1630.00mil 25.00mil 20.00mil "clearline"]
+	Line[120.0300mm 1815.00mil 120.0300mm 42.0220mm 25.00mil 20.00mil "clearline"]
+	Line[120.0300mm 42.0220mm 4740.00mil 1640.00mil 25.00mil 20.00mil "clearline"]
+	Line[117.7440mm 1590.00mil 117.7440mm 40.7520mm 25.00mil 20.00mil "clearline"]
+	Line[117.7440mm 40.7520mm 4591.30mil 41.8770mm 25.00mil 20.00mil "clearline"]
+	Line[4591.30mil 44.6710mm 4591.30mil 41.8770mm 25.00mil 20.00mil "clearline"]
+	Line[4740.00mil 1640.00mil 4740.00mil 1375.00mil 25.00mil 20.00mil "clearline"]
+	Line[4740.00mil 1375.00mil 4765.00mil 1350.00mil 25.00mil 20.00mil "clearline"]
+	Line[4705.00mil 1630.00mil 4705.00mil 1390.00mil 25.00mil 20.00mil "clearline"]
+	Line[4705.00mil 1390.00mil 4665.00mil 1350.00mil 25.00mil 20.00mil "clearline"]
+	Line[4510.00mil 1350.00mil 4510.00mil 1465.00mil 25.00mil 20.00mil "clearline"]
+	Line[4510.00mil 1465.00mil 4590.00mil 1545.00mil 25.00mil 20.00mil "clearline"]
+	Line[4410.00mil 1350.00mil 4410.00mil 1510.00mil 25.00mil 20.00mil "clearline"]
+	Line[5735.00mil 1795.00mil 5735.00mil 1845.00mil 10.00mil 14.00mil "clearline"]
+	Line[5735.00mil 1845.00mil 5795.00mil 1905.00mil 10.00mil 14.00mil "clearline"]
+	Line[5795.00mil 1905.00mil 5795.00mil 2175.00mil 10.00mil 14.00mil "clearline"]
+	Line[5785.00mil 1795.00mil 5785.00mil 1820.00mil 10.00mil 14.00mil "clearline"]
+	Line[5785.00mil 1820.00mil 5835.00mil 1870.00mil 10.00mil 14.00mil "clearline"]
+	Line[5835.00mil 1870.00mil 5835.00mil 2175.00mil 10.00mil 14.00mil "clearline"]
+	Line[5835.00mil 2175.00mil 5710.00mil 2300.00mil 10.00mil 14.00mil "clearline"]
+	Line[4460.00mil 2825.00mil 4370.00mil 2735.00mil 10.00mil 14.00mil "clearline"]
+	Line[4560.00mil 2825.00mil 4435.00mil 2700.00mil 10.00mil 14.00mil "clearline"]
+	Line[4560.00mil 2225.00mil 4265.00mil 2520.00mil 10.00mil 14.00mil "clearline"]
+	Line[4460.00mil 2225.00mil 4200.00mil 2485.00mil 10.00mil 14.00mil "clearline"]
+	Line[4260.00mil 2225.00mil 4065.00mil 2420.00mil 10.00mil 14.00mil "clearline"]
+	Line[4065.00mil 2420.00mil 2145.00mil 2420.00mil 10.00mil 14.00mil "clearline"]
+	Line[2145.00mil 2420.00mil 2000.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[2000.00mil 2565.00mil 2000.00mil 2690.00mil 10.00mil 14.00mil "clearline"]
+	Line[2100.00mil 2690.00mil 2100.00mil 2560.00mil 10.00mil 14.00mil "clearline"]
+	Line[2100.00mil 2560.00mil 2175.00mil 2485.00mil 10.00mil 14.00mil "clearline"]
+	Line[2175.00mil 2485.00mil 4200.00mil 2485.00mil 10.00mil 14.00mil "clearline"]
+	Line[4360.00mil 2225.00mil 4130.00mil 2455.00mil 10.00mil 14.00mil "clearline"]
+	Line[4130.00mil 2455.00mil 2160.00mil 2455.00mil 10.00mil 14.00mil "clearline"]
+	Line[2050.00mil 2565.00mil 2160.00mil 2455.00mil 10.00mil 14.00mil "clearline"]
+	Line[4435.00mil 2700.00mil 2385.00mil 2700.00mil 10.00mil 14.00mil "clearline"]
+	Line[4370.00mil 2735.00mil 2245.00mil 2735.00mil 10.00mil 14.00mil "clearline"]
+	Line[4265.00mil 2520.00mil 2195.00mil 2520.00mil 10.00mil 14.00mil "clearline"]
+	Line[2195.00mil 2520.00mil 2150.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[2245.00mil 2735.00mil 2200.00mil 2690.00mil 10.00mil 14.00mil "clearline"]
+	Line[2385.00mil 2700.00mil 2250.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[4902.00mil 2111.00mil 4921.00mil 2111.00mil 10.00mil 14.00mil "clearline"]
+	Line[4921.00mil 2111.00mil 4945.00mil 2135.00mil 10.00mil 14.00mil "clearline"]
+	Line[5710.00mil 2300.00mil 4910.00mil 2300.00mil 10.00mil 14.00mil "clearline"]
+	Line[4910.00mil 2300.00mil 4850.00mil 2360.00mil 10.00mil 14.00mil "clearline"]
+	Line[4850.00mil 2360.00mil 4645.00mil 2360.00mil 10.00mil 14.00mil "clearline"]
+	Line[4860.00mil 2230.00mil 4790.00mil 2300.00mil 10.00mil 14.00mil "clearline"]
+	Line[4790.00mil 2300.00mil 4655.00mil 2300.00mil 10.00mil 14.00mil "clearline"]
+	Line[5057.00mil 1901.00mil 5057.00mil 2093.00mil 10.00mil 14.00mil "clearline"]
+	Line[5057.00mil 2093.00mil 4985.00mil 2165.00mil 10.00mil 14.00mil "clearline"]
+	Line[4985.00mil 2165.00mil 4185.00mil 2165.00mil 10.00mil 14.00mil "clearline"]
+	Line[4185.00mil 2165.00mil 4155.00mil 2135.00mil 10.00mil 14.00mil "clearline"]
+	Line[4860.00mil 2230.00mil 5060.00mil 2230.00mil 10.00mil 14.00mil "clearline"]
+	Line[5060.00mil 2230.00mil 5095.00mil 2265.00mil 10.00mil 14.00mil "clearline"]
+	Line[5095.00mil 2265.00mil 5705.00mil 2265.00mil 10.00mil 14.00mil "clearline"]
+	Line[5795.00mil 2175.00mil 5705.00mil 2265.00mil 10.00mil 14.00mil "clearline"]
+	Line[137.3990mm 2230.00mil 5325.00mil 54.4980mm 10.00mil 14.00mil "clearline"]
+	Line[5325.00mil 54.4980mm 5325.00mil 2120.00mil 10.00mil 14.00mil "clearline"]
+	Line[138.6990mm 2230.00mil 140.0660mm 2230.00mil 10.00mil 14.00mil "clearline"]
+	Line[141.3660mm 2230.00mil 141.3660mm 53.2280mm 10.00mil 14.00mil "clearline"]
+	Line[141.3660mm 53.2280mm 5480.00mil 2010.00mil 10.00mil 14.00mil "clearline"]
+	Line[5480.00mil 2010.00mil 5480.00mil 43.2360mm 10.00mil 14.00mil "clearline"]
+	Line[3765.00mil 45.6080mm 3765.00mil 46.9750mm 10.00mil 14.00mil "clearline"]
+	Line[3765.00mil 48.2750mm 3765.00mil 1935.00mil 10.00mil 14.00mil "clearline"]
+	Line[3545.00mil 43.2360mm 94.5590mm 43.2360mm 10.00mil 14.00mil "clearline"]
+	Line[94.5590mm 43.2360mm 3765.00mil 44.3080mm 10.00mil 14.00mil "clearline"]
+	Line[4895.00mil 66.9440mm 128.6360mm 66.9440mm 10.00mil 14.00mil "clearline"]
+	Line[128.6360mm 66.9440mm 5075.00mil 2625.00mil 10.00mil 14.00mil "clearline"]
+	Line[4895.00mil 63.2310mm 125.9990mm 63.2310mm 10.00mil 14.00mil "clearline"]
+	Line[125.9990mm 63.2310mm 4980.00mil 2470.00mil 10.00mil 14.00mil "clearline"]
+	Line[4980.00mil 2470.00mil 4980.00mil 2430.00mil 10.00mil 14.00mil "clearline"]
+	Line[4895.00mil 65.6440mm 4895.00mil 64.5310mm 10.00mil 14.00mil "clearline"]
+	Line[3390.00mil 1350.00mil 3390.00mil 35.2910mm 10.00mil 14.00mil "clearline"]
+	Line[3390.00mil 35.2910mm 3215.00mil 39.7360mm 10.00mil 14.00mil "clearline"]
+	Line[3215.00mil 42.2760mm 3215.00mil 41.0360mm 10.00mil 14.00mil "clearline"]
+	Line[3215.00mil 43.5760mm 80.4060mm 1765.00mil 10.00mil 14.00mil "clearline"]
+	Line[80.4060mm 1765.00mil 3135.00mil 1765.00mil 10.00mil 14.00mil "clearline"]
+	Line[2180.00mil 1350.00mil 2180.00mil 1485.00mil 15.00mil 20.00mil "clearline"]
+	Line[2180.00mil 1485.00mil 2050.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[2600.00mil 1440.00mil 2310.00mil 1440.00mil 15.00mil 20.00mil "clearline"]
+	Line[2310.00mil 1440.00mil 2135.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[2315.00mil 1490.00mil 2210.00mil 1595.00mil 15.00mil 20.00mil "clearline"]
+	Line[2210.00mil 1595.00mil 2210.00mil 1860.00mil 15.00mil 20.00mil "clearline"]
+	Line[2135.00mil 1615.00mil 2135.00mil 1860.00mil 15.00mil 20.00mil "clearline"]
+	Line[2050.00mil 1615.00mil 2050.00mil 1860.00mil 15.00mil 20.00mil "clearline"]
+	Line[2600.00mil 1440.00mil 2665.00mil 1375.00mil 15.00mil 20.00mil "clearline"]
+	Line[2315.00mil 1490.00mil 2620.00mil 1490.00mil 15.00mil 20.00mil "clearline"]
+	Line[2620.00mil 1490.00mil 2735.00mil 1375.00mil 15.00mil 20.00mil "clearline"]
+	Line[2735.00mil 1375.00mil 2735.00mil 1350.00mil 15.00mil 20.00mil "clearline"]
+	Line[2665.00mil 1375.00mil 2665.00mil 1250.00mil 15.00mil 20.00mil "clearline"]
+	Line[2665.00mil 1250.00mil 2750.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[2750.00mil 1165.00mil 3105.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[3290.00mil 1350.00mil 3105.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[2460.00mil 2225.00mil 2785.00mil 1900.00mil 10.00mil 14.00mil "clearline"]
+	Line[2785.00mil 1900.00mil 2785.00mil 1200.00mil 10.00mil 14.00mil "clearline"]
+	Line[5760.00mil 42.7110mm 5760.00mil 1715.00mil 6.00mil 12.00mil "clearline"]
+	Text[1575.00mil 2715.00mil 0 142 "20190115" "clearline"]
+	Polygon("")
+	(
+		[6405.00mil 1795.00mil] [6405.00mil 2135.00mil] [6315.00mil 2225.00mil] [6315.00mil 2430.00mil] [6505.00mil 2430.00mil] 
+		[6505.00mil 2215.00mil] [6525.00mil 2195.00mil] [6590.00mil 2195.00mil] [6610.00mil 2215.00mil] [6610.00mil 2225.00mil] 
+		[6590.00mil 2245.00mil] [6565.00mil 2245.00mil] [6565.00mil 2310.00mil] [6705.00mil 2310.00mil] [6705.00mil 2160.00mil] 
+		[6615.00mil 2070.00mil] [6615.00mil 1795.00mil] 
+	)
+	Polygon("")
+	(
+		[6200.00mil 1795.00mil] [6200.00mil 1985.00mil] [6230.00mil 2015.00mil] [6230.00mil 2215.00mil] [6260.00mil 2245.00mil] 
+		[6305.00mil 2245.00mil] [6305.00mil 2430.00mil] [6115.00mil 2430.00mil] [6115.00mil 2310.00mil] [5965.00mil 2310.00mil] 
+		[5965.00mil 2200.00mil] [6005.00mil 2160.00mil] [6005.00mil 1795.00mil] 
+	)
+	Polygon("")
+	(
+		[6515.00mil 2320.00mil] [7015.00mil 2320.00mil] [7015.00mil 2500.00mil] [6755.00mil 2500.00mil] [6665.00mil 2590.00mil] 
+		[6515.00mil 2590.00mil] 
+	)
+	Polygon("")
+	(
+		[6105.00mil 2320.00mil] [4940.00mil 2320.00mil] [4940.00mil 2500.00mil] [5865.00mil 2500.00mil] [5955.00mil 2590.00mil] 
+		[6105.00mil 2590.00mil] 
+	)
+	Polygon("")
+	(
+		[7015.00mil 2510.00mil] [6760.00mil 2510.00mil] [6670.00mil 2600.00mil] [6455.00mil 2600.00mil] [6415.00mil 2640.00mil] 
+		[6235.00mil 2640.00mil] [6235.00mil 2675.00mil] [6225.00mil 2685.00mil] [6195.00mil 2685.00mil] [6185.00mil 2675.00mil] 
+		[6185.00mil 2600.00mil] [5950.00mil 2600.00mil] [5860.00mil 2510.00mil] [4940.00mil 2510.00mil] [4940.00mil 2880.00mil] 
+		[6830.00mil 2880.00mil] [7010.00mil 2700.00mil] 
+	)
+	Polygon("")
+	(
+		[6115.00mil 2440.00mil] [6260.00mil 2440.00mil] [6260.00mil 2555.00mil] [6270.00mil 2565.00mil] [6300.00mil 2565.00mil] 
+		[6310.00mil 2555.00mil] [6310.00mil 2440.00mil] [6455.00mil 2440.00mil] [6455.00mil 2585.00mil] [6410.00mil 2630.00mil] 
+		[6235.00mil 2630.00mil] [6235.00mil 2600.00mil] [6225.00mil 2590.00mil] [6115.00mil 2590.00mil] 
+	)
+	Polygon("clearpoly")
+	(
+		[6715.00mil 2330.00mil] [6715.00mil 2155.00mil] [6625.00mil 2065.00mil] [6625.00mil 1560.00mil] [5995.00mil 1560.00mil] 
+		[5995.00mil 1765.00mil] [5860.00mil 1765.00mil] [5860.00mil 1100.00mil] [7015.00mil 1100.00mil] [7015.00mil 2330.00mil] 
+	)
+)
+Layer(2 "signal2")
+(
+	Polygon("clearpoly")
+	(
+		[7015.00mil 1795.00mil] [6625.00mil 1795.00mil] [6625.00mil 1600.00mil] [6065.00mil 1600.00mil] [5995.00mil 1670.00mil] 
+		[5995.00mil 1945.00mil] [5910.00mil 2030.00mil] [5910.00mil 2310.00mil] [4930.00mil 2310.00mil] [4930.00mil 2925.00mil] 
+		[1410.00mil 2925.00mil] [1410.00mil 1100.00mil] [7015.00mil 1100.00mil] 
+	)
+	Polygon("clearpoly")
+	(
+		[7015.00mil 1795.00mil] [7015.00mil 2880.00mil] [4940.00mil 2880.00mil] [4940.00mil 2320.00mil] [5920.00mil 2320.00mil] 
+		[5920.00mil 2040.00mil] [6005.00mil 1955.00mil] [6005.00mil 1675.00mil] [6070.00mil 1610.00mil] [6615.00mil 1610.00mil] 
+		[6615.00mil 1795.00mil] 
+	)
+)
+Layer(3 "signal3")
+(
+	Line[6580.00mil 2220.00mil 6580.00mil 2250.00mil 35.00mil 20.00mil "clearline"]
+	Line[6580.00mil 2250.00mil 6560.00mil 2270.00mil 35.00mil 20.00mil "clearline"]
+	Line[6560.00mil 2270.00mil 6320.00mil 2270.00mil 35.00mil 20.00mil "clearline"]
+	Line[6190.00mil 2140.00mil 6320.00mil 2270.00mil 35.00mil 20.00mil "clearline"]
+	Line[6190.00mil 2140.00mil 6130.00mil 2140.00mil 35.00mil 20.00mil "clearline"]
+	Line[6130.00mil 2140.00mil 6055.00mil 2065.00mil 35.00mil 20.00mil "clearline"]
+	Line[6310.00mil 54.1630mm 6322.60mil 54.1630mm 15.00mil 20.00mil "clearline"]
+	Line[6322.60mil 54.1630mm 6340.00mil 2115.00mil 15.00mil 20.00mil "clearline"]
+	Line[6340.00mil 2115.00mil 6340.00mil 2005.00mil 15.00mil 20.00mil "clearline"]
+	Line[6340.00mil 2005.00mil 6375.00mil 1970.00mil 15.00mil 20.00mil "clearline"]
+	Line[5980.00mil 2065.00mil 6055.00mil 2065.00mil 35.00mil 20.00mil "clearline"]
+	Line[6250.00mil 1970.00mil 6375.00mil 1970.00mil 15.00mil 20.00mil "clearline"]
+	Line[6225.00mil 1890.00mil 6110.00mil 2005.00mil 10.00mil 14.00mil "clearline"]
+	Line[6110.00mil 2005.00mil 5995.00mil 2005.00mil 10.00mil 14.00mil "clearline"]
+	Line[6225.00mil 1935.00mil 6255.00mil 1905.00mil 10.00mil 14.00mil "clearline"]
+	Line[6255.00mil 1905.00mil 6255.00mil 1830.00mil 10.00mil 14.00mil "clearline"]
+	Line[6255.00mil 1830.00mil 6225.00mil 1800.00mil 10.00mil 14.00mil "clearline"]
+	Line[6270.00mil 1745.00mil 6375.00mil 1850.00mil 15.00mil 20.00mil "clearline"]
+	Line[6375.00mil 1850.00mil 6375.00mil 1970.00mil 15.00mil 20.00mil "clearline"]
+	Line[5940.00mil 2545.00mil 5970.00mil 2515.00mil 10.00mil 14.00mil "clearline"]
+	Line[5970.00mil 2515.00mil 5970.00mil 2110.00mil 10.00mil 14.00mil "clearline"]
+	Line[5970.00mil 2110.00mil 5950.00mil 2090.00mil 10.00mil 14.00mil "clearline"]
+	Line[5950.00mil 2090.00mil 5950.00mil 2050.00mil 10.00mil 14.00mil "clearline"]
+	Line[5950.00mil 2050.00mil 5995.00mil 2005.00mil 10.00mil 14.00mil "clearline"]
+	Line[5950.00mil 1480.00mil 5955.00mil 1485.00mil 10.00mil 14.00mil "clearline"]
+	Line[5955.00mil 1485.00mil 6465.00mil 1485.00mil 10.00mil 14.00mil "clearline"]
+	Line[5880.00mil 1370.00mil 5915.00mil 1405.00mil 6.00mil 12.00mil "clearline"]
+	Line[5915.00mil 1405.00mil 5915.00mil 1500.00mil 6.00mil 12.00mil "clearline"]
+	Line[5880.00mil 1410.00mil 5880.00mil 1545.00mil 6.00mil 12.00mil "clearline"]
+	Line[5950.00mil 1480.00mil 5950.00mil 1505.00mil 10.00mil 14.00mil "clearline"]
+	Line[5950.00mil 1505.00mil 5910.00mil 1545.00mil 10.00mil 14.00mil "clearline"]
+	Line[5910.00mil 1545.00mil 5675.00mil 1545.00mil 10.00mil 14.00mil "clearline"]
+	Line[5675.00mil 1545.00mil 5645.00mil 1515.00mil 10.00mil 14.00mil "clearline"]
+	Line[1725.00mil 1160.00mil 6060.00mil 1160.00mil 115.00mil 20.00mil "clearline"]
+	Line[5540.00mil 1350.00mil 5540.00mil 1160.00mil 35.00mil 20.00mil "clearline"]
+	Line[5285.00mil 1350.00mil 5285.00mil 1160.00mil 35.00mil 20.00mil "clearline"]
+	Line[3945.00mil 1350.00mil 3945.00mil 1160.00mil 25.00mil 20.00mil "clearline"]
+	Line[3390.00mil 1350.00mil 3390.00mil 1160.00mil 25.00mil 20.00mil "clearline"]
+	Line[2835.00mil 1350.00mil 2835.00mil 1160.00mil 25.00mil 20.00mil "clearline"]
+	Line[2280.00mil 1350.00mil 2280.00mil 1160.00mil 25.00mil 20.00mil "clearline"]
+	Line[1725.00mil 1350.00mil 1725.00mil 1160.00mil 25.00mil 20.00mil "clearline"]
+	Line[1880.00mil 43.2360mm 4100.00mil 43.2360mm 65.00mil 20.00mil "clearline"]
+	Line[4100.00mil 43.2360mm 4337.20mil 1465.00mil 65.00mil 20.00mil "clearline"]
+	Line[4337.20mil 1465.00mil 5485.00mil 1465.00mil 65.00mil 20.00mil "clearline"]
+	Line[5485.00mil 1465.00mil 5545.00mil 1525.00mil 65.00mil 20.00mil "clearline"]
+	Line[5545.00mil 1525.00mil 5545.00mil 1610.00mil 65.00mil 20.00mil "clearline"]
+	Line[5545.00mil 1610.00mil 5590.00mil 1610.00mil 65.00mil 20.00mil "clearline"]
+	Line[5590.00mil 1610.00mil 5635.00mil 1655.00mil 65.00mil 20.00mil "clearline"]
+	Line[3845.00mil 1350.00mil 3750.00mil 1445.00mil 15.00mil 20.00mil "clearline"]
+	Line[3750.00mil 1445.00mil 2775.00mil 1445.00mil 15.00mil 20.00mil "clearline"]
+	Line[2775.00mil 1445.00mil 2680.00mil 1540.00mil 15.00mil 20.00mil "clearline"]
+	Line[2680.00mil 1540.00mil 2535.00mil 1540.00mil 15.00mil 20.00mil "clearline"]
+	Line[2535.00mil 1540.00mil 2460.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[5440.00mil 1350.00mil 5380.00mil 1410.00mil 15.00mil 20.00mil "clearline"]
+	Line[5380.00mil 1410.00mil 4320.00mil 1410.00mil 15.00mil 20.00mil "clearline"]
+	Line[4320.00mil 1410.00mil 4255.00mil 1475.00mil 15.00mil 20.00mil "clearline"]
+	Line[5185.00mil 1350.00mil 5105.00mil 1270.00mil 15.00mil 20.00mil "clearline"]
+	Line[5105.00mil 1270.00mil 4400.00mil 1270.00mil 15.00mil 20.00mil "clearline"]
+	Line[4400.00mil 1270.00mil 4340.00mil 1330.00mil 15.00mil 20.00mil "clearline"]
+	Line[4340.00mil 1330.00mil 4340.00mil 1355.00mil 15.00mil 20.00mil "clearline"]
+	Line[4340.00mil 1355.00mil 4275.00mil 1420.00mil 15.00mil 20.00mil "clearline"]
+	Line[4275.00mil 1420.00mil 3860.00mil 1420.00mil 15.00mil 20.00mil "clearline"]
+	Line[3860.00mil 1420.00mil 3800.00mil 1480.00mil 15.00mil 20.00mil "clearline"]
+	Line[4255.00mil 1475.00mil 3870.00mil 1475.00mil 15.00mil 20.00mil "clearline"]
+	Line[3870.00mil 1475.00mil 3835.00mil 1510.00mil 15.00mil 20.00mil "clearline"]
+	Line[3800.00mil 1480.00mil 2785.00mil 1480.00mil 15.00mil 20.00mil "clearline"]
+	Line[2785.00mil 1480.00mil 2690.00mil 1575.00mil 15.00mil 20.00mil "clearline"]
+	Line[2690.00mil 1575.00mil 2670.00mil 1575.00mil 15.00mil 20.00mil "clearline"]
+	Line[2670.00mil 1575.00mil 2630.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[3835.00mil 1510.00mil 2845.00mil 1510.00mil 15.00mil 20.00mil "clearline"]
+	Line[2845.00mil 1510.00mil 2740.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[4765.00mil 2060.00mil 4980.00mil 2275.00mil 25.00mil 20.00mil "clearline"]
+	Line[4980.00mil 2275.00mil 4980.00mil 2430.00mil 25.00mil 20.00mil "clearline"]
+	Line[3760.00mil 2825.00mil 3760.00mil 2665.00mil 10.00mil 14.00mil "clearline"]
+	Line[3760.00mil 2665.00mil 3825.00mil 2600.00mil 10.00mil 14.00mil "clearline"]
+	Line[3660.00mil 2825.00mil 3660.00mil 2705.00mil 10.00mil 14.00mil "clearline"]
+	Line[3660.00mil 2705.00mil 3800.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[2760.00mil 2825.00mil 2820.00mil 2885.00mil 10.00mil 14.00mil "clearline"]
+	Line[2820.00mil 2885.00mil 4805.00mil 2885.00mil 10.00mil 14.00mil "clearline"]
+	Line[4805.00mil 2885.00mil 4875.00mil 2815.00mil 10.00mil 14.00mil "clearline"]
+	Line[3800.00mil 2565.00mil 4635.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[3825.00mil 2600.00mil 4495.00mil 2600.00mil 10.00mil 14.00mil "clearline"]
+	Line[4545.00mil 2505.00mil 3590.00mil 2505.00mil 10.00mil 14.00mil "clearline"]
+	Line[4875.00mil 2815.00mil 4875.00mil 2280.00mil 10.00mil 14.00mil "clearline"]
+	Line[4875.00mil 2280.00mil 4895.00mil 2260.00mil 10.00mil 14.00mil "clearline"]
+	Line[4290.00mil 2455.00mil 3275.00mil 2455.00mil 10.00mil 14.00mil "clearline"]
+	Line[3275.00mil 2455.00mil 3110.00mil 2290.00mil 10.00mil 14.00mil "clearline"]
+	Line[3110.00mil 2290.00mil 3110.00mil 2195.00mil 10.00mil 14.00mil "clearline"]
+	Line[3110.00mil 2195.00mil 3085.00mil 2170.00mil 10.00mil 14.00mil "clearline"]
+	Line[3085.00mil 2170.00mil 3015.00mil 2170.00mil 10.00mil 14.00mil "clearline"]
+	Line[3015.00mil 2170.00mil 2960.00mil 2225.00mil 10.00mil 14.00mil "clearline"]
+	Line[4655.00mil 2300.00mil 3655.00mil 2300.00mil 10.00mil 14.00mil "clearline"]
+	Line[3655.00mil 2300.00mil 3610.00mil 2255.00mil 10.00mil 14.00mil "clearline"]
+	Line[3610.00mil 2255.00mil 3610.00mil 2195.00mil 10.00mil 14.00mil "clearline"]
+	Line[3610.00mil 2195.00mil 3580.00mil 2165.00mil 10.00mil 14.00mil "clearline"]
+	Line[3580.00mil 2165.00mil 3520.00mil 2165.00mil 10.00mil 14.00mil "clearline"]
+	Line[3520.00mil 2165.00mil 3460.00mil 2225.00mil 10.00mil 14.00mil "clearline"]
+	Line[4645.00mil 2360.00mil 3650.00mil 2360.00mil 10.00mil 14.00mil "clearline"]
+	Line[3650.00mil 2360.00mil 3560.00mil 2270.00mil 10.00mil 14.00mil "clearline"]
+	Line[3560.00mil 2270.00mil 3560.00mil 2225.00mil 10.00mil 14.00mil "clearline"]
+	Line[4545.00mil 2505.00mil 4550.00mil 2500.00mil 10.00mil 14.00mil "clearline"]
+	Line[2860.00mil 2225.00mil 2875.00mil 2225.00mil 10.00mil 14.00mil "clearline"]
+	Line[2875.00mil 2225.00mil 3080.00mil 2020.00mil 10.00mil 14.00mil "clearline"]
+	Line[2760.00mil 2225.00mil 2760.00mil 2070.00mil 10.00mil 14.00mil "clearline"]
+	Line[2760.00mil 2070.00mil 2810.00mil 2020.00mil 10.00mil 14.00mil "clearline"]
+	Line[2810.00mil 2020.00mil 3035.00mil 2020.00mil 10.00mil 14.00mil "clearline"]
+	Line[3035.00mil 2020.00mil 3060.00mil 1995.00mil 10.00mil 14.00mil "clearline"]
+	Line[3060.00mil 1995.00mil 3490.00mil 1995.00mil 10.00mil 14.00mil "clearline"]
+	Line[3490.00mil 1995.00mil 3525.00mil 2030.00mil 10.00mil 14.00mil "clearline"]
+	Line[3525.00mil 2030.00mil 3590.00mil 2030.00mil 10.00mil 14.00mil "clearline"]
+	Line[3080.00mil 2020.00mil 3470.00mil 2020.00mil 10.00mil 14.00mil "clearline"]
+	Line[3470.00mil 2020.00mil 3505.00mil 2055.00mil 10.00mil 14.00mil "clearline"]
+	Line[4660.00mil 2225.00mil 4660.00mil 2080.00mil 10.00mil 14.00mil "clearline"]
+	Line[4660.00mil 2080.00mil 4550.00mil 1970.00mil 10.00mil 14.00mil "clearline"]
+	Line[4550.00mil 1970.00mil 4550.00mil 1850.00mil 10.00mil 14.00mil "clearline"]
+	Line[4550.00mil 1850.00mil 4500.00mil 1800.00mil 10.00mil 14.00mil "clearline"]
+	Line[4500.00mil 1800.00mil 4340.00mil 1800.00mil 10.00mil 14.00mil "clearline"]
+	Line[4340.00mil 1800.00mil 4225.00mil 1685.00mil 10.00mil 14.00mil "clearline"]
+	Line[4495.00mil 1865.00mil 4330.00mil 2030.00mil 10.00mil 14.00mil "clearline"]
+	Line[4330.00mil 2030.00mil 4085.00mil 2030.00mil 10.00mil 14.00mil "clearline"]
+	Line[4085.00mil 2030.00mil 4045.00mil 1990.00mil 10.00mil 14.00mil "clearline"]
+	Line[4045.00mil 1990.00mil 3625.00mil 1995.00mil 10.00mil 14.00mil "clearline"]
+	Line[3625.00mil 1995.00mil 3590.00mil 2030.00mil 10.00mil 14.00mil "clearline"]
+	Line[3505.00mil 2055.00mil 3860.00mil 2055.00mil 10.00mil 14.00mil "clearline"]
+	Line[3860.00mil 2055.00mil 3890.00mil 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[3890.00mil 2025.00mil 4030.00mil 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[4030.00mil 2025.00mil 4140.00mil 2135.00mil 10.00mil 14.00mil "clearline"]
+	Line[4140.00mil 2135.00mil 4155.00mil 2135.00mil 10.00mil 14.00mil "clearline"]
+	Line[3590.00mil 2505.00mil 3360.00mil 2735.00mil 10.00mil 14.00mil "clearline"]
+	Line[3360.00mil 2735.00mil 3150.00mil 2735.00mil 10.00mil 14.00mil "clearline"]
+	Line[3150.00mil 2735.00mil 3060.00mil 2825.00mil 10.00mil 14.00mil "clearline"]
+	Line[3390.00mil 2655.00mil 3045.00mil 2655.00mil 10.00mil 14.00mil "clearline"]
+	Line[3045.00mil 2655.00mil 2710.00mil 2320.00mil 10.00mil 14.00mil "clearline"]
+	Line[3295.00mil 2595.00mil 3085.00mil 2595.00mil 10.00mil 14.00mil "clearline"]
+	Line[3085.00mil 2595.00mil 2810.00mil 2320.00mil 10.00mil 14.00mil "clearline"]
+	Line[3435.00mil 2550.00mil 3380.00mil 2495.00mil 10.00mil 14.00mil "clearline"]
+	Line[3380.00mil 2495.00mil 3185.00mil 2495.00mil 10.00mil 14.00mil "clearline"]
+	Line[3185.00mil 2495.00mil 3010.00mil 2320.00mil 10.00mil 14.00mil "clearline"]
+	Line[3370.00mil 2580.00mil 3325.00mil 2535.00mil 10.00mil 14.00mil "clearline"]
+	Line[3325.00mil 2535.00mil 3125.00mil 2535.00mil 10.00mil 14.00mil "clearline"]
+	Line[3125.00mil 2535.00mil 2910.00mil 2320.00mil 10.00mil 14.00mil "clearline"]
+	Polygon("clearpoly")
+	(
+		[5510.00mil 2320.00mil] [5510.00mil 2880.00mil] [7015.00mil 2880.00mil] [7015.00mil 1200.00mil] [6580.00mil 1200.00mil] 
+		[6580.00mil 2320.00mil] 
+	)
+	Polygon("clearpoly")
+	(
+		[5675.00mil 1840.00mil] [5995.00mil 1840.00mil] [5995.00mil 1560.00mil] [5675.00mil 1560.00mil] 
+	)
+)
+Layer(4 "bottom")
+(
+	Line[159.0241mm 2169.80mil 159.0241mm 55.4789mm 10.00mil 14.00mil "clearline"]
+	Line[159.0241mm 55.4789mm 6230.00mil 2215.00mil 10.00mil 14.00mil "clearline"]
+	Line[6230.00mil 2215.00mil 6230.00mil 57.3890mm 10.00mil 14.00mil "clearline"]
+	Line[161.5239mm 2169.80mil 161.5239mm 55.6059mm 10.00mil 14.00mil "clearline"]
+	Line[161.0241mm 2169.80mil 161.0241mm 55.7411mm 10.00mil 14.00mil "clearline"]
+	Line[160.5239mm 2169.80mil 160.5239mm 55.8759mm 10.00mil 14.00mil "clearline"]
+	Line[160.5239mm 55.8759mm 6350.00mil 2230.00mil 10.00mil 14.00mil "clearline"]
+	Line[160.0241mm 2169.80mil 160.0241mm 56.0111mm 10.00mil 14.00mil "clearline"]
+	Line[160.0241mm 56.0111mm 6320.00mil 2225.00mil 10.00mil 14.00mil "clearline"]
+	Line[6320.00mil 2225.00mil 6320.00mil 2230.00mil 10.00mil 14.00mil "clearline"]
+	Line[6230.00mil 58.6890mm 159.7510mm 58.6890mm 15.00mil 20.00mil "clearline"]
+	Line[159.7510mm 58.6890mm 6320.00mil 2280.00mil 15.00mil 20.00mil "clearline"]
+	Line[6320.00mil 2280.00mil 6320.00mil 2230.00mil 15.00mil 20.00mil "clearline"]
+	Line[6285.00mil 57.3890mm 6285.00mil 2235.00mil 15.00mil 20.00mil "clearline"]
+	Line[6285.00mil 2235.00mil 6270.00mil 2220.00mil 15.00mil 20.00mil "clearline"]
+	Line[159.5239mm 2169.80mil 159.5239mm 56.1221mm 10.00mil 14.00mil "clearline"]
+	Line[159.5239mm 56.1221mm 6270.00mil 2220.00mil 10.00mil 14.00mil "clearline"]
+	Line[161.5239mm 55.6059mm 6385.00mil 2215.00mil 10.00mil 14.00mil "clearline"]
+	Line[6385.00mil 2215.00mil 6405.00mil 2215.00mil 10.00mil 14.00mil "clearline"]
+	Line[161.0241mm 55.7411mm 6405.00mil 2260.00mil 10.00mil 14.00mil "clearline"]
+	Line[6350.00mil 2230.00mil 6350.00mil 2240.00mil 10.00mil 14.00mil "clearline"]
+	Line[6350.00mil 2240.00mil 6350.00mil 2405.00mil 25.00mil 20.00mil "clearline"]
+	Line[6350.00mil 2405.00mil 6485.00mil 2540.00mil 25.00mil 20.00mil "clearline"]
+	Line[6585.00mil 54.9580mm 6585.00mil 2215.00mil 25.00mil 20.00mil "clearline"]
+	Line[6585.00mil 2215.00mil 6580.00mil 2220.00mil 25.00mil 20.00mil "clearline"]
+	Line[160.0241mm 55.1139mm 160.0241mm 54.4129mm 15.00mil 20.00mil "clearline"]
+	Line[160.0241mm 54.4129mm 6310.00mil 54.1630mm 15.00mil 20.00mil "clearline"]
+	Line[6241.10mil 2169.80mil 6190.00mil 2220.90mil 15.00mil 20.00mil "clearline"]
+	Line[5935.00mil 2165.00mil 5935.00mil 2225.00mil 25.00mil 20.00mil "clearline"]
+	Line[6190.00mil 2225.00mil 6190.00mil 2445.00mil 25.00mil 20.00mil "clearline"]
+	Line[6190.00mil 2445.00mil 6285.00mil 2540.00mil 25.00mil 20.00mil "clearline"]
+	Line[6190.00mil 2220.90mil 6190.00mil 2225.00mil 15.00mil 20.00mil "clearline"]
+	Line[157.8741mm 53.4629mm 156.8409mm 53.4629mm 10.00mil 14.00mil "clearline"]
+	Line[156.8409mm 53.4629mm 6165.00mil 2095.00mil 10.00mil 14.00mil "clearline"]
+	Line[157.8741mm 53.9631mm 156.1981mm 53.9631mm 10.00mil 14.00mil "clearline"]
+	Line[5935.00mil 2165.00mil 5985.00mil 2115.00mil 25.00mil 20.00mil "clearline"]
+	Line[5985.00mil 2115.00mil 6130.00mil 2115.00mil 25.00mil 20.00mil "clearline"]
+	Line[156.1981mm 53.9631mm 6140.00mil 2115.00mil 10.00mil 14.00mil "clearline"]
+	Line[6140.00mil 2115.00mil 6130.00mil 2115.00mil 10.00mil 14.00mil "clearline"]
+	Line[6050.00mil 55.1510mm 6071.30mil 2150.00mil 25.00mil 20.00mil "clearline"]
+	Line[6071.30mil 2150.00mil 6180.00mil 2150.00mil 25.00mil 20.00mil "clearline"]
+	Line[157.8741mm 54.4629mm 157.1191mm 54.4629mm 10.00mil 14.00mil "clearline"]
+	Line[157.1191mm 54.4629mm 6180.00mil 2150.00mil 10.00mil 14.00mil "clearline"]
+	Line[6165.00mil 2195.00mil 155.7170mm 2195.00mil 25.00mil 20.00mil "clearline"]
+	Line[155.7170mm 2195.00mil 6125.00mil 55.8950mm 25.00mil 20.00mil "clearline"]
+	Line[6535.00mil 2225.00mil 6535.00mil 2215.00mil 25.00mil 20.00mil "clearline"]
+	Line[6535.00mil 2215.00mil 6505.00mil 2185.00mil 25.00mil 20.00mil "clearline"]
+	Line[6505.00mil 2185.00mil 6475.00mil 2185.00mil 25.00mil 20.00mil "clearline"]
+	Line[6475.00mil 2185.00mil 6445.00mil 2215.00mil 25.00mil 20.00mil "clearline"]
+	Line[6445.00mil 2215.00mil 6405.00mil 2215.00mil 25.00mil 20.00mil "clearline"]
+	Line[6405.00mil 2260.00mil 6405.00mil 2285.00mil 25.00mil 20.00mil "clearline"]
+	Line[6405.00mil 2285.00mil 6420.00mil 2300.00mil 25.00mil 20.00mil "clearline"]
+	Line[6420.00mil 2300.00mil 6561.30mil 2300.00mil 25.00mil 20.00mil "clearline"]
+	Line[6561.30mil 2300.00mil 6585.00mil 57.8180mm 25.00mil 20.00mil "clearline"]
+	Line[6490.00mil 2225.00mil 6465.00mil 2250.00mil 25.00mil 20.00mil "clearline"]
+	Line[6465.00mil 2250.00mil 6445.00mil 2250.00mil 25.00mil 20.00mil "clearline"]
+	Line[162.6739mm 54.4629mm 163.3421mm 54.4629mm 10.00mil 14.00mil "clearline"]
+	Line[163.3421mm 54.4629mm 6460.00mil 2115.00mil 10.00mil 14.00mil "clearline"]
+	Line[162.6739mm 52.4629mm 162.6739mm 52.9631mm 10.00mil 14.00mil "clearline"]
+	Line[162.6739mm 52.9631mm 161.9739mm 52.9631mm 10.00mil 14.00mil "clearline"]
+	Line[161.9739mm 52.9631mm 161.7240mm 2095.00mil 10.00mil 14.00mil "clearline"]
+	Line[162.6739mm 53.9631mm 163.2069mm 53.9631mm 10.00mil 14.00mil "clearline"]
+	Line[6378.90mil 2169.80mil 6450.20mil 2169.80mil 15.00mil 20.00mil "clearline"]
+	Line[6450.20mil 2169.80mil 6475.00mil 2145.00mil 15.00mil 20.00mil "clearline"]
+	Line[163.2069mm 53.9631mm 6465.00mil 2085.00mil 10.00mil 14.00mil "clearline"]
+	Line[162.6739mm 53.4629mm 163.0721mm 53.4629mm 10.00mil 14.00mil "clearline"]
+	Line[163.0721mm 53.4629mm 6430.00mil 2095.00mil 10.00mil 14.00mil "clearline"]
+	Line[6430.00mil 2095.00mil 6430.00mil 2060.00mil 10.00mil 14.00mil "clearline"]
+	Line[6430.00mil 2060.00mil 6455.00mil 2035.00mil 10.00mil 14.00mil "clearline"]
+	Line[6455.00mil 2035.00mil 6465.00mil 2035.00mil 10.00mil 14.00mil "clearline"]
+	Line[6460.00mil 2115.00mil 6490.00mil 2115.00mil 10.00mil 14.00mil "clearline"]
+	Line[6490.00mil 2115.00mil 6500.00mil 2125.00mil 10.00mil 14.00mil "clearline"]
+	Line[6465.00mil 52.9740mm 165.3240mm 52.9740mm 15.00mil 20.00mil "clearline"]
+	Line[165.3240mm 52.9740mm 165.4660mm 2080.00mil 15.00mil 20.00mil "clearline"]
+	Line[6465.00mil 2035.00mil 165.2120mm 2035.00mil 15.00mil 20.00mil "clearline"]
+	Line[165.2120mm 2035.00mil 165.4660mm 2025.00mil 15.00mil 20.00mil "clearline"]
+	Line[6730.00mil 2140.00mil 6670.00mil 2080.00mil 10.00mil 14.00mil "clearline"]
+	Line[6670.00mil 2080.00mil 6565.00mil 2080.00mil 10.00mil 14.00mil "clearline"]
+	Line[6210.00mil 2660.00mil 6235.00mil 2635.00mil 10.00mil 14.00mil "clearline"]
+	Line[6235.00mil 2635.00mil 6545.00mil 2635.00mil 10.00mil 14.00mil "clearline"]
+	Line[6750.00mil 2135.00mil 6640.00mil 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[6640.00mil 2025.00mil 166.7660mm 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[6750.00mil 2135.00mil 6750.00mil 2430.00mil 10.00mil 14.00mil "clearline"]
+	Line[6750.00mil 2430.00mil 6545.00mil 2635.00mil 10.00mil 14.00mil "clearline"]
+	Line[6210.00mil 2615.00mil 6540.00mil 2615.00mil 10.00mil 14.00mil "clearline"]
+	Line[6540.00mil 2615.00mil 6730.00mil 2425.00mil 10.00mil 14.00mil "clearline"]
+	Line[6730.00mil 2140.00mil 6730.00mil 2425.00mil 10.00mil 14.00mil "clearline"]
+	Line[6680.00mil 2545.00mil 6740.00mil 2545.00mil 10.00mil 14.00mil "clearline"]
+	Line[6740.00mil 2545.00mil 6810.00mil 2475.00mil 10.00mil 14.00mil "clearline"]
+	Line[161.5239mm 2020.20mil 161.5239mm 50.4391mm 10.00mil 14.00mil "clearline"]
+	Line[6050.00mil 52.2910mm 5986.30mil 52.2910mm 25.00mil 20.00mil "clearline"]
+	Line[5986.30mil 52.2910mm 5980.00mil 2065.00mil 25.00mil 20.00mil "clearline"]
+	Line[156.7330mm 52.2120mm 157.4841mm 52.9631mm 10.00mil 14.00mil "clearline"]
+	Line[157.4841mm 52.9631mm 157.8741mm 52.9631mm 10.00mil 14.00mil "clearline"]
+	Line[6090.00mil 50.8150mm 6105.00mil 51.1960mm 10.00mil 14.00mil "clearline"]
+	Line[6105.00mil 51.1960mm 6105.00mil 2030.00mil 10.00mil 14.00mil "clearline"]
+	Line[6105.00mil 2030.00mil 155.7170mm 52.2120mm 10.00mil 14.00mil "clearline"]
+	Line[155.7170mm 52.2120mm 156.7330mm 52.2120mm 10.00mil 14.00mil "clearline"]
+	Line[161.0241mm 2020.20mil 161.0241mm 48.8980mm 10.00mil 14.00mil "clearline"]
+	Line[161.0241mm 48.8980mm 161.0210mm 1925.00mil 10.00mil 14.00mil "clearline"]
+	Line[161.0210mm 1925.00mil 161.0210mm 1880.00mil 10.00mil 14.00mil "clearline"]
+	Line[161.0210mm 1880.00mil 6335.00mil 47.6400mm 10.00mil 14.00mil "clearline"]
+	Line[161.5239mm 50.4391mm 162.3210mm 49.6420mm 10.00mil 14.00mil "clearline"]
+	Line[162.3210mm 49.6420mm 162.3210mm 1880.00mil 10.00mil 14.00mil "clearline"]
+	Line[162.3210mm 1880.00mil 6395.00mil 47.6400mm 10.00mil 14.00mil "clearline"]
+	Line[6335.00mil 46.3400mm 6395.00mil 46.3400mm 10.00mil 14.00mil "clearline"]
+	Line[162.6739mm 51.9631mm 6430.00mil 51.3150mm 10.00mil 14.00mil "clearline"]
+	Line[6430.00mil 51.3150mm 6430.00mil 2015.00mil 10.00mil 14.00mil "clearline"]
+	Line[6430.00mil 2015.00mil 6440.00mil 2005.00mil 10.00mil 14.00mil "clearline"]
+	Line[6440.00mil 2005.00mil 164.4800mm 2005.00mil 10.00mil 14.00mil "clearline"]
+	Line[164.4800mm 2005.00mil 165.3690mm 1970.00mil 10.00mil 14.00mil "clearline"]
+	Line[6378.90mil 2020.20mil 6379.80mil 2020.20mil 10.00mil 14.00mil "clearline"]
+	Line[6379.80mil 2020.20mil 6430.00mil 1970.00mil 10.00mil 14.00mil "clearline"]
+	Line[6430.00mil 1970.00mil 164.0690mm 1970.00mil 10.00mil 14.00mil "clearline"]
+	Line[6430.00mil 1970.00mil 6430.00mil 49.1640mm 10.00mil 14.00mil "clearline"]
+	Line[6430.00mil 49.1640mm 6445.00mil 48.7830mm 10.00mil 14.00mil "clearline"]
+	Line[6395.00mil 47.6400mm 163.5460mm 47.6400mm 10.00mil 14.00mil "clearline"]
+	Line[163.5460mm 47.6400mm 6445.00mil 47.4830mm 10.00mil 14.00mil "clearline"]
+	Line[165.3690mm 1970.00mil 6670.00mil 1970.00mil 10.00mil 14.00mil "clearline"]
+	Line[6670.00mil 1970.00mil 6810.00mil 2110.00mil 10.00mil 14.00mil "clearline"]
+	Line[6810.00mil 2475.00mil 6810.00mil 2110.00mil 10.00mil 14.00mil "clearline"]
+	Line[6085.00mil 49.5150mm 155.7990mm 49.5150mm 10.00mil 14.00mil "clearline"]
+	Line[155.7990mm 49.5150mm 155.8140mm 1950.00mil 10.00mil 14.00mil "clearline"]
+	Line[160.5239mm 2020.20mil 160.5239mm 48.6369mm 10.00mil 14.00mil "clearline"]
+	Line[160.5239mm 48.6369mm 6305.00mil 1900.00mil 10.00mil 14.00mil "clearline"]
+	Line[157.8741mm 52.4629mm 157.8741mm 51.3211mm 10.00mil 14.00mil "clearline"]
+	Line[157.8741mm 51.3211mm 157.1140mm 50.5610mm 10.00mil 14.00mil "clearline"]
+	Line[6145.00mil 50.9120mm 156.8600mm 50.9120mm 10.00mil 14.00mil "clearline"]
+	Line[156.8600mm 50.9120mm 6187.50mil 1992.50mil 10.00mil 14.00mil "clearline"]
+	Line[159.0241mm 2020.20mil 159.0241mm 50.3121mm 10.00mil 14.00mil "clearline"]
+	Line[159.0241mm 50.3121mm 6250.00mil 1970.00mil 10.00mil 14.00mil "clearline"]
+	Line[6241.10mil 2020.20mil 6241.10mil 2016.10mil 10.00mil 14.00mil "clearline"]
+	Line[6241.10mil 2016.10mil 6220.00mil 1995.00mil 10.00mil 14.00mil "clearline"]
+	Line[6220.00mil 1995.00mil 6220.00mil 1940.00mil 10.00mil 14.00mil "clearline"]
+	Line[6220.00mil 1940.00mil 6225.00mil 1935.00mil 10.00mil 14.00mil "clearline"]
+	Line[157.1140mm 50.5610mm 157.1140mm 49.0070mm 10.00mil 14.00mil "clearline"]
+	Line[157.1140mm 49.0070mm 6225.00mil 1890.00mil 10.00mil 14.00mil "clearline"]
+	Line[159.5239mm 2020.20mil 159.5239mm 49.6689mm 10.00mil 14.00mil "clearline"]
+	Line[159.5239mm 49.6689mm 6255.00mil 1930.00mil 10.00mil 14.00mil "clearline"]
+	Line[6255.00mil 1930.00mil 6255.00mil 47.6100mm 10.00mil 14.00mil "clearline"]
+	Line[6255.00mil 47.6100mm 158.1300mm 1845.00mil 10.00mil 14.00mil "clearline"]
+	Line[160.0241mm 2020.20mil 160.0241mm 49.2801mm 10.00mil 14.00mil "clearline"]
+	Line[160.0241mm 49.2801mm 6280.00mil 1920.00mil 10.00mil 14.00mil "clearline"]
+	Line[6280.00mil 1920.00mil 6280.00mil 46.7510mm 10.00mil 14.00mil "clearline"]
+	Line[6280.00mil 46.7510mm 6270.00mil 46.4970mm 10.00mil 14.00mil "clearline"]
+	Line[158.0030mm 1760.00mil 6225.00mil 44.8160mm 10.00mil 14.00mil "clearline"]
+	Line[6225.00mil 44.8160mm 6225.00mil 1800.00mil 10.00mil 14.00mil "clearline"]
+	Line[6305.00mil 1900.00mil 6305.00mil 45.4551mm 10.00mil 14.00mil "clearline"]
+	Line[6305.00mil 45.4551mm 160.7711mm 1765.00mil 10.00mil 14.00mil "clearline"]
+	Line[6270.00mil 45.1970mm 6270.00mil 1745.00mil 10.00mil 14.00mil "clearline"]
+	Line[162.5709mm 1765.00mil 162.5709mm 44.5879mm 10.00mil 14.00mil "clearline"]
+	Line[162.5709mm 44.5879mm 6365.00mil 1720.00mil 10.00mil 14.00mil "clearline"]
+	Line[6365.00mil 1720.00mil 6295.00mil 1720.00mil 10.00mil 14.00mil "clearline"]
+	Line[6295.00mil 1720.00mil 6270.00mil 1745.00mil 10.00mil 14.00mil "clearline"]
+	Line[155.8140mm 49.5150mm 155.8140mm 1880.00mil 10.00mil 14.00mil "clearline"]
+	Line[155.8140mm 1880.00mil 156.7030mm 1845.00mil 10.00mil 14.00mil "clearline"]
+	Line[156.7030mm 1845.00mil 156.7030mm 44.5920mm 10.00mil 14.00mil "clearline"]
+	Line[156.7030mm 44.5920mm 6205.00mil 1720.00mil 10.00mil 14.00mil "clearline"]
+	Line[6205.00mil 1720.00mil 6245.00mil 1720.00mil 10.00mil 14.00mil "clearline"]
+	Line[6245.00mil 1720.00mil 6270.00mil 1745.00mil 10.00mil 14.00mil "clearline"]
+	Line[6295.00mil 1350.00mil 157.9490mm 36.2340mm 10.00mil 14.00mil "clearline"]
+	Line[157.9490mm 36.2340mm 157.2830mm 36.2340mm 10.00mil 14.00mil "clearline"]
+	Line[6195.00mil 1350.00mil 156.4830mm 35.1600mm 10.00mil 14.00mil "clearline"]
+	Line[156.4830mm 35.1600mm 156.4830mm 36.2340mm 10.00mil 14.00mil "clearline"]
+	Line[6095.00mil 1350.00mil 155.6830mm 35.1600mm 10.00mil 14.00mil "clearline"]
+	Line[155.6830mm 35.1600mm 155.6830mm 36.2340mm 10.00mil 14.00mil "clearline"]
+	Line[5995.00mil 1350.00mil 154.2170mm 36.2340mm 10.00mil 14.00mil "clearline"]
+	Line[154.2170mm 36.2340mm 154.8830mm 36.2340mm 10.00mil 14.00mil "clearline"]
+	Line[5020.00mil 1350.00mil 5020.00mil 1565.00mil 25.00mil 20.00mil "clearline"]
+	Line[5020.00mil 1565.00mil 5135.00mil 1680.00mil 25.00mil 20.00mil "clearline"]
+	Line[4665.00mil 1925.00mil 4665.00mil 2015.00mil 25.00mil 20.00mil "clearline"]
+	Line[4665.00mil 1925.00mil 4625.00mil 1885.00mil 25.00mil 20.00mil "clearline"]
+	Line[4635.00mil 1895.00mil 4760.00mil 1770.00mil 25.00mil 20.00mil "clearline"]
+	Line[4710.00mil 2060.00mil 4665.00mil 2015.00mil 25.00mil 20.00mil "clearline"]
+	Line[4710.00mil 2060.00mil 4765.00mil 2060.00mil 25.00mil 20.00mil "clearline"]
+	Line[4760.00mil 1770.00mil 4870.00mil 1770.00mil 25.00mil 20.00mil "clearline"]
+	Line[4870.00mil 1770.00mil 4960.00mil 1680.00mil 25.00mil 20.00mil "clearline"]
+	Line[6798.90mil 1260.00mil 6798.90mil 40.9930mm 25.00mil 20.00mil "clearline"]
+	Line[6798.90mil 40.9930mm 6805.00mil 1620.00mil 25.00mil 20.00mil "clearline"]
+	Line[6661.10mil 1260.00mil 6661.10mil 40.9930mm 25.00mil 20.00mil "clearline"]
+	Line[6661.10mil 40.9930mm 6655.00mil 1620.00mil 25.00mil 20.00mil "clearline"]
+	Line[5828.90mil 1260.00mil 146.9540mm 33.1040mm 25.00mil 20.00mil "clearline"]
+	Line[146.9540mm 33.1040mm 146.9540mm 36.4040mm 25.00mil 20.00mil "clearline"]
+	Line[146.9540mm 36.4040mm 5828.90mil 37.5040mm 25.00mil 20.00mil "clearline"]
+	Line[5691.10mil 1260.00mil 145.6540mm 33.1040mm 25.00mil 20.00mil "clearline"]
+	Line[145.6540mm 33.1040mm 145.6540mm 36.4040mm 25.00mil 20.00mil "clearline"]
+	Line[145.6540mm 36.4040mm 5691.10mil 37.5040mm 25.00mil 20.00mil "clearline"]
+	Line[5545.00mil 43.2360mm 5480.00mil 44.8870mm 25.00mil 20.00mil "clearline"]
+	Line[5480.00mil 44.8870mm 5480.00mil 46.0860mm 25.00mil 20.00mil "clearline"]
+	Line[5480.00mil 47.3860mm 5480.00mil 48.5850mm 25.00mil 20.00mil "clearline"]
+	Line[5480.00mil 48.5850mm 5545.00mil 50.2360mm 25.00mil 20.00mil "clearline"]
+	Line[5285.00mil 43.2360mm 5220.00mil 44.8870mm 25.00mil 20.00mil "clearline"]
+	Line[5220.00mil 44.8870mm 5220.00mil 46.0860mm 25.00mil 20.00mil "clearline"]
+	Line[5220.00mil 47.3860mm 5220.00mil 48.5850mm 25.00mil 20.00mil "clearline"]
+	Line[5220.00mil 48.5850mm 5285.00mil 50.2360mm 25.00mil 20.00mil "clearline"]
+	Line[4100.00mil 43.2360mm 4035.00mil 44.8870mm 25.00mil 20.00mil "clearline"]
+	Line[4035.00mil 44.8870mm 4035.00mil 46.0860mm 25.00mil 20.00mil "clearline"]
+	Line[4035.00mil 47.3860mm 4035.00mil 48.5850mm 25.00mil 20.00mil "clearline"]
+	Line[4035.00mil 48.5850mm 4100.00mil 50.2360mm 25.00mil 20.00mil "clearline"]
+	Line[3545.00mil 43.2360mm 3480.00mil 44.8870mm 25.00mil 20.00mil "clearline"]
+	Line[3480.00mil 44.8870mm 3480.00mil 46.0860mm 25.00mil 20.00mil "clearline"]
+	Line[3480.00mil 47.3860mm 3480.00mil 48.5850mm 25.00mil 20.00mil "clearline"]
+	Line[3480.00mil 48.5850mm 3545.00mil 50.2360mm 25.00mil 20.00mil "clearline"]
+	Line[2990.00mil 43.2360mm 2925.00mil 44.8870mm 25.00mil 20.00mil "clearline"]
+	Line[2925.00mil 44.8870mm 2925.00mil 46.0860mm 25.00mil 20.00mil "clearline"]
+	Line[2925.00mil 47.3860mm 2925.00mil 48.5850mm 25.00mil 20.00mil "clearline"]
+	Line[2925.00mil 48.5850mm 2990.00mil 50.2360mm 25.00mil 20.00mil "clearline"]
+	Line[2435.00mil 43.2360mm 2370.00mil 44.8870mm 25.00mil 20.00mil "clearline"]
+	Line[2370.00mil 44.8870mm 2370.00mil 46.0860mm 25.00mil 20.00mil "clearline"]
+	Line[2370.00mil 47.3860mm 2370.00mil 48.5850mm 25.00mil 20.00mil "clearline"]
+	Line[2370.00mil 48.5850mm 2435.00mil 50.2360mm 25.00mil 20.00mil "clearline"]
+	Line[1880.00mil 43.2360mm 1815.00mil 44.8870mm 25.00mil 20.00mil "clearline"]
+	Line[1815.00mil 44.8870mm 1815.00mil 46.0860mm 25.00mil 20.00mil "clearline"]
+	Line[1815.00mil 47.3860mm 1815.00mil 48.5850mm 25.00mil 20.00mil "clearline"]
+	Line[1815.00mil 48.5850mm 1880.00mil 50.2360mm 25.00mil 20.00mil "clearline"]
+	Line[6500.00mil 2125.00mil 6645.00mil 2125.00mil 10.00mil 14.00mil "clearline"]
+	Line[6645.00mil 2125.00mil 6670.00mil 2150.00mil 10.00mil 14.00mil "clearline"]
+	Line[6670.00mil 2150.00mil 6670.00mil 2425.00mil 10.00mil 14.00mil "clearline"]
+	Line[6670.00mil 2425.00mil 6515.00mil 2580.00mil 10.00mil 14.00mil "clearline"]
+	Line[6515.00mil 2580.00mil 5915.00mil 2580.00mil 10.00mil 14.00mil "clearline"]
+	Line[5610.00mil 1935.00mil 5610.00mil 51.4200mm 10.00mil 14.00mil "clearline"]
+	Line[5610.00mil 51.4200mm 142.4790mm 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[5660.00mil 1935.00mil 5660.00mil 51.4200mm 10.00mil 14.00mil "clearline"]
+	Line[5660.00mil 51.4200mm 143.7790mm 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[6495.00mil 1350.00mil 6470.00mil 1375.00mil 15.00mil 20.00mil "clearline"]
+	Line[6470.00mil 1375.00mil 6470.00mil 1435.00mil 15.00mil 20.00mil "clearline"]
+	Line[163.0530mm 1435.00mil 163.0530mm 34.9100mm 15.00mil 20.00mil "clearline"]
+	Line[163.0530mm 34.9100mm 6395.00mil 1350.00mil 15.00mil 20.00mil "clearline"]
+	Line[5910.00mil 1575.00mil 5910.00mil 1505.00mil 6.00mil 12.00mil "clearline"]
+	Line[5910.00mil 1505.00mil 5915.00mil 1500.00mil 6.00mil 12.00mil "clearline"]
+	Line[6470.00mil 1435.00mil 6470.00mil 1480.00mil 10.00mil 14.00mil "clearline"]
+	Line[6470.00mil 1480.00mil 6465.00mil 1485.00mil 10.00mil 14.00mil "clearline"]
+	Line[5960.00mil 1575.00mil 5960.00mil 1490.00mil 10.00mil 14.00mil "clearline"]
+	Line[5960.00mil 1490.00mil 5950.00mil 1480.00mil 10.00mil 14.00mil "clearline"]
+	Line[5860.00mil 1575.00mil 5860.00mil 1525.00mil 6.00mil 12.00mil "clearline"]
+	Line[5810.00mil 1575.00mil 5810.00mil 1555.00mil 6.00mil 12.00mil "clearline"]
+	Line[5860.00mil 1525.00mil 5935.00mil 1450.00mil 6.00mil 12.00mil "clearline"]
+	Line[5935.00mil 1450.00mil 5995.00mil 1450.00mil 6.00mil 12.00mil "clearline"]
+	Line[5995.00mil 1450.00mil 6035.00mil 1490.00mil 6.00mil 12.00mil "clearline"]
+	Line[6035.00mil 1490.00mil 6035.00mil 1510.00mil 6.00mil 12.00mil "clearline"]
+	Line[6035.00mil 1510.00mil 6050.00mil 1525.00mil 6.00mil 12.00mil "clearline"]
+	Line[6050.00mil 1525.00mil 6120.00mil 1525.00mil 6.00mil 12.00mil "clearline"]
+	Line[6120.00mil 1525.00mil 155.6830mm 38.5000mm 6.00mil 12.00mil "clearline"]
+	Line[155.6830mm 38.5000mm 155.6830mm 37.9340mm 6.00mil 12.00mil "clearline"]
+	Line[5810.00mil 1555.00mil 5930.00mil 1435.00mil 6.00mil 12.00mil "clearline"]
+	Line[5930.00mil 1435.00mil 153.3980mm 1435.00mil 6.00mil 12.00mil "clearline"]
+	Line[153.3980mm 1435.00mil 154.8830mm 37.9340mm 6.00mil 12.00mil "clearline"]
+	Line[5760.00mil 1575.00mil 5760.00mil 1600.00mil 6.00mil 12.00mil "clearline"]
+	Line[5760.00mil 1600.00mil 5785.00mil 1625.00mil 6.00mil 12.00mil "clearline"]
+	Line[5785.00mil 1625.00mil 5975.00mil 1625.00mil 6.00mil 12.00mil "clearline"]
+	Line[5975.00mil 1625.00mil 5985.00mil 1615.00mil 6.00mil 12.00mil "clearline"]
+	Line[5985.00mil 1615.00mil 5985.00mil 1560.00mil 6.00mil 12.00mil "clearline"]
+	Line[5985.00mil 1560.00mil 6005.00mil 1540.00mil 6.00mil 12.00mil "clearline"]
+	Line[6005.00mil 1540.00mil 6130.00mil 1540.00mil 6.00mil 12.00mil "clearline"]
+	Line[6130.00mil 1540.00mil 156.4830mm 38.3350mm 6.00mil 12.00mil "clearline"]
+	Line[156.4830mm 38.3350mm 156.4830mm 37.9340mm 6.00mil 12.00mil "clearline"]
+	Line[157.2830mm 37.9340mm 157.2830mm 38.2970mm 6.00mil 12.00mil "clearline"]
+	Line[157.2830mm 38.2970mm 6145.00mil 1555.00mil 6.00mil 12.00mil "clearline"]
+	Line[6145.00mil 1555.00mil 6010.00mil 1555.00mil 6.00mil 12.00mil "clearline"]
+	Line[6010.00mil 1555.00mil 6000.00mil 1565.00mil 6.00mil 12.00mil "clearline"]
+	Line[6000.00mil 1565.00mil 6000.00mil 1685.00mil 6.00mil 12.00mil "clearline"]
+	Line[6000.00mil 1685.00mil 5985.00mil 1700.00mil 6.00mil 12.00mil "clearline"]
+	Line[5985.00mil 1700.00mil 5875.00mil 1700.00mil 6.00mil 12.00mil "clearline"]
+	Line[5875.00mil 1700.00mil 5825.00mil 1650.00mil 6.00mil 12.00mil "clearline"]
+	Line[5825.00mil 1650.00mil 5755.00mil 1650.00mil 6.00mil 12.00mil "clearline"]
+	Line[5755.00mil 1650.00mil 5710.00mil 1605.00mil 6.00mil 12.00mil "clearline"]
+	Line[5710.00mil 1605.00mil 5710.00mil 1575.00mil 6.00mil 12.00mil "clearline"]
+	Line[5925.00mil 1408.00mil 5925.00mil 1430.00mil 6.00mil 12.00mil "clearline"]
+	Line[5925.00mil 1430.00mil 5930.00mil 1435.00mil 6.00mil 12.00mil "clearline"]
+	Line[5843.00mil 1330.00mil 5855.00mil 1330.00mil 10.00mil 14.00mil "clearline"]
+	Line[5855.00mil 1330.00mil 5890.00mil 1295.00mil 10.00mil 14.00mil "clearline"]
+	Line[5890.00mil 1295.00mil 6325.00mil 1295.00mil 10.00mil 14.00mil "clearline"]
+	Line[6325.00mil 1295.00mil 6345.00mil 1315.00mil 10.00mil 14.00mil "clearline"]
+	Line[6345.00mil 1315.00mil 6345.00mil 1415.00mil 10.00mil 14.00mil "clearline"]
+	Line[6345.00mil 1415.00mil 6365.00mil 1435.00mil 10.00mil 14.00mil "clearline"]
+	Line[6365.00mil 1435.00mil 163.0530mm 1435.00mil 10.00mil 14.00mil "clearline"]
+	Line[5880.00mil 1370.00mil 5844.00mil 1370.00mil 6.00mil 12.00mil "clearline"]
+	Line[5844.00mil 1370.00mil 5843.00mil 1369.00mil 6.00mil 12.00mil "clearline"]
+	Line[5880.00mil 1410.00mil 5845.00mil 1410.00mil 6.00mil 12.00mil "clearline"]
+	Line[5845.00mil 1410.00mil 5843.00mil 1408.00mil 6.00mil 12.00mil "clearline"]
+	Line[5660.00mil 1575.00mil 5660.00mil 1530.00mil 10.00mil 14.00mil "clearline"]
+	Line[5660.00mil 1530.00mil 5645.00mil 1515.00mil 10.00mil 14.00mil "clearline"]
+	Line[5610.00mil 1260.00mil 5660.00mil 1210.00mil 10.00mil 14.00mil "clearline"]
+	Line[5660.00mil 1210.00mil 5855.00mil 1210.00mil 10.00mil 14.00mil "clearline"]
+	Line[5855.00mil 1210.00mil 5890.00mil 1245.00mil 10.00mil 14.00mil "clearline"]
+	Line[5890.00mil 1245.00mil 5890.00mil 1295.00mil 10.00mil 14.00mil "clearline"]
+	Line[5960.00mil 1935.00mil 5960.00mil 1875.00mil 10.00mil 14.00mil "clearline"]
+	Line[5690.00mil 2025.00mil 5660.00mil 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[5910.00mil 1935.00mil 5910.00mil 1900.00mil 10.00mil 14.00mil "clearline"]
+	Line[5910.00mil 1900.00mil 5890.00mil 1880.00mil 10.00mil 14.00mil "clearline"]
+	Line[5890.00mil 1880.00mil 5630.00mil 1880.00mil 10.00mil 14.00mil "clearline"]
+	Line[5630.00mil 1880.00mil 5610.00mil 1900.00mil 10.00mil 14.00mil "clearline"]
+	Line[5610.00mil 1900.00mil 5610.00mil 1945.00mil 10.00mil 14.00mil "clearline"]
+	Line[5710.00mil 1935.00mil 5710.00mil 1985.00mil 10.00mil 14.00mil "clearline"]
+	Line[5710.00mil 1985.00mil 5725.00mil 2000.00mil 10.00mil 14.00mil "clearline"]
+	Line[5725.00mil 2000.00mil 5725.00mil 2040.00mil 10.00mil 14.00mil "clearline"]
+	Line[5760.00mil 1935.00mil 5760.00mil 2030.00mil 10.00mil 14.00mil "clearline"]
+	Line[5810.00mil 1935.00mil 5810.00mil 2015.00mil 10.00mil 14.00mil "clearline"]
+	Line[5860.00mil 1935.00mil 5860.00mil 1995.00mil 10.00mil 14.00mil "clearline"]
+	Line[5610.00mil 1260.00mil 5610.00mil 1575.00mil 10.00mil 14.00mil "clearline"]
+	Line[5610.00mil 1575.00mil 5590.00mil 1595.00mil 10.00mil 14.00mil "clearline"]
+	Line[5590.00mil 1595.00mil 5590.00mil 1810.00mil 10.00mil 14.00mil "clearline"]
+	Line[5590.00mil 1810.00mil 5620.00mil 1840.00mil 10.00mil 14.00mil "clearline"]
+	Line[5610.00mil 2025.00mil 5610.00mil 2030.00mil 10.00mil 14.00mil "clearline"]
+	Line[5610.00mil 2030.00mil 5470.00mil 2170.00mil 10.00mil 14.00mil "clearline"]
+	Line[5725.00mil 2040.00mil 5575.00mil 2190.00mil 10.00mil 14.00mil "clearline"]
+	Line[5760.00mil 2030.00mil 5575.00mil 2215.00mil 10.00mil 14.00mil "clearline"]
+	Line[5810.00mil 2015.00mil 5585.00mil 2240.00mil 10.00mil 14.00mil "clearline"]
+	Line[5860.00mil 1995.00mil 5590.00mil 2265.00mil 10.00mil 14.00mil "clearline"]
+	Line[4245.00mil 1350.00mil 4245.00mil 32.1460mm 15.00mil 20.00mil "clearline"]
+	Line[106.5380mm 1265.00mil 4160.00mil 1265.00mil 15.00mil 20.00mil "clearline"]
+	Line[92.4410mm 1265.00mil 3605.00mil 1265.00mil 15.00mil 20.00mil "clearline"]
+	Line[78.3440mm 1265.00mil 3050.00mil 1265.00mil 15.00mil 20.00mil "clearline"]
+	Line[2580.00mil 1350.00mil 2580.00mil 32.1460mm 15.00mil 20.00mil "clearline"]
+	Line[64.2470mm 1265.00mil 2495.00mil 1265.00mil 15.00mil 20.00mil "clearline"]
+	Line[2025.00mil 1350.00mil 2025.00mil 32.1460mm 15.00mil 20.00mil "clearline"]
+	Line[50.1500mm 1265.00mil 1940.00mil 1265.00mil 15.00mil 20.00mil "clearline"]
+	Line[5915.00mil 2580.00mil 5625.00mil 2290.00mil 10.00mil 14.00mil "clearline"]
+	Line[1625.00mil 1350.00mil 1625.00mil 2085.00mil 15.00mil 20.00mil "clearline"]
+	Line[1625.00mil 2085.00mil 1810.00mil 2270.00mil 15.00mil 20.00mil "clearline"]
+	Line[1810.00mil 2270.00mil 1945.00mil 2270.00mil 15.00mil 20.00mil "clearline"]
+	Line[1945.00mil 2270.00mil 2000.00mil 2325.00mil 15.00mil 20.00mil "clearline"]
+	Line[2000.00mil 2325.00mil 2000.00mil 2422.50mil 15.00mil 20.00mil "clearline"]
+	Line[2050.00mil 1860.00mil 2050.00mil 2422.50mil 15.00mil 20.00mil "clearline"]
+	Line[1925.00mil 1350.00mil 1925.00mil 1360.00mil 10.00mil 14.00mil "clearline"]
+	Line[1925.00mil 1360.00mil 1985.00mil 1420.00mil 10.00mil 14.00mil "clearline"]
+	Line[1985.00mil 1420.00mil 2070.00mil 1420.00mil 10.00mil 14.00mil "clearline"]
+	Line[2070.00mil 1420.00mil 53.0670mm 36.5570mm 10.00mil 14.00mil "clearline"]
+	Line[53.0670mm 36.5570mm 53.0670mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[1825.00mil 1350.00mil 49.3150mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[49.3150mm 37.2500mm 52.2670mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[3035.00mil 1350.00mil 3105.00mil 1420.00mil 10.00mil 14.00mil "clearline"]
+	Line[3105.00mil 1420.00mil 3185.00mil 1420.00mil 10.00mil 14.00mil "clearline"]
+	Line[3185.00mil 1420.00mil 81.2610mm 36.4300mm 10.00mil 14.00mil "clearline"]
+	Line[81.2610mm 36.4300mm 81.2610mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[2935.00mil 1350.00mil 77.5090mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[77.5090mm 37.2500mm 80.4610mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[3490.00mil 1350.00mil 3420.00mil 1420.00mil 10.00mil 14.00mil "clearline"]
+	Line[3420.00mil 1420.00mil 3245.00mil 1420.00mil 10.00mil 14.00mil "clearline"]
+	Line[3245.00mil 1420.00mil 3230.00mil 1435.00mil 10.00mil 14.00mil "clearline"]
+	Line[3230.00mil 1435.00mil 3230.00mil 1470.00mil 10.00mil 14.00mil "clearline"]
+	Line[3590.00mil 1350.00mil 88.2260mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[88.2260mm 37.2500mm 82.8610mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[2100.00mil 2422.50mil 2100.00mil 2060.00mil 15.00mil 20.00mil "clearline"]
+	Line[2100.00mil 2060.00mil 2135.00mil 2025.00mil 15.00mil 20.00mil "clearline"]
+	Line[2135.00mil 2025.00mil 2135.00mil 1860.00mil 15.00mil 20.00mil "clearline"]
+	Line[2210.00mil 1860.00mil 2210.00mil 2145.00mil 15.00mil 20.00mil "clearline"]
+	Line[2210.00mil 2145.00mil 2150.00mil 2205.00mil 15.00mil 20.00mil "clearline"]
+	Line[2150.00mil 2205.00mil 2150.00mil 2425.00mil 15.00mil 20.00mil "clearline"]
+	Line[1950.00mil 2627.50mil 1917.50mil 2627.50mil 15.00mil 20.00mil "clearline"]
+	Line[1917.50mil 2627.50mil 1915.00mil 2630.00mil 15.00mil 20.00mil "clearline"]
+	Line[1950.00mil 2422.50mil 1917.50mil 2422.50mil 15.00mil 20.00mil "clearline"]
+	Line[1917.50mil 2422.50mil 1915.00mil 2420.00mil 15.00mil 20.00mil "clearline"]
+	Line[4145.00mil 1350.00mil 4145.00mil 1400.00mil 10.00mil 14.00mil "clearline"]
+	Line[4145.00mil 1400.00mil 4125.00mil 1420.00mil 10.00mil 14.00mil "clearline"]
+	Line[4125.00mil 1420.00mil 4125.00mil 1490.00mil 10.00mil 14.00mil "clearline"]
+	Line[4045.00mil 1350.00mil 4045.00mil 1395.00mil 10.00mil 14.00mil "clearline"]
+	Line[4045.00mil 1395.00mil 103.9560mm 36.6460mm 10.00mil 14.00mil "clearline"]
+	Line[103.9560mm 36.6460mm 103.9560mm 37.7580mm 10.00mil 14.00mil "clearline"]
+	Line[2200.00mil 2422.50mil 2200.00mil 2245.00mil 15.00mil 20.00mil "clearline"]
+	Line[2200.00mil 2245.00mil 2255.00mil 2190.00mil 15.00mil 20.00mil "clearline"]
+	Line[2255.00mil 2190.00mil 2255.00mil 1780.00mil 15.00mil 20.00mil "clearline"]
+	Line[2255.00mil 1780.00mil 2420.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[2420.00mil 1615.00mil 2460.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[2250.00mil 2422.50mil 2250.00mil 2290.00mil 15.00mil 20.00mil "clearline"]
+	Line[2300.00mil 2422.50mil 2300.00mil 2295.00mil 15.00mil 20.00mil "clearline"]
+	Line[2250.00mil 2290.00mil 2630.00mil 1910.00mil 15.00mil 20.00mil "clearline"]
+	Line[2630.00mil 1910.00mil 2630.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[2300.00mil 2295.00mil 2740.00mil 1855.00mil 15.00mil 20.00mil "clearline"]
+	Line[2740.00mil 1855.00mil 2740.00mil 1615.00mil 15.00mil 20.00mil "clearline"]
+	Line[2460.00mil 2225.00mil 2460.00mil 58.4050mm 10.00mil 14.00mil "clearline"]
+	Line[2460.00mil 59.7050mm 2460.00mil 2385.00mil 10.00mil 14.00mil "clearline"]
+	Line[3860.00mil 2825.00mil 3860.00mil 69.8650mm 10.00mil 14.00mil "clearline"]
+	Line[3860.00mil 68.5650mm 3860.00mil 2665.00mil 10.00mil 14.00mil "clearline"]
+	Line[2000.00mil 2627.50mil 2000.00mil 2690.00mil 10.00mil 14.00mil "clearline"]
+	Line[2050.00mil 2627.50mil 2050.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[2100.00mil 2627.50mil 2100.00mil 2690.00mil 10.00mil 14.00mil "clearline"]
+	Line[2150.00mil 2627.50mil 2150.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[2200.00mil 2627.50mil 2200.00mil 2690.00mil 10.00mil 14.00mil "clearline"]
+	Line[2250.00mil 2627.50mil 2250.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[4895.00mil 2260.00mil 4915.00mil 2240.00mil 10.00mil 14.00mil "clearline"]
+	Line[5585.00mil 2240.00mil 4915.00mil 2240.00mil 10.00mil 14.00mil "clearline"]
+	Line[5590.00mil 2265.00mil 4935.00mil 2265.00mil 10.00mil 14.00mil "clearline"]
+	Line[4935.00mil 2265.00mil 4635.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[4635.00mil 2565.00mil 4635.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[4945.00mil 2135.00mil 4940.00mil 2135.00mil 10.00mil 14.00mil "clearline"]
+	Line[4940.00mil 2135.00mil 4575.00mil 2500.00mil 10.00mil 14.00mil "clearline"]
+	Line[4575.00mil 2500.00mil 4550.00mil 2500.00mil 10.00mil 14.00mil "clearline"]
+	Line[4495.00mil 2600.00mil 4510.00mil 2600.00mil 10.00mil 14.00mil "clearline"]
+	Line[4510.00mil 2600.00mil 4895.00mil 2215.00mil 10.00mil 14.00mil "clearline"]
+	Line[5575.00mil 2215.00mil 4895.00mil 2215.00mil 10.00mil 14.00mil "clearline"]
+	Line[5625.00mil 2290.00mil 4950.00mil 2290.00mil 10.00mil 14.00mil "clearline"]
+	Line[4950.00mil 2290.00mil 4675.00mil 2565.00mil 10.00mil 14.00mil "clearline"]
+	Line[4675.00mil 2565.00mil 4675.00mil 2590.00mil 10.00mil 14.00mil "clearline"]
+	Line[4675.00mil 2590.00mil 4630.00mil 2635.00mil 10.00mil 14.00mil "clearline"]
+	Line[4630.00mil 2635.00mil 4470.00mil 2635.00mil 10.00mil 14.00mil "clearline"]
+	Line[4470.00mil 2635.00mil 4290.00mil 2455.00mil 10.00mil 14.00mil "clearline"]
+	Line[4830.00mil 2175.00mil 4905.00mil 2100.00mil 10.00mil 14.00mil "clearline"]
+	Line[4905.00mil 2100.00mil 5015.00mil 2100.00mil 10.00mil 14.00mil "clearline"]
+	Line[5015.00mil 2100.00mil 5105.00mil 2190.00mil 10.00mil 14.00mil "clearline"]
+	Line[5105.00mil 2190.00mil 5345.00mil 2190.00mil 10.00mil 14.00mil "clearline"]
+	Line[5575.00mil 2190.00mil 5345.00mil 2190.00mil 10.00mil 14.00mil "clearline"]
+	Line[3660.00mil 2225.00mil 3715.00mil 2280.00mil 10.00mil 14.00mil "clearline"]
+	Line[3715.00mil 2280.00mil 4610.00mil 2280.00mil 10.00mil 14.00mil "clearline"]
+	Line[4610.00mil 2280.00mil 4620.00mil 2270.00mil 10.00mil 14.00mil "clearline"]
+	Line[4620.00mil 2270.00mil 4775.00mil 2270.00mil 10.00mil 14.00mil "clearline"]
+	Line[4775.00mil 2270.00mil 4830.00mil 2215.00mil 10.00mil 14.00mil "clearline"]
+	Line[4830.00mil 2215.00mil 4830.00mil 2175.00mil 10.00mil 14.00mil "clearline"]
+	Line[4225.00mil 1685.00mil 104.7560mm 40.2400mm 10.00mil 14.00mil "clearline"]
+	Line[104.7560mm 40.2400mm 104.7560mm 39.4580mm 10.00mil 14.00mil "clearline"]
+	Line[4760.00mil 2225.00mil 4270.00mil 1735.00mil 10.00mil 14.00mil "clearline"]
+	Line[4270.00mil 1735.00mil 4200.00mil 1735.00mil 10.00mil 14.00mil "clearline"]
+	Line[4200.00mil 1735.00mil 103.9560mm 41.3450mm 10.00mil 14.00mil "clearline"]
+	Line[103.9560mm 41.3450mm 103.9560mm 39.4580mm 10.00mil 14.00mil "clearline"]
+	Line[4760.00mil 2825.00mil 4700.00mil 2885.00mil 10.00mil 14.00mil "clearline"]
+	Line[4700.00mil 2885.00mil 4650.00mil 2885.00mil 10.00mil 14.00mil "clearline"]
+	Line[4650.00mil 2885.00mil 4610.00mil 2845.00mil 10.00mil 14.00mil "clearline"]
+	Line[4610.00mil 2845.00mil 4610.00mil 2810.00mil 10.00mil 14.00mil "clearline"]
+	Line[4660.00mil 2825.00mil 4500.00mil 2665.00mil 10.00mil 14.00mil "clearline"]
+	Line[4500.00mil 2665.00mil 4360.00mil 2665.00mil 10.00mil 14.00mil "clearline"]
+	Line[4360.00mil 2665.00mil 4075.00mil 2380.00mil 10.00mil 14.00mil "clearline"]
+	Line[4610.00mil 2810.00mil 4555.00mil 2755.00mil 10.00mil 14.00mil "clearline"]
+	Line[4555.00mil 2755.00mil 4325.00mil 2755.00mil 10.00mil 14.00mil "clearline"]
+	Line[4075.00mil 2380.00mil 3510.00mil 2380.00mil 10.00mil 14.00mil "clearline"]
+	Line[3510.00mil 2380.00mil 3410.00mil 2280.00mil 10.00mil 14.00mil "clearline"]
+	Line[3410.00mil 2280.00mil 3410.00mil 2190.00mil 10.00mil 14.00mil "clearline"]
+	Line[4325.00mil 2755.00mil 4015.00mil 2445.00mil 10.00mil 14.00mil "clearline"]
+	Line[4015.00mil 2445.00mil 3460.00mil 2445.00mil 10.00mil 14.00mil "clearline"]
+	Line[3460.00mil 2445.00mil 3310.00mil 2295.00mil 10.00mil 14.00mil "clearline"]
+	Line[3410.00mil 2190.00mil 3360.00mil 2140.00mil 10.00mil 14.00mil "clearline"]
+	Line[82.8610mm 38.9500mm 82.8610mm 45.2690mm 10.00mil 14.00mil "clearline"]
+	Line[82.8610mm 45.2690mm 3360.00mil 1880.00mil 10.00mil 14.00mil "clearline"]
+	Line[3360.00mil 1880.00mil 3360.00mil 2140.00mil 10.00mil 14.00mil "clearline"]
+	Line[82.0610mm 38.9500mm 82.0610mm 47.1360mm 10.00mil 14.00mil "clearline"]
+	Line[82.0610mm 47.1360mm 3310.00mil 1935.00mil 10.00mil 14.00mil "clearline"]
+	Line[3310.00mil 2295.00mil 3310.00mil 1935.00mil 10.00mil 14.00mil "clearline"]
+	Line[81.2610mm 38.9500mm 81.2610mm 49.0030mm 10.00mil 14.00mil "clearline"]
+	Line[81.2610mm 49.0030mm 3210.00mil 1940.00mil 10.00mil 14.00mil "clearline"]
+	Line[80.4610mm 38.9500mm 80.4610mm 53.0160mm 10.00mil 14.00mil "clearline"]
+	Line[80.4610mm 53.0160mm 3110.00mil 2145.00mil 10.00mil 14.00mil "clearline"]
+	Line[3110.00mil 2145.00mil 3110.00mil 2620.00mil 10.00mil 14.00mil "clearline"]
+	Line[3110.00mil 2620.00mil 3210.00mil 2720.00mil 10.00mil 14.00mil "clearline"]
+	Line[3210.00mil 2720.00mil 3210.00mil 2855.00mil 10.00mil 14.00mil "clearline"]
+	Line[3210.00mil 2855.00mil 3235.00mil 2880.00mil 10.00mil 14.00mil "clearline"]
+	Line[3235.00mil 2880.00mil 3305.00mil 2880.00mil 10.00mil 14.00mil "clearline"]
+	Line[3305.00mil 2880.00mil 3360.00mil 2825.00mil 10.00mil 14.00mil "clearline"]
+	Line[3210.00mil 1940.00mil 3210.00mil 2535.00mil 10.00mil 14.00mil "clearline"]
+	Line[3210.00mil 2535.00mil 3260.00mil 2585.00mil 10.00mil 14.00mil "clearline"]
+	Line[3260.00mil 2585.00mil 3260.00mil 2825.00mil 10.00mil 14.00mil "clearline"]
+	Line[5470.00mil 2170.00mil 5315.00mil 2170.00mil 10.00mil 14.00mil "clearline"]
+	Line[5315.00mil 2170.00mil 5285.00mil 2140.00mil 10.00mil 14.00mil "clearline"]
+	Line[5285.00mil 2140.00mil 5285.00mil 2075.00mil 10.00mil 14.00mil "clearline"]
+	Line[5285.00mil 2075.00mil 5165.00mil 1955.00mil 10.00mil 14.00mil "clearline"]
+	Line[5165.00mil 1955.00mil 5165.00mil 1750.00mil 10.00mil 14.00mil "clearline"]
+	Line[5165.00mil 1750.00mil 5225.00mil 1690.00mil 10.00mil 14.00mil "clearline"]
+	Line[5225.00mil 1690.00mil 5225.00mil 1665.00mil 10.00mil 14.00mil "clearline"]
+	Line[5225.00mil 1665.00mil 5270.00mil 1620.00mil 10.00mil 14.00mil "clearline"]
+	Line[5270.00mil 1620.00mil 5270.00mil 1540.00mil 10.00mil 14.00mil "clearline"]
+	Line[5270.00mil 1540.00mil 5105.00mil 1375.00mil 10.00mil 14.00mil "clearline"]
+	Line[5105.00mil 1375.00mil 5105.00mil 1315.00mil 10.00mil 14.00mil "clearline"]
+	Line[5105.00mil 1315.00mil 5035.00mil 1245.00mil 10.00mil 14.00mil "clearline"]
+	Line[2025.00mil 1265.00mil 2025.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[2580.00mil 1265.00mil 2580.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[3135.00mil 1350.00mil 3135.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[3690.00mil 1350.00mil 3690.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[4245.00mil 1265.00mil 4245.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[5035.00mil 1245.00mil 4325.00mil 1245.00mil 10.00mil 14.00mil "clearline"]
+	Line[4325.00mil 1245.00mil 4245.00mil 1165.00mil 10.00mil 14.00mil "clearline"]
+	Line[3860.00mil 2825.00mil 3785.00mil 2900.00mil 15.00mil 20.00mil "clearline"]
+	Line[3785.00mil 2900.00mil 1880.00mil 2900.00mil 15.00mil 20.00mil "clearline"]
+	Line[1880.00mil 2900.00mil 1545.00mil 2565.00mil 15.00mil 20.00mil "clearline"]
+	Line[1545.00mil 2565.00mil 1545.00mil 1330.00mil 15.00mil 20.00mil "clearline"]
+	Line[1545.00mil 1330.00mil 1710.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[4245.00mil 1165.00mil 1710.00mil 1165.00mil 15.00mil 20.00mil "clearline"]
+	Line[54.6670mm 38.9500mm 55.0300mm 38.9500mm 10.00mil 14.00mil "clearline"]
+	Line[2205.00mil 1610.00mil 2305.00mil 1510.00mil 10.00mil 14.00mil "clearline"]
+	Line[2190.00mil 1590.00mil 2290.00mil 1490.00mil 10.00mil 14.00mil "clearline"]
+	Line[2170.00mil 1570.00mil 2270.00mil 1470.00mil 10.00mil 14.00mil "clearline"]
+	Line[55.0300mm 38.9500mm 2250.00mil 1450.00mil 10.00mil 14.00mil "clearline"]
+	Line[2380.00mil 1350.00mil 2330.00mil 1405.00mil 10.00mil 14.00mil "clearline"]
+	Line[53.8670mm 39.5160mm 2135.00mil 1570.00mil 10.00mil 14.00mil "clearline"]
+	Line[53.8670mm 38.9500mm 53.8670mm 39.5160mm 10.00mil 14.00mil "clearline"]
+	Line[2135.00mil 1570.00mil 2170.00mil 1570.00mil 10.00mil 14.00mil "clearline"]
+	Line[53.0670mm 38.9500mm 53.0670mm 39.7320mm 10.00mil 14.00mil "clearline"]
+	Line[53.0670mm 1565.00mil 53.0670mm 39.9860mm 10.00mil 14.00mil "clearline"]
+	Line[53.0670mm 39.9860mm 2105.00mil 1590.00mil 10.00mil 14.00mil "clearline"]
+	Line[2190.00mil 1590.00mil 2105.00mil 1590.00mil 10.00mil 14.00mil "clearline"]
+	Line[52.2670mm 38.9500mm 52.2670mm 40.2020mm 10.00mil 14.00mil "clearline"]
+	Line[52.2670mm 40.2020mm 2085.00mil 1610.00mil 10.00mil 14.00mil "clearline"]
+	Line[2205.00mil 1610.00mil 2085.00mil 1610.00mil 10.00mil 14.00mil "clearline"]
+	Line[2120.00mil 1465.00mil 2120.00mil 1415.00mil 10.00mil 14.00mil "clearline"]
+	Line[2120.00mil 1415.00mil 2130.00mil 1405.00mil 10.00mil 14.00mil "clearline"]
+	Line[2330.00mil 1405.00mil 2130.00mil 1405.00mil 10.00mil 14.00mil "clearline"]
+	Line[2480.00mil 1350.00mil 2405.00mil 1425.00mil 10.00mil 14.00mil "clearline"]
+	Line[2405.00mil 1425.00mil 55.7220mm 1425.00mil 10.00mil 14.00mil "clearline"]
+	Line[55.7220mm 1425.00mil 54.6670mm 37.2500mm 10.00mil 14.00mil "clearline"]
+	Line[2305.00mil 1510.00mil 2695.00mil 1510.00mil 10.00mil 14.00mil "clearline"]
+	Line[2695.00mil 1510.00mil 2780.00mil 1595.00mil 10.00mil 14.00mil "clearline"]
+	Line[2780.00mil 1595.00mil 2780.00mil 1945.00mil 10.00mil 14.00mil "clearline"]
+	Line[2780.00mil 1945.00mil 2710.00mil 2015.00mil 10.00mil 14.00mil "clearline"]
+	Line[2290.00mil 1490.00mil 2730.00mil 1490.00mil 10.00mil 14.00mil "clearline"]
+	Line[2730.00mil 1490.00mil 2805.00mil 1565.00mil 10.00mil 14.00mil "clearline"]
+	Line[2805.00mil 1565.00mil 2805.00mil 2155.00mil 10.00mil 14.00mil "clearline"]
+	Line[2805.00mil 2155.00mil 2810.00mil 2160.00mil 10.00mil 14.00mil "clearline"]
+	Line[2270.00mil 1470.00mil 2895.00mil 1470.00mil 10.00mil 14.00mil "clearline"]
+	Line[2895.00mil 1470.00mil 2955.00mil 1530.00mil 10.00mil 14.00mil "clearline"]
+	Line[2955.00mil 1530.00mil 2955.00mil 1630.00mil 10.00mil 14.00mil "clearline"]
+	Line[2955.00mil 1630.00mil 2885.00mil 1700.00mil 10.00mil 14.00mil "clearline"]
+	Line[2885.00mil 1700.00mil 2885.00mil 1975.00mil 10.00mil 14.00mil "clearline"]
+	Line[2885.00mil 1975.00mil 2955.00mil 2045.00mil 10.00mil 14.00mil "clearline"]
+	Line[2955.00mil 2045.00mil 2955.00mil 2130.00mil 10.00mil 14.00mil "clearline"]
+	Line[2955.00mil 2130.00mil 2910.00mil 2175.00mil 10.00mil 14.00mil "clearline"]
+	Line[2910.00mil 2175.00mil 2910.00mil 2320.00mil 10.00mil 14.00mil "clearline"]
+	Line[2250.00mil 1450.00mil 2945.00mil 1450.00mil 10.00mil 14.00mil "clearline"]
+	Line[2945.00mil 1450.00mil 3045.00mil 1550.00mil 10.00mil 14.00mil "clearline"]
+	Line[3045.00mil 1550.00mil 3045.00mil 2090.00mil 10.00mil 14.00mil "clearline"]
+	Line[3045.00mil 2090.00mil 3010.00mil 2125.00mil 10.00mil 14.00mil "clearline"]
+	Line[3010.00mil 2125.00mil 3010.00mil 2320.00mil 10.00mil 14.00mil "clearline"]
+	Line[2300.00mil 2627.50mil 2962.50mil 2627.50mil 10.00mil 14.00mil "clearline"]
+	Line[2962.50mil 2627.50mil 3060.00mil 2530.00mil 10.00mil 14.00mil "clearline"]
+	Line[3060.00mil 2530.00mil 3060.00mil 2225.00mil 10.00mil 14.00mil "clearline"]
+	Line[3460.00mil 2825.00mil 3455.00mil 2825.00mil 10.00mil 14.00mil "clearline"]
+	Line[3560.00mil 2825.00mil 3390.00mil 2655.00mil 10.00mil 14.00mil "clearline"]
+	Line[3460.00mil 2825.00mil 3295.00mil 2660.00mil 10.00mil 14.00mil "clearline"]
+	Line[3295.00mil 2660.00mil 3295.00mil 2595.00mil 10.00mil 14.00mil "clearline"]
+	Line[2810.00mil 2160.00mil 2810.00mil 2320.00mil 10.00mil 14.00mil "clearline"]
+	Line[2710.00mil 2015.00mil 2710.00mil 2320.00mil 10.00mil 14.00mil "clearline"]
+	Line[4260.00mil 2825.00mil 3985.00mil 2550.00mil 10.00mil 14.00mil "clearline"]
+	Line[3985.00mil 2550.00mil 3435.00mil 2550.00mil 10.00mil 14.00mil "clearline"]
+	Line[4160.00mil 2825.00mil 3920.00mil 2585.00mil 10.00mil 14.00mil "clearline"]
+	Line[3920.00mil 2585.00mil 3375.00mil 2585.00mil 10.00mil 14.00mil "clearline"]
+	Line[3375.00mil 2585.00mil 3370.00mil 2580.00mil 10.00mil 14.00mil "clearline"]
+	Text[6660.00mil 1890.00mil 0 142 "20190115" "clearline,onsolder"]
+)
+Layer(5 "outline")
+(
+	Line[7140.00mil 1100.00mil 7140.00mil 2980.00mil 10.00mil 14.00mil "clearline"]
+	Line[1310.00mil 1075.00mil 7115.00mil 1075.00mil 10.00mil 14.00mil "clearline"]
+	Line[1310.00mil 3005.00mil 7115.00mil 3005.00mil 10.00mil 14.00mil "clearline"]
+	Line[1285.00mil 1100.00mil 1285.00mil 2980.00mil 10.00mil 14.00mil "clearline"]
+	Arc[7115.00mil 1100.00mil 25.00mil 25.00mil 10.00mil 14.00mil -90 -90 "clearline"]
+	Arc[7115.00mil 2980.00mil 25.00mil 25.00mil 10.00mil 14.00mil 180 -90 "clearline"]
+	Arc[1310.00mil 1100.00mil 25.00mil 25.00mil 10.00mil 14.00mil 0 -90 "clearline"]
+	Arc[1310.00mil 2980.00mil 25.00mil 25.00mil 10.00mil 14.00mil 90 -90 "clearline"]
+)
+Layer(6 "silk")
+(
+	Line[6465.00mil 2115.00mil 6475.00mil 2115.00mil 10.00mil 14.00mil "clearline"]
+	Line[6475.00mil 2115.00mil 6505.00mil 2145.00mil 10.00mil 14.00mil "clearline"]
+	Line[6115.00mil 2030.00mil 6110.00mil 2035.00mil 10.00mil 14.00mil "clearline"]
+	Line[6110.00mil 2035.00mil 6110.00mil 2080.00mil 10.00mil 14.00mil "clearline"]
+	Line[6435.00mil 1820.00mil 6450.00mil 1820.00mil 10.00mil 14.00mil "clearline"]
+	Line[6310.00mil 1850.00mil 6295.00mil 1865.00mil 10.00mil 14.00mil "clearline"]
+	Text[6300.00mil 2885.00mil 0 98 "20190115" "clearline,onsolder"]
+	Text[6325.00mil 2825.00mil 0 98 "FRC 971" "clearline,onsolder"]
+	Text[6145.00mil 2775.00mil 0 98 "Spartan Robotics" "clearline,onsolder"]
+	Text[5500.00mil 2840.00mil 0 98 "UART Camera Board" "clearline,onsolder"]
+)
+Layer(7 "silk")
+(
+	Line[4410.00mil 1695.00mil 4410.00mil 1715.00mil 10.00mil 14.00mil "clearline"]
+	Line[4390.00mil 1705.00mil 4440.00mil 1705.00mil 10.00mil 14.00mil "clearline"]
+	Line[4420.00mil 1705.00mil 4410.00mil 1715.00mil 10.00mil 14.00mil "clearline"]
+	Line[4420.00mil 1705.00mil 4410.00mil 1695.00mil 10.00mil 14.00mil "clearline"]
+	Line[4425.00mil 1690.00mil 4425.00mil 1720.00mil 10.00mil 14.00mil "clearline"]
+	Line[4660.00mil 2025.00mil 4680.00mil 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[4670.00mil 1995.00mil 4670.00mil 2045.00mil 10.00mil 14.00mil "clearline"]
+	Line[4670.00mil 2015.00mil 4680.00mil 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[4670.00mil 2015.00mil 4660.00mil 2025.00mil 10.00mil 14.00mil "clearline"]
+	Line[4655.00mil 2010.00mil 4685.00mil 2010.00mil 10.00mil 14.00mil "clearline"]
+	Line[4435.00mil 1940.00mil 4425.00mil 1950.00mil 10.00mil 14.00mil "clearline"]
+	Line[4435.00mil 1910.00mil 4435.00mil 1940.00mil 10.00mil 14.00mil "clearline"]
+	Line[4695.00mil 1925.00mil 4705.00mil 1925.00mil 10.00mil 14.00mil "clearline"]
+	Line[4700.00mil 1815.00mil 4700.00mil 1825.00mil 10.00mil 14.00mil "clearline"]
+	Line[4910.00mil 1835.00mil 4910.00mil 1855.00mil 10.00mil 14.00mil "clearline"]
+	Line[4910.00mil 1855.00mil 4905.00mil 1860.00mil 10.00mil 14.00mil "clearline"]
+	Line[4745.00mil 1775.00mil 4775.00mil 1775.00mil 10.00mil 14.00mil "clearline"]
+	Line[4760.00mil 1780.00mil 4750.00mil 1790.00mil 10.00mil 14.00mil "clearline"]
+	Line[4760.00mil 1780.00mil 4770.00mil 1790.00mil 10.00mil 14.00mil "clearline"]
+	Line[4760.00mil 1765.00mil 4760.00mil 1800.00mil 10.00mil 14.00mil "clearline"]
+	Line[4750.00mil 1790.00mil 4770.00mil 1790.00mil 10.00mil 14.00mil "clearline"]
+	Line[5075.00mil 1730.00mil 5085.00mil 1730.00mil 10.00mil 14.00mil "clearline"]
+	Line[4900.00mil 1920.00mil 4905.00mil 1920.00mil 10.00mil 14.00mil "clearline"]
+	Line[4905.00mil 1920.00mil 4915.00mil 1930.00mil 10.00mil 14.00mil "clearline"]
+	Line[5770.00mil 1555.00mil 5770.00mil 1530.00mil 10.00mil 14.00mil "clearline"]
+	Line[5770.00mil 1530.00mil 5765.00mil 1525.00mil 10.00mil 14.00mil "clearline"]
+	Line[5705.00mil 1945.00mil 5705.00mil 2000.00mil 10.00mil 14.00mil "clearline"]
+	Line[5685.00mil 1980.00mil 5725.00mil 1980.00mil 10.00mil 14.00mil "clearline"]
+	Line[5705.00mil 1980.00mil 5720.00mil 1965.00mil 10.00mil 14.00mil "clearline"]
+	Line[5720.00mil 1965.00mil 5690.00mil 1965.00mil 10.00mil 14.00mil "clearline"]
+	Line[5690.00mil 1965.00mil 5705.00mil 1980.00mil 10.00mil 14.00mil "clearline"]
+	Line[3715.00mil 1735.00mil 3715.00mil 1790.00mil 10.00mil 14.00mil "clearline"]
+	Line[3695.00mil 1770.00mil 3735.00mil 1770.00mil 10.00mil 14.00mil "clearline"]
+	Line[3715.00mil 1770.00mil 3730.00mil 1755.00mil 10.00mil 14.00mil "clearline"]
+	Line[3730.00mil 1755.00mil 3700.00mil 1755.00mil 10.00mil 14.00mil "clearline"]
+	Line[3700.00mil 1755.00mil 3715.00mil 1770.00mil 10.00mil 14.00mil "clearline"]
+	Line[3165.00mil 1555.00mil 3165.00mil 1610.00mil 10.00mil 14.00mil "clearline"]
+	Line[3145.00mil 1590.00mil 3185.00mil 1590.00mil 10.00mil 14.00mil "clearline"]
+	Line[3165.00mil 1590.00mil 3180.00mil 1575.00mil 10.00mil 14.00mil "clearline"]
+	Line[3180.00mil 1575.00mil 3150.00mil 1575.00mil 10.00mil 14.00mil "clearline"]
+	Line[3150.00mil 1575.00mil 3165.00mil 1590.00mil 10.00mil 14.00mil "clearline"]
+	Line[5520.00mil 2180.00mil 5575.00mil 2180.00mil 10.00mil 14.00mil "clearline"]
+	Line[5540.00mil 2160.00mil 5540.00mil 2200.00mil 10.00mil 14.00mil "clearline"]
+	Line[5540.00mil 2180.00mil 5555.00mil 2195.00mil 10.00mil 14.00mil "clearline"]
+	Line[5555.00mil 2165.00mil 5555.00mil 2195.00mil 10.00mil 14.00mil "clearline"]
+	Line[5555.00mil 2165.00mil 5540.00mil 2180.00mil 10.00mil 14.00mil "clearline"]
+	Line[4945.00mil 2480.00mil 4945.00mil 2535.00mil 10.00mil 14.00mil "clearline"]
+	Line[4925.00mil 2515.00mil 4965.00mil 2515.00mil 10.00mil 14.00mil "clearline"]
+	Line[4945.00mil 2515.00mil 4930.00mil 2500.00mil 10.00mil 14.00mil "clearline"]
+	Line[4930.00mil 2500.00mil 4960.00mil 2500.00mil 10.00mil 14.00mil "clearline"]
+	Line[4960.00mil 2500.00mil 4945.00mil 2515.00mil 10.00mil 14.00mil "clearline"]
+	Text[1530.00mil 2300.00mil 0 98 "20190115" "clearline"]
+	Text[1535.00mil 2385.00mil 0 98 "FRC 971" "clearline"]
+	Text[1495.00mil 2440.00mil 0 98 "Spartan Robotics" "clearline"]
+	Text[1470.00mil 2535.00mil 0 98 "UART Camera Board" "clearline"]
+	Text[150.2260mm 48.8800mm 3 120 "SPI 5V" "clearline"]
+	Text[3645.00mil 1620.00mil 0 142 "CAM 5V" "clearline"]
+	Text[3085.00mil 1620.00mil 0 140 "5V" "clearline"]
+	Text[5110.00mil 2180.00mil 0 142 "ODROID" "clearline"]
+	Text[1995.00mil 1160.00mil 0 75 "3.3V" "clearline"]
+	Text[1900.00mil 1160.00mil 0 75 "TX" "clearline"]
+	Text[1810.00mil 1160.00mil 0 75 "RX" "clearline"]
+	Text[1705.00mil 1160.00mil 0 75 "5V" "clearline"]
+	Text[1585.00mil 1160.00mil 0 75 "LED" "clearline"]
+	Text[2550.00mil 1160.00mil 0 75 "3.3V" "clearline"]
+	Text[2455.00mil 1160.00mil 0 75 "TX" "clearline"]
+	Text[2365.00mil 1160.00mil 0 75 "RX" "clearline"]
+	Text[2260.00mil 1160.00mil 0 75 "5V" "clearline"]
+	Text[2140.00mil 1160.00mil 0 75 "LED" "clearline"]
+	Text[3105.00mil 1160.00mil 0 75 "3.3V" "clearline"]
+	Text[3010.00mil 1160.00mil 0 75 "TX" "clearline"]
+	Text[2920.00mil 1160.00mil 0 75 "RX" "clearline"]
+	Text[2815.00mil 1160.00mil 0 75 "5V" "clearline"]
+	Text[2695.00mil 1160.00mil 0 75 "LED" "clearline"]
+	Text[3660.00mil 1160.00mil 0 75 "3.3V" "clearline"]
+	Text[3565.00mil 1160.00mil 0 75 "TX" "clearline"]
+	Text[3475.00mil 1160.00mil 0 75 "RX" "clearline"]
+	Text[3370.00mil 1160.00mil 0 75 "5V" "clearline"]
+	Text[3250.00mil 1160.00mil 0 75 "LED" "clearline"]
+	Text[4215.00mil 1160.00mil 0 75 "3.3V" "clearline"]
+	Text[4120.00mil 1160.00mil 0 75 "TX" "clearline"]
+	Text[4030.00mil 1160.00mil 0 75 "RX" "clearline"]
+	Text[3925.00mil 1160.00mil 0 75 "5V" "clearline"]
+	Text[3805.00mil 1160.00mil 0 75 "LED" "clearline"]
+	Text[4385.00mil 1145.00mil 0 142 "-" "clearline"]
+	Text[4490.00mil 1140.00mil 0 142 "+" "clearline"]
+	Text[4640.00mil 1145.00mil 0 142 "-" "clearline"]
+	Text[4745.00mil 1140.00mil 0 142 "+" "clearline"]
+	Text[4900.00mil 1145.00mil 0 142 "-" "clearline"]
+	Text[5005.00mil 1140.00mil 0 142 "+" "clearline"]
+	Text[5265.00mil 1160.00mil 0 75 "5V" "clearline"]
+	Text[5145.00mil 1160.00mil 0 75 "LED" "clearline"]
+	Text[5520.00mil 1160.00mil 0 75 "5V" "clearline"]
+	Text[5400.00mil 1160.00mil 0 75 "LED" "clearline"]
+	Text[5620.00mil 1155.00mil 0 75 "ODROID" "clearline"]
+	Text[5795.00mil 1160.00mil 0 75 "GND" "clearline"]
+	Text[6610.00mil 1155.00mil 0 75 "VBAT" "clearline"]
+	Text[6760.00mil 1155.00mil 0 75 "GND" "clearline"]
+	Text[6460.00mil 1155.00mil 0 75 "GND" "clearline"]
+	Text[6345.00mil 1155.00mil 0 75 "PWR" "clearline"]
+	Text[6265.00mil 1155.00mil 0 75 "CLK" "clearline"]
+	Text[6150.00mil 1160.00mil 0 75 "MOSI" "clearline"]
+	Text[6045.00mil 1160.00mil 0 75 "MISO" "clearline"]
+	Text[5980.00mil 1160.00mil 0 75 "CS" "clearline"]
+	Text[1935.00mil 1100.00mil 0 98 "CAM0" "clearline"]
+	Text[2500.00mil 1095.00mil 0 98 "CAM1" "clearline"]
+	Text[3020.00mil 1100.00mil 0 98 "CAM2" "clearline"]
+	Text[3580.00mil 1100.00mil 0 98 "CAM3" "clearline"]
+	Text[4140.00mil 1100.00mil 0 98 "CAM4" "clearline"]
+	Text[4435.00mil 1130.00mil 0 98 "5" "clearline"]
+	Text[4690.00mil 1145.00mil 0 98 "6" "clearline"]
+	Text[4945.00mil 1135.00mil 0 98 "7" "clearline"]
+	Text[5230.00mil 1135.00mil 0 75 "8" "clearline"]
+	Text[5480.00mil 1130.00mil 0 75 "9" "clearline"]
+)
+NetList()
+(
+	Net("+3.3V" "(unknown)")
+	(
+		Connect("C102-1")
+		Connect("C201-1")
+		Connect("C315-1")
+		Connect("C316-1")
+		Connect("C317-1")
+		Connect("C318-1")
+		Connect("C319-1")
+		Connect("CONN302-1")
+		Connect("CONN304-1")
+		Connect("CONN305-1")
+		Connect("CONN306-1")
+		Connect("CONN307-1")
+		Connect("U101-15")
+		Connect("U201-10")
+		Connect("U201-16")
+	)
+	Net("+5V" "(unknown)")
+	(
+		Connect("C4-1")
+		Connect("C5-1")
+		Connect("C12-1")
+		Connect("C101-1")
+		Connect("C304-1")
+		Connect("CONN301-1")
+		Connect("CONN302-4")
+		Connect("CONN303-1")
+		Connect("CONN304-4")
+		Connect("CONN305-4")
+		Connect("CONN306-4")
+		Connect("CONN307-4")
+		Connect("D4-2")
+		Connect("Q3-D")
+		Connect("R6-1")
+		Connect("U1-9")
+		Connect("U101-48")
+		Connect("U301-1_2")
+		Connect("U301-4")
+		Connect("U301-6_7")
+	)
+	Net("5V_PGOOD" "(unknown)")
+	(
+		Connect("U1-14")
+		Connect("U101-43")
+	)
+	Net("CAM_5V" "(unknown)")
+	(
+		Connect("C303-1")
+		Connect("C306-1")
+		Connect("C307-1")
+		Connect("C308-1")
+		Connect("C309-1")
+		Connect("C310-1")
+		Connect("CONN308-1")
+		Connect("CONN309-1")
+		Connect("CONN310-1")
+		Connect("CONN311-1")
+		Connect("CONN312-1")
+		Connect("D301-2")
+		Connect("U301-13_14")
+	)
+	Net("CAM_EN" "(unknown)")
+	(
+		Connect("U101-38")
+		Connect("U301-3")
+	)
+	Net("GND" "(unknown)")
+	(
+		Connect("C1-2")
+		Connect("C2-2")
+		Connect("C3-2")
+		Connect("C4-2")
+		Connect("C5-2")
+		Connect("C6-2")
+		Connect("C7-2")
+		Connect("C8-2")
+		Connect("C9-2")
+		Connect("C10-1")
+		Connect("C11-1")
+		Connect("C12-2")
+		Connect("C13-2")
+		Connect("C18-2")
+		Connect("C101-2")
+		Connect("C102-2")
+		Connect("C201-2")
+		Connect("C301-2")
+		Connect("C302-2")
+		Connect("C303-2")
+		Connect("C304-2")
+		Connect("C305-2")
+		Connect("C306-2")
+		Connect("C307-2")
+		Connect("C308-2")
+		Connect("C309-2")
+		Connect("C310-2")
+		Connect("C311-2")
+		Connect("C312-2")
+		Connect("C313-2")
+		Connect("C314-2")
+		Connect("C315-2")
+		Connect("C316-2")
+		Connect("C317-2")
+		Connect("C318-2")
+		Connect("C319-2")
+		Connect("C402-2")
+		Connect("C404-2")
+		Connect("C406-2")
+		Connect("CONN308-4")
+		Connect("CONN308-5")
+		Connect("CONN309-4")
+		Connect("CONN309-5")
+		Connect("CONN310-4")
+		Connect("CONN310-5")
+		Connect("CONN311-4")
+		Connect("CONN311-5")
+		Connect("CONN312-4")
+		Connect("CONN312-5")
+		Connect("CONN313-4")
+		Connect("CONN313-5")
+		Connect("CONN314-4")
+		Connect("CONN314-5")
+		Connect("CONN315-2")
+		Connect("CONN316-2")
+		Connect("D1-1")
+		Connect("R1-1")
+		Connect("R2-1")
+		Connect("R3-2")
+		Connect("R4-2")
+		Connect("R7-2")
+		Connect("R9-2")
+		Connect("R10-2")
+		Connect("R11-2")
+		Connect("R12-2")
+		Connect("R202-2")
+		Connect("R301-2")
+		Connect("R302-2")
+		Connect("U1-2")
+		Connect("U1-7")
+		Connect("U1-10")
+		Connect("U1-11")
+		Connect("U1-19")
+		Connect("U1-29")
+		Connect("U101-1")
+		Connect("U101-34")
+		Connect("U201-9")
+		Connect("U201-15")
+		Connect("U301-11")
+		Connect("U301-15")
+		Connect("U302-8")
+		Connect("U302-9")
+		Connect("U401-2")
+		Connect("U402-2")
+		Connect("U403-2")
+	)
+	Net("LED0" "(unknown)")
+	(
+		Connect("U101-44")
+		Connect("U401-3")
+	)
+	Net("LED1" "(unknown)")
+	(
+		Connect("U101-45")
+		Connect("U402-3")
+	)
+	Net("LED2" "(unknown)")
+	(
+		Connect("U101-7")
+		Connect("U403-3")
+	)
+	Net("LED3" "(unknown)")
+	(
+		Connect("U101-42")
+		Connect("U302-1")
+	)
+	Net("LED4" "(unknown)")
+	(
+		Connect("U101-22")
+		Connect("U302-2")
+	)
+	Net("LED5" "(unknown)")
+	(
+		Connect("U101-21")
+		Connect("U302-3")
+	)
+	Net("LED6" "(unknown)")
+	(
+		Connect("U101-27")
+		Connect("U302-4")
+	)
+	Net("LED7" "(unknown)")
+	(
+		Connect("U101-28")
+		Connect("U302-5")
+	)
+	Net("LED8" "(unknown)")
+	(
+		Connect("U101-29")
+		Connect("U302-6")
+	)
+	Net("LED9" "(unknown)")
+	(
+		Connect("U101-30")
+		Connect("U302-7")
+	)
+	Net("ODROID_5V" "(unknown)")
+	(
+		Connect("C302-1")
+		Connect("C311-1")
+		Connect("C312-1")
+		Connect("C313-1")
+		Connect("C314-1")
+		Connect("CONN313-1")
+		Connect("CONN314-1")
+		Connect("CONN316-1")
+		Connect("D302-2")
+		Connect("U301-8_9")
+	)
+	Net("ODROID_EN" "(unknown)")
+	(
+		Connect("U101-37")
+		Connect("U301-5")
+	)
+	Net("RAW_SPI_CLK" "(unknown)")
+	(
+		Connect("R201-2")
+		Connect("U201-3")
+	)
+	Net("RAW_SPI_CS" "(unknown)")
+	(
+		Connect("R201-8")
+		Connect("U201-5")
+		Connect("U202-2")
+	)
+	Net("RAW_SPI_MISO" "(unknown)")
+	(
+		Connect("R201-6")
+		Connect("U201-6")
+	)
+	Net("RAW_SPI_MOSI" "(unknown)")
+	(
+		Connect("R201-4")
+		Connect("U201-4")
+	)
+	Net("SPI_5V" "(unknown)")
+	(
+		Connect("C202-1")
+		Connect("CONN201-2")
+		Connect("D201-2")
+		Connect("U201-1")
+		Connect("U202-5")
+	)
+	Net("SPI_CLK" "(unknown)")
+	(
+		Connect("U101-36")
+		Connect("U201-14")
+	)
+	Net("SPI_CS" "(unknown)")
+	(
+		Connect("U101-4")
+		Connect("U201-12")
+	)
+	Net("SPI_GND" "(unknown)")
+	(
+		Connect("C202-2")
+		Connect("CONN201-1")
+		Connect("U201-2")
+		Connect("U201-8")
+		Connect("U202-3")
+	)
+	Net("SPI_MISO" "(unknown)")
+	(
+		Connect("U101-13")
+		Connect("U201-11")
+	)
+	Net("SPI_MOSI" "(unknown)")
+	(
+		Connect("U101-14")
+		Connect("U201-13")
+	)
+	Net("UART0_RX" "(unknown)")
+	(
+		Connect("R101-3")
+		Connect("U101-11")
+	)
+	Net("UART0_RX_RAW" "(unknown)")
+	(
+		Connect("CONN302-3")
+		Connect("R101-2")
+	)
+	Net("UART0_TX" "(unknown)")
+	(
+		Connect("R101-1")
+		Connect("U101-12")
+	)
+	Net("UART0_TX_RAW" "(unknown)")
+	(
+		Connect("CONN302-2")
+		Connect("R101-4")
+	)
+	Net("UART1_RX" "(unknown)")
+	(
+		Connect("R101-7")
+		Connect("U101-19")
+	)
+	Net("UART1_RX_RAW" "(unknown)")
+	(
+		Connect("CONN304-3")
+		Connect("R101-6")
+	)
+	Net("UART1_TX" "(unknown)")
+	(
+		Connect("R101-5")
+		Connect("U101-18")
+	)
+	Net("UART1_TX_RAW" "(unknown)")
+	(
+		Connect("CONN304-2")
+		Connect("R101-8")
+	)
+	Net("UART2_RX" "(unknown)")
+	(
+		Connect("R102-3")
+		Connect("U101-9")
+	)
+	Net("UART2_RX_RAW" "(unknown)")
+	(
+		Connect("CONN305-3")
+		Connect("R102-2")
+	)
+	Net("UART2_TX" "(unknown)")
+	(
+		Connect("R102-1")
+		Connect("U101-10")
+	)
+	Net("UART2_TX_RAW" "(unknown)")
+	(
+		Connect("CONN305-2")
+		Connect("R102-4")
+	)
+	Net("UART3_RX" "(unknown)")
+	(
+		Connect("R102-7")
+		Connect("U101-23")
+	)
+	Net("UART3_RX_RAW" "(unknown)")
+	(
+		Connect("CONN306-3")
+		Connect("R102-6")
+	)
+	Net("UART3_TX" "(unknown)")
+	(
+		Connect("R102-5")
+		Connect("U101-24")
+	)
+	Net("UART3_TX_RAW" "(unknown)")
+	(
+		Connect("CONN306-2")
+		Connect("R102-8")
+	)
+	Net("UART4_RX" "(unknown)")
+	(
+		Connect("R103-3")
+		Connect("U101-26")
+	)
+	Net("UART4_RX_RAW" "(unknown)")
+	(
+		Connect("CONN307-3")
+		Connect("R103-2")
+	)
+	Net("UART4_TX" "(unknown)")
+	(
+		Connect("R103-1")
+		Connect("U101-25")
+	)
+	Net("UART4_TX_RAW" "(unknown)")
+	(
+		Connect("CONN307-2")
+		Connect("R103-4")
+	)
+	Net("unnamed_net1" "(unknown)")
+	(
+		Connect("R1-2")
+		Connect("U1-1")
+	)
+	Net("unnamed_net2" "(unknown)")
+	(
+		Connect("R2-2")
+		Connect("U1-3")
+	)
+	Net("unnamed_net3" "(unknown)")
+	(
+		Connect("C10-2")
+		Connect("U1-4")
+	)
+	Net("unnamed_net4" "(unknown)")
+	(
+		Connect("C11-2")
+		Connect("U1-5")
+	)
+	Net("unnamed_net5" "(unknown)")
+	(
+		Connect("C17-1")
+		Connect("C18-1")
+		Connect("U1-6")
+	)
+	Net("unnamed_net6" "(unknown)")
+	(
+		Connect("R4-1")
+		Connect("R6-2")
+		Connect("U1-8")
+	)
+	Net("unnamed_net7" "(unknown)")
+	(
+		Connect("R3-1")
+		Connect("R5-2")
+		Connect("U1-26")
+	)
+	Net("unnamed_net8" "(unknown)")
+	(
+		Connect("C16-1")
+		Connect("R9-1")
+		Connect("U1-12")
+	)
+	Net("unnamed_net9" "(unknown)")
+	(
+		Connect("C16-2")
+		Connect("R8-1")
+		Connect("U1-13")
+	)
+	Net("unnamed_net10" "(unknown)")
+	(
+		Connect("C13-1")
+		Connect("D2-1")
+		Connect("D3-1")
+		Connect("U1-20")
+	)
+	Net("unnamed_net11" "(unknown)")
+	(
+		Connect("C9-1")
+		Connect("U1-21")
+	)
+	Net("unnamed_net12" "(unknown)")
+	(
+		Connect("Q1-G")
+		Connect("U1-18")
+	)
+	Net("unnamed_net13" "(unknown)")
+	(
+		Connect("Q3-G")
+		Connect("U1-16")
+	)
+	Net("unnamed_net14" "(unknown)")
+	(
+		Connect("C15-2")
+		Connect("L1-2")
+		Connect("Q1-D")
+		Connect("Q3-S")
+		Connect("U1-15")
+	)
+	Net("unnamed_net15" "(unknown)")
+	(
+		Connect("Q4-G")
+		Connect("U1-22")
+	)
+	Net("unnamed_net16" "(unknown)")
+	(
+		Connect("C14-1")
+		Connect("D2-2")
+		Connect("U1-23")
+	)
+	Net("unnamed_net17" "(unknown)")
+	(
+		Connect("C15-1")
+		Connect("D3-2")
+		Connect("U1-17")
+	)
+	Net("unnamed_net18" "(unknown)")
+	(
+		Connect("Q2-G")
+		Connect("U1-24")
+	)
+	Net("unnamed_net19" "(unknown)")
+	(
+		Connect("C14-2")
+		Connect("L1-1")
+		Connect("Q2-S")
+		Connect("Q4-D")
+		Connect("U1-25")
+	)
+	Net("unnamed_net20" "(unknown)")
+	(
+		Connect("Q1-S")
+		Connect("Q4-S")
+		Connect("R7-1")
+		Connect("R8-2")
+	)
+	Net("unnamed_net21" "(unknown)")
+	(
+		Connect("C17-2")
+		Connect("R10-1")
+	)
+	Net("unnamed_net22" "(unknown)")
+	(
+		Connect("D4-1")
+		Connect("R11-1")
+	)
+	Net("unnamed_net23" "(unknown)")
+	(
+		Connect("D5-1")
+		Connect("R12-1")
+	)
+	Net("unnamed_net24" "(unknown)")
+	(
+		Connect("CONN201-4")
+		Connect("R201-3")
+	)
+	Net("unnamed_net25" "(unknown)")
+	(
+		Connect("CONN201-6")
+		Connect("R201-7")
+	)
+	Net("unnamed_net26" "(unknown)")
+	(
+		Connect("CONN201-3")
+		Connect("R201-1")
+	)
+	Net("unnamed_net27" "(unknown)")
+	(
+		Connect("CONN201-5")
+		Connect("R201-5")
+	)
+	Net("unnamed_net28" "(unknown)")
+	(
+		Connect("U201-7")
+		Connect("U202-4")
+	)
+	Net("unnamed_net29" "(unknown)")
+	(
+		Connect("D201-1")
+		Connect("R202-1")
+	)
+	Net("unnamed_net30" "(unknown)")
+	(
+		Connect("CONN301-2")
+		Connect("U302-16")
+	)
+	Net("unnamed_net31" "(unknown)")
+	(
+		Connect("CONN302-5")
+		Connect("U302-10")
+	)
+	Net("unnamed_net32" "(unknown)")
+	(
+		Connect("CONN303-2")
+		Connect("U302-15")
+	)
+	Net("unnamed_net33" "(unknown)")
+	(
+		Connect("CONN304-5")
+		Connect("U302-11")
+	)
+	Net("unnamed_net34" "(unknown)")
+	(
+		Connect("CONN305-5")
+		Connect("U302-13")
+	)
+	Net("unnamed_net35" "(unknown)")
+	(
+		Connect("CONN306-5")
+		Connect("U302-12")
+	)
+	Net("unnamed_net36" "(unknown)")
+	(
+		Connect("CONN307-5")
+		Connect("U302-14")
+	)
+	Net("unnamed_net37" "(unknown)")
+	(
+		Connect("C301-1")
+		Connect("U301-12")
+	)
+	Net("unnamed_net38" "(unknown)")
+	(
+		Connect("C305-1")
+		Connect("U301-10")
+	)
+	Net("unnamed_net39" "(unknown)")
+	(
+		Connect("D301-1")
+		Connect("R301-1")
+	)
+	Net("unnamed_net40" "(unknown)")
+	(
+		Connect("D302-1")
+		Connect("R302-1")
+	)
+	Net("unnamed_net41" "(unknown)")
+	(
+		Connect("C401-2")
+		Connect("CONN401-1")
+		Connect("R401-1")
+		Connect("U401-4")
+	)
+	Net("unnamed_net42" "(unknown)")
+	(
+		Connect("D401-1")
+		Connect("L401-1")
+		Connect("U401-1")
+	)
+	Net("unnamed_net43" "(unknown)")
+	(
+		Connect("C401-1")
+		Connect("CONN401-2")
+		Connect("L401-2")
+	)
+	Net("unnamed_net44" "(unknown)")
+	(
+		Connect("C403-2")
+		Connect("CONN403-1")
+		Connect("R402-1")
+		Connect("U402-4")
+	)
+	Net("unnamed_net45" "(unknown)")
+	(
+		Connect("D402-1")
+		Connect("L402-1")
+		Connect("U402-1")
+	)
+	Net("unnamed_net46" "(unknown)")
+	(
+		Connect("C403-1")
+		Connect("CONN403-2")
+		Connect("L402-2")
+	)
+	Net("unnamed_net47" "(unknown)")
+	(
+		Connect("C405-2")
+		Connect("CONN402-1")
+		Connect("R403-1")
+		Connect("U403-4")
+	)
+	Net("unnamed_net48" "(unknown)")
+	(
+		Connect("D403-1")
+		Connect("L403-1")
+		Connect("U403-1")
+	)
+	Net("unnamed_net49" "(unknown)")
+	(
+		Connect("C405-1")
+		Connect("CONN402-2")
+		Connect("L403-2")
+	)
+	Net("Vcc" "(unknown)")
+	(
+		Connect("C1-1")
+		Connect("C2-1")
+		Connect("C3-1")
+		Connect("C6-1")
+		Connect("C7-1")
+		Connect("C8-1")
+		Connect("C402-1")
+		Connect("C404-1")
+		Connect("C406-1")
+		Connect("CONN315-1")
+		Connect("D1-2")
+		Connect("D5-2")
+		Connect("D401-2")
+		Connect("D402-2")
+		Connect("D403-2")
+		Connect("Q2-D")
+		Connect("R5-1")
+		Connect("R401-2")
+		Connect("R402-2")
+		Connect("R403-2")
+		Connect("U1-27")
+		Connect("U1-28")
+		Connect("U401-5")
+		Connect("U402-5")
+		Connect("U403-5")
+	)
+)
diff --git a/third_party/BUILD b/third_party/BUILD
index 20bb7e0..934486e 100644
--- a/third_party/BUILD
+++ b/third_party/BUILD
@@ -1,7 +1,14 @@
 cc_library(
-  name = 'wpilib',
-  deps = ['//third_party/allwpilib_2018:wpilib'],
-  visibility = ['//visibility:public'],
-  linkstatic = True,
-  restricted_to = ['//tools:roborio'],
+    name = "wpilib",
+    linkstatic = True,
+    restricted_to = ["//tools:roborio"],
+    visibility = ["//visibility:public"],
+    deps = ["//frc971/wpilib/ahal"],
+)
+
+cc_library(
+    name = "wpilib_hal",
+    restricted_to = ["//tools:roborio"],
+    visibility = ["//visibility:public"],
+    deps = ["//third_party/allwpilib_2018:hal"],
 )
diff --git a/third_party/Phoenix-frc-lib/BUILD b/third_party/Phoenix-frc-lib/BUILD
index 7a1934a..dcfd0dc 100644
--- a/third_party/Phoenix-frc-lib/BUILD
+++ b/third_party/Phoenix-frc-lib/BUILD
@@ -1,6 +1,7 @@
 # It also restricts use to only with CTRE products and a roboRIO in FRC.
 licenses(["permissive"])
 
+# Excludes motor/sensor code because those have reliances on WPILib.
 cc_library(
     name = "phoenix",
     srcs = glob(
@@ -12,6 +13,8 @@
             "**/Tasking/**",
             "cpp/src/RCRadio3Ch.cpp",
             "cpp/src/CompileTest.cpp",
+            "**/MotorControl/**",
+            "**/Sensors/**",
         ],
     ) + [
         "libraries/driver/lib/libCTRE_PhoenixCCI.a",
@@ -23,6 +26,8 @@
         ],
         exclude = [
             "**/Tasking/**",
+            "**/MotorControl/**",
+            "**/Sensors/**",
             "cpp/include/ctre/phoenix/RCRadio3Ch.h",
         ],
     ),
@@ -33,6 +38,6 @@
     restricted_to = ["//tools:roborio"],
     visibility = ["//visibility:public"],
     deps = [
-        "//third_party:wpilib",
+        "//third_party/allwpilib_2018:hal",
     ],
 )
diff --git a/third_party/allwpilib_2018/BUILD b/third_party/allwpilib_2018/BUILD
index 38d9559..9381a96 100644
--- a/third_party/allwpilib_2018/BUILD
+++ b/third_party/allwpilib_2018/BUILD
@@ -1,143 +1,68 @@
-licenses(['notice'])
-
-genrule(
-  name = 'wpilib_version',
-  outs = ['shared/src/WPILibVersion.cpp'],
-  cmd = '\n'.join([
-    "cat > \"$@\" << EOF",
-    "// Autogenerated file! Do not manually edit this file.",
-    "#include \"WPILibVersion.h\"",
-    "const char* GetWPILibVersion() {",
-    "  return \"2018-frc971\";",
-    "}",
-    "EOF",
-  ]),
-)
-
-_header_dirs = [
-  'wpilibc/src/main/native/include',
-  #'wpilibc/shared/include',
-  #'wpilibc/athena/include',
-  'hal/src/main/native/include',
-  'hal/src/main/native/athena',
-  'hal/src/main/native/include/HAL/cpp',
-  #'hal/include',
-  #'hal/lib/athena',
-]
+licenses(["notice"])
 
 # Names of WPILib "devices" I don't want to deal with making trivial updates to
 # chop out various ugliness or have to vet for sanity.
 _excluded_devices = [
-  'ADXL345_I2C',
-  'ADXL345_SPI',
-  'ADXL362',
-  'ADXRS450_Gyro',
-  'AnalogAccelerometer',
-  #'AnalogGyro',
-  'AnalogPotentiometer',
-  'CANJaguar',
-  'CANSpeedController',
-  'CANTalon',
-  'CameraServer',
-  'DoubleSolenoid',
-  'GamepadBase',
-  'GearTooth',
-  'GenericHID',
-  #'GyroBase',
-  'IterativeRobot',
-  'Jaguar',
-  'Joystick',
-  'JoystickBase',
-  #'Log',
-  #'MotorSafety',
-  #'MotorSafetyHelper',
-  'OSSerialPort',
-  #'PIDController',
-  #'PIDSource',
-  #'PWMSpeedController',
-  'Potentiometer',
-  'RobotDrive',
-  'SD540',
-  #'SafePWM',
-  #'SerialHelper',
-  #'SerialPort',
-  #'Spark',
-  #'SpeedController',
-  'TalonSRX',
-  'Ultrasonic',
-  'Victor',
-  'XboxController',
-  #'visa',
-]
-
-# Whole subdirectories of WPILib we don't want around.
-_excluded_directories = [
-  #'SmartDashboard',
-  #'LiveWindow',
-  #'Commands',
-  #'Buttons',
-  #'Filters',
-  'LabView',
-  'vision',
+    "AnalogGyro",
+    "SerialPort",
+    "SerialHelper",
+    "OSSerialPort",
+    "visa",
 ]
 
 # Header files we don't want to have.
 _bad_hdrs = ([
-  'wpilibc/src/main/native/include/WPILib.h',
-  'hal/src/main/native/include/HAL/LabVIEW/HAL.h',
-  #'wpilibc/**/Accelerometer.*',
-] + ['**/%s/**' % d for d in _excluded_directories] +
- ['**/%s.*' % d for d in _excluded_devices])
-_h_hdrs = glob([d + '/**/*.h' for d in _header_dirs], exclude=_bad_hdrs)
-_hpp_hdrs = glob([d + '/**/*.hpp' for d in _header_dirs], exclude=_bad_hdrs)
+    "hal/include/HAL/LabVIEW/HAL.h",
+] + ["**/%s.*" % d for d in _excluded_devices])
+
+_hal_header_dirs = [
+    "hal/src/main/native/athena",
+    "hal/src/main/native/include",
+]
+
+_hal_h_hdrs = glob(
+    [d + "/**/*.h" for d in _hal_header_dirs],
+    exclude = _bad_hdrs,
+)
+
+_hal_hpp_hdrs = glob(
+    [d + "/**/*.hpp" for d in _hal_header_dirs],
+    exclude = _bad_hdrs,
+)
 
 cc_library(
-  name = 'wpilib',
-  visibility = ['//third_party:__pkg__'],
-  srcs = glob([
-    'wpilibc/src/main/native/cpp/*.cpp',
-    'wpilibc/src/main/native/cpp/interfaces/*.cpp',
-    'wpilibc/src/main/native/cpp/LiveWindow/*.cpp',
-    'wpilibc/src/main/native/cpp/Commands/*.cpp',
-    'wpilibc/src/main/native/cpp/SmartDashboard/*.cpp',
-
-    'hal/src/main/native/athena/*.cpp',
-    'hal/src/main/native/athena/cpp/*.cpp',
-    'hal/src/main/native/athena/ctre/*.cpp',
-    'hal/src/main/native/shared/handles/*.cpp',
-    'wpilibc/src/main/native/cpp/Internal/*.cpp',
-  ], exclude = (
-    ['**/%s/**' % d for d in _excluded_directories] +
-    ['**/%s.*' % d for d in _excluded_devices] + [
-    #'wpilibc/**/Accelerometer.*',
-  ])) + [
-    ':wpilib_version',
-  ],
-  copts = [
-    '-Wno-unused-parameter',
-    '-Wno-switch-enum',
-    '-Wno-attributes',
-    '-Wno-cast-align',
-    '-Wno-cast-qual',
-    '-Wno-deprecated-declarations',
-    '-Wno-error',
-    #'-Wno-unused-const-variable',
-  ],
-  deps = [
-    '//third_party/ntcore_2018:ntcore',
-    '@allwpilib_ni_libraries_repo_2018//:ni-libraries',
-    '//aos/logging',
-  ],
-  hdrs = _h_hdrs + _hpp_hdrs + [
-    'wpilibc/src/main/native/include/circular_buffer.inc',
-    'wpilibc/src/main/native/include/SpeedControllerGroup.inc',
-  ],
-  includes = _header_dirs,
-  linkopts = [
-    '-lpthread',
-  ],
-  defines = [
-    'WPILIB2018=1',
-  ],
-  restricted_to = ['//tools:roborio'],
+    name = "hal",
+    srcs = glob(
+        [
+            "hal/src/main/native/athena/*.cpp",
+            "hal/src/main/native/athena/cpp/*.cpp",
+            "hal/src/main/native/athena/ctre/*.cpp",
+            "hal/src/main/native/shared/handles/*.cpp",
+        ],
+        exclude = ["**/%s.*" % d for d in _excluded_devices],
+    ),
+    hdrs = _hal_h_hdrs + _hal_hpp_hdrs,
+    copts = [
+        "-Wno-unused-parameter",
+        "-Wno-switch-enum",
+        "-Wno-attributes",
+        "-Wno-cast-align",
+        "-Wno-cast-qual",
+        "-Wno-deprecated-declarations",
+        "-Wno-error",
+        "-Wno-unused-const-variable",
+    ],
+    defines = ["WPILIB2018=1"],
+    includes = _hal_header_dirs,
+    linkopts = ["-lpthread"],
+    restricted_to = ["//tools:roborio"],
+    visibility = [
+        "//third_party:__pkg__",
+        "//third_party/Phoenix-frc-lib:__pkg__",
+    ],
+    deps = [
+        "//aos/logging",
+        "//third_party/wpiutil_2018:wpiutil",
+        "@allwpilib_ni_libraries_repo_2018//:ni-libraries",
+    ],
 )
diff --git a/third_party/allwpilib_2018/hal/src/main/native/athena/HAL.cpp b/third_party/allwpilib_2018/hal/src/main/native/athena/HAL.cpp
index faa88b5..5a2fc1c 100644
--- a/third_party/allwpilib_2018/hal/src/main/native/athena/HAL.cpp
+++ b/third_party/allwpilib_2018/hal/src/main/native/athena/HAL.cpp
@@ -29,7 +29,6 @@
 #include "HAL/handles/HandlesInternal.h"
 #include "HALInitializer.h"
 #include "ctre/ctre.h"
-#include "visa/visa.h"
 
 using namespace hal;
 
@@ -44,7 +43,6 @@
   InitializeHandlesInternal();
   InitializeAccelerometer();
   InitializeAnalogAccumulator();
-  InitializeAnalogGyro();
   InitializeAnalogInput();
   InitializeAnalogInternal();
   InitializeAnalogOutput();
@@ -61,14 +59,12 @@
   InitializeI2C();
   InitialzeInterrupts();
   InitializeNotifier();
-  //InitializeOSSerialPort();
   InitializePCMInternal();
   InitializePDP();
   InitializePorts();
   InitializePower();
   InitializePWM();
   InitializeRelay();
-  InitializeSerialPort();
   InitializeSolenoid();
   InitializeSPI();
   InitializeThreads();
@@ -172,30 +168,6 @@
       return ERR_CANSessionMux_NotAllowed_MESSAGE;
     case HAL_ERR_CANSessionMux_NotInitialized:
       return ERR_CANSessionMux_NotInitialized_MESSAGE;
-    case VI_ERROR_SYSTEM_ERROR:
-      return VI_ERROR_SYSTEM_ERROR_MESSAGE;
-    case VI_ERROR_INV_OBJECT:
-      return VI_ERROR_INV_OBJECT_MESSAGE;
-    case VI_ERROR_RSRC_LOCKED:
-      return VI_ERROR_RSRC_LOCKED_MESSAGE;
-    case VI_ERROR_RSRC_NFOUND:
-      return VI_ERROR_RSRC_NFOUND_MESSAGE;
-    case VI_ERROR_INV_RSRC_NAME:
-      return VI_ERROR_INV_RSRC_NAME_MESSAGE;
-    case VI_ERROR_QUEUE_OVERFLOW:
-      return VI_ERROR_QUEUE_OVERFLOW_MESSAGE;
-    case VI_ERROR_IO:
-      return VI_ERROR_IO_MESSAGE;
-    case VI_ERROR_ASRL_PARITY:
-      return VI_ERROR_ASRL_PARITY_MESSAGE;
-    case VI_ERROR_ASRL_FRAMING:
-      return VI_ERROR_ASRL_FRAMING_MESSAGE;
-    case VI_ERROR_ASRL_OVERRUN:
-      return VI_ERROR_ASRL_OVERRUN_MESSAGE;
-    case VI_ERROR_RSRC_BUSY:
-      return VI_ERROR_RSRC_BUSY_MESSAGE;
-    case VI_ERROR_INV_PARAMETER:
-      return VI_ERROR_INV_PARAMETER_MESSAGE;
     case HAL_PWM_SCALE_ERROR:
       return HAL_PWM_SCALE_ERROR_MESSAGE;
     case HAL_SERIAL_PORT_NOT_FOUND:
diff --git a/third_party/allwpilib_2018/hal/src/main/native/include/HAL/HAL.h b/third_party/allwpilib_2018/hal/src/main/native/include/HAL/HAL.h
index ea396ca..c0d2572 100644
--- a/third_party/allwpilib_2018/hal/src/main/native/include/HAL/HAL.h
+++ b/third_party/allwpilib_2018/hal/src/main/native/include/HAL/HAL.h
@@ -13,7 +13,6 @@
 
 #include "HAL/Accelerometer.h"
 #include "HAL/AnalogAccumulator.h"
-#include "HAL/AnalogGyro.h"
 #include "HAL/AnalogInput.h"
 #include "HAL/AnalogOutput.h"
 #include "HAL/AnalogTrigger.h"
@@ -33,7 +32,6 @@
 #include "HAL/Power.h"
 #include "HAL/Relay.h"
 #include "HAL/SPI.h"
-#include "HAL/SerialPort.h"
 #include "HAL/Solenoid.h"
 
 #endif  // HAL_USE_LABVIEW
diff --git a/third_party/allwpilib_2019/.clang-format b/third_party/allwpilib_2019/.clang-format
new file mode 100644
index 0000000..92b4049
--- /dev/null
+++ b/third_party/allwpilib_2019/.clang-format
@@ -0,0 +1,107 @@
+---
+Language:        Cpp
+BasedOnStyle:  Google
+AccessModifierOffset: -1
+AlignAfterOpenBracket: Align
+AlignConsecutiveAssignments: false
+AlignConsecutiveDeclarations: false
+AlignEscapedNewlines: Left
+AlignOperands:   true
+AlignTrailingComments: true
+AllowAllParametersOfDeclarationOnNextLine: true
+AllowShortBlocksOnASingleLine: false
+AllowShortCaseLabelsOnASingleLine: false
+AllowShortFunctionsOnASingleLine: All
+AllowShortIfStatementsOnASingleLine: true
+AllowShortLoopsOnASingleLine: true
+AlwaysBreakAfterDefinitionReturnType: None
+AlwaysBreakAfterReturnType: None
+AlwaysBreakBeforeMultilineStrings: true
+AlwaysBreakTemplateDeclarations: true
+BinPackArguments: true
+BinPackParameters: true
+BraceWrapping:
+  AfterClass:      false
+  AfterControlStatement: false
+  AfterEnum:       false
+  AfterFunction:   false
+  AfterNamespace:  false
+  AfterObjCDeclaration: false
+  AfterStruct:     false
+  AfterUnion:      false
+  BeforeCatch:     false
+  BeforeElse:      false
+  IndentBraces:    false
+  SplitEmptyFunction: true
+  SplitEmptyRecord: true
+  SplitEmptyNamespace: true
+BreakBeforeBinaryOperators: None
+BreakBeforeBraces: Attach
+BreakBeforeInheritanceComma: false
+BreakBeforeTernaryOperators: true
+BreakConstructorInitializersBeforeComma: false
+BreakConstructorInitializers: BeforeColon
+BreakAfterJavaFieldAnnotations: false
+BreakStringLiterals: true
+ColumnLimit:     80
+CommentPragmas:  '^ IWYU pragma:'
+CompactNamespaces: false
+ConstructorInitializerAllOnOneLineOrOnePerLine: true
+ConstructorInitializerIndentWidth: 4
+ContinuationIndentWidth: 4
+Cpp11BracedListStyle: true
+DerivePointerAlignment: false
+DisableFormat:   false
+ExperimentalAutoDetectBinPacking: false
+FixNamespaceComments: true
+ForEachMacros:
+  - foreach
+  - Q_FOREACH
+  - BOOST_FOREACH
+IncludeCategories:
+  - Regex:           '^<.*\.h>'
+    Priority:        1
+  - Regex:           '^<.*'
+    Priority:        2
+  - Regex:           '.*'
+    Priority:        3
+IncludeIsMainRegex: '([-_](test|unittest))?$'
+IndentCaseLabels: true
+IndentWidth:     2
+IndentWrappedFunctionNames: false
+JavaScriptQuotes: Leave
+JavaScriptWrapImports: true
+KeepEmptyLinesAtTheStartOfBlocks: false
+MacroBlockBegin: ''
+MacroBlockEnd:   ''
+MaxEmptyLinesToKeep: 1
+NamespaceIndentation: None
+ObjCBlockIndentWidth: 2
+ObjCSpaceAfterProperty: false
+ObjCSpaceBeforeProtocolList: false
+PenaltyBreakAssignment: 2
+PenaltyBreakBeforeFirstCallParameter: 1
+PenaltyBreakComment: 300
+PenaltyBreakFirstLessLess: 120
+PenaltyBreakString: 1000
+PenaltyExcessCharacter: 1000000
+PenaltyReturnTypeOnItsOwnLine: 200
+PointerAlignment: Left
+ReflowComments:  true
+SortIncludes:    false
+SortUsingDeclarations: true
+SpaceAfterCStyleCast: false
+SpaceAfterTemplateKeyword: true
+SpaceBeforeAssignmentOperators: true
+SpaceBeforeParens: ControlStatements
+SpaceInEmptyParentheses: false
+SpacesBeforeTrailingComments: 2
+SpacesInAngles:  false
+SpacesInContainerLiterals: true
+SpacesInCStyleCastParentheses: false
+SpacesInParentheses: false
+SpacesInSquareBrackets: false
+Standard:        Auto
+TabWidth:        8
+UseTab:          Never
+...
diff --git a/third_party/allwpilib_2019/.gitignore b/third_party/allwpilib_2019/.gitignore
new file mode 100644
index 0000000..25cbab1
--- /dev/null
+++ b/third_party/allwpilib_2019/.gitignore
@@ -0,0 +1,216 @@
+# WPIlib Specific
+
+dependency-reduced-pom.xml
+doxygen.log
+buildcmake/
+
+# Created by the jenkins test script
+test-reports
+
+# IntelliJ
+*.iml
+*.ipr
+*.iws
+.idea/
+out/
+
+# Created by http://www.gitignore.io
+
+### Linux ###
+*~
+
+# KDE directory preferences
+.directory
+
+
+### Windows ###
+# Windows image file caches
+Thumbs.db
+ehthumbs.db
+
+# Folder config file
+Desktop.ini
+
+# Recycle Bin used on file shares
+$RECYCLE.BIN/
+
+# Windows Installer files
+*.cab
+*.msi
+*.msm
+*.msp
+
+
+### OSX ###
+.DS_Store
+.AppleDouble
+.LSOverride
+
+# Icon must end with two \r
+Icon
+
+
+# Thumbnails
+._*
+
+# Files that might appear on external disk
+.Spotlight-V100
+.Trashes
+
+# Directories potentially created on remote AFP share
+.AppleDB
+.AppleDesktop
+Network Trash Folder
+Temporary Items
+.apdisk
+
+
+### Java ###
+*.class
+
+# Mobile Tools for Java (J2ME)
+.mtj.tmp/
+
+# Package Files #
+*.jar
+*.war
+*.ear
+
+# virtual machine crash logs, see http://www.java.com/en/download/help/error_hotspot.xml
+hs_err_pid*
+
+
+### C++ ###
+# Compiled Object files
+*.slo
+*.lo
+*.o
+*.obj
+
+# Compiled Dynamic libraries
+*.dylib
+*.dll
+
+# Fortran module files
+*.mod
+
+# Compiled Static libraries
+*.lai
+*.la
+*.a
+*.lib
+
+# Executables
+*.exe
+*.out
+*.app
+
+
+### Maven ###
+target/
+pom.xml.tag
+pom.xml.releaseBackup
+pom.xml.versionsBackup
+pom.xml.next
+release.properties
+
+
+### CMake ###
+CMakeCache.txt
+CMakeFiles
+cmake_install.cmake
+install_manifest.txt
+
+
+### Gradle ###
+.gradle
+build/
+
+# Ignore Gradle GUI config
+gradle-app.setting
+
+
+### Vagrant ###
+.vagrant/
+
+
+### Eclipse ###
+*.pydevproject
+.metadata
+.gradle
+bin/
+tmp/
+*.tmp
+*.bak
+*.swp
+*~.nib
+local.properties
+.settings/
+.loadpath
+
+### Python ###
+*.pyc
+__pycache__
+
+# Gradle wrapper
+!gradle-wrapper.jar
+
+# External tool builders
+.externalToolBuilders/
+
+# Locally stored "Eclipse launch configurations"
+*.launch
+
+# CDT-specific
+.cproject
+
+# PDT-specific
+.buildpath
+
+# sbteclipse plugin
+.target
+
+# TeXlipse plugin
+.texlipse
+
+#catkin stuff
+package.xml
+
+# Doxygen stuff
+NO
+
+# Simulation folder stuff
+!simulation/install_resources/*
+
+# VSCode
+.vscode/
+
+#classpaths and projects
+.project
+.classpath
+
+#Visual Studio
+# User-specific files
+*.suo
+*.user
+*.userosscache
+*.sln.docstates
+
+# Visual C++ cache files
+ipch/
+*.aps
+*.ncb
+*.opendb
+*.opensdf
+*.cachefile
+*.VC.db
+*.VC.VC.opendb
+*.VC.db-shm
+*.VC.db-wal
+
+*.sln
+*.vcxproj
+*.vcxproj.filters
+
+# Visual Studio 2015 cache/options directory
+.vs/
diff --git a/third_party/allwpilib_2019/.styleguide b/third_party/allwpilib_2019/.styleguide
new file mode 100644
index 0000000..b93b522
--- /dev/null
+++ b/third_party/allwpilib_2019/.styleguide
@@ -0,0 +1,39 @@
+cppHeaderFileInclude {
+  \.h$
+  \.hpp$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+generatedFileExclude {
+  gtest/
+  ni-libraries/include/
+  ni-libraries/lib/
+  FRCNetComm\.java$
+  simulation/frc_gazebo_plugins/frcgazebo/
+  simulation/gz_msgs/src/include/simulation/gz_msgs/msgs\.h$
+}
+
+modifiableFileExclude {
+  \.so$
+}
+
+repoRootNameOverride {
+  wpilib
+}
+
+includeOtherLibs {
+  ^cameraserver/
+  ^cscore
+  ^hal/
+  ^mockdata/
+  ^networktables/
+  ^ntcore
+  ^opencv2/
+  ^support/
+  ^vision/
+  ^wpi/
+}
diff --git a/third_party/allwpilib_2019/.styleguide-license b/third_party/allwpilib_2019/.styleguide-license
new file mode 100644
index 0000000..b802370
--- /dev/null
+++ b/third_party/allwpilib_2019/.styleguide-license
@@ -0,0 +1,6 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) {year} FIRST. All Rights Reserved.{padding}*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
diff --git a/third_party/allwpilib_2019/CMakeLists.txt b/third_party/allwpilib_2019/CMakeLists.txt
new file mode 100644
index 0000000..e659add
--- /dev/null
+++ b/third_party/allwpilib_2019/CMakeLists.txt
@@ -0,0 +1,92 @@
+# Disable in-source builds to prevent source tree corruption.
+if(" ${CMAKE_SOURCE_DIR}" STREQUAL " ${CMAKE_BINARY_DIR}")
+  message(FATAL_ERROR "
+FATAL: In-source builds are not allowed.
+       You should create a separate directory for build files.
+")
+endif()
+
+
+project(allwpilib)
+cmake_minimum_required(VERSION 3.3.0)
+set(CMAKE_MODULE_PATH ${CMAKE_MODULE_PATH} "${CMAKE_SOURCE_DIR}/cmake/modules")
+
+INCLUDE(CPack)
+
+set(CMAKE_WINDOWS_EXPORT_ALL_SYMBOLS TRUE)
+set_property(GLOBAL PROPERTY USE_FOLDERS ON)
+
+if(CMAKE_INSTALL_PREFIX_INITIALIZED_TO_DEFAULT AND MSVC)
+    set(CMAKE_INSTALL_PREFIX "${CMAKE_BINARY_DIR}/install" CACHE PATH "Default install dir on windows" FORCE)
+endif()
+
+set(CMAKE_ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
+set(CMAKE_LIBRARY_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/lib)
+set(CMAKE_RUNTIME_OUTPUT_DIRECTORY ${CMAKE_BINARY_DIR}/bin)
+set(CMAKE_JAVA_TARGET_OUTPUT_DIR ${CMAKE_BINARY_DIR}/jar)
+
+# use, i.e. don't skip the full RPATH for the build tree
+SET(CMAKE_SKIP_BUILD_RPATH  FALSE)
+
+# when building, don't use the install RPATH already
+# (but later on when installing)
+SET(CMAKE_BUILD_WITH_INSTALL_RPATH FALSE)
+
+SET(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/wpilib/lib")
+
+# add the automatically determined parts of the RPATH
+# which point to directories outside the build tree to the install RPATH
+SET(CMAKE_INSTALL_RPATH_USE_LINK_PATH TRUE)
+
+# the RPATH to be used when installing, but only if it's not a system directory
+LIST(FIND CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES "${CMAKE_INSTALL_PREFIX}/wpilib/lib" isSystemDir)
+IF("${isSystemDir}" STREQUAL "-1")
+   SET(CMAKE_INSTALL_RPATH "${CMAKE_INSTALL_PREFIX}/wpilib/lib")
+ENDIF("${isSystemDir}" STREQUAL "-1")
+
+option(WITHOUT_JAVA "don't include java and JNI in the build" OFF)
+option(BUILD_SHARED_LIBS "build with shared libs (needed for JNI)" ON)
+option(WITHOUT_CSCORE "Don't build cscore (removes OpenCV requirement)" OFF)
+option(WITHOUT_ALLWPILIB "Don't build allwpilib (removes OpenCV requirement)" ON)
+option(USE_EXTERNAL_HAL "Use a separately built HAL" OFF)
+set(EXTERNAL_HAL_FILE "" CACHE FILEPATH "Location to look for an external HAL CMake File")
+
+if (NOT WITHOUT_JAVA AND NOT BUILD_SHARED_LIBS)
+    message(FATAL_ERROR "
+FATAL: Cannot build static libs with Java enabled.
+       Static libs requires both BUILD_SHARED_LIBS=OFF and
+       WITHOUT_JAVA=ON
+")
+endif()
+
+set( wpilib_dest wpilib)
+set( include_dest wpilib/include )
+set( main_lib_dest wpilib/lib )
+set( java_lib_dest wpilib/java )
+set( jni_lib_dest wpilib/jni )
+
+if (MSVC)
+    set (wpilib_config_dir ${wpilib_dest})
+else()
+    set (wpilib_config_dir share/wpilib)
+endif()
+
+add_subdirectory(wpiutil)
+add_subdirectory(ntcore)
+
+if (NOT WITHOUT_CSCORE)
+    add_subdirectory(cscore)
+    add_subdirectory(cameraserver)
+    set (CSCORE_DEP_REPLACE "find_dependency(cscore)")
+    set (CAMERASERVER_DEP_REPLACE "find_dependency(cameraserver)")
+    if (NOT WITHOUT_ALLWPILIB)
+        add_subdirectory(hal)
+        add_subdirectory(wpilibj)
+        add_subdirectory(wpilibc)
+        set (HAL_DEP_REPLACE "find_dependency(hal)")
+        set (WPILIBC_DEP_REPLACE "find_dependency(wpilibc)")
+    endif()
+endif()
+
+configure_file(wpilib-config.cmake.in ${CMAKE_BINARY_DIR}/wpilib-config.cmake )
+install(FILES ${CMAKE_BINARY_DIR}/wpilib-config.cmake DESTINATION ${wpilib_config_dir})
diff --git a/third_party/allwpilib_2019/CONTRIBUTING.md b/third_party/allwpilib_2019/CONTRIBUTING.md
new file mode 100644
index 0000000..b25e4d4
--- /dev/null
+++ b/third_party/allwpilib_2019/CONTRIBUTING.md
@@ -0,0 +1,56 @@
+# Contributing to WPILib
+
+So you want to contribute your changes back to WPILib. Great! We have a few contributing rules that will help you make sure your changes will be accepted into the project. Please remember to follow the rules written here, and behave with Gracious Professionalism.
+
+- [General Contribution Rules](#general-contribution-rules)
+- [What to Contribute](#what-to-contribute)
+- [Coding Guidelines](#coding-guidelines)
+- [Submitting Changes](#submitting-changes)
+    - [Pull Request Format](#pull-request-format)
+    - [Merge Process](#merge-process)
+- [Licensing](#licensing)
+
+## General Contribution Rules
+
+- Everything in the library must work for the 3000+ teams that will be using it.
+- We need to be able to maintain submitted changes, even if you are no longer working on the project.
+- Tool suite changes must be generally useful to a broad range of teams
+- Excluding bug fixes, changes in one language generally need to have corresponding changes in other languages.
+    - Some features, such the addition of C++11 for WPILibC or Functional Interfaces for WPILibJ, are specific to that version of WPILib only.
+    - Substantial changes often need to have corresponding LabVIEW changes. To do this, we will work with NI on these large changes.
+- Changes should have tests.
+- Code should be well documented.
+    - This often involves ScreenSteps. To add content to ScreenSteps, we will work with you to get the appropriate articles written.
+
+## What to Contribute
+
+- Bug reports and fixes
+    - We will generally accept bug fixes without too much question. If they are only implemented for one language, we will implement them for any other necessary languages. Bug reports are also welcome, please submit them to our GitHub issue tracker.
+- While we do welcome improvements to the API, there are a few important rules to consider:
+    - Features must be added to both WPILibC and WPILibJ, with rare exceptions.
+    - During competition season, we will not merge any new feature additions. We want to ensure that the API is stable during the season to help minimize issues for teams.
+    - Ask about large changes before spending a bunch of time on them! You can create a new issue on our GitHub tracker for feature request/discussion and talk about it with us there.
+    - Features that make it easier for teams with less experience to be more successful are more likely to be accepted.
+    - Features in WPILib should be broadly applicable to all teams. Anything that is team specific should not be submitted.
+    - As a rule, we are happy with the general structure of WPILib. We are not interested in major rewrites of all of WPILib. We are open to talking about ideas, but backwards compatibility is very important for WPILib, so be sure to keep this in mind when proposing major changes.
+    - Generally speaking, we do not accept code for specific sensors. We have to be able to test the sensor in hardware on the WPILib test bed. Additionally, hardware availability for teams is important. Therefore, as a general rule, the library only directly supports hardware that is in the Kit of Parts. If you are a company interested in getting a sensor into the Kit of Parts, please contact FIRST directly at frcparts@firstinspires.org.
+
+## Coding Guidelines
+
+WPILib uses modified Google style guides for both C++ and Java, which can be found in the [styleguide repository](https://github.com/wpilibsuite/styleguide). Autoformatters are available for many popular editors at https://github.com/google/styleguide. Running wpiformat is required for all contributions and is enforced by our continuous integration system. We currently use clang-format 5.0 with wpiformat.
+
+While the library should be fully formatted according to the styles, additional elements of the style guide were not followed when the library was initially created. All new code should follow the guidelines. If you are looking for some easy ramp-up tasks, finding areas that don't follow the style guide and fixing them is very welcome.
+
+## Submitting Changes
+
+### Pull Request Format
+
+Changes should be submitted as a Pull Request against the master branch of WPILib. For most changes, we ask that you squash your changes down to a single commit. For particularly large changes, multiple commits are ok, but assume one commit unless asked otherwise. No change will be merged unless it is up to date with the current master. We will also not merge any changes with merge commits in them; please rebase off of master before submitting a pull request. We do this to make sure that the git history isn't too cluttered.
+
+### Merge Process
+
+When you first submit changes, Travis-CI will attempt to run `./gradlew check` on your change. If this fails, you will need to fix any issues that it sees. Once Travis passes, we will begin the review process in more earnest. One or more WPILib team members will review your change. This will be a back-and-forth process with the WPILib team and the greater community. Once we are satisfied that your change is ready, we will allow our Jenkins instance to test it. This will run the full gamut of checks, including integration tests on actual hardware. Once all tests have passed and the team is satisfied, we will merge your change into the WPILib repository.
+
+## Licensing
+
+By contributing to WPILib, you agree that your code will be distributed with WPILib, and licensed under the license for the WPILib project. You should not contribute code that you do not have permission to relicense in this manner. This includes code that is licensed under the GPL that you do not have permission to relicense, as WPILib is not released under a copyleft license. Our license is the 3-clause BSD license, which you can find [here](license.txt).
diff --git a/third_party/allwpilib_2019/LICENSE.txt b/third_party/allwpilib_2019/LICENSE.txt
new file mode 100644
index 0000000..1b05ea8
--- /dev/null
+++ b/third_party/allwpilib_2019/LICENSE.txt
@@ -0,0 +1,24 @@
+Copyright (c) 2009-2018 FIRST
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+    * Redistributions of source code must retain the above copyright
+      notice, this list of conditions and the following disclaimer.
+    * Redistributions in binary form must reproduce the above copyright
+      notice, this list of conditions and the following disclaimer in the
+      documentation and/or other materials provided with the distribution.
+    * Neither the name of the FIRST nor the
+      names of its contributors may be used to endorse or promote products
+      derived from this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY FIRST AND CONTRIBUTORS``AS IS'' AND ANY
+EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY NONINFRINGEMENT AND FITNESS FOR A PARTICULAR
+PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL FIRST OR CONTRIBUTORS BE LIABLE FOR
+ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
+ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
diff --git a/third_party/allwpilib_2019/MavenArtifacts.md b/third_party/allwpilib_2019/MavenArtifacts.md
new file mode 100644
index 0000000..825a23a
--- /dev/null
+++ b/third_party/allwpilib_2019/MavenArtifacts.md
@@ -0,0 +1,102 @@
+# WPILib Maven Artifacts
+
+WPILib publishes its built artifacts to our Maven server for use by downstream projects. This document explains these locations, and the meanings of artifact names, classifiers, and versions.
+
+## Repositories
+We provide two repositories. These repositories are:
+
+* (Release)     http://first.wpi.edu/FRC/roborio/maven/release/
+* (Development) http://first.wpi.edu/FRC/roborio/maven/development/
+
+The release repository is where official WPILib releases are pushed.
+The development repository is where development releases of every commit to [master](https://github.com/wpilibsuite/allwpilib/tree/master) is pushed.
+
+## Artifact classifiers
+We provide two base types of artifacts.
+
+The first types are Java artifacts. These are usually published as `jar` files. Usually, the actual jar file is published with no classifier. The sources are published with the `-sources` classifier, and the javadocs are published with the `-javadoc` classifier.
+
+The second types are native artifacts. These are usually published as `zip` files (except for the `JNI` artifact types, which are `jar` files. See below for information on this). The `-sources` and `-headers` classifiers contain the sources and headers respecively for the library. Each artifact also contains a classifier for each platform we publish. This platform is in the format `{os}{arch}`. The platform artifact only contains the binaries for a specific platform. In addition, we provide a `-all` classifier. This classifer combines all of the platform artifacts into a single artifact. This is useful for tools that cannot determine what version to use during builds. However, we recommend using the platform specific classifier when possible. Note that the binary artifacts never contain the headers, you always need the `-headers` classifier to get those.
+
+## Artifact Names
+
+WPILib builds four different types of artifacts.
+
+##### C++ Only Libraries
+When we publish C++ only libraries, they are published with the base artifact name as their artifact name, with a `-cpp` extension. All dependencies for the library are linked as shared libraries to the binary.
+
+
+Example:
+```
+edu.wpi.first.wpilibc:wpilibc-cpp:version:classifier@zip
+```
+
+#### Java Only Libraries
+When we publish Java only libraries, they are published with the base artifact name as their artifact name, with a `-java` extension.
+
+Example:
+```
+edu.wpi.first.wpilibj:wpilibj-java:version
+```
+
+#### C++/Java Libraries without JNI
+For libraries that are both C++ and Java, but without a JNI component, the C++ component is published with the `basename-cpp` artifact name, and the Java component is published with the `basename-java` artifact name.
+
+Example:
+```
+edu.wpi.first.wpiutil:wpiutil-cpp:version:classifier@zip (C++)
+edu.wpi.first.wpiutil:wpiutil-java:version (Java)
+```
+
+#### C++/Java Libraries with JNI
+For libraries that are both C++ and Java with a JNI component there are three different artifact names. For Java, the component is published as `basename-java`. For C++, the `basename-cpp` artifact contains the C++ artifacts with all dependencies linked as shared libraries to the binary. These binaries DO contain the JNI entry points. The `basename-jni` artifact contains identical C++ binaries to the `-cpp` artifact, however all of its dependencies are statically linked, and only the JNI and C entry points are exported.
+
+The `-jni` artifact should only be used in cases where you want to create a self contained Java application where the native artifacts are embedded in the jar. Note in an extraction scenario, extending off of the library is never supported, which is why the C++ entry points are not exposed. The name of the library is randomly generated during extraction. For pretty much all cases, and if you ever want to extend from a native library, you should use the `-cpp` artifacts. GradleRIO uses the `-cpp` artifacts for all platforms, even desktop, for this reason.
+
+Example:
+```
+edu.wpi.first.ntcore:ntcore-cpp:version:classifier@zip (C++)
+edu.wpi.first.ntcore:ntcore-jni:version:classifier (JNI jar library)
+edu.wpi.first.ntcore:ntcore-java:version (Java)
+```
+
+## Provided Artifacts
+This repository provides the following artifacts. Below each artifact is its dependencies. Note if ever using the `-jni` artifacts, no dependencies are needed for native binaries.
+
+For C++, if building with static dependencies, the listed order should be the link order in your linker.
+
+All artifacts are based at `edu.wpi.first.artifactname` in the repository.
+
+* wpiutil
+
+* hal
+  * wpiutil
+
+* ntcore
+  * wpiutil
+
+* cscore
+  * opencv
+  * wpiutil
+
+* cameraserver
+  * ntcore
+  * cscore
+  * opencv
+  * wpiutil
+
+
+* wpilibj
+  * hal
+  * cameraserver
+  * ntcore
+  * cscore
+  * wpiutil
+
+
+* wpilibc
+  * hal
+  * cameraserver
+  * ntcore
+  * cscore
+  * wpiutil
diff --git a/third_party/allwpilib_2019/README-CMAKE.md b/third_party/allwpilib_2019/README-CMAKE.md
new file mode 100644
index 0000000..68e8175
--- /dev/null
+++ b/third_party/allwpilib_2019/README-CMAKE.md
@@ -0,0 +1,138 @@
+# WPILib CMake Support
+
+WPILib is normally built with Gradle, however for some systems, such a linux based coprocessors, Gradle doesn't work correctly, especially if cscore is needed, which requires OpenCV. We provide the CMake build for these cases. Although it is supported on Windows, these docs will only go over linux builds.
+
+## Libraries that get built
+* wpiutil
+* ntcore
+* cscore
+* cameraserver
+* hal
+* wpilib
+
+By default, all libraries except for the HAL and WPILib get built with a default cmake setup. The libraries are built as shared libraries, and include the JNI libraries as well as building the Java jars.
+
+## Prerequisites
+
+The most common prerequisite is going to be OpenCV. OpenCV needs to be findable by cmake. On systems like the Jetson, this is installed by default. Otherwise, you will need to build cmake from source and install it.
+
+In addition, if you want JNI and Java, you will need a JDK of at least version 8 installed. In addition, you need a `JAVA_HOME` environment variable set properly and set to the jdk directory.
+
+## Build Options
+
+The following build options are available:
+
+* WITHOUT_JAVA (OFF Default)
+  * Enabling this option will disable Java and JNI builds. If this is off, `BUILD_SHARED_LIBS` must be on. Otherwise cmake will error.
+* BUILD_SHARED_LIBS (ON Default)
+  * Disabling this option will cause cmake to build static libraries instead of shared libraries. If this is off, `WITHOUT_JAVA` must be on. Otherwise cmake will error.
+* WITHOUT_CSCORE (OFF Default)
+  * Enabling this option will cause cscore to not be built. This will also implicitly disable cameraserver, the hal and wpilib as well, irrespective of their specific options. If this is on, the opencv build requirement is removed.
+* WITHOUT_ALLWPILIB (ON Default)
+  * Disabling this option will build the hal and wpilib during the build. The HAL is the simulator hal, unless the external hal options are used. The cmake build has no capability to build for the RoboRIO.
+* USE_EXTERNAL_HAL (OFF Default)
+  * TODO
+* EXTERNAL_HAL_FILE
+  * TODO
+
+## Build Setup
+
+The WPILib CMake build does not allow in source builds. Because the `build` directory is used by gradle, we recommend a `buildcmake` directory in the root. This folder is included in the gitignore.
+
+Once you have a build folder, run cmake configuration in that build directory with the following command.
+
+```
+cmake path/to/allwpilib/root
+```
+
+If you want to change any of the options, add `-DOPTIONHERE=VALUE` to the cmake command. This will check for any dependencies. If everything works properly this will succeed. If not, please check out the troubleshooting section for help.
+
+If you want, you can also use `ccmake` in order to visually set these properties as well.
+https://cmake.org/cmake/help/v3.0/manual/ccmake.1.html
+Here is the link to the documentation for that program.
+
+## Building
+
+Once you have cmake setup. run `make` from the directory you configured cmake in. This will build all libraries possible. If you have a multicore system, we recommend running make with multiple jobs. The usual rule of thumb is 1.5x the number of cores you have. To run a multiple job build, run the following command with x being the number of jobs you want.
+
+```
+make -jx
+```
+
+## Installing
+
+After build, the easiest way to use the libraries is to install them. Run the following command to install the libraries. This will install them so that they can be used from external cmake projects.
+
+```
+sudo make install
+```
+
+## Using the installed libraries for C++.
+
+Using the libraries from C++ is the easiest way to use the built libraries.
+
+To do so, create a new folder to contain your project. Add the following code below to a `CMakeLists.txt` file in that directory.
+
+```
+cmake_minimum_required(VERSION 3.5)
+project(vision_app) # Project Name Here
+
+find_package(wpilib REQUIRED)
+
+add_executable(my_vision_app main.cpp) # exectuable name as first parameter
+target_link_libraries(my_vision_app cameraserver ntcore cscore wpiutil)
+```
+
+If you are using them, `wpilibc` and `hal` should be added before the `cameraserver` declaration in the `target_link_libraries` function.
+
+Add a `main.cpp` file to contain your code, and create a build folder. Move into the build folder, and run
+
+```
+cmake /path/to/folder/containing/CMakeLists
+```
+
+After that, run `make`. That will create your executable. Then you should be able to run `./my_vision_app` to run your application.
+
+
+## Using the installed libraries for Java
+TODO
+
+## Troubleshooting
+Below are some common issues that are run into when building.
+
+#### Missing OpenCV
+
+If you are missing OpenCV, you will get an error message similar to this.
+
+```
+CMake Error at cscore/CMakeLists.txt:3 (find_package):
+  By not providing "FindOpenCV.cmake" in CMAKE_MODULE_PATH this project has
+  asked CMake to find a package configuration file provided by "OpenCV", but
+  CMake did not find one.
+
+  Could not find a package configuration file provided by "OpenCV" with any
+  of the following names:
+
+    OpenCVConfig.cmake
+    opencv-config.cmake
+
+  Add the installation prefix of "OpenCV" to CMAKE_PREFIX_PATH or set
+  "OpenCV_DIR" to a directory containing one of the above files.  If "OpenCV"
+  provides a separate development package or SDK, be sure it has been
+  installed.
+```
+
+If you get that, you need make sure opencv was installed, and then reattempt to configure. If that doesn't work, set the `OpenCV_DIR` variable to the directory where you built OpenCV.
+
+#### Missing Java
+
+If you are missing Java, you will get a message like the following.
+```
+CMake Error at /usr/share/cmake-3.5/Modules/FindPackageHandleStandardArgs.cmake:148 (message):
+  Could NOT find Java (missing: Java_JAVA_EXECUTABLE Java_JAR_EXECUTABLE
+  Java_JAVAC_EXECUTABLE Java_JAVAH_EXECUTABLE Java_JAVADOC_EXECUTABLE)
+```
+
+If this happens, make sure you have a JDK of at least version 8 installed, and that your JAVA_HOME variable is set properly to point to the JDK.
+
+In addition, if you do not need Java, you can disable it with `-DWITHOUT_JAVA=ON`.
diff --git a/third_party/allwpilib_2019/README.md b/third_party/allwpilib_2019/README.md
new file mode 100644
index 0000000..8bb93b3
--- /dev/null
+++ b/third_party/allwpilib_2019/README.md
@@ -0,0 +1,114 @@
+# WPILib Project
+
+[![Build Status](https://dev.azure.com/wpilib/wpilib/_apis/build/status/wpilibsuite.allwpilib)](https://dev.azure.com/wpilib/wpilib/_build/latest?definitionId=1)
+
+Welcome to the WPILib project. This repository contains the HAL, WPILibJ, and WPILibC projects. These are the core libraries for creating robot programs for the roboRIO.
+
+- [WPILib Mission](#wpilib-mission)
+- [Building WPILib](#building-wpilib)
+    - [Requirements](#requirements)
+    - [Setup](#setup)
+    - [Building](#building)
+    - [Publishing](#publishing)
+    - [Structure and Organization](#structure-and-organization)
+- [Contributing to WPILib](#contributing-to-wpilib)
+
+## WPILib Mission
+
+The WPILib Mission is to enable FIRST Robotics teams to focus on writing game-specific software rather than focusing on hardware details - "raise the floor, don't lower the ceiling". We work to enable teams with limited programming knowledge and/or mentor experience to be as successful as possible, while not hampering the abilities of teams with more advanced programming capabilities. We support Kit of Parts control system components directly in the library. We also strive to keep parity between major features of each language (Java, C++, and NI's LabVIEW), so that teams aren't at a disadvantage for choosing a specific programming language. WPILib is an open source project, licensed under the BSD 3-clause license. You can find a copy of the license [here](LICENSE.txt).
+
+# Building WPILib
+
+Using Gradle makes building WPILib very straightforward. It only has a few dependencies on outside tools, such as the ARM cross compiler for creating roboRIO binaries.
+
+## Requirements
+
+- A C++ compiler
+    - On Linux, GCC works fine
+    - On Windows, you need Visual Studio 2015 (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
+- Doxygen (Only required if you want to build the C++ documentation)
+
+## Setup
+
+Clone the WPILib repository. If the toolchains are not installed, install them, and make sure they are available on the system PATH.
+
+See the [styleguide README](https://github.com/wpilibsuite/styleguide/blob/master/README.md) for wpiformat setup instructions.
+
+## Building
+
+All build steps are executed using the Gradle wrapper, `gradlew`. Each target that Gradle can build is referred to as a task. The most common Gradle task to use is `build`. This will build all the outputs created by WPILib. To run, open a console and cd into the cloned WPILib directory. Then:
+
+```bash
+./gradlew build
+```
+
+To build a specific subproject, such as WPILibC, you must access the subproject and run the build task only on that project. Accessing a subproject in Gradle is quite easy. Simply use `:subproject_name:task_name` with the Gradle wrapper. For example, building just WPILibC:
+
+```bash
+./gradlew :wpilibc:build
+```
+
+If you have installed the FRC Toolchain to a directory other than the default, or if the Toolchain location is not on your System PATH, you can pass the `toolChainPath` property to specify where it is located. Example:
+
+```bash
+./gradlew build -PtoolChainPath=some/path/to/frc/toolchain/bin
+```
+
+If you also want simulation to be built, add -PmakeSim. This requires gazebo_transport. We have tested on 14.04 and 15.05, but any correct install of Gazebo should work, even on Windows if you build Gazebo from source. Correct means CMake needs to be able to find gazebo-config.cmake. See [The Gazebo website](https://gazebosim.org/) for installation instructions.
+
+```bash
+./gradlew build -PmakeSim
+```
+
+If you prefer to use CMake directly, the you can still do so.
+The common CMake tasks are wpilibcSim, frc_gazebo_plugins, and gz_msgs
+
+```bash
+mkdir build #run this in the root of allwpilib
+cd build
+cmake ..
+make
+```
+
+The gradlew wrapper only exists in the root of the main project, so be sure to run all commands from there. All of the subprojects have build tasks that can be run. Gradle automatically determines and rebuilds dependencies, so if you make a change in the HAL and then run `./gradlew :wpilibc:build`, the HAL will be rebuilt, then WPILibC.
+
+There are a few tasks other than `build` available. To see them, run the meta-task `tasks`. This will print a list of all available tasks, with a description of each task.
+
+wpiformat can be executed anywhere in the repository via `py -3 -m wpiformat` on Windows or `python3 -m wpiformat` on other platforms.
+
+## 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:
+
+- 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.
+
+## Structure and Organization
+
+The main WPILib code you're probably looking for is in WPILibJ and WPILibC. Those directories are split into shared, sim, and athena. Athena contains the WPILib code meant to run on your roboRIO. Sim is WPILib code meant to run on your computer with Gazebo, and shared is code shared between the two. Shared code must be platform-independent, since it will be compiled with both the ARM cross-compiler and whatever desktop compiler you are using (g++, msvc, etc...).
+
+The Simulation directory contains extra simulation tools and libraries, such as gz_msgs and JavaGazebo. See sub-directories for more information.
+
+The integration test directories for C++ and Java contain test code that runs on our test-system. When you submit code for review, it is tested by those programs. If you add new functionality you should make sure to write tests for it so we don't break it in the future.
+
+The hal directory contains more C++ code meant to run on the roboRIO. HAL is an acronym for "Hardware Abstraction Layer", and it interfaces with the NI Libraries. The NI Libraries contain the low-level code for controlling devices on your robot. The NI Libraries are found in the ni-libraries folder.
+
+The [styleguide repository](https://github.com/wpilibsuite/styleguide) contains our style guides for C++ and Java code. Anything submitted to the WPILib project needs to follow the code style guides outlined in there. For details about the style, please see the contributors document [here](CONTRIBUTING.md#coding-guidelines).
+
+# Contributing to WPILib
+
+See [CONTRIBUTING.md](CONTRIBUTING.md).
diff --git a/third_party/allwpilib_2019/ThirdPartyNotices.txt b/third_party/allwpilib_2019/ThirdPartyNotices.txt
new file mode 100644
index 0000000..1ec0097
--- /dev/null
+++ b/third_party/allwpilib_2019/ThirdPartyNotices.txt
@@ -0,0 +1,373 @@
+==============================================================================
+Copyrights and Licenses for Third Party Software Distributed with WPILib
+==============================================================================
+The WPILib software contains code written by third parties.  The copyrights,
+license, and restrictions which apply to each piece of software is included
+later in this file and/or inside of the individual applicable source files.
+
+The disclaimer of warranty in the WPILib license above applies to all code in
+WPILib, and nothing in any of the other licenses gives permission to use the
+names of FIRST nor the names of the WPILib contributors to endorse or promote
+products derived from this software.
+
+The following pieces of software have additional or alternate copyrights,
+licenses, and/or restrictions:
+
+Program               Locations
+-------               ---------
+RoboRIO Libraries     ni-libraries
+Google Test           gtest
+LLVM                  wpiutil/src/main/native/include/wpi/{various files}
+                      wpiutil/src/main/native/cpp/llvm/
+                      wpiutil/src/main/native/cpp/leb128.cpp
+                      wpiutil/src/test/native/cpp/leb128Test.cpp
+JSON for Modern C++   wpiutil/src/main/native/include/wpi/json.h
+                      wpiutil/src/main/native/cpp/json_*.cpp
+                      wpiutil/src/test/native/cpp/json/
+libuv                 wpiutil/src/main/native/include/uv.h
+                      wpiutil/src/main/native/include/uv/
+                      wpiutil/src/main/native/libuv/
+sigslot               wpiutil/src/main/native/include/wpi/Signal.h
+                      wpiutil/src/test/native/cpp/sigslot/
+tcpsockets            wpiutil/src/main/native/cpp/TCP{Stream,Connector,Acceptor}.cpp
+                      wpiutil/src/main/native/include/wpi/TCP*.h
+Optional              wpiutil/src/main/native/include/wpi/optional.h
+                      wpiutil/src/test/native/cpp/test_optional.cpp
+Bootstrap             wpiutil/src/main/native/resources/bootstrap-*
+CoreUI                wpiutil/src/main/native/resources/coreui-*
+Feather Icons         wpiutil/src/main/native/resources/feather-*
+jQuery                wpiutil/src/main/native/resources/jquery-*
+popper.js             wpiutil/src/main/native/resources/popper-*
+
+
+==============================================================================
+Google Test License
+==============================================================================
+Copyright 2008, Google Inc.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are
+met:
+
+    * Redistributions of source code must retain the above copyright
+notice, this list of conditions and the following disclaimer.
+    * Redistributions in binary form must reproduce the above
+copyright notice, this list of conditions and the following disclaimer
+in the documentation and/or other materials provided with the
+distribution.
+    * Neither the name of Google Inc. nor the names of its
+contributors may be used to endorse or promote products derived from
+this software without specific prior written permission.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+
+
+==============================================================================
+LLVM Release License
+==============================================================================
+University of Illinois/NCSA
+Open Source License
+
+Copyright (c) 2003-2017 University of Illinois at Urbana-Champaign.
+All rights reserved.
+
+Developed by:
+
+    LLVM Team
+
+    University of Illinois at Urbana-Champaign
+
+    http://llvm.org
+
+Permission is hereby granted, free of charge, to any person obtaining a copy of
+this software and associated documentation files (the "Software"), to deal with
+the Software without restriction, including without limitation the rights to
+use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies
+of the Software, and to permit persons to whom the Software is furnished to do
+so, subject to the following conditions:
+
+    * Redistributions of source code must retain the above copyright notice,
+      this list of conditions and the following disclaimers.
+
+    * Redistributions in binary form must reproduce the above copyright notice,
+      this list of conditions and the following disclaimers in the
+      documentation and/or other materials provided with the distribution.
+
+    * Neither the names of the LLVM Team, University of Illinois at
+      Urbana-Champaign, nor the names of its contributors may be used to
+      endorse or promote products derived from this Software without specific
+      prior written permission.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS
+FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.  IN NO EVENT SHALL THE
+CONTRIBUTORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS WITH THE
+SOFTWARE.
+
+
+==============================================================================
+JSON for Modern C++ License
+==============================================================================
+
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+
+
+==============================================================================
+libuv License
+==============================================================================
+Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to
+deal in the Software without restriction, including without limitation the
+rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+sell copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+IN THE SOFTWARE.
+
+
+==============================================================================
+sigslot License
+==============================================================================
+Sigslot, a signal-slot library
+
+https://github.com/palacaze/sigslot
+
+MIT License
+
+Copyright (c) 2017 Pierre-Antoine Lacaze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+
+
+==============================================================================
+tcpsockets License
+==============================================================================
+Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+Licensed under the Apache License, Version 2.0 (the "License");
+you may not use this file except in compliance with the License.
+You may obtain a copy of the License at
+
+    http://www.apache.org/licenses/LICENSE-2.0
+
+Unless required by applicable law or agreed to in writing, software
+distributed under the License is distributed on an "AS IS" BASIS,
+WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+See the License for the specific language governing permissions and
+limitations under the License.
+
+
+==============================================================================
+Optional License
+==============================================================================
+Copyright (C) 2011 - 2017 Andrzej Krzemienski.
+
+Boost Software License - Version 1.0 - August 17th, 2003
+
+Permission is hereby granted, free of charge, to any person or organization
+obtaining a copy of the software and accompanying documentation covered by
+this license (the "Software") to use, reproduce, display, distribute,
+execute, and transmit the Software, and to prepare derivative works of the
+Software, and to permit third-parties to whom the Software is furnished to
+do so, all subject to the following:
+
+The copyright notices in the Software and this entire statement, including
+the above license grant, this restriction and the following disclaimer,
+must be included in all copies of the Software, in whole or in part, and
+all derivative works of the Software, unless such copies or derivative
+works are solely in the form of machine-executable object code generated by
+a source language processor.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT
+SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE
+FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE,
+ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER
+DEALINGS IN THE SOFTWARE.
+
+
+==============================================================================
+Bootstrap License
+==============================================================================
+Copyright (c) 2011-2018 Twitter, Inc.
+Copyright (c) 2011-2018 The Bootstrap Authors
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+
+
+==============================================================================
+CoreUI License
+==============================================================================
+Copyright (c) 2018 creativeLabs tukasz Holeczek.
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in
+all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+THE SOFTWARE.
+
+
+==============================================================================
+Feather Icons License
+==============================================================================
+Copyright (c) 2013-2017 Cole Bemis
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+
+
+==============================================================================
+jQuery License
+==============================================================================
+Copyright JS Foundation and other contributors, https://js.foundation/
+
+Permission is hereby granted, free of charge, to any person obtaining
+a copy of this software and associated documentation files (the
+"Software"), to deal in the Software without restriction, including
+without limitation the rights to use, copy, modify, merge, publish,
+distribute, sublicense, and/or sell copies of the Software, and to
+permit persons to whom the Software is furnished to do so, subject to
+the following conditions:
+
+The above copyright notice and this permission notice shall be
+included in all copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND,
+EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF
+MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND
+NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE
+LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION
+OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION
+WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
+
+
+==============================================================================
+popper.js License
+==============================================================================
+Copyright (c) 2016 Federico Zivolo and contributors
+
+Permission is hereby granted, free of charge, to any person obtaining a copy of
+this software and associated documentation files (the "Software"), to deal in
+the Software without restriction, including without limitation the rights to
+use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies
+of the Software, and to permit persons to whom the Software is furnished to do
+so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
diff --git a/third_party/allwpilib_2019/azure-pipelines.yml b/third_party/allwpilib_2019/azure-pipelines.yml
new file mode 100644
index 0000000..73e85a7
--- /dev/null
+++ b/third_party/allwpilib_2019/azure-pipelines.yml
@@ -0,0 +1,183 @@
+# Gradle
+# Build your Java projects and run tests with Gradle using a Gradle wrapper script.
+# Add steps that analyze code, save build artifacts, deploy, and more:
+# https://docs.microsoft.com/vsts/pipelines/languages/java
+
+resources:
+  containers:
+  - container: wpilib2019
+    image: wpilib/roborio-cross-ubuntu:2019-18.04
+  - container: raspbian
+    image:  wpilib/raspbian-cross-ubuntu:18.04
+
+jobs:
+ - job: Linux_Arm
+   pool:
+     vmImage: 'Ubuntu 16.04'
+
+   container: wpilib2019
+
+   steps:
+    - task: Gradle@2
+      inputs:
+        workingDirectory: ''
+        gradleWrapperFile: 'gradlew'
+        gradleOptions: '-Xmx3072m'
+        publishJUnitResults: false
+        testResultsFiles: '**/TEST-*.xml'
+        tasks: 'build'
+        options: '-PonlyAthena'
+        # checkStyleRunAnalysis: true
+        # pmdRunAnalysis: true
+
+ - job: Linux_Raspbian
+   pool:
+     vmImage: 'Ubuntu 16.04'
+
+   container: raspbian
+
+   steps:
+    - task: Gradle@2
+      inputs:
+        workingDirectory: ''
+        gradleWrapperFile: 'gradlew'
+        gradleOptions: '-Xmx3072m'
+        publishJUnitResults: true
+        testResultsFiles: '**/TEST-*.xml'
+        tasks: 'build'
+        options: '-PonlyRaspbian'
+        # checkStyleRunAnalysis: true
+        # pmdRunAnalysis: true
+
+ - job: Linux
+   pool:
+     vmImage: 'Ubuntu 16.04'
+
+   container: wpilib2019
+
+   steps:
+    - task: Gradle@2
+      inputs:
+        workingDirectory: ''
+        gradleWrapperFile: 'gradlew'
+        gradleOptions: '-Xmx3072m'
+        publishJUnitResults: true
+        testResultsFiles: '**/TEST-*.xml'
+        tasks: 'build'
+        options: '-PskipAthena'
+        # checkStyleRunAnalysis: true
+        # pmdRunAnalysis: true
+
+ - job: Styleguide
+   pool:
+     vmImage: 'Ubuntu 16.04'
+
+   steps:
+      - script: |
+          sudo apt-get update -y
+          sudo apt-get install clang-format-5.0 python3-setuptools -y
+          sudo pip3 install --upgrade pip
+          sudo pip3 install wpiformat
+          git checkout -b master
+        displayName: 'Install Dependencies'
+      - script: |
+          wpiformat -y 2018 -clang 5.0
+        displayName: 'Run WPIFormat'
+        failOnStderr: true
+      - script: |
+          git --no-pager diff --exit-code HEAD  # Ensure formatter made no changes
+        displayName: 'Check WPIFormat Output'
+        failOnStderr: true
+
+ - job: CMakeBuild
+   pool:
+     vmImage: 'Ubuntu 16.04'
+
+   container: wpilib2019
+
+   steps:
+      - task: CMake@1
+        inputs:
+          cmakeArgs: '-DWITHOUT_ALLWPILIB=OFF ..'
+      - script: |
+          make -j3
+        workingDirectory: 'build'
+        displayName: 'Build'
+
+ - job: Windows_64_Bit
+   pool:
+     vmImage: 'vs2017-win2016'
+   steps:
+    - powershell: |
+        mkdir build
+        $ProgressPreference = 'SilentlyContinue'
+        wget "https://download.java.net/java/ga/jdk11/openjdk-11_windows-x64_bin.zip" -O "build\jdk.zip"
+      displayName: 'Download JDK'
+    - task: JavaToolInstaller@0
+      inputs:
+        jdkSourceOption: localDirectory
+        jdkFile: 'build/jdk.zip'
+        jdkDestinationDirectory: 'build/jdkinst'
+        jdkArchitectureOption: x64
+    - task: Gradle@2
+      inputs:
+        workingDirectory: ''
+        gradleWrapperFile: 'gradlew'
+        gradleOptions: '-Xmx3072m'
+        publishJUnitResults: true
+        testResultsFiles: '**/TEST-*.xml'
+        tasks: 'build'
+        # checkStyleRunAnalysis: true
+        # pmdRunAnalysis: true
+
+ - job: Windows_32_Bit
+   pool:
+     vmImage: 'vs2017-win2016'
+   steps:
+    - powershell: |
+        mkdir build
+        $ProgressPreference = 'SilentlyContinue'
+        wget "https://github.com/wpilibsuite/frc-openjdk-windows/releases/download/v11.0.0u28-1/jdk-x86-11.0.0u28-1.zip" -O "build\jdk.zip"
+      displayName: 'Download JDK'
+    - task: JavaToolInstaller@0
+      inputs:
+        jdkSourceOption: localDirectory
+        jdkFile: 'build/jdk.zip'
+        jdkDestinationDirectory: 'build/jdkinst'
+        jdkArchitectureOption: x86
+    - task: Gradle@2
+      inputs:
+        workingDirectory: ''
+        gradleWrapperFile: 'gradlew'
+        gradleOptions: '-Xmx1024m'
+        publishJUnitResults: true
+        testResultsFiles: '**/TEST-*.xml'
+        tasks: 'build'
+        # checkStyleRunAnalysis: true
+        # pmdRunAnalysis: true
+
+ - job: Mac
+   pool:
+     vmImage: 'xcode9-macos10.13'
+   steps:
+    - script: |
+        mkdir build
+        wget "https://download.java.net/java/ga/jdk11/openjdk-11_osx-x64_bin.tar.gz" -O "build/jdk.tar.gz"
+        sudo tar xvzf build/jdk.tar.gz -C /Library/Java/JavaVirtualMachines/
+        export JAVA_HOME=/Library/Java/JavaVirtualMachines/jdk-11.jdk/Contents/Home/
+      displayName: 'Setup JDK'
+    - script: |
+        rm /Users/vsts/.gradle/init.d/log-gradle-version-plugin.gradle
+      displayName: 'Delete Version init script'
+    - task: Gradle@2
+      inputs:
+        workingDirectory: ''
+        gradleWrapperFile: 'gradlew'
+        gradleOptions: '-Xmx3072m'
+        javaHomeOption: 'path'
+        jdkDirectory: '/Library/Java/JavaVirtualMachines/jdk-11.jdk/Contents/Home/'
+        publishJUnitResults: true
+        testResultsFiles: '**/TEST-*.xml'
+        tasks: 'build'
+        # checkStyleRunAnalysis: true
+        # pmdRunAnalysis: true
diff --git a/third_party/allwpilib_2019/build.gradle b/third_party/allwpilib_2019/build.gradle
new file mode 100644
index 0000000..aac1e12
--- /dev/null
+++ b/third_party/allwpilib_2019/build.gradle
@@ -0,0 +1,104 @@
+plugins {
+    id 'base'
+    id 'edu.wpi.first.wpilib.versioning.WPILibVersioningPlugin' version '2.3'
+    id 'edu.wpi.first.NativeUtils' version '2.1.2'
+    id 'edu.wpi.first.GradleJni' version '0.3.1'
+    id 'edu.wpi.first.GradleVsCode' version '0.7.1'
+    id 'idea'
+    id 'visual-studio'
+    id 'com.gradle.build-scan' version '2.0.2'
+    id 'net.ltgt.errorprone' version '0.6' apply false
+    id 'com.github.johnrengelman.shadow' version '4.0.3' apply false
+}
+
+repositories {
+    mavenCentral()
+}
+
+buildScan {
+    termsOfServiceUrl = 'https://gradle.com/terms-of-service'
+    termsOfServiceAgree = 'yes'
+
+    publishAlways()
+}
+
+ext.licenseFile = files("$rootDir/LICENSE.txt", "$rootDir/ThirdPartyNotices.txt")
+
+// Ensure that the WPILibVersioningPlugin is setup by setting the release type, if releaseType wasn't
+// already specified on the command line
+if (!hasProperty('releaseType')) {
+    WPILibVersion {
+        releaseType = 'dev'
+    }
+}
+
+def pubVersion
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def outputsFolder = file("$buildDir/allOutputs")
+
+def versionFile = file("$outputsFolder/version.txt")
+
+task outputVersions() {
+    description = 'Prints the versions of wpilib to a file for use by the downstream packaging project'
+    group = 'Build'
+    outputs.files(versionFile)
+
+    doFirst {
+        buildDir.mkdir()
+        outputsFolder.mkdir()
+    }
+
+    doLast {
+        versionFile.write pubVersion
+    }
+}
+
+task libraryBuild() {}
+
+build.dependsOn outputVersions
+
+task copyAllOutputs(type: Copy) {
+    destinationDir outputsFolder
+}
+
+build.dependsOn copyAllOutputs
+copyAllOutputs.dependsOn outputVersions
+
+ext.addTaskToCopyAllOutputs = { task ->
+    copyAllOutputs.dependsOn task
+    copyAllOutputs.inputs.file task.archivePath
+    copyAllOutputs.from task.archivePath
+}
+
+subprojects {
+    apply plugin: 'eclipse'
+    apply plugin: 'idea'
+
+    def subproj = it
+
+    plugins.withType(NativeComponentPlugin) {
+        subproj.apply plugin: MultiBuilds
+    }
+
+    apply from: "${rootDir}/shared/java/javastyle.gradle"
+
+    repositories {
+        mavenCentral()
+    }
+
+    // Disables doclint in java 8.
+    if (JavaVersion.current().isJava8Compatible()) {
+        tasks.withType(Javadoc) {
+            options.addStringOption('Xdoclint:none', '-quiet')
+        }
+    }
+}
+
+wrapper {
+    gradleVersion = '5.0'
+}
diff --git a/third_party/allwpilib_2019/buildSrc/src/main/groovy/ExtraTasks.groovy b/third_party/allwpilib_2019/buildSrc/src/main/groovy/ExtraTasks.groovy
new file mode 100644
index 0000000..8b0b123
--- /dev/null
+++ b/third_party/allwpilib_2019/buildSrc/src/main/groovy/ExtraTasks.groovy
@@ -0,0 +1,88 @@
+import java.io.ByteArrayOutputStream;
+import java.io.File;
+import java.io.IOException;
+import java.lang.reflect.Field;
+import java.nio.file.Files;
+import java.util.ArrayList;
+import java.util.List;
+
+import org.gradle.api.GradleException;
+import org.gradle.api.Plugin;
+import org.gradle.api.Project;
+import org.gradle.api.Task;
+import org.gradle.api.file.FileTree;
+import org.gradle.api.tasks.compile.JavaCompile;
+import org.gradle.language.base.internal.ProjectLayout;
+import org.gradle.language.base.plugins.ComponentModelBasePlugin;
+import org.gradle.language.nativeplatform.tasks.AbstractNativeSourceCompileTask;
+import org.gradle.model.ModelMap;
+import org.gradle.model.Mutate;
+import org.gradle.model.RuleSource;
+import org.gradle.model.Validate;
+import org.gradle.nativeplatform.NativeBinarySpec;
+import org.gradle.nativeplatform.NativeComponentSpec;
+import org.gradle.nativeplatform.NativeLibrarySpec;
+import org.gradle.nativeplatform.SharedLibraryBinarySpec;
+import org.gradle.nativeplatform.StaticLibraryBinarySpec;
+import org.gradle.nativeplatform.platform.internal.NativePlatformInternal;
+import org.gradle.nativeplatform.toolchain.NativeToolChain;
+import org.gradle.nativeplatform.toolchain.NativeToolChainRegistry;
+import org.gradle.nativeplatform.toolchain.internal.PlatformToolProvider;
+import org.gradle.nativeplatform.toolchain.internal.ToolType;
+import org.gradle.nativeplatform.toolchain.internal.gcc.AbstractGccCompatibleToolChain;
+import org.gradle.nativeplatform.toolchain.internal.msvcpp.VisualCppToolChain;
+import org.gradle.nativeplatform.toolchain.internal.tools.ToolRegistry;
+import org.gradle.nativeplatform.test.googletest.GoogleTestTestSuiteBinarySpec;
+import org.gradle.platform.base.BinarySpec;
+import org.gradle.platform.base.ComponentSpec;
+import org.gradle.platform.base.ComponentSpecContainer;
+import org.gradle.platform.base.ComponentType;
+import org.gradle.platform.base.TypeBuilder;
+import org.gradle.nativeplatform.test.tasks.RunTestExecutable;
+import org.gradle.platform.base.BinaryContainer;
+import groovy.transform.CompileStatic;
+
+@CompileStatic
+class ExtraTasks implements Plugin<Project> {
+    @CompileStatic
+    public void apply(Project project) {
+
+    }
+
+    @CompileStatic
+    static class Rules extends RuleSource {
+        @Mutate
+        @CompileStatic
+        void createNativeCompileTask(ModelMap<Task> tasks, BinaryContainer binaries) {
+            tasks.create('compileCpp', Task) { oTask ->
+                def task = (Task) oTask
+                task.group = 'build'
+                task.description = 'Uber task to compile all native code for this project'
+                binaries.each { binary ->
+                    if (binary instanceof NativeBinarySpec && binary.buildable) {
+                        binary.tasks.withType(AbstractNativeSourceCompileTask) { compileTask ->
+                            task.dependsOn compileTask
+                        }
+                    }
+                }
+            }
+        }
+
+        @Mutate
+        @CompileStatic
+        void createNativeTestTask(ModelMap<Task> tasks, BinaryContainer binaries) {
+            tasks.create('testCpp', Task) { oTask ->
+                def task = (Task) oTask
+                task.group = 'build'
+                task.description = 'Uber task to run all native tests for project'
+                binaries.each { binary ->
+                    if (binary instanceof GoogleTestTestSuiteBinarySpec && binary.buildable) {
+                        binary.tasks.withType(RunTestExecutable) { testTask ->
+                            task.dependsOn testTask
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/buildSrc/src/main/groovy/MultiBuilds.groovy b/third_party/allwpilib_2019/buildSrc/src/main/groovy/MultiBuilds.groovy
new file mode 100644
index 0000000..aa1a225
--- /dev/null
+++ b/third_party/allwpilib_2019/buildSrc/src/main/groovy/MultiBuilds.groovy
@@ -0,0 +1,95 @@
+

+import org.gradle.api.GradleException;

+import org.gradle.api.Plugin;

+import org.gradle.api.Project;

+import org.gradle.api.Task;

+import org.gradle.api.file.FileTree;

+import org.gradle.api.tasks.compile.JavaCompile;

+import org.gradle.language.base.internal.ProjectLayout;

+import org.gradle.language.base.plugins.ComponentModelBasePlugin;

+import org.gradle.language.nativeplatform.tasks.AbstractNativeSourceCompileTask;

+import org.gradle.model.ModelMap;

+import org.gradle.model.Mutate;

+import org.gradle.nativeplatform.test.googletest.GoogleTestTestSuiteBinarySpec;

+import org.gradle.model.RuleSource;

+import org.gradle.model.Validate;

+import org.gradle.nativeplatform.NativeExecutableBinarySpec

+import org.gradle.nativeplatform.NativeBinarySpec;

+import org.gradle.nativeplatform.NativeComponentSpec;

+import org.gradle.nativeplatform.NativeLibrarySpec;

+import org.gradle.nativeplatform.SharedLibraryBinarySpec;

+import org.gradle.nativeplatform.StaticLibraryBinarySpec;

+import org.gradle.nativeplatform.platform.internal.NativePlatformInternal;

+import org.gradle.nativeplatform.toolchain.NativeToolChain;

+import org.gradle.nativeplatform.toolchain.NativeToolChainRegistry;

+import org.gradle.nativeplatform.toolchain.internal.PlatformToolProvider;

+import org.gradle.nativeplatform.toolchain.internal.ToolType;

+import org.gradle.nativeplatform.toolchain.internal.gcc.AbstractGccCompatibleToolChain;

+import org.gradle.nativeplatform.toolchain.internal.msvcpp.VisualCppToolChain;

+import org.gradle.nativeplatform.toolchain.internal.tools.ToolRegistry;

+import org.gradle.platform.base.BinarySpec;

+import org.gradle.platform.base.ComponentSpec;

+import org.gradle.platform.base.ComponentSpecContainer;

+import org.gradle.platform.base.BinaryContainer;

+import org.gradle.platform.base.ComponentType;

+import org.gradle.platform.base.TypeBuilder;

+import org.gradle.nativeplatform.tasks.ObjectFilesToBinary;

+import groovy.transform.CompileStatic;

+import groovy.transform.CompileDynamic

+import org.gradle.nativeplatform.BuildTypeContainer

+

+@CompileStatic

+class MultiBuilds implements Plugin<Project> {

+  @CompileStatic

+  public void apply(Project project) {

+

+  }

+

+  @CompileStatic

+  static class Rules extends RuleSource {

+    @Mutate

+    void setupBuildTypes(BuildTypeContainer buildTypes, ProjectLayout projectLayout) {

+        def project = (Project) projectLayout.projectIdentifier

+        if (project.hasProperty('releaseBuild')) {

+            buildTypes.create('debug')

+        } else {

+            buildTypes.create('release')

+        }

+    }

+

+    @CompileDynamic

+    private static void setBuildableFalseDynamically(NativeBinarySpec binary) {

+        binary.buildable = false

+    }

+

+    @Mutate

+    @CompileStatic

+    void disableReleaseGoogleTest(BinaryContainer binaries, ProjectLayout projectLayout) {

+      def project = (Project) projectLayout.projectIdentifier

+      if (project.hasProperty('testRelease')) {

+        return

+      }

+      binaries.withType(GoogleTestTestSuiteBinarySpec) { oSpec ->

+        GoogleTestTestSuiteBinarySpec spec = (GoogleTestTestSuiteBinarySpec) oSpec

+        if (spec.buildType.name == 'release') {

+          Rules.setBuildableFalseDynamically(spec)

+        }

+      }

+        // def crossCompileConfigs = []

+        // for (BuildConfig config : configs) {

+        //     if (!BuildConfigRulesBase.isCrossCompile(config)) {

+        //         continue

+        //     }

+        //     crossCompileConfigs << config.architecture

+        // }

+        // if (!crossCompileConfigs.empty) {

+        //     binaries.withType(GoogleTestTestSuiteBinarySpec) { oSpec ->

+        //         GoogleTestTestSuiteBinarySpec spec = (GoogleTestTestSuiteBinarySpec) oSpec

+        //         if (crossCompileConfigs.contains(spec.targetPlatform.architecture.name)) {

+        //             setBuildableFalseDynamically(spec)

+        //         }

+        //     }

+        // }

+    }

+  }

+}

diff --git a/third_party/allwpilib_2019/buildSrc/src/main/groovy/SingleNativeBuild.groovy b/third_party/allwpilib_2019/buildSrc/src/main/groovy/SingleNativeBuild.groovy
new file mode 100644
index 0000000..f37fc57
--- /dev/null
+++ b/third_party/allwpilib_2019/buildSrc/src/main/groovy/SingleNativeBuild.groovy
@@ -0,0 +1,113 @@
+import java.io.ByteArrayOutputStream;
+import java.io.File;
+import java.io.IOException;
+import java.lang.reflect.Field;
+import java.nio.file.Files;
+import java.util.ArrayList;
+import java.util.List;
+
+import org.gradle.api.GradleException;
+import org.gradle.api.Plugin;
+import org.gradle.api.Project;
+import org.gradle.api.Task;
+import org.gradle.api.file.FileTree;
+import org.gradle.api.tasks.compile.JavaCompile;
+import org.gradle.language.base.internal.ProjectLayout;
+import org.gradle.language.base.plugins.ComponentModelBasePlugin;
+import org.gradle.language.nativeplatform.tasks.AbstractNativeSourceCompileTask;
+import org.gradle.model.ModelMap;
+import org.gradle.model.Mutate;
+import org.gradle.model.RuleSource;
+import org.gradle.model.Validate;
+import org.gradle.nativeplatform.NativeBinarySpec;
+import org.gradle.nativeplatform.NativeComponentSpec;
+import org.gradle.nativeplatform.NativeLibrarySpec;
+import org.gradle.nativeplatform.SharedLibraryBinarySpec;
+import org.gradle.nativeplatform.StaticLibraryBinarySpec;
+import org.gradle.nativeplatform.platform.internal.NativePlatformInternal;
+import org.gradle.nativeplatform.toolchain.NativeToolChain;
+import org.gradle.nativeplatform.toolchain.NativeToolChainRegistry;
+import org.gradle.nativeplatform.toolchain.internal.PlatformToolProvider;
+import org.gradle.nativeplatform.toolchain.internal.ToolType;
+import org.gradle.nativeplatform.toolchain.internal.gcc.AbstractGccCompatibleToolChain;
+import org.gradle.nativeplatform.toolchain.internal.msvcpp.VisualCppToolChain;
+import org.gradle.nativeplatform.toolchain.internal.tools.ToolRegistry;
+import org.gradle.platform.base.BinarySpec;
+import org.gradle.platform.base.ComponentSpec;
+import org.gradle.platform.base.ComponentSpecContainer;
+import org.gradle.platform.base.BinaryContainer;
+import org.gradle.platform.base.ComponentType;
+import org.gradle.platform.base.TypeBuilder;
+import org.gradle.nativeplatform.tasks.ObjectFilesToBinary;
+import groovy.transform.CompileStatic;
+
+@CompileStatic
+class SingleNativeBuild implements Plugin<Project> {
+    @CompileStatic
+    public void apply(Project project) {
+
+    }
+
+    @CompileStatic
+    static class Rules extends RuleSource {
+        @Mutate
+        @CompileStatic
+        void setupSingleNativeBuild(ModelMap<Task> tasks, ComponentSpecContainer components, BinaryContainer binaryContainer, ProjectLayout projectLayout) {
+            Project project = (Project) projectLayout.projectIdentifier;
+
+            def nativeName = project.extensions.extraProperties.get('nativeName')
+
+            NativeLibrarySpec base = null
+            def subs = []
+            components.each { component ->
+                if (component.name == "${nativeName}Base") {
+                    base = (NativeLibrarySpec) component
+                } else if (component.name == "${nativeName}" || component.name == "${nativeName}JNI") {
+                    subs << component
+                }
+            }
+            subs.each {
+                ((NativeLibrarySpec) it).binaries.each { oBinary ->
+                    if (oBinary.buildable == false) {
+                        return
+                    }
+                    NativeBinarySpec binary = (NativeBinarySpec) oBinary
+                    NativeBinarySpec baseBin = null
+                    base.binaries.each { oTmpBaseBin ->
+                        if (oTmpBaseBin.buildable == false) {
+                            return
+                        }
+                        def tmpBaseBin = (NativeBinarySpec) oTmpBaseBin
+                        if (tmpBaseBin.targetPlatform.operatingSystem.name == binary.targetPlatform.operatingSystem.name &&
+                                tmpBaseBin.targetPlatform.architecture.name == binary.targetPlatform.architecture.name &&
+                                tmpBaseBin.buildType == binary.buildType) {
+                            baseBin = tmpBaseBin
+                        }
+                    }
+                    baseBin.tasks.withType(AbstractNativeSourceCompileTask) { oCompileTask ->
+                        def compileTask = (AbstractNativeSourceCompileTask) oCompileTask
+                        if (binary instanceof SharedLibraryBinarySpec) {
+                            def sBinary = (SharedLibraryBinarySpec) binary
+                            ObjectFilesToBinary link = (ObjectFilesToBinary) sBinary.tasks.link
+                            link.dependsOn compileTask
+                            link.inputs.dir compileTask.objectFileDir
+                            def tree = project.fileTree(compileTask.objectFileDir)
+                            tree.include '**/*.o'
+                            tree.include '**/*.obj'
+                            link.source tree
+                        } else if (binary instanceof StaticLibraryBinarySpec) {
+                            def sBinary = (StaticLibraryBinarySpec) binary
+                            ObjectFilesToBinary assemble = (ObjectFilesToBinary) sBinary.tasks.createStaticLib
+                            assemble.dependsOn compileTask
+                            assemble.inputs.dir compileTask.objectFileDir
+                            def tree = project.fileTree(compileTask.objectFileDir)
+                            tree.include '**/*.o'
+                            tree.include '**/*.obj'
+                            assemble.source tree
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/cameraserver/.styleguide b/third_party/allwpilib_2019/cameraserver/.styleguide
new file mode 100644
index 0000000..899d9c2
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/.styleguide
@@ -0,0 +1,28 @@
+cppHeaderFileInclude {
+  \.h$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+modifiableFileExclude {
+  \.so$
+}
+
+repoRootNameOverride {
+  cameraserver
+}
+
+includeOtherLibs {
+  ^HAL/
+  ^networktables/
+  ^opencv2/
+  ^support/
+  ^wpi/
+}
+
+includeGuardRoots {
+  cameraserver/src/main/native/include/
+}
diff --git a/third_party/allwpilib_2019/cameraserver/CMakeLists.txt b/third_party/allwpilib_2019/cameraserver/CMakeLists.txt
new file mode 100644
index 0000000..a3a7460
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/CMakeLists.txt
@@ -0,0 +1,57 @@
+project(cameraserver)
+
+find_package( OpenCV REQUIRED )
+
+# Java bindings
+if (NOT WITHOUT_JAVA)
+    find_package(Java REQUIRED)
+    include(UseJava)
+    set(CMAKE_JAVA_COMPILE_FLAGS "-Xlint:unchecked")
+
+    #find java files, copy them locally
+
+    set(OPENCV_JAVA_INSTALL_DIR ${OpenCV_INSTALL_PATH}/share/OpenCV/java/)
+
+    find_file(OPENCV_JAR_FILE NAMES opencv-${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.jar PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin NO_DEFAULT_PATH)
+
+    file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+
+    add_jar(cameraserver_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar cscore_jar ntcore_jar ${OPENCV_JAR_FILE} OUTPUT_NAME cameraserver)
+
+    get_property(CAMERASERVER_JAR_FILE TARGET cameraserver_jar PROPERTY JAR_FILE)
+    install(FILES ${CAMERASERVER_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+    set_property(TARGET cameraserver_jar PROPERTY FOLDER "java")
+
+endif()
+
+file(GLOB_RECURSE
+    cameraserver_native_src src/main/native/cpp/*.cpp)
+add_library(cameraserver ${cameraserver_native_src})
+set_target_properties(cameraserver PROPERTIES DEBUG_POSTFIX "d")
+target_include_directories(cameraserver PUBLIC
+                $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/cameraserver>)
+target_link_libraries(cameraserver PUBLIC ntcore cscore wpiutil ${OpenCV_LIBS})
+
+set_property(TARGET cameraserver PROPERTY FOLDER "libraries")
+
+install(TARGETS cameraserver EXPORT cameraserver DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/cameraserver")
+
+if (NOT WITHOUT_JAVA AND MSVC)
+    install(TARGETS cameraserver RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+endif()
+
+if (MSVC)
+    set (cameraserver_config_dir ${wpilib_dest})
+else()
+    set (cameraserver_config_dir share/cameraserver)
+endif()
+
+install(FILES cameraserver-config.cmake DESTINATION ${cameraserver_config_dir})
+install(EXPORT cameraserver DESTINATION ${cameraserver_config_dir})
+
+file(GLOB multiCameraServer_src multiCameraServer/src/main/native/cpp/*.cpp)
+add_executable(multiCameraServer ${multiCameraServer_src})
+target_link_libraries(multiCameraServer cameraserver)
diff --git a/third_party/allwpilib_2019/cameraserver/build.gradle b/third_party/allwpilib_2019/cameraserver/build.gradle
new file mode 100644
index 0000000..2b19454
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/build.gradle
@@ -0,0 +1,80 @@
+ext {
+    nativeName = 'cameraserver'
+    devMain = 'edu.wpi.first.cameraserver.DevMain'
+}
+
+evaluationDependsOn(':ntcore')
+evaluationDependsOn(':cscore')
+evaluationDependsOn(':hal')
+
+apply from: "${rootDir}/shared/javacpp/setupBuild.gradle"
+
+dependencies {
+    compile project(':wpiutil')
+    compile project(':ntcore')
+    compile project(':cscore')
+    devCompile project(':wpiutil')
+    devCompile project(':ntcore')
+    devCompile project(':cscore')
+}
+
+ext {
+    sharedCvConfigs = [cameraserver    : [],
+                       cameraserverBase: [],
+                       cameraserverDev : [],
+                       cameraserverTest: []]
+    staticCvConfigs = [:]
+    useJava = true
+    useCpp = true
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+model {
+    // Exports config is a utility to enable exporting all symbols in a C++ library on windows to a DLL.
+    // This removes the need for DllExport on a library. However, the gradle C++ builder has a bug
+    // where some extra symbols are added that cannot be resolved at link time. This configuration
+    // lets you specify specific symbols to exlude from exporting.
+    exportsConfigs {
+        cameraserver(ExportsConfig) {
+            x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure', '_CT??_R0?AVout_of_range', '_CTA3?AVout_of_range',
+                                 '_TI3?AVout_of_range', '_CT??_R0?AVbad_cast']
+            x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure', '_CT??_R0?AVout_of_range', '_CTA3?AVout_of_range',
+                                 '_TI3?AVout_of_range', '_CT??_R0?AVbad_cast']
+        }
+    }
+    components {}
+    binaries {
+        all {
+            if (!it.buildable || !(it instanceof NativeBinarySpec)) {
+                return
+            }
+            lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+            lib project: ':cscore', library: 'cscore', linkage: 'shared'
+            lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+        }
+    }
+    tasks {
+        def c = $.components
+        def found = false
+        def systemArch = getCurrentArch()
+        c.each {
+            if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
+                it.binaries.each {
+                    if (!found) {
+                        def arch = it.targetPlatform.architecture.name
+                        if (arch == systemArch) {
+                            def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib'
+
+                            found = true
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/cameraserver/cameraserver-config.cmake b/third_party/allwpilib_2019/cameraserver/cameraserver-config.cmake
new file mode 100644
index 0000000..2c2b1cc
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/cameraserver-config.cmake
@@ -0,0 +1,8 @@
+include(CMakeFindDependencyMacro)

+find_dependency(wpiutil)

+find_dependency(ntcore)

+find_dependency(cscore)

+find_dependency(OpenCV)

+

+get_filename_component(SELF_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)

+include(${SELF_DIR}/cameraserver.cmake)

diff --git a/third_party/allwpilib_2019/cameraserver/multiCameraServer/build.gradle b/third_party/allwpilib_2019/cameraserver/multiCameraServer/build.gradle
new file mode 100644
index 0000000..c49cfb0
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/multiCameraServer/build.gradle
@@ -0,0 +1,62 @@
+plugins {
+    id 'java'
+    id 'application'
+    id 'cpp'
+    id 'visual-studio'
+}
+
+apply plugin: 'edu.wpi.first.NativeUtils'
+
+apply from: "${rootDir}/shared/config.gradle"
+
+ext {
+    staticCvConfigs = [multiCameraServerCpp: []]
+    useJava = true
+    useCpp = true
+    skipDev = true
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+mainClassName = 'Main'
+
+apply plugin: 'com.github.johnrengelman.shadow'
+
+repositories {
+    mavenCentral()
+}
+
+dependencies {
+    compile 'com.google.code.gson:gson:2.8.5'
+
+    compile project(':wpiutil')
+    compile project(':ntcore')
+    compile project(':cscore')
+    compile project(':cameraserver')
+}
+
+model {
+    components {
+        multiCameraServerCpp(NativeExecutableSpec) {
+            targetBuildTypes 'release'
+            sources {
+                cpp {
+                    source {
+                        srcDirs = ['src/main/native/cpp']
+                        includes = ['**/*.cpp']
+                    }
+                    exportedHeaders {
+                        srcDirs = ['src/main/native/include']
+                        includes = ['**/*.h']
+                    }
+                }
+            }
+            binaries.all { binary ->
+                    lib project: ':cameraserver', library: 'cameraserver', linkage: 'static'
+                    lib project: ':ntcore', library: 'ntcore', linkage: 'static'
+                    lib project: ':cscore', library: 'cscore', linkage: 'static'
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/cameraserver/multiCameraServer/src/main/java/Main.java b/third_party/allwpilib_2019/cameraserver/multiCameraServer/src/main/java/Main.java
new file mode 100644
index 0000000..8bcc54d
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/multiCameraServer/src/main/java/Main.java
@@ -0,0 +1,211 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+import java.io.IOException;
+import java.nio.file.Files;
+import java.nio.file.Paths;
+import java.util.ArrayList;
+import java.util.List;
+
+import com.google.gson.Gson;
+import com.google.gson.GsonBuilder;
+import com.google.gson.JsonArray;
+import com.google.gson.JsonElement;
+import com.google.gson.JsonObject;
+import com.google.gson.JsonParser;
+
+import edu.wpi.cscore.VideoSource;
+import edu.wpi.first.cameraserver.CameraServer;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+/*
+   JSON format:
+   {
+       "team": <team number>,
+       "ntmode": <"client" or "server", "client" if unspecified>
+       "cameras": [
+           {
+               "name": <camera name>
+               "path": <path, e.g. "/dev/video0">
+               "pixel format": <"MJPEG", "YUYV", etc>   // optional
+               "width": <video mode width>              // optional
+               "height": <video mode height>            // optional
+               "fps": <video mode fps>                  // optional
+               "brightness": <percentage brightness>    // optional
+               "white balance": <"auto", "hold", value> // optional
+               "exposure": <"auto", "hold", value>      // optional
+               "properties": [                          // optional
+                   {
+                       "name": <property name>
+                       "value": <property value>
+                   }
+               ]
+           }
+       ]
+   }
+ */
+
+public final class Main {
+  private static String configFile = "/boot/frc.json";
+
+  @SuppressWarnings("MemberName")
+  public static class CameraConfig {
+    public String name;
+    public String path;
+    public JsonObject config;
+  }
+
+  public static int team;
+  public static boolean server;
+  public static List<CameraConfig> cameras = new ArrayList<>();
+
+  private Main() {
+  }
+
+  /**
+   * Report parse error.
+   */
+  public static void parseError(String str) {
+    System.err.println("config error in '" + configFile + "': " + str);
+  }
+
+  /**
+   * Read single camera configuration.
+   */
+  public static boolean readCameraConfig(JsonObject config) {
+    CameraConfig cam = new CameraConfig();
+
+    // name
+    JsonElement nameElement = config.get("name");
+    if (nameElement == null) {
+      parseError("could not read camera name");
+      return false;
+    }
+    cam.name = nameElement.getAsString();
+
+    // path
+    JsonElement pathElement = config.get("path");
+    if (pathElement == null) {
+      parseError("camera '" + cam.name + "': could not read path");
+      return false;
+    }
+    cam.path = pathElement.getAsString();
+
+    cam.config = config;
+
+    cameras.add(cam);
+    return true;
+  }
+
+  /**
+   * Read configuration file.
+   */
+  @SuppressWarnings("PMD.CyclomaticComplexity")
+  public static boolean readConfig() {
+    // parse file
+    JsonElement top;
+    try {
+      top = new JsonParser().parse(Files.newBufferedReader(Paths.get(configFile)));
+    } catch (IOException ex) {
+      System.err.println("could not open '" + configFile + "': " + ex);
+      return false;
+    }
+
+    // top level must be an object
+    if (!top.isJsonObject()) {
+      parseError("must be JSON object");
+      return false;
+    }
+    JsonObject obj = top.getAsJsonObject();
+
+    // team number
+    JsonElement teamElement = obj.get("team");
+    if (teamElement == null) {
+      parseError("could not read team number");
+      return false;
+    }
+    team = teamElement.getAsInt();
+
+    // ntmode (optional)
+    if (obj.has("ntmode")) {
+      String str = obj.get("ntmode").getAsString();
+      if ("client".equalsIgnoreCase(str)) {
+        server = false;
+      } else if ("server".equalsIgnoreCase(str)) {
+        server = true;
+      } else {
+        parseError("could not understand ntmode value '" + str + "'");
+      }
+    }
+
+    // cameras
+    JsonElement camerasElement = obj.get("cameras");
+    if (camerasElement == null) {
+      parseError("could not read cameras");
+      return false;
+    }
+    JsonArray cameras = camerasElement.getAsJsonArray();
+    for (JsonElement camera : cameras) {
+      if (!readCameraConfig(camera.getAsJsonObject())) {
+        return false;
+      }
+    }
+
+    return true;
+  }
+
+  /**
+   * 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);
+
+    Gson gson = new GsonBuilder().create();
+
+    camera.setConfigJson(gson.toJson(config.config));
+  }
+
+  /**
+   * Main.
+   */
+  public static void main(String... args) {
+    if (args.length > 0) {
+      configFile = args[0];
+    }
+
+    // read configuration
+    if (!readConfig()) {
+      return;
+    }
+
+    // start NetworkTables
+    NetworkTableInstance ntinst = NetworkTableInstance.getDefault();
+    if (server) {
+      System.out.println("Setting up NetworkTables server");
+      ntinst.startServer();
+    } else {
+      System.out.println("Setting up NetworkTables client for team " + team);
+      ntinst.startClientTeam(team);
+    }
+
+    // start cameras
+    for (CameraConfig camera : cameras) {
+      startCamera(camera);
+    }
+
+    // loop forever
+    for (;;) {
+      try {
+        Thread.sleep(10000);
+      } catch (InterruptedException ex) {
+        return;
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp b/third_party/allwpilib_2019/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp
new file mode 100644
index 0000000..dbfc7b6
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp
@@ -0,0 +1,190 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <cstdio>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/StringRef.h>
+#include <wpi/json.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+#include "cameraserver/CameraServer.h"
+
+/*
+   JSON format:
+   {
+       "team": <team number>,
+       "ntmode": <"client" or "server", "client" if unspecified>
+       "cameras": [
+           {
+               "name": <camera name>
+               "path": <path, e.g. "/dev/video0">
+               "pixel format": <"MJPEG", "YUYV", etc>   // optional
+               "width": <video mode width>              // optional
+               "height": <video mode height>            // optional
+               "fps": <video mode fps>                  // optional
+               "brightness": <percentage brightness>    // optional
+               "white balance": <"auto", "hold", value> // optional
+               "exposure": <"auto", "hold", value>      // optional
+               "properties": [                          // optional
+                   {
+                       "name": <property name>
+                       "value": <property value>
+                   }
+               ]
+           }
+       ]
+   }
+ */
+
+#ifdef __RASPBIAN__
+static const char* configFile = "/boot/frc.json";
+#else
+static const char* configFile = "frc.json";
+#endif
+
+namespace {
+
+unsigned int team;
+bool server = false;
+
+struct CameraConfig {
+  std::string name;
+  std::string path;
+  wpi::json config;
+};
+
+std::vector<CameraConfig> cameras;
+
+wpi::raw_ostream& ParseError() {
+  return wpi::errs() << "config error in '" << configFile << "': ";
+}
+
+bool ReadCameraConfig(const wpi::json& config) {
+  CameraConfig c;
+
+  // name
+  try {
+    c.name = config.at("name").get<std::string>();
+  } catch (const wpi::json::exception& e) {
+    ParseError() << "could not read camera name: " << e.what() << '\n';
+    return false;
+  }
+
+  // path
+  try {
+    c.path = config.at("path").get<std::string>();
+  } catch (const wpi::json::exception& e) {
+    ParseError() << "camera '" << c.name
+                 << "': could not read path: " << e.what() << '\n';
+    return false;
+  }
+
+  c.config = config;
+
+  cameras.emplace_back(std::move(c));
+  return true;
+}
+
+bool ReadConfig() {
+  // open config file
+  std::error_code ec;
+  wpi::raw_fd_istream is(configFile, ec);
+  if (ec) {
+    wpi::errs() << "could not open '" << configFile << "': " << ec.message()
+                << '\n';
+    return false;
+  }
+
+  // parse file
+  wpi::json j;
+  try {
+    j = wpi::json::parse(is);
+  } catch (const wpi::json::parse_error& e) {
+    ParseError() << "byte " << e.byte << ": " << e.what() << '\n';
+    return false;
+  }
+
+  // top level must be an object
+  if (!j.is_object()) {
+    ParseError() << "must be JSON object\n";
+    return false;
+  }
+
+  // team number
+  try {
+    team = j.at("team").get<unsigned int>();
+  } catch (const wpi::json::exception& e) {
+    ParseError() << "could not read team number: " << e.what() << '\n';
+    return false;
+  }
+
+  // ntmode (optional)
+  if (j.count("ntmode") != 0) {
+    try {
+      auto str = j.at("ntmode").get<std::string>();
+      wpi::StringRef s(str);
+      if (s.equals_lower("client")) {
+        server = false;
+      } else if (s.equals_lower("server")) {
+        server = true;
+      } else {
+        ParseError() << "could not understand ntmode value '" << str << "'\n";
+      }
+    } catch (const wpi::json::exception& e) {
+      ParseError() << "could not read ntmode: " << e.what() << '\n';
+    }
+  }
+
+  // cameras
+  try {
+    for (auto&& camera : j.at("cameras")) {
+      if (!ReadCameraConfig(camera)) return false;
+    }
+  } catch (const wpi::json::exception& e) {
+    ParseError() << "could not read cameras: " << e.what() << '\n';
+    return false;
+  }
+
+  return true;
+}
+
+void StartCamera(const CameraConfig& config) {
+  wpi::outs() << "Starting camera '" << config.name << "' on " << config.path
+              << '\n';
+  auto camera = frc::CameraServer::GetInstance()->StartAutomaticCapture(
+      config.name, config.path);
+
+  camera.SetConfigJson(config.config);
+}
+}  // namespace
+
+int main(int argc, char* argv[]) {
+  if (argc >= 2) configFile = argv[1];
+
+  // read configuration
+  if (!ReadConfig()) return EXIT_FAILURE;
+
+  // start NetworkTables
+  auto ntinst = nt::NetworkTableInstance::GetDefault();
+  if (server) {
+    wpi::outs() << "Setting up NetworkTables server\n";
+    ntinst.StartServer();
+  } else {
+    wpi::outs() << "Setting up NetworkTables client for team " << team << '\n';
+    ntinst.StartClientTeam(team);
+  }
+
+  // start cameras
+  for (auto&& camera : cameras) StartCamera(camera);
+
+  // loop forever
+  for (;;) std::this_thread::sleep_for(std::chrono::seconds(10));
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/dev/java/edu/wpi/first/cameraserver/DevMain.java b/third_party/allwpilib_2019/cameraserver/src/dev/java/edu/wpi/first/cameraserver/DevMain.java
new file mode 100644
index 0000000..1182ac4
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/dev/java/edu/wpi/first/cameraserver/DevMain.java
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.cameraserver;
+
+public final class DevMain {
+  public static void main(String[] args) {
+
+  }
+
+  private DevMain() {
+  }
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/cameraserver/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..e324b44
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/dev/native/cpp/main.cpp
@@ -0,0 +1,8 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+int main() {}
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
new file mode 100644
index 0000000..58da593
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServer.java
@@ -0,0 +1,775 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.cameraserver;
+
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.Hashtable;
+import java.util.Map;
+import java.util.concurrent.atomic.AtomicInteger;
+
+import edu.wpi.cscore.AxisCamera;
+import edu.wpi.cscore.CameraServerJNI;
+import edu.wpi.cscore.CvSink;
+import edu.wpi.cscore.CvSource;
+import edu.wpi.cscore.MjpegServer;
+import edu.wpi.cscore.UsbCamera;
+import edu.wpi.cscore.VideoEvent;
+import edu.wpi.cscore.VideoException;
+import edu.wpi.cscore.VideoListener;
+import edu.wpi.cscore.VideoMode;
+import edu.wpi.cscore.VideoMode.PixelFormat;
+import edu.wpi.cscore.VideoProperty;
+import edu.wpi.cscore.VideoSink;
+import edu.wpi.cscore.VideoSource;
+import edu.wpi.first.networktables.EntryListenerFlags;
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+/**
+ * Singleton class for creating and keeping camera servers.
+ * Also publishes camera information to NetworkTables.
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public final class CameraServer {
+  public static final int kBasePort = 1181;
+
+  @Deprecated
+  public static final int kSize640x480 = 0;
+  @Deprecated
+  public static final int kSize320x240 = 1;
+  @Deprecated
+  public static final int kSize160x120 = 2;
+
+  private static final String kPublishName = "/CameraPublisher";
+  private static CameraServer server;
+
+  /**
+   * Get the CameraServer instance.
+   */
+  public static synchronized CameraServer getInstance() {
+    if (server == null) {
+      server = new 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 final NetworkTable m_publishTable;
+  private final VideoListener m_videoListener; //NOPMD
+  private final int m_tableListener; //NOPMD
+  private int m_nextPort;
+  private String[] m_addresses;
+
+  @SuppressWarnings("JavadocMethod")
+  private static String makeSourceValue(int source) {
+    switch (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))) {
+      case kUsb:
+        return "usb:" + CameraServerJNI.getUsbCameraPath(source);
+      case kHttp: {
+        String[] urls = CameraServerJNI.getHttpCameraUrls(source);
+        if (urls.length > 0) {
+          return "ip:" + urls[0];
+        } else {
+          return "ip:";
+        }
+      }
+      case kCv:
+        return "cv:";
+      default:
+        return "unknown:";
+    }
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  private static String makeStreamValue(String address, int port) {
+    return "mjpg:http://" + address + ":" + port + "/?action=stream";
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.AvoidUsingHardCodedIP"})
+  private synchronized String[] getSinkStreamValues(int sink) {
+    // Ignore all but MjpegServer
+    if (VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) != VideoSink.Kind.kMjpeg) {
+      return new String[0];
+    }
+
+    // Get port
+    int port = CameraServerJNI.getMjpegServerPort(sink);
+
+    // Generate values
+    ArrayList<String> values = new ArrayList<>(m_addresses.length + 1);
+    String listenAddress = CameraServerJNI.getMjpegServerListenAddress(sink);
+    if (!listenAddress.isEmpty()) {
+      // If a listen address is specified, only use that
+      values.add(makeStreamValue(listenAddress, port));
+    } else {
+      // Otherwise generate for hostname and all interface addresses
+      values.add(makeStreamValue(CameraServerJNI.getHostname() + ".local", port));
+      for (String addr : m_addresses) {
+        if ("127.0.0.1".equals(addr)) {
+          continue;  // ignore localhost
+        }
+        values.add(makeStreamValue(addr, port));
+      }
+    }
+
+    return values.toArray(new String[0]);
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.AvoidUsingHardCodedIP"})
+  private synchronized String[] getSourceStreamValues(int source) {
+    // Ignore all but HttpCamera
+    if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))
+            != VideoSource.Kind.kHttp) {
+      return new String[0];
+    }
+
+    // Generate values
+    String[] values = CameraServerJNI.getHttpCameraUrls(source);
+    for (int j = 0; j < values.length; j++) {
+      values[j] = "mjpg:" + values[j];
+    }
+
+    // Look to see if we have a passthrough server for this source
+    for (VideoSink i : m_sinks.values()) {
+      int sink = i.getHandle();
+      int sinkSource = CameraServerJNI.getSinkSource(sink);
+      if (source == sinkSource
+          && VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) == VideoSink.Kind.kMjpeg) {
+        // Add USB-only passthrough
+        String[] finalValues = Arrays.copyOf(values, values.length + 1);
+        int port = CameraServerJNI.getMjpegServerPort(sink);
+        finalValues[values.length] = makeStreamValue("172.22.11.2", port);
+        return finalValues;
+      }
+    }
+
+    return values;
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.AvoidUsingHardCodedIP"})
+  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);
+      if (source == 0) {
+        continue;
+      }
+      NetworkTable table = m_tables.get(source);
+      if (table != null) {
+        // Don't set stream values if this is a HttpCamera passthrough
+        if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))
+            == VideoSource.Kind.kHttp) {
+          continue;
+        }
+
+        // Set table value
+        String[] values = getSinkStreamValues(sink);
+        if (values.length > 0) {
+          table.getEntry("streams").setStringArray(values);
+        }
+      }
+    }
+
+    // Over all the sources...
+    for (VideoSource i : m_sources.values()) {
+      int source = i.getHandle();
+
+      // Get the source's subtable (if none exists, we're done)
+      NetworkTable table = m_tables.get(source);
+      if (table != null) {
+        // Set table value
+        String[] values = getSourceStreamValues(source);
+        if (values.length > 0) {
+          table.getEntry("streams").setStringArray(values);
+        }
+      }
+    }
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  private static String pixelFormatToString(PixelFormat pixelFormat) {
+    switch (pixelFormat) {
+      case kMJPEG:
+        return "MJPEG";
+      case kYUYV:
+        return "YUYV";
+      case kRGB565:
+        return "RGB565";
+      case kBGR:
+        return "BGR";
+      case kGray:
+        return "Gray";
+      default:
+        return "Unknown";
+    }
+  }
+
+  /// Provide string description of video mode.
+  /// The returned string is "{width}x{height} {format} {fps} fps".
+  @SuppressWarnings("JavadocMethod")
+  private static String videoModeToString(VideoMode mode) {
+    return mode.width + "x" + mode.height + " " + pixelFormatToString(mode.pixelFormat)
+        + " " + mode.fps + " fps";
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  private static String[] getSourceModeValues(int sourceHandle) {
+    VideoMode[] modes = CameraServerJNI.enumerateSourceVideoModes(sourceHandle);
+    String[] modeStrings = new String[modes.length];
+    for (int i = 0; i < modes.length; i++) {
+      modeStrings[i] = videoModeToString(modes[i]);
+    }
+    return modeStrings;
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.CyclomaticComplexity"})
+  private static void putSourcePropertyValue(NetworkTable table, VideoEvent event, boolean isNew) {
+    String name;
+    String infoName;
+    if (event.name.startsWith("raw_")) {
+      name = "RawProperty/" + event.name;
+      infoName = "RawPropertyInfo/" + event.name;
+    } else {
+      name = "Property/" + event.name;
+      infoName = "PropertyInfo/" + event.name;
+    }
+
+    NetworkTableEntry entry = table.getEntry(name);
+    try {
+      switch (event.propertyKind) {
+        case kBoolean:
+          if (isNew) {
+            entry.setDefaultBoolean(event.value != 0);
+          } else {
+            entry.setBoolean(event.value != 0);
+          }
+          break;
+        case kInteger:
+        case kEnum:
+          if (isNew) {
+            entry.setDefaultDouble(event.value);
+            table.getEntry(infoName + "/min").setDouble(
+                CameraServerJNI.getPropertyMin(event.propertyHandle));
+            table.getEntry(infoName + "/max").setDouble(
+                CameraServerJNI.getPropertyMax(event.propertyHandle));
+            table.getEntry(infoName + "/step").setDouble(
+                CameraServerJNI.getPropertyStep(event.propertyHandle));
+            table.getEntry(infoName + "/default").setDouble(
+                CameraServerJNI.getPropertyDefault(event.propertyHandle));
+          } else {
+            entry.setDouble(event.value);
+          }
+          break;
+        case kString:
+          if (isNew) {
+            entry.setDefaultString(event.valueStr);
+          } else {
+            entry.setString(event.valueStr);
+          }
+          break;
+        default:
+          break;
+      }
+    } catch (VideoException ignored) {
+      // ignore
+    }
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.UnusedLocalVariable", "PMD.ExcessiveMethodLength",
+      "PMD.NPathComplexity"})
+  private CameraServer() {
+    m_defaultUsbDevice = new AtomicInteger();
+    m_sources = new Hashtable<>();
+    m_sinks = new Hashtable<>();
+    m_tables = new Hashtable<>();
+    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);
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * <p>You should call this method to see a camera feed on the dashboard.
+   * If you also want to perform vision processing on the roboRIO, use
+   * getVideo() to get access to the camera images.
+   *
+   * <p>The first time this overload is called, it calls
+   * {@link #startAutomaticCapture(int)} with device 0, creating a camera
+   * named "USB Camera 0".  Subsequent calls increment the device number
+   * (e.g. 1, 2, etc).
+   */
+  public UsbCamera startAutomaticCapture() {
+    UsbCamera camera = startAutomaticCapture(m_defaultUsbDevice.getAndIncrement());
+    CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * <p>This overload calls {@link #startAutomaticCapture(String, int)} with
+   * a name of "USB Camera {dev}".
+   *
+   * @param dev The device number of the camera interface
+   */
+  public UsbCamera startAutomaticCapture(int dev) {
+    UsbCamera camera = new UsbCamera("USB Camera " + dev, dev);
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * @param name The name to give the camera
+   * @param dev The device number of the camera interface
+   */
+  public UsbCamera startAutomaticCapture(String name, int dev) {
+    UsbCamera camera = new UsbCamera(name, dev);
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * @param name The name to give the camera
+   * @param path The device path (e.g. "/dev/video0") of the camera
+   */
+  public UsbCamera startAutomaticCapture(String name, String path) {
+    UsbCamera camera = new UsbCamera(name, path);
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard from
+   * an existing camera.
+   *
+   * @param camera Camera
+   */
+  public MjpegServer startAutomaticCapture(VideoSource camera) {
+    addCamera(camera);
+    MjpegServer server = addServer("serve_" + camera.getName());
+    server.setSource(camera);
+    return server;
+  }
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #addAxisCamera(String, String)} with
+   * name "Axis Camera".
+   *
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  public AxisCamera addAxisCamera(String host) {
+    return addAxisCamera("Axis Camera", host);
+  }
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #addAxisCamera(String, String[])} with
+   * name "Axis Camera".
+   *
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  public AxisCamera addAxisCamera(String[] hosts) {
+    return addAxisCamera("Axis Camera", hosts);
+  }
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  public AxisCamera addAxisCamera(String name, String host) {
+    AxisCamera camera = new AxisCamera(name, host);
+    // Create a passthrough MJPEG server for USB access
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportAxisCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  public AxisCamera addAxisCamera(String name, String[] hosts) {
+    AxisCamera camera = new AxisCamera(name, hosts);
+    // Create a passthrough MJPEG server for USB access
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportAxisCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Get OpenCV access to the primary camera feed.  This allows you to
+   * get images from the camera for image processing on the roboRIO.
+   *
+   * <p>This is only valid to call after a camera feed has been added
+   * with startAutomaticCapture() or addServer().
+   */
+  public CvSink getVideo() {
+    VideoSource source;
+    synchronized (this) {
+      if (m_primarySourceName == null) {
+        throw new VideoException("no camera available");
+      }
+      source = m_sources.get(m_primarySourceName);
+    }
+    if (source == null) {
+      throw new VideoException("no camera available");
+    }
+    return getVideo(source);
+  }
+
+  /**
+   * Get OpenCV access to the specified camera.  This allows you to get
+   * images from the camera for image processing on the roboRIO.
+   *
+   * @param camera Camera (e.g. as returned by startAutomaticCapture).
+   */
+  public CvSink getVideo(VideoSource camera) {
+    String name = "opencv_" + camera.getName();
+
+    synchronized (this) {
+      VideoSink sink = m_sinks.get(name);
+      if (sink != null) {
+        VideoSink.Kind kind = sink.getKind();
+        if (kind != VideoSink.Kind.kCv) {
+          throw new VideoException("expected OpenCV sink, but got " + kind);
+        }
+        return (CvSink) sink;
+      }
+    }
+
+    CvSink newsink = new CvSink(name);
+    newsink.setSource(camera);
+    addServer(newsink);
+    return newsink;
+  }
+
+  /**
+   * Get OpenCV access to the specified camera.  This allows you to get
+   * images from the camera for image processing on the roboRIO.
+   *
+   * @param name Camera name
+   */
+  public CvSink getVideo(String name) {
+    VideoSource source;
+    synchronized (this) {
+      source = m_sources.get(name);
+      if (source == null) {
+        throw new VideoException("could not find camera " + name);
+      }
+    }
+    return getVideo(source);
+  }
+
+  /**
+   * Create a MJPEG stream with OpenCV input. This can be called to pass custom
+   * annotated images to the dashboard.
+   *
+   * @param name Name to give the stream
+   * @param width Width of the image being sent
+   * @param height Height of the image being sent
+   */
+  public CvSource putVideo(String name, int width, int height) {
+    CvSource source = new CvSource(name, VideoMode.PixelFormat.kMJPEG, width, height, 30);
+    startAutomaticCapture(source);
+    return source;
+  }
+
+  /**
+   * Adds a MJPEG server at the next available port.
+   *
+   * @param name Server name
+   */
+  public MjpegServer addServer(String name) {
+    int port;
+    synchronized (this) {
+      port = m_nextPort;
+      m_nextPort++;
+    }
+    return addServer(name, port);
+  }
+
+  /**
+   * Adds a MJPEG server.
+   *
+   * @param name Server name
+   */
+  public MjpegServer addServer(String name, int port) {
+    MjpegServer server = new MjpegServer(name, port);
+    addServer(server);
+    return server;
+  }
+
+  /**
+   * Adds an already created server.
+   *
+   * @param server Server
+   */
+  public void addServer(VideoSink server) {
+    synchronized (this) {
+      m_sinks.put(server.getName(), server);
+    }
+  }
+
+  /**
+   * Removes a server by name.
+   *
+   * @param name Server name
+   */
+  public void removeServer(String name) {
+    synchronized (this) {
+      m_sinks.remove(name);
+    }
+  }
+
+  /**
+   * Get server for the primary camera feed.
+   *
+   * <p>This is only valid to call after a camera feed has been added
+   * with startAutomaticCapture() or addServer().
+   */
+  public VideoSink getServer() {
+    synchronized (this) {
+      if (m_primarySourceName == null) {
+        throw new VideoException("no camera available");
+      }
+      return getServer("serve_" + m_primarySourceName);
+    }
+  }
+
+  /**
+   * Gets a server by name.
+   *
+   * @param name Server name
+   */
+  public VideoSink getServer(String name) {
+    synchronized (this) {
+      return m_sinks.get(name);
+    }
+  }
+
+  /**
+   * Adds an already created camera.
+   *
+   * @param camera Camera
+   */
+  public void addCamera(VideoSource camera) {
+    String name = camera.getName();
+    synchronized (this) {
+      if (m_primarySourceName == null) {
+        m_primarySourceName = name;
+      }
+      m_sources.put(name, camera);
+    }
+  }
+
+  /**
+   * Removes a camera by name.
+   *
+   * @param name Camera name
+   */
+  public void removeCamera(String name) {
+    synchronized (this) {
+      m_sources.remove(name);
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerShared.java b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerShared.java
new file mode 100644
index 0000000..32a4d01
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerShared.java
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.cameraserver;
+
+
+public interface CameraServerShared {
+  /**
+   * get the main thread id func.
+   *
+   * @return the robotMainThreadId
+   */
+  Long getRobotMainThreadId();
+
+  /**
+   * Report an error to the driver station.
+   *
+   * @param error the error to set
+   */
+  void reportDriverStationError(String error);
+
+  /**
+   * Report an video server usage.
+   *
+   * @param id the usage id
+   */
+  void reportVideoServer(int id);
+
+  /**
+   * Report a usb camera usage.
+   *
+   * @param id the usage id
+   */
+  void reportUsbCamera(int id);
+
+  /**
+   * Report an axis camera usage.
+   *
+   * @param id the usage id
+   */
+  void reportAxisCamera(int id);
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java
new file mode 100644
index 0000000..c0cf2bb
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/cameraserver/CameraServerSharedStore.java
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.cameraserver;
+
+public final class CameraServerSharedStore {
+  private static CameraServerShared cameraServerShared;
+
+  private CameraServerSharedStore() {
+  }
+
+  /**
+   * get the CameraServerShared object.
+   */
+  public static synchronized CameraServerShared getCameraServerShared() {
+    if (cameraServerShared == null) {
+      cameraServerShared = new CameraServerShared() {
+
+        @Override
+        public void reportVideoServer(int id) {
+
+        }
+
+        @Override
+        public void reportUsbCamera(int id) {
+
+        }
+
+        @Override
+        public void reportDriverStationError(String error) {
+
+        }
+
+        @Override
+        public void reportAxisCamera(int id) {
+
+        }
+
+        @Override
+        public Long getRobotMainThreadId() {
+          return null;
+        }
+      };
+    }
+    return cameraServerShared;
+  }
+
+  /**
+   * set the CameraServerShared object.
+   */
+  public static synchronized void setCameraServerShared(CameraServerShared shared) {
+    cameraServerShared = shared;
+  }
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionPipeline.java b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionPipeline.java
new file mode 100644
index 0000000..6df10e7
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionPipeline.java
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.vision;
+
+import org.opencv.core.Mat;
+
+/**
+ * A vision pipeline is responsible for running a group of
+ * OpenCV algorithms to extract data from an image.
+ *
+ * @see VisionRunner
+ * @see VisionThread
+ */
+public interface VisionPipeline {
+  /**
+   * Processes the image input and sets the result objects.
+   * Implementations should make these objects accessible.
+   */
+  void process(Mat image);
+
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionRunner.java b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionRunner.java
new file mode 100644
index 0000000..24ffcda
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionRunner.java
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.vision;
+
+import org.opencv.core.Mat;
+
+import edu.wpi.cscore.CvSink;
+import edu.wpi.cscore.VideoSource;
+import edu.wpi.first.cameraserver.CameraServerSharedStore;
+
+/**
+ * A vision runner is a convenient wrapper object to make it easy to run vision pipelines
+ * from robot code. The easiest  way to use this is to run it in a {@link VisionThread}
+ * and use the listener to take snapshots of the pipeline's outputs.
+ *
+ * @see VisionPipeline
+ * @see VisionThread
+ * @see <a href="package-summary.html">vision</a>
+ */
+public class VisionRunner<P extends VisionPipeline> {
+  private final CvSink m_cvSink = new CvSink("VisionRunner CvSink");
+  private final P m_pipeline;
+  private final Mat m_image = new Mat();
+  private final Listener<? super P> m_listener;
+  private volatile boolean m_enabled = true;
+
+  /**
+   * Listener interface for a callback that should run after a pipeline has processed its input.
+   *
+   * @param <P> the type of the pipeline this listener is for
+   */
+  @FunctionalInterface
+  public interface Listener<P extends VisionPipeline> {
+    /**
+     * Called when the pipeline has run. This shouldn't take much time to run because it will delay
+     * later calls to the pipeline's {@link VisionPipeline#process process} method. Copying the
+     * outputs and code that uses the copies should be <i>synchronized</i> on the same mutex to
+     * prevent multiple threads from reading and writing to the same memory at the same time.
+     *
+     * @param pipeline the vision pipeline that ran
+     */
+    void copyPipelineOutputs(P pipeline);
+
+  }
+
+  /**
+   * Creates a new vision runner. It will take images from the {@code videoSource}, send them to
+   * the {@code pipeline}, and call the {@code listener} when the pipeline has finished to alert
+   * user code when it is safe to access the pipeline's outputs.
+   *
+   * @param videoSource the video source to use to supply images for the pipeline
+   * @param pipeline    the vision pipeline to run
+   * @param listener    a function to call after the pipeline has finished running
+   */
+  public VisionRunner(VideoSource videoSource, P pipeline, Listener<? super P> listener) {
+    this.m_pipeline = pipeline;
+    this.m_listener = listener;
+    m_cvSink.setSource(videoSource);
+  }
+
+  /**
+   * Runs the pipeline one time, giving it the next image from the video source specified
+   * in the constructor. This will block until the source either has an image or throws an error.
+   * If the source successfully supplied a frame, the pipeline's image input will be set,
+   * the pipeline will run, and the listener specified in the constructor will be called to notify
+   * it that the pipeline ran.
+   *
+   * <p>This method is exposed to allow teams to add additional functionality or have their own
+   * ways to run the pipeline. Most teams, however, should just use {@link #runForever} in its own
+   * thread using a {@link VisionThread}.</p>
+   */
+  public void runOnce() {
+    Long id = CameraServerSharedStore.getCameraServerShared().getRobotMainThreadId();
+
+    if (id != null && Thread.currentThread().getId() == id.longValue()) {
+      throw new IllegalStateException(
+          "VisionRunner.runOnce() cannot be called from the main robot thread");
+    }
+    runOnceInternal();
+  }
+
+  private void runOnceInternal() {
+    long frameTime = m_cvSink.grabFrame(m_image);
+    if (frameTime == 0) {
+      // There was an error, report it
+      String error = m_cvSink.getError();
+      CameraServerSharedStore.getCameraServerShared().reportDriverStationError(error);
+    } else {
+      // No errors, process the image
+      m_pipeline.process(m_image);
+      m_listener.copyPipelineOutputs(m_pipeline);
+    }
+  }
+
+  /**
+   * A convenience method that calls {@link #runOnce()} in an infinite loop. This must
+   * be run in a dedicated thread, and cannot be used in the main robot thread because
+   * it will freeze the robot program.
+   *
+   * <p><strong>Do not call this method directly from the main thread.</strong></p>
+   *
+   * @throws IllegalStateException if this is called from the main robot thread
+   * @see VisionThread
+   */
+  public void runForever() {
+    Long id = CameraServerSharedStore.getCameraServerShared().getRobotMainThreadId();
+
+    if (id != null && Thread.currentThread().getId() == id.longValue()) {
+      throw new IllegalStateException(
+          "VisionRunner.runForever() cannot be called from the main robot thread");
+    }
+    while (m_enabled && !Thread.interrupted()) {
+      runOnceInternal();
+    }
+  }
+
+  /**
+   * Stop a RunForever() loop.
+   */
+  public void stop() {
+    m_enabled = false;
+  }
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionThread.java b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionThread.java
new file mode 100644
index 0000000..576cb96
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/VisionThread.java
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.vision;
+
+import edu.wpi.cscore.VideoSource;
+
+/**
+ * A vision thread is a special thread that runs a vision pipeline. It is a <i>daemon</i> thread;
+ * it does not prevent the program from exiting when all other non-daemon threads
+ * have finished running.
+ *
+ * @see VisionPipeline
+ * @see VisionRunner
+ * @see Thread#setDaemon(boolean)
+ */
+public class VisionThread extends Thread {
+  /**
+   * Creates a vision thread that continuously runs a {@link VisionPipeline}.
+   *
+   * @param visionRunner the runner for a vision pipeline
+   */
+  public VisionThread(VisionRunner<?> visionRunner) {
+    super(visionRunner::runForever, "WPILib Vision Thread");
+    setDaemon(true);
+  }
+
+  /**
+   * Creates a new vision thread that continuously runs the given vision pipeline. This is
+   * equivalent to {@code new VisionThread(new VisionRunner<>(videoSource, pipeline, listener))}.
+   *
+   * @param videoSource the source for images the pipeline should process
+   * @param pipeline    the pipeline to run
+   * @param listener    the listener to copy outputs from the pipeline after it runs
+   * @param <P>         the type of the pipeline
+   */
+  public <P extends VisionPipeline> VisionThread(VideoSource videoSource,
+                                                 P pipeline,
+                                                 VisionRunner.Listener<? super P> listener) {
+    this(new VisionRunner<>(videoSource, pipeline, listener));
+  }
+
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java
new file mode 100644
index 0000000..e2e5c62
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/java/edu/wpi/first/vision/package-info.java
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/**
+ * Classes in the {@code edu.wpi.first.vision} package are designed to
+ * simplify using OpenCV vision processing code from a robot program.
+ *
+ * <p>An example use case for grabbing a yellow tote from 2015 in autonomous:
+ * <br>
+ * <pre><code>
+ * public class Robot extends IterativeRobot
+ *     implements VisionRunner.Listener&lt;MyFindTotePipeline&gt; {
+ *
+ *      // A USB camera connected to the roboRIO.
+ *      private {@link edu.wpi.cscore.VideoSource VideoSource} usbCamera;
+ *
+ *      // A vision pipeline. This could be handwritten or generated by GRIP.
+ *      // This has to implement {@link edu.wpi.first.vision.VisionPipeline}.
+ *      // For this example, assume that it's perfect and will always see the tote.
+ *      private MyFindTotePipeline findTotePipeline;
+ *      private {@link edu.wpi.first.vision.VisionThread} findToteThread;
+ *
+ *      // The object to synchronize on to make sure the vision thread doesn't
+ *      // write to variables the main thread is using.
+ *      private final Object visionLock = new Object();
+ *
+ *      // The pipeline outputs we want
+ *      private boolean pipelineRan = false; // lets us know when the pipeline has actually run
+ *      private double angleToTote = 0;
+ *      private double distanceToTote = 0;
+ *
+ *     {@literal @}Override
+ *      public void {@link edu.wpi.first.vision.VisionRunner.Listener#copyPipelineOutputs
+ *          copyPipelineOutputs(MyFindTotePipeline pipeline)} {
+ *          synchronized (visionLock) {
+ *              // Take a snapshot of the pipeline's output because
+ *              // it may have changed the next time this method is called!
+ *              this.pipelineRan = true;
+ *              this.angleToTote = pipeline.getAngleToTote();
+ *              this.distanceToTote = pipeline.getDistanceToTote();
+ *          }
+ *      }
+ *
+ *     {@literal @}Override
+ *      public void robotInit() {
+ *          usbCamera = CameraServer.getInstance().startAutomaticCapture(0);
+ *          findTotePipeline = new MyFindTotePipeline();
+ *          findToteThread = new VisionThread(usbCamera, findTotePipeline, this);
+ *      }
+ *
+ *     {@literal @}Override
+ *      public void autonomousInit() {
+ *          findToteThread.start();
+ *      }
+ *
+ *     {@literal @}Override
+ *      public void autonomousPeriodic() {
+ *          double angle;
+ *          double distance;
+ *          synchronized (visionLock) {
+ *              if (!pipelineRan) {
+ *                  // Wait until the pipeline has run
+ *                  return;
+ *              }
+ *              // Copy the outputs to make sure they're all from the same run
+ *              angle = this.angleToTote;
+ *              distance = this.distanceToTote;
+ *          }
+ *          if (!aimedAtTote()) {
+ *              turnToAngle(angle);
+ *          } else if (!droveToTote()) {
+ *              driveDistance(distance);
+ *          } else if (!grabbedTote()) {
+ *              grabTote();
+ *          } else {
+ *              // Tote was grabbed and we're done!
+ *              return;
+ *          }
+ *      }
+ *
+ * }
+ * </code></pre>
+ */
+package edu.wpi.first.vision;
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
new file mode 100644
index 0000000..3069d22
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp
@@ -0,0 +1,695 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "cameraserver/CameraServer.h"
+
+#include <atomic>
+#include <vector>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/DenseMap.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringMap.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "cameraserver/CameraServerShared.h"
+#include "ntcore_cpp.h"
+
+using namespace frc;
+
+static constexpr char const* kPublishName = "/CameraPublisher";
+
+struct CameraServer::Impl {
+  Impl();
+  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);
+  void UpdateStreamValues();
+
+  wpi::mutex m_mutex;
+  std::atomic<int> m_defaultUsbDevice;
+  std::string m_primarySourceName;
+  wpi::StringMap<cs::VideoSource> m_sources;
+  wpi::StringMap<cs::VideoSink> m_sinks;
+  wpi::DenseMap<CS_Source, std::shared_ptr<nt::NetworkTable>> m_tables;
+  std::shared_ptr<nt::NetworkTable> m_publishTable;
+  cs::VideoListener m_videoListener;
+  int m_tableListener;
+  int m_nextPort;
+  std::vector<std::string> m_addresses;
+};
+
+CameraServer* CameraServer::GetInstance() {
+  static CameraServer instance;
+  return &instance;
+}
+
+static wpi::StringRef MakeSourceValue(CS_Source source,
+                                      wpi::SmallVectorImpl<char>& buf) {
+  CS_Status status = 0;
+  buf.clear();
+  switch (cs::GetSourceKind(source, &status)) {
+    case cs::VideoSource::kUsb: {
+      wpi::StringRef prefix{"usb:"};
+      buf.append(prefix.begin(), prefix.end());
+      auto path = cs::GetUsbCameraPath(source, &status);
+      buf.append(path.begin(), path.end());
+      break;
+    }
+    case cs::VideoSource::kHttp: {
+      wpi::StringRef prefix{"ip:"};
+      buf.append(prefix.begin(), prefix.end());
+      auto urls = cs::GetHttpCameraUrls(source, &status);
+      if (!urls.empty()) buf.append(urls[0].begin(), urls[0].end());
+      break;
+    }
+    case cs::VideoSource::kCv:
+      return "cv:";
+    default:
+      return "unknown:";
+  }
+
+  return wpi::StringRef{buf.begin(), buf.size()};
+}
+
+static std::string MakeStreamValue(const wpi::Twine& address, int port) {
+  return ("mjpg:http://" + address + wpi::Twine(':') + wpi::Twine(port) +
+          "/?action=stream")
+      .str();
+}
+
+std::shared_ptr<nt::NetworkTable> CameraServer::Impl::GetSourceTable(
+    CS_Source source) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return m_tables.lookup(source);
+}
+
+std::vector<std::string> CameraServer::Impl::GetSinkStreamValues(CS_Sink sink) {
+  CS_Status status = 0;
+
+  // Ignore all but MjpegServer
+  if (cs::GetSinkKind(sink, &status) != CS_SINK_MJPEG)
+    return std::vector<std::string>{};
+
+  // Get port
+  int port = cs::GetMjpegServerPort(sink, &status);
+
+  // Generate values
+  std::vector<std::string> values;
+  auto listenAddress = cs::GetMjpegServerListenAddress(sink, &status);
+  if (!listenAddress.empty()) {
+    // If a listen address is specified, only use that
+    values.emplace_back(MakeStreamValue(listenAddress, port));
+  } else {
+    // Otherwise generate for hostname and all interface addresses
+    values.emplace_back(MakeStreamValue(cs::GetHostname() + ".local", port));
+
+    for (const auto& addr : m_addresses) {
+      if (addr == "127.0.0.1") continue;  // ignore localhost
+      values.emplace_back(MakeStreamValue(addr, port));
+    }
+  }
+
+  return values;
+}
+
+std::vector<std::string> CameraServer::Impl::GetSourceStreamValues(
+    CS_Source source) {
+  CS_Status status = 0;
+
+  // Ignore all but HttpCamera
+  if (cs::GetSourceKind(source, &status) != CS_SOURCE_HTTP)
+    return std::vector<std::string>{};
+
+  // Generate values
+  auto values = cs::GetHttpCameraUrls(source, &status);
+  for (auto& value : values) value = "mjpg:" + value;
+
+  // Look to see if we have a passthrough server for this source
+  for (const auto& i : m_sinks) {
+    CS_Sink sink = i.second.GetHandle();
+    CS_Source sinkSource = cs::GetSinkSource(sink, &status);
+    if (source == sinkSource &&
+        cs::GetSinkKind(sink, &status) == CS_SINK_MJPEG) {
+      // Add USB-only passthrough
+      int port = cs::GetMjpegServerPort(sink, &status);
+      values.emplace_back(MakeStreamValue("172.22.11.2", port));
+      break;
+    }
+  }
+
+  // Set table value
+  return values;
+}
+
+void CameraServer::Impl::UpdateStreamValues() {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  // Over all the sinks...
+  for (const auto& i : m_sinks) {
+    CS_Status status = 0;
+    CS_Sink sink = i.second.GetHandle();
+
+    // Get the source's subtable (if none exists, we're done)
+    CS_Source source = cs::GetSinkSource(sink, &status);
+    if (source == 0) continue;
+    auto table = m_tables.lookup(source);
+    if (table) {
+      // Don't set stream values if this is a HttpCamera passthrough
+      if (cs::GetSourceKind(source, &status) == CS_SOURCE_HTTP) continue;
+
+      // Set table value
+      auto values = GetSinkStreamValues(sink);
+      if (!values.empty()) table->GetEntry("streams").SetStringArray(values);
+    }
+  }
+
+  // Over all the sources...
+  for (const auto& i : m_sources) {
+    CS_Source source = i.second.GetHandle();
+
+    // Get the source's subtable (if none exists, we're done)
+    auto table = m_tables.lookup(source);
+    if (table) {
+      // Set table value
+      auto values = GetSourceStreamValues(source);
+      if (!values.empty()) table->GetEntry("streams").SetStringArray(values);
+    }
+  }
+}
+
+static std::string PixelFormatToString(int pixelFormat) {
+  switch (pixelFormat) {
+    case cs::VideoMode::PixelFormat::kMJPEG:
+      return "MJPEG";
+    case cs::VideoMode::PixelFormat::kYUYV:
+      return "YUYV";
+    case cs::VideoMode::PixelFormat::kRGB565:
+      return "RGB565";
+    case cs::VideoMode::PixelFormat::kBGR:
+      return "BGR";
+    case cs::VideoMode::PixelFormat::kGray:
+      return "Gray";
+    default:
+      return "Unknown";
+  }
+}
+
+static std::string VideoModeToString(const cs::VideoMode& mode) {
+  std::string rv;
+  wpi::raw_string_ostream oss{rv};
+  oss << mode.width << "x" << mode.height;
+  oss << " " << PixelFormatToString(mode.pixelFormat) << " ";
+  oss << mode.fps << " fps";
+  return oss.str();
+}
+
+static std::vector<std::string> GetSourceModeValues(int source) {
+  std::vector<std::string> rv;
+  CS_Status status = 0;
+  for (const auto& mode : cs::EnumerateSourceVideoModes(source, &status))
+    rv.emplace_back(VideoModeToString(mode));
+  return rv;
+}
+
+static void PutSourcePropertyValue(nt::NetworkTable* table,
+                                   const cs::VideoEvent& event, bool isNew) {
+  wpi::SmallString<64> name;
+  wpi::SmallString<64> infoName;
+  if (wpi::StringRef{event.name}.startswith("raw_")) {
+    name = "RawProperty/";
+    name += event.name;
+    infoName = "RawPropertyInfo/";
+    infoName += event.name;
+  } else {
+    name = "Property/";
+    name += event.name;
+    infoName = "PropertyInfo/";
+    infoName += event.name;
+  }
+
+  wpi::SmallString<64> buf;
+  CS_Status status = 0;
+  nt::NetworkTableEntry entry = table->GetEntry(name);
+  switch (event.propertyKind) {
+    case cs::VideoProperty::kBoolean:
+      if (isNew)
+        entry.SetDefaultBoolean(event.value != 0);
+      else
+        entry.SetBoolean(event.value != 0);
+      break;
+    case cs::VideoProperty::kInteger:
+    case cs::VideoProperty::kEnum:
+      if (isNew) {
+        entry.SetDefaultDouble(event.value);
+        table->GetEntry(infoName + "/min")
+            .SetDouble(cs::GetPropertyMin(event.propertyHandle, &status));
+        table->GetEntry(infoName + "/max")
+            .SetDouble(cs::GetPropertyMax(event.propertyHandle, &status));
+        table->GetEntry(infoName + "/step")
+            .SetDouble(cs::GetPropertyStep(event.propertyHandle, &status));
+        table->GetEntry(infoName + "/default")
+            .SetDouble(cs::GetPropertyDefault(event.propertyHandle, &status));
+      } else {
+        entry.SetDouble(event.value);
+      }
+      break;
+    case cs::VideoProperty::kString:
+      if (isNew)
+        entry.SetDefaultString(event.valueStr);
+      else
+        entry.SetString(event.valueStr);
+      break;
+    default:
+      break;
+  }
+}
+
+CameraServer::Impl::Impl()
+    : m_publishTable{nt::NetworkTableInstance::GetDefault().GetTable(
+          kPublishName)},
+      m_nextPort(kBasePort) {
+  // 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 = cs::VideoListener{
+      [=](const cs::VideoEvent& event) {
+        CS_Status status = 0;
+        switch (event.kind) {
+          case cs::VideoEvent::kSourceCreated: {
+            // Create subtable for the camera
+            auto table = m_publishTable->GetSubTable(event.name);
+            {
+              std::lock_guard<wpi::mutex> lock(m_mutex);
+              m_tables.insert(std::make_pair(event.sourceHandle, table));
+            }
+            wpi::SmallString<64> buf;
+            table->GetEntry("source").SetString(
+                MakeSourceValue(event.sourceHandle, buf));
+            wpi::SmallString<64> descBuf;
+            table->GetEntry("description")
+                .SetString(cs::GetSourceDescription(event.sourceHandle, descBuf,
+                                                    &status));
+            table->GetEntry("connected")
+                .SetBoolean(cs::IsSourceConnected(event.sourceHandle, &status));
+            table->GetEntry("streams").SetStringArray(
+                GetSourceStreamValues(event.sourceHandle));
+            auto mode = cs::GetSourceVideoMode(event.sourceHandle, &status);
+            table->GetEntry("mode").SetDefaultString(VideoModeToString(mode));
+            table->GetEntry("modes").SetStringArray(
+                GetSourceModeValues(event.sourceHandle));
+            break;
+          }
+          case cs::VideoEvent::kSourceDestroyed: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) {
+              table->GetEntry("source").SetString("");
+              table->GetEntry("streams").SetStringArray(
+                  std::vector<std::string>{});
+              table->GetEntry("modes").SetStringArray(
+                  std::vector<std::string>{});
+            }
+            break;
+          }
+          case cs::VideoEvent::kSourceConnected: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) {
+              // update the description too (as it may have changed)
+              wpi::SmallString<64> descBuf;
+              table->GetEntry("description")
+                  .SetString(cs::GetSourceDescription(event.sourceHandle,
+                                                      descBuf, &status));
+              table->GetEntry("connected").SetBoolean(true);
+            }
+            break;
+          }
+          case cs::VideoEvent::kSourceDisconnected: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) table->GetEntry("connected").SetBoolean(false);
+            break;
+          }
+          case cs::VideoEvent::kSourceVideoModesUpdated: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table)
+              table->GetEntry("modes").SetStringArray(
+                  GetSourceModeValues(event.sourceHandle));
+            break;
+          }
+          case cs::VideoEvent::kSourceVideoModeChanged: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table)
+              table->GetEntry("mode").SetString(VideoModeToString(event.mode));
+            break;
+          }
+          case cs::VideoEvent::kSourcePropertyCreated: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) PutSourcePropertyValue(table.get(), event, true);
+            break;
+          }
+          case cs::VideoEvent::kSourcePropertyValueUpdated: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) PutSourcePropertyValue(table.get(), event, false);
+            break;
+          }
+          case cs::VideoEvent::kSourcePropertyChoicesUpdated: {
+            auto table = GetSourceTable(event.sourceHandle);
+            if (table) {
+              wpi::SmallString<64> name{"PropertyInfo/"};
+              name += event.name;
+              name += "/choices";
+              auto choices =
+                  cs::GetEnumPropertyChoices(event.propertyHandle, &status);
+              table->GetEntry(name).SetStringArray(choices);
+            }
+            break;
+          }
+          case cs::VideoEvent::kSinkSourceChanged:
+          case cs::VideoEvent::kSinkCreated:
+          case cs::VideoEvent::kSinkDestroyed:
+          case cs::VideoEvent::kNetworkInterfacesChanged: {
+            m_addresses = cs::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.
+  wpi::SmallString<64> buf;
+  m_tableListener = nt::NetworkTableInstance::GetDefault().AddEntryListener(
+      kPublishName + wpi::Twine('/'),
+      [=](const nt::EntryNotification& event) {
+        wpi::StringRef relativeKey =
+            event.name.substr(wpi::StringRef(kPublishName).size() + 1);
+
+        // get source (sourceName/...)
+        auto subKeyIndex = relativeKey.find('/');
+        if (subKeyIndex == wpi::StringRef::npos) return;
+        wpi::StringRef sourceName = relativeKey.slice(0, subKeyIndex);
+        auto sourceIt = m_sources.find(sourceName);
+        if (sourceIt == m_sources.end()) return;
+
+        // get subkey
+        relativeKey = relativeKey.substr(subKeyIndex + 1);
+
+        // handle standard names
+        wpi::StringRef propName;
+        nt::NetworkTableEntry entry{event.entry};
+        if (relativeKey == "mode") {
+          // reset to current mode
+          entry.SetString(VideoModeToString(sourceIt->second.GetVideoMode()));
+          return;
+        } else if (relativeKey.startswith("Property/")) {
+          propName = relativeKey.substr(9);
+        } else if (relativeKey.startswith("RawProperty/")) {
+          propName = relativeKey.substr(12);
+        } else {
+          return;  // ignore
+        }
+
+        // everything else is a property
+        auto property = sourceIt->second.GetProperty(propName);
+        switch (property.GetKind()) {
+          case cs::VideoProperty::kNone:
+            return;
+          case cs::VideoProperty::kBoolean:
+            entry.SetBoolean(property.Get() != 0);
+            return;
+          case cs::VideoProperty::kInteger:
+          case cs::VideoProperty::kEnum:
+            entry.SetDouble(property.Get());
+            return;
+          case cs::VideoProperty::kString:
+            entry.SetString(property.GetString());
+            return;
+          default:
+            return;
+        }
+      },
+      NT_NOTIFY_IMMEDIATE | NT_NOTIFY_UPDATE);
+}
+
+CameraServer::CameraServer() : m_impl(new Impl) {}
+
+CameraServer::~CameraServer() {}
+
+cs::UsbCamera CameraServer::StartAutomaticCapture() {
+  cs::UsbCamera camera = StartAutomaticCapture(m_impl->m_defaultUsbDevice++);
+  auto csShared = GetCameraServerShared();
+  csShared->ReportUsbCamera(camera.GetHandle());
+  return camera;
+}
+
+cs::UsbCamera CameraServer::StartAutomaticCapture(int dev) {
+  cs::UsbCamera camera{"USB Camera " + wpi::Twine(dev), dev};
+  StartAutomaticCapture(camera);
+  auto csShared = GetCameraServerShared();
+  csShared->ReportUsbCamera(camera.GetHandle());
+  return camera;
+}
+
+cs::UsbCamera CameraServer::StartAutomaticCapture(const wpi::Twine& name,
+                                                  int dev) {
+  cs::UsbCamera camera{name, dev};
+  StartAutomaticCapture(camera);
+  auto csShared = GetCameraServerShared();
+  csShared->ReportUsbCamera(camera.GetHandle());
+  return camera;
+}
+
+cs::UsbCamera CameraServer::StartAutomaticCapture(const wpi::Twine& name,
+                                                  const wpi::Twine& path) {
+  cs::UsbCamera camera{name, path};
+  StartAutomaticCapture(camera);
+  auto csShared = GetCameraServerShared();
+  csShared->ReportUsbCamera(camera.GetHandle());
+  return camera;
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const wpi::Twine& host) {
+  return AddAxisCamera("Axis Camera", host);
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const char* host) {
+  return AddAxisCamera("Axis Camera", host);
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const std::string& host) {
+  return AddAxisCamera("Axis Camera", host);
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(wpi::ArrayRef<std::string> hosts) {
+  return AddAxisCamera("Axis Camera", hosts);
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const wpi::Twine& name,
+                                           const wpi::Twine& host) {
+  cs::AxisCamera camera{name, host};
+  StartAutomaticCapture(camera);
+  auto csShared = GetCameraServerShared();
+  csShared->ReportAxisCamera(camera.GetHandle());
+  return camera;
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const wpi::Twine& name,
+                                           const char* host) {
+  cs::AxisCamera camera{name, host};
+  StartAutomaticCapture(camera);
+  auto csShared = GetCameraServerShared();
+  csShared->ReportAxisCamera(camera.GetHandle());
+  return camera;
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const wpi::Twine& name,
+                                           const std::string& host) {
+  cs::AxisCamera camera{name, host};
+  StartAutomaticCapture(camera);
+  auto csShared = GetCameraServerShared();
+  csShared->ReportAxisCamera(camera.GetHandle());
+  return camera;
+}
+
+cs::AxisCamera CameraServer::AddAxisCamera(const wpi::Twine& name,
+                                           wpi::ArrayRef<std::string> hosts) {
+  cs::AxisCamera camera{name, hosts};
+  StartAutomaticCapture(camera);
+  auto csShared = GetCameraServerShared();
+  csShared->ReportAxisCamera(camera.GetHandle());
+  return camera;
+}
+
+cs::MjpegServer CameraServer::StartAutomaticCapture(
+    const cs::VideoSource& camera) {
+  AddCamera(camera);
+  auto server = AddServer(wpi::Twine("serve_") + camera.GetName());
+  server.SetSource(camera);
+  return server;
+}
+
+cs::CvSink CameraServer::GetVideo() {
+  cs::VideoSource source;
+  {
+    auto csShared = GetCameraServerShared();
+    std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+    if (m_impl->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()) {
+      csShared->SetCameraServerError("no camera available");
+      return cs::CvSink{};
+    }
+    source = it->second;
+  }
+  return GetVideo(std::move(source));
+}
+
+cs::CvSink CameraServer::GetVideo(const cs::VideoSource& camera) {
+  wpi::SmallString<64> name{"opencv_"};
+  name += camera.GetName();
+
+  {
+    std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+    auto it = m_impl->m_sinks.find(name);
+    if (it != m_impl->m_sinks.end()) {
+      auto kind = it->second.GetKind();
+      if (kind != cs::VideoSink::kCv) {
+        auto csShared = GetCameraServerShared();
+        csShared->SetCameraServerError("expected OpenCV sink, but got " +
+                                       wpi::Twine(kind));
+        return cs::CvSink{};
+      }
+      return *static_cast<cs::CvSink*>(&it->second);
+    }
+  }
+
+  cs::CvSink newsink{name};
+  newsink.SetSource(camera);
+  AddServer(newsink);
+  return newsink;
+}
+
+cs::CvSink CameraServer::GetVideo(const wpi::Twine& name) {
+  wpi::SmallString<64> nameBuf;
+  wpi::StringRef nameStr = name.toStringRef(nameBuf);
+  cs::VideoSource source;
+  {
+    std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+    auto it = m_impl->m_sources.find(nameStr);
+    if (it == m_impl->m_sources.end()) {
+      auto csShared = GetCameraServerShared();
+      csShared->SetCameraServerError("could not find camera " + nameStr);
+      return cs::CvSink{};
+    }
+    source = it->second;
+  }
+  return GetVideo(source);
+}
+
+cs::CvSource CameraServer::PutVideo(const wpi::Twine& name, int width,
+                                    int height) {
+  cs::CvSource source{name, cs::VideoMode::kMJPEG, width, height, 30};
+  StartAutomaticCapture(source);
+  return source;
+}
+
+cs::MjpegServer CameraServer::AddServer(const wpi::Twine& name) {
+  int port;
+  {
+    std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+    port = m_impl->m_nextPort++;
+  }
+  return AddServer(name, port);
+}
+
+cs::MjpegServer CameraServer::AddServer(const wpi::Twine& name, int port) {
+  cs::MjpegServer server{name, port};
+  AddServer(server);
+  return server;
+}
+
+void CameraServer::AddServer(const cs::VideoSink& server) {
+  std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+  m_impl->m_sinks.try_emplace(server.GetName(), server);
+}
+
+void CameraServer::RemoveServer(const wpi::Twine& name) {
+  std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+  wpi::SmallString<64> nameBuf;
+  m_impl->m_sinks.erase(name.toStringRef(nameBuf));
+}
+
+cs::VideoSink CameraServer::GetServer() {
+  wpi::SmallString<64> name;
+  {
+    std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+    if (m_impl->m_primarySourceName.empty()) {
+      auto csShared = GetCameraServerShared();
+      csShared->SetCameraServerError("no camera available");
+      return cs::VideoSink{};
+    }
+    name = "serve_";
+    name += m_impl->m_primarySourceName;
+  }
+  return GetServer(name);
+}
+
+cs::VideoSink CameraServer::GetServer(const wpi::Twine& name) {
+  wpi::SmallString<64> nameBuf;
+  wpi::StringRef nameStr = name.toStringRef(nameBuf);
+  std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+  auto it = m_impl->m_sinks.find(nameStr);
+  if (it == m_impl->m_sinks.end()) {
+    auto csShared = GetCameraServerShared();
+    csShared->SetCameraServerError("could not find server " + nameStr);
+    return cs::VideoSink{};
+  }
+  return it->second;
+}
+
+void CameraServer::AddCamera(const cs::VideoSource& camera) {
+  std::string name = camera.GetName();
+  std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+  if (m_impl->m_primarySourceName.empty()) m_impl->m_primarySourceName = name;
+  m_impl->m_sources.try_emplace(name, camera);
+}
+
+void CameraServer::RemoveCamera(const wpi::Twine& name) {
+  std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+  wpi::SmallString<64> nameBuf;
+  m_impl->m_sources.erase(name.toStringRef(nameBuf));
+}
+
+void CameraServer::SetSize(int size) {
+  std::lock_guard<wpi::mutex> lock(m_impl->m_mutex);
+  if (m_impl->m_primarySourceName.empty()) return;
+  auto it = m_impl->m_sources.find(m_impl->m_primarySourceName);
+  if (it == m_impl->m_sources.end()) return;
+  if (size == kSize160x120)
+    it->second.SetResolution(160, 120);
+  else if (size == kSize320x240)
+    it->second.SetResolution(320, 240);
+  else if (size == kSize640x480)
+    it->second.SetResolution(640, 480);
+}
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp b/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp
new file mode 100644
index 0000000..97ab090
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "cameraserver/CameraServerShared.h"
+
+#include <wpi/mutex.h>
+
+namespace {
+class DefaultCameraServerShared : public frc::CameraServerShared {
+ public:
+  void ReportUsbCamera(int id) override {}
+  void ReportAxisCamera(int id) override {}
+  void ReportVideoServer(int id) override {}
+  void SetCameraServerError(const wpi::Twine& error) override {}
+  void SetVisionRunnerError(const wpi::Twine& error) override {}
+  void ReportDriverStationError(const wpi::Twine& error) override {}
+  std::pair<std::thread::id, bool> GetRobotMainThreadId() const override {
+    return std::make_pair(std::thread::id(), false);
+  }
+};
+}  // namespace
+
+namespace frc {
+
+static std::unique_ptr<CameraServerShared> cameraServerShared = nullptr;
+static wpi::mutex setLock;
+
+void SetCameraServerShared(std::unique_ptr<CameraServerShared> shared) {
+  std::unique_lock<wpi::mutex> lock(setLock);
+  cameraServerShared = std::move(shared);
+}
+CameraServerShared* GetCameraServerShared() {
+  std::unique_lock<wpi::mutex> lock(setLock);
+  if (!cameraServerShared) {
+    cameraServerShared = std::make_unique<DefaultCameraServerShared>();
+  }
+  return cameraServerShared.get();
+}
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/vision/VisionRunner.cpp b/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/vision/VisionRunner.cpp
new file mode 100644
index 0000000..9896bbd
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/cpp/vision/VisionRunner.cpp
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "vision/VisionRunner.h"
+
+#include <thread>
+
+#include <opencv2/core/mat.hpp>
+
+#include "cameraserver/CameraServerShared.h"
+
+using namespace frc;
+
+VisionRunnerBase::VisionRunnerBase(cs::VideoSource videoSource)
+    : m_image(std::make_unique<cv::Mat>()),
+      m_cvSink("VisionRunner CvSink"),
+      m_enabled(true) {
+  m_cvSink.SetSource(videoSource);
+}
+
+// Located here and not in header due to cv::Mat forward declaration.
+VisionRunnerBase::~VisionRunnerBase() {}
+
+void VisionRunnerBase::RunOnce() {
+  auto csShared = frc::GetCameraServerShared();
+  auto res = csShared->GetRobotMainThreadId();
+  if (res.second && (std::this_thread::get_id() == res.first)) {
+    csShared->SetVisionRunnerError(
+        "VisionRunner::RunOnce() cannot be called from the main robot thread");
+    return;
+  }
+  auto frameTime = m_cvSink.GrabFrame(*m_image);
+  if (frameTime == 0) {
+    auto error = m_cvSink.GetError();
+    csShared->ReportDriverStationError(error);
+  } else {
+    DoProcess(*m_image);
+  }
+}
+
+void VisionRunnerBase::RunForever() {
+  auto csShared = frc::GetCameraServerShared();
+  auto res = csShared->GetRobotMainThreadId();
+  if (res.second && (std::this_thread::get_id() == res.first)) {
+    csShared->SetVisionRunnerError(
+        "VisionRunner::RunForever() cannot be called from the main robot "
+        "thread");
+    return;
+  }
+  while (m_enabled) {
+    RunOnce();
+  }
+}
+
+void VisionRunnerBase::Stop() { m_enabled = false; }
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/include/CameraServer.h b/third_party/allwpilib_2019/cameraserver/src/main/native/include/CameraServer.h
new file mode 100644
index 0000000..2fcc0f2
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/include/CameraServer.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: CameraServer.h is deprecated; include cameraserver/CameraServer.h instead"
+#else
+#warning "CameraServer.h is deprecated; include cameraserver/CameraServer.h instead"
+#endif
+
+// clang-format on
+
+#include "cameraserver/CameraServer.h"
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
new file mode 100644
index 0000000..42a9f0c
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServer.h
@@ -0,0 +1,289 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <string>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/Twine.h>
+
+#include "cscore.h"
+
+namespace frc {
+
+/**
+ * Singleton class for creating and keeping camera servers.
+ *
+ * Also publishes camera information to NetworkTables.
+ */
+class CameraServer {
+ public:
+  static constexpr uint16_t kBasePort = 1181;
+  static constexpr int kSize640x480 = 0;
+  static constexpr int kSize320x240 = 1;
+  static constexpr int kSize160x120 = 2;
+
+  /**
+   * Get the CameraServer instance.
+   */
+  static CameraServer* GetInstance();
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * You should call this method to see a camera feed on the dashboard. If you
+   * also want to perform vision processing on the roboRIO, use getVideo() to
+   * get access to the camera images.
+   *
+   * The first time this overload is called, it calls StartAutomaticCapture()
+   * with device 0, creating a camera named "USB Camera 0".  Subsequent calls
+   * increment the device number (e.g. 1, 2, etc).
+   */
+  cs::UsbCamera StartAutomaticCapture();
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * This overload calls StartAutomaticCapture() with a name of "USB Camera
+   * {dev}".
+   *
+   * @param dev The device number of the camera interface
+   */
+  cs::UsbCamera StartAutomaticCapture(int dev);
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * @param name The name to give the camera
+   * @param dev  The device number of the camera interface
+   */
+  cs::UsbCamera StartAutomaticCapture(const wpi::Twine& name, int dev);
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * @param name The name to give the camera
+   * @param path The device path (e.g. "/dev/video0") of the camera
+   */
+  cs::UsbCamera StartAutomaticCapture(const wpi::Twine& name,
+                                      const wpi::Twine& path);
+
+  /**
+   * Start automatically capturing images to send to the dashboard from
+   * an existing camera.
+   *
+   * @param camera Camera
+   */
+  cs::MjpegServer StartAutomaticCapture(const cs::VideoSource& camera);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * This overload calls AddAxisCamera() with name "Axis Camera".
+   *
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(const wpi::Twine& host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * This overload calls AddAxisCamera() with name "Axis Camera".
+   *
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(const char* host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * This overload calls AddAxisCamera() with name "Axis Camera".
+   *
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  cs::AxisCamera AddAxisCamera(const std::string& host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * This overload calls AddAxisCamera() with name "Axis Camera".
+   *
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  cs::AxisCamera AddAxisCamera(wpi::ArrayRef<std::string> hosts);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * This overload calls AddAxisCamera() with name "Axis Camera".
+   *
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  template <typename T>
+  cs::AxisCamera AddAxisCamera(std::initializer_list<T> hosts);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @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(const wpi::Twine& name, const wpi::Twine& host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @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(const wpi::Twine& name, const char* host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @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(const wpi::Twine& name, const std::string& host);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  cs::AxisCamera AddAxisCamera(const wpi::Twine& name,
+                               wpi::ArrayRef<std::string> hosts);
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  template <typename T>
+  cs::AxisCamera AddAxisCamera(const wpi::Twine& name,
+                               std::initializer_list<T> hosts);
+
+  /**
+   * Get OpenCV access to the primary camera feed.  This allows you to
+   * get images from the camera for image processing on the roboRIO.
+   *
+   * <p>This is only valid to call after a camera feed has been added
+   * with startAutomaticCapture() or addServer().
+   */
+  cs::CvSink GetVideo();
+
+  /**
+   * Get OpenCV access to the specified camera.  This allows you to get
+   * images from the camera for image processing on the roboRIO.
+   *
+   * @param camera Camera (e.g. as returned by startAutomaticCapture).
+   */
+  cs::CvSink GetVideo(const cs::VideoSource& camera);
+
+  /**
+   * Get OpenCV access to the specified camera.  This allows you to get
+   * images from the camera for image processing on the roboRIO.
+   *
+   * @param name Camera name
+   */
+  cs::CvSink GetVideo(const wpi::Twine& name);
+
+  /**
+   * Create a MJPEG stream with OpenCV input. This can be called to pass custom
+   * annotated images to the dashboard.
+   *
+   * @param name Name to give the stream
+   * @param width Width of the image being sent
+   * @param height Height of the image being sent
+   */
+  cs::CvSource PutVideo(const wpi::Twine& name, int width, int height);
+
+  /**
+   * Adds a MJPEG server at the next available port.
+   *
+   * @param name Server name
+   */
+  cs::MjpegServer AddServer(const wpi::Twine& name);
+
+  /**
+   * Adds a MJPEG server.
+   *
+   * @param name Server name
+   */
+  cs::MjpegServer AddServer(const wpi::Twine& name, int port);
+
+  /**
+   * Adds an already created server.
+   *
+   * @param server Server
+   */
+  void AddServer(const cs::VideoSink& server);
+
+  /**
+   * Removes a server by name.
+   *
+   * @param name Server name
+   */
+  void RemoveServer(const wpi::Twine& name);
+
+  /**
+   * Get server for the primary camera feed.
+   *
+   * This is only valid to call after a camera feed has been added with
+   * StartAutomaticCapture() or AddServer().
+   */
+  cs::VideoSink GetServer();
+
+  /**
+   * Gets a server by name.
+   *
+   * @param name Server name
+   */
+  cs::VideoSink GetServer(const wpi::Twine& name);
+
+  /**
+   * Adds an already created camera.
+   *
+   * @param camera Camera
+   */
+  void AddCamera(const cs::VideoSource& camera);
+
+  /**
+   * Removes a camera by name.
+   *
+   * @param name Camera name
+   */
+  void RemoveCamera(const wpi::Twine& name);
+
+  /**
+   * Sets the size of the image to use. Use the public kSize constants to set
+   * the correct mode, or set it directly on a camera and call the appropriate
+   * StartAutomaticCapture method.
+   *
+   * @deprecated Use SetResolution on the UsbCamera returned by
+   *             StartAutomaticCapture() instead.
+   * @param size The size to use
+   */
+  void SetSize(int size);
+
+ private:
+  CameraServer();
+  ~CameraServer();
+
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace frc
+
+#include "cameraserver/CameraServer.inc"
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServer.inc b/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServer.inc
new file mode 100644
index 0000000..5daf29f
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServer.inc
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+#include <vector>
+
+namespace frc {
+
+template <typename T>
+inline cs::AxisCamera CameraServer::AddAxisCamera(
+    std::initializer_list<T> hosts) {
+  return AddAxisCamera("Axis Camera", hosts);
+}
+
+template <typename T>
+inline cs::AxisCamera CameraServer::AddAxisCamera(
+    const wpi::Twine& name, std::initializer_list<T> hosts) {
+  std::vector<std::string> vec;
+  vec.reserve(hosts.size());
+  for (const auto& host : hosts) vec.emplace_back(host);
+  return AddAxisCamera(name, vec);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h b/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h
new file mode 100644
index 0000000..72b784e
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/include/cameraserver/CameraServerShared.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <thread>
+#include <utility>
+
+#include <wpi/Twine.h>
+
+namespace frc {
+class CameraServerShared {
+ public:
+  virtual ~CameraServerShared() = default;
+  virtual void ReportUsbCamera(int id) = 0;
+  virtual void ReportAxisCamera(int id) = 0;
+  virtual void ReportVideoServer(int id) = 0;
+  virtual void SetCameraServerError(const wpi::Twine& error) = 0;
+  virtual void SetVisionRunnerError(const wpi::Twine& error) = 0;
+  virtual void ReportDriverStationError(const wpi::Twine& error) = 0;
+  virtual std::pair<std::thread::id, bool> GetRobotMainThreadId() const = 0;
+};
+
+void SetCameraServerShared(std::unique_ptr<CameraServerShared> shared);
+CameraServerShared* GetCameraServerShared();
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionPipeline.h b/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionPipeline.h
new file mode 100644
index 0000000..de8e54c
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionPipeline.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace cv {
+class Mat;
+}  // namespace cv
+
+namespace frc {
+
+/**
+ * A vision pipeline is responsible for running a group of OpenCV algorithms to
+ * extract data from an image.
+ *
+ * @see VisionRunner
+ */
+class VisionPipeline {
+ public:
+  virtual ~VisionPipeline() = default;
+
+  /**
+   * Processes the image input and sets the result objects. Implementations
+   * should make these objects accessible.
+   */
+  virtual void Process(cv::Mat& mat) = 0;
+};
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionRunner.h b/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionRunner.h
new file mode 100644
index 0000000..a317f80
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionRunner.h
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <functional>
+#include <memory>
+
+#include "cscore.h"
+#include "vision/VisionPipeline.h"
+
+namespace frc {
+
+/**
+ * Non-template base class for VisionRunner.
+ */
+class VisionRunnerBase {
+ public:
+  /**
+   * Creates a new vision runner. It will take images from the {@code
+   * videoSource}, and call the virtual DoProcess() method.
+   *
+   * @param videoSource the video source to use to supply images for the
+   *                    pipeline
+   */
+  explicit VisionRunnerBase(cs::VideoSource videoSource);
+
+  ~VisionRunnerBase();
+
+  VisionRunnerBase(const VisionRunnerBase&) = delete;
+  VisionRunnerBase& operator=(const VisionRunnerBase&) = delete;
+
+  /**
+   * Runs the pipeline one time, giving it the next image from the video source
+   * specified in the constructor. This will block until the source either has
+   * an image or throws an error. If the source successfully supplied a frame,
+   * the pipeline's image input will be set, the pipeline will run, and the
+   * listener specified in the constructor will be called to notify it that the
+   * pipeline ran. This must be run in a dedicated thread, and cannot be used in
+   * the main robot thread because it will freeze the robot program.
+   *
+   * <p>This method is exposed to allow teams to add additional functionality or
+   * have their own ways to run the pipeline. Most teams, however, should just
+   * use {@link #runForever} in its own thread using a std::thread.</p>
+   */
+  void RunOnce();
+
+  /**
+   * A convenience method that calls {@link #runOnce()} in an infinite loop.
+   * This must be run in a dedicated thread, and cannot be used in the main
+   * robot thread because it will freeze the robot program.
+   *
+   * <strong>Do not call this method directly from the main thread.</strong>
+   */
+  void RunForever();
+
+  /**
+   * Stop a RunForever() loop.
+   */
+  void Stop();
+
+ protected:
+  virtual void DoProcess(cv::Mat& image) = 0;
+
+ private:
+  std::unique_ptr<cv::Mat> m_image;
+  cs::CvSink m_cvSink;
+  std::atomic_bool m_enabled;
+};
+
+/**
+ * A vision runner is a convenient wrapper object to make it easy to run vision
+ * pipelines from robot code. The easiest way to use this is to run it in a
+ * std::thread and use the listener to take snapshots of the pipeline's outputs.
+ *
+ * @see VisionPipeline
+ */
+template <typename T>
+class VisionRunner : public VisionRunnerBase {
+ public:
+  VisionRunner(cs::VideoSource videoSource, T* pipeline,
+               std::function<void(T&)> listener);
+  virtual ~VisionRunner() = default;
+
+ protected:
+  void DoProcess(cv::Mat& image) override;
+
+ private:
+  T* m_pipeline;
+  std::function<void(T&)> m_listener;
+};
+}  // namespace frc
+
+#include "VisionRunner.inc"
diff --git a/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionRunner.inc b/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionRunner.inc
new file mode 100644
index 0000000..1a38048
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/main/native/include/vision/VisionRunner.inc
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Creates a new vision runner. It will take images from the {@code
+ * videoSource}, send them to the {@code pipeline}, and call the {@code
+ * listener} when the pipeline has finished to alert user code when it is safe
+ * to access the pipeline's outputs.
+ *
+ * @param videoSource The video source to use to supply images for the pipeline
+ * @param pipeline    The vision pipeline to run
+ * @param listener    A function to call after the pipeline has finished running
+ */
+template <typename T>
+VisionRunner<T>::VisionRunner(cs::VideoSource videoSource, T* pipeline,
+                              std::function<void(T&)> listener)
+    : VisionRunnerBase(videoSource),
+      m_pipeline(pipeline),
+      m_listener(listener) {}
+
+template <typename T>
+void VisionRunner<T>::DoProcess(cv::Mat& image) {
+  m_pipeline->Process(image);
+  m_listener(*m_pipeline);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/cameraserver/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/cameraserver/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..f07ede3
--- /dev/null
+++ b/third_party/allwpilib_2019/cameraserver/src/test/native/cpp/main.cpp
@@ -0,0 +1,8 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+int main() { return 0; }
diff --git a/third_party/allwpilib_2019/cmake/modules/GenResources.cmake b/third_party/allwpilib_2019/cmake/modules/GenResources.cmake
new file mode 100644
index 0000000..2b2386f
--- /dev/null
+++ b/third_party/allwpilib_2019/cmake/modules/GenResources.cmake
@@ -0,0 +1,25 @@
+MACRO(GENERATE_RESOURCES inputDir outputDir prefix namespace outputFiles)
+  FILE(GLOB inputFiles ${inputDir}/*)
+  SET(${outputFiles})
+  FOREACH(input ${inputFiles})
+    GET_FILENAME_COMPONENT(inputBase ${input} NAME)
+    IF("${inputBase}" MATCHES "^\\.")
+      CONTINUE()
+    ENDIF()
+    SET(output "${outputDir}/${inputBase}.cpp")
+    LIST(APPEND ${outputFiles} "${output}")
+
+    ADD_CUSTOM_COMMAND(
+      OUTPUT ${output}
+      COMMAND ${CMAKE_COMMAND}
+        "-Dinput=${input}"
+        "-Doutput=${output}"
+        "-Dprefix=${prefix}"
+        "-Dnamespace=${namespace}"
+        -P "${CMAKE_SOURCE_DIR}/cmake/scripts/GenResource.cmake"
+      MAIN_DEPENDENCY ${input}
+      DEPENDS ${CMAKE_SOURCE_DIR}/cmake/scripts/GenResource.cmake
+      VERBATIM
+    )
+  ENDFOREACH()
+ENDMACRO()
diff --git a/third_party/allwpilib_2019/cmake/modules/SubDirList.cmake b/third_party/allwpilib_2019/cmake/modules/SubDirList.cmake
new file mode 100644
index 0000000..b67160e
--- /dev/null
+++ b/third_party/allwpilib_2019/cmake/modules/SubDirList.cmake
@@ -0,0 +1,17 @@
+MACRO(SUBDIR_LIST result curdir)
+  FILE(GLOB children RELATIVE ${curdir} ${curdir}/*)
+  SET(dirlist "")
+  FOREACH(child ${children})
+    IF(IS_DIRECTORY ${curdir}/${child})
+      LIST(APPEND dirlist ${child})
+    ENDIF()
+  ENDFOREACH()
+  SET(${result} ${dirlist})
+ENDMACRO()
+
+MACRO(ADD_ALL_SUBDIRECTORIES curdir)
+  SUBDIR_LIST (_SUBPROJECTS ${curdir})
+  FOREACH (dir ${_SUBPROJECTS})
+    ADD_SUBDIRECTORY (${dir})
+  ENDFOREACH ()
+ENDMACRO()
diff --git a/third_party/allwpilib_2019/cmake/scripts/GenResource.cmake b/third_party/allwpilib_2019/cmake/scripts/GenResource.cmake
new file mode 100644
index 0000000..d28e564
--- /dev/null
+++ b/third_party/allwpilib_2019/cmake/scripts/GenResource.cmake
@@ -0,0 +1,23 @@
+# Parameters: input output prefix namespace
+FILE(READ ${input} fileHex HEX)
+STRING(LENGTH "${fileHex}" fileHexSize)
+MATH(EXPR fileSize "${fileHexSize} / 2")
+
+GET_FILENAME_COMPONENT(inputBase ${input} NAME)
+STRING(REGEX REPLACE "[^a-zA-Z0-9]" "_" funcName "${inputBase}")
+SET(funcName "GetResource_${funcName}")
+
+FILE(WRITE "${output}" "#include <stddef.h>\n#include <wpi/StringRef.h>\nextern \"C\" {\nstatic const unsigned char contents[] = {")
+
+STRING(REGEX MATCHALL ".." outputData "${fileHex}")
+STRING(REGEX REPLACE ";" ", 0x" outputData "${outputData}")
+FILE(APPEND "${output}" " 0x${outputData} };\n")
+FILE(APPEND "${output}" "const unsigned char* ${prefix}${funcName}(size_t* len) {\n  *len = ${fileSize};\n  return contents;\n}\n}\n")
+
+IF(NOT namespace STREQUAL "")
+  FILE(APPEND "${output}" "namespace ${namespace} {\n")
+ENDIF()
+FILE(APPEND "${output}" "wpi::StringRef ${funcName}() {\n  return wpi::StringRef(reinterpret_cast<const char*>(contents), ${fileSize});\n}\n")
+IF(NOT namespace STREQUAL "")
+  FILE(APPEND "${output}" "}\n")
+ENDIF()
diff --git a/third_party/allwpilib_2019/cscore/.styleguide b/third_party/allwpilib_2019/cscore/.styleguide
new file mode 100644
index 0000000..f38c850
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/.styleguide
@@ -0,0 +1,37 @@
+cHeaderFileInclude {
+  _c\.h$
+}
+
+cppHeaderFileInclude {
+  (?<!_c)\.h$
+  \.hpp$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+licenseUpdateExclude {
+  src/main/native/cpp/default_init_allocator\.h$
+}
+
+includeGuardRoots {
+  cscore/src/main/native/cpp/
+  cscore/src/main/native/include/
+  cscore/src/main/native/linux/
+  cscore/src/main/native/osx/
+  cscore/src/main/native/windows/
+  cscore/src/main/test/native/cpp/
+}
+
+repoRootNameOverride {
+  cscore
+}
+
+includeOtherLibs {
+  ^opencv2/
+  ^support/
+  ^tcpsockets/
+  ^wpi/
+}
diff --git a/third_party/allwpilib_2019/cscore/CMakeLists.txt b/third_party/allwpilib_2019/cscore/CMakeLists.txt
new file mode 100644
index 0000000..52bcb54
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/CMakeLists.txt
@@ -0,0 +1,122 @@
+project(cscore)
+
+include(SubDirList)
+
+find_package( OpenCV REQUIRED )
+
+file(GLOB
+    cscore_native_src src/main/native/cpp/*.cpp)
+file(GLOB cscore_linux_src src/main/native/linux/*.cpp)
+file(GLOB cscore_osx_src src/main/native/osx/*.cpp)
+file(GLOB cscore_windows_src src/main/native/windows/*.cpp)
+
+add_library(cscore ${cscore_native_src})
+set_target_properties(cscore PROPERTIES DEBUG_POSTFIX "d")
+
+if(NOT MSVC)
+    if (APPLE)
+        target_sources(cscore PRIVATE ${cscore_osx_src})
+    else()
+        target_sources(cscore PRIVATE ${cscore_linux_src})
+    endif()
+else()
+    target_sources(cscore PRIVATE ${cscore_windows_src})
+    target_compile_options(cscore PUBLIC -DNOMINMAX)
+    target_compile_options(cscore PRIVATE -D_CRT_SECURE_NO_WARNINGS)
+endif()
+
+target_include_directories(cscore PUBLIC
+                $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/cscore>)
+target_include_directories(cscore PRIVATE src/main/native/cpp)
+target_link_libraries(cscore PUBLIC wpiutil ${OpenCV_LIBS})
+
+set_property(TARGET cscore PROPERTY FOLDER "libraries")
+
+install(TARGETS cscore EXPORT cscore DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/cscore")
+
+if (MSVC)
+    set (cscore_config_dir ${wpilib_dest})
+else()
+    set (cscore_config_dir share/cscore)
+endif()
+
+install(FILES cscore-config.cmake DESTINATION ${cscore_config_dir})
+install(EXPORT cscore DESTINATION ${cscore_config_dir})
+
+SUBDIR_LIST(cscore_examples "${CMAKE_CURRENT_SOURCE_DIR}/examples")
+foreach(example ${cscore_examples})
+    file(GLOB cscore_example_src examples/${example}/*.cpp)
+    if(cscore_example_src)
+        add_executable(cscore_${example} ${cscore_example_src})
+        target_link_libraries(cscore_${example} cscore)
+    endif()
+endforeach()
+
+# Java bindings
+if (NOT WITHOUT_JAVA)
+    find_package(Java REQUIRED)
+    find_package(JNI REQUIRED)
+    include(UseJava)
+    set(CMAKE_JAVA_COMPILE_FLAGS "-Xlint:unchecked")
+
+    #find java files, copy them locally
+
+    set(OPENCV_JAVA_INSTALL_DIR ${OpenCV_INSTALL_PATH}/share/OpenCV/java/)
+
+    find_file(OPENCV_JAR_FILE NAMES opencv-${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.jar PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin NO_DEFAULT_PATH)
+    find_file(OPENCV_JNI_FILE NAMES libopencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.so
+                                    libopencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dylib
+                                    opencv_java${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dll
+                                    PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin ${OpenCV_INSTALL_PATH}/bin/Release ${OpenCV_INSTALL_PATH}/bin/Debug ${OpenCV_INSTALL_PATH}/lib NO_DEFAULT_PATH)
+
+    file(GLOB
+        cscore_jni_src src/main/native/cpp/jni/CameraServerJNI.cpp)
+
+    file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+    set(CMAKE_JNI_TARGET true)
+
+    if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+        set(CMAKE_JAVA_COMPILE_FLAGS "-h" "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+        add_jar(cscore_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar ${OPENCV_JAR_FILE} OUTPUT_NAME cscore)
+    else()
+        add_jar(cscore_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar ${OPENCV_JAR_FILE} OUTPUT_NAME cscore GENERATE_NATIVE_HEADERS cscore_jni_headers)
+    endif()
+
+    get_property(CSCORE_JAR_FILE TARGET cscore_jar PROPERTY JAR_FILE)
+    install(FILES ${CSCORE_JAR_FILE} DESTINATION "${java_lib_dest}")
+    install(FILES ${OPENCV_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+    if (MSVC)
+        install(FILES ${OPENCV_JNI_FILE} DESTINATION "${jni_lib_dest}")
+
+        foreach(cvFile ${OpenCV_LIBS})
+            find_file(${cvFile}Loc NAMES ${cvFile}${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.dll
+                              PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin ${OpenCV_INSTALL_PATH}/bin/Release ${OpenCV_INSTALL_PATH}/bin/Debug ${OpenCV_INSTALL_PATH}/lib NO_DEFAULT_PATH)
+            install(FILES ${${cvFile}Loc} DESTINATION "${jni_lib_dest}")
+        endforeach()
+    endif()
+
+    set_property(TARGET cscore_jar PROPERTY FOLDER "java")
+
+    add_library(cscorejni ${cscore_jni_src})
+    target_link_libraries(cscorejni PUBLIC cscore wpiutil ${OpenCV_LIBS})
+
+    set_property(TARGET cscorejni PROPERTY FOLDER "libraries")
+
+    if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+        target_include_directories(cscorejni PRIVATE ${JNI_INCLUDE_DIRS})
+        target_include_directories(cscorejni PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+    else()
+        target_link_libraries(cscorejni PRIVATE cscore_jni_headers)
+    endif()
+    add_dependencies(cscorejni cscore_jar)
+
+    if (MSVC)
+        install(TARGETS cscorejni RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+    endif()
+
+    install(TARGETS cscorejni EXPORT cscorejni DESTINATION "${main_lib_dest}")
+
+endif()
diff --git a/third_party/allwpilib_2019/cscore/build.gradle b/third_party/allwpilib_2019/cscore/build.gradle
new file mode 100644
index 0000000..3162c88
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/build.gradle
@@ -0,0 +1,147 @@
+import org.gradle.internal.os.OperatingSystem
+
+ext {
+    nativeName = 'cscore'
+    devMain = 'edu.wpi.cscore.DevMain'
+}
+
+if (OperatingSystem.current().isMacOsX()) {
+    apply plugin: 'objective-cpp'
+}
+
+apply from: "${rootDir}/shared/jni/setupBuild.gradle"
+
+ext {
+    sharedCvConfigs = [cscore    : [],
+                       cscoreBase: [],
+                       cscoreDev : [],
+                       cscoreTest: []]
+    staticCvConfigs = [cscoreJNI: []]
+    useJava = true
+    useCpp = true
+    splitSetup = {
+        if (it.targetPlatform.operatingSystem.name == 'osx') {
+            it.sources {
+                macObjCpp(ObjectiveCppSourceSet) {
+                    source {
+                        srcDirs = ['src/main/native/objcpp']
+                        include '**/*.mm'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include'
+                        include '**/*.h'
+                    }
+                }
+                cscoreMacCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/osx'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        } else if (it.targetPlatform.operatingSystem.name == 'linux') {
+            it.sources {
+                cscoreLinuxCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/linux'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        } else if (it.targetPlatform.operatingSystem.name == 'windows') {
+            it.sources {
+                cscoreWindowsCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/windows'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/cpp'
+                        include '**/*.h'
+                    }
+                }
+            }
+        }
+    }
+}
+
+def examplesMap = [:];
+
+File examplesTree = file("$projectDir/examples")
+examplesTree.list(new FilenameFilter() {
+    @Override
+    public boolean accept(File current, String name) {
+        return new File(current, name).isDirectory();
+    }
+}).each {
+    sharedCvConfigs.put(it, [])
+    examplesMap.put(it, [])
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+model {
+    // Exports config is a utility to enable exporting all symbols in a C++ library on windows to a DLL.
+    // This removes the need for DllExport on a library. However, the gradle C++ builder has a bug
+    // where some extra symbols are added that cannot be resolved at link time. This configuration
+    // lets you specify specific symbols to exlude from exporting.
+    exportsConfigs {
+        cscore(ExportsConfig) {
+            x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVbad_cast',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure', '==']
+            x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVbad_cast',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure', '==']
+        }
+        cscoreJNI(ExportsConfig) {
+            x86SymbolFilter = { symbols ->
+                def retList = []
+                symbols.each { symbol ->
+                    if (symbol.startsWith('CS_')) {
+                        retList << symbol
+                    }
+                }
+                return retList
+            }
+            x64SymbolFilter = { symbols ->
+                def retList = []
+                symbols.each { symbol ->
+                    if (symbol.startsWith('CS_')) {
+                        retList << symbol
+                    }
+                }
+                return retList
+            }
+        }
+    }
+    components {
+        examplesMap.each { key, value ->
+            "${key}"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                binaries.all {
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib library: 'cscore', linkage: 'shared'
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'examples/' + "${key}"
+                            include '**/*.cpp'
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/cscore/cscore-config.cmake b/third_party/allwpilib_2019/cscore/cscore-config.cmake
new file mode 100644
index 0000000..790633b
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/cscore-config.cmake
@@ -0,0 +1,6 @@
+include(CMakeFindDependencyMacro)

+find_dependency(wpiutil)

+find_dependency(OpenCV)

+

+get_filename_component(SELF_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)

+include(${SELF_DIR}/cscore.cmake)

diff --git a/third_party/allwpilib_2019/cscore/examples/enum_usb/enum_usb.cpp b/third_party/allwpilib_2019/cscore/examples/enum_usb/enum_usb.cpp
new file mode 100644
index 0000000..866e2f1
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/examples/enum_usb/enum_usb.cpp
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "cscore.h"
+
+int main() {
+  CS_Status status = 0;
+  wpi::SmallString<64> buf;
+
+  for (const auto& caminfo : cs::EnumerateUsbCameras(&status)) {
+    wpi::outs() << caminfo.dev << ": " << caminfo.path << " (" << caminfo.name
+                << ")\n";
+    if (!caminfo.otherPaths.empty()) {
+      wpi::outs() << "Other device paths:\n";
+      for (auto&& path : caminfo.otherPaths)
+        wpi::outs() << "  " << path << '\n';
+    }
+
+    cs::UsbCamera camera{"usbcam", caminfo.dev};
+
+    wpi::outs() << "Properties:\n";
+    for (const auto& prop : camera.EnumerateProperties()) {
+      wpi::outs() << "  " << prop.GetName();
+      switch (prop.GetKind()) {
+        case cs::VideoProperty::kBoolean:
+          wpi::outs() << " (bool): "
+                      << "value=" << prop.Get()
+                      << " default=" << prop.GetDefault();
+          break;
+        case cs::VideoProperty::kInteger:
+          wpi::outs() << " (int): "
+                      << "value=" << prop.Get() << " min=" << prop.GetMin()
+                      << " max=" << prop.GetMax() << " step=" << prop.GetStep()
+                      << " default=" << prop.GetDefault();
+          break;
+        case cs::VideoProperty::kString:
+          wpi::outs() << " (string): " << prop.GetString(buf);
+          break;
+        case cs::VideoProperty::kEnum: {
+          wpi::outs() << " (enum): "
+                      << "value=" << prop.Get();
+          auto choices = prop.GetChoices();
+          for (size_t i = 0; i < choices.size(); ++i) {
+            if (choices[i].empty()) continue;
+            wpi::outs() << "\n    " << i << ": " << choices[i];
+          }
+          break;
+        }
+        default:
+          break;
+      }
+      wpi::outs() << '\n';
+    }
+
+    wpi::outs() << "Video Modes:\n";
+    for (const auto& mode : camera.EnumerateVideoModes()) {
+      wpi::outs() << "  PixelFormat:";
+      switch (mode.pixelFormat) {
+        case cs::VideoMode::kMJPEG:
+          wpi::outs() << "MJPEG";
+          break;
+        case cs::VideoMode::kYUYV:
+          wpi::outs() << "YUYV";
+          break;
+        case cs::VideoMode::kRGB565:
+          wpi::outs() << "RGB565";
+          break;
+        default:
+          wpi::outs() << "Unknown";
+          break;
+      }
+      wpi::outs() << " Width:" << mode.width;
+      wpi::outs() << " Height:" << mode.height;
+      wpi::outs() << " FPS:" << mode.fps << '\n';
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/examples/httpcvstream/httpcvstream.cpp b/third_party/allwpilib_2019/cscore/examples/httpcvstream/httpcvstream.cpp
new file mode 100644
index 0000000..db8e0d7
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/examples/httpcvstream/httpcvstream.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <cstdio>
+#include <iostream>
+
+#include <opencv2/core/core.hpp>
+
+#include "cscore.h"
+
+int main() {
+  cs::HttpCamera camera{"httpcam", "http://localhost:8081/?action=stream"};
+  camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30);
+  cs::CvSink cvsink{"cvsink"};
+  cvsink.SetSource(camera);
+  cs::CvSource cvsource{"cvsource", cs::VideoMode::kMJPEG, 320, 240, 30};
+  cs::MjpegServer cvMjpegServer{"cvhttpserver", 8083};
+  cvMjpegServer.SetSource(cvsource);
+
+  cv::Mat test;
+  cv::Mat flip;
+  for (;;) {
+    uint64_t time = cvsink.GrabFrame(test);
+    if (time == 0) {
+      std::cout << "error: " << cvsink.GetError() << std::endl;
+      continue;
+    }
+    std::cout << "got frame at time " << time << " size " << test.size()
+              << std::endl;
+    cv::flip(test, flip, 0);
+    cvsource.PutFrame(flip);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/examples/settings/settings.cpp b/third_party/allwpilib_2019/cscore/examples/settings/settings.cpp
new file mode 100644
index 0000000..5aa919f
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/examples/settings/settings.cpp
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <chrono>
+#include <thread>
+
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "cscore.h"
+
+int main(int argc, char** argv) {
+  if (argc < 2) {
+    wpi::errs() << "Usage: settings camera [prop val] ... -- [prop val]...\n";
+    wpi::errs() << "  Example: settings 1 brightness 30 raw_contrast 10\n";
+    return 1;
+  }
+
+  int id;
+  if (wpi::StringRef{argv[1]}.getAsInteger(10, id)) {
+    wpi::errs() << "Expected number for camera\n";
+    return 2;
+  }
+
+  cs::UsbCamera camera{"usbcam", id};
+
+  // Set prior to connect
+  int arg = 2;
+  wpi::StringRef propName;
+  for (; arg < argc && wpi::StringRef{argv[arg]} != "--"; ++arg) {
+    if (propName.empty()) {
+      propName = argv[arg];
+    } else {
+      wpi::StringRef propVal{argv[arg]};
+      int intVal;
+      if (propVal.getAsInteger(10, intVal))
+        camera.GetProperty(propName).SetString(propVal);
+      else
+        camera.GetProperty(propName).Set(intVal);
+      propName = wpi::StringRef{};
+    }
+  }
+  if (arg < argc && wpi::StringRef{argv[arg]} == "--") ++arg;
+
+  // Wait to connect
+  while (!camera.IsConnected())
+    std::this_thread::sleep_for(std::chrono::milliseconds(10));
+
+  // Set rest
+  propName = wpi::StringRef{};
+  for (; arg < argc; ++arg) {
+    if (propName.empty()) {
+      propName = argv[arg];
+    } else {
+      wpi::StringRef propVal{argv[arg]};
+      int intVal;
+      if (propVal.getAsInteger(10, intVal))
+        camera.GetProperty(propName).SetString(propVal);
+      else
+        camera.GetProperty(propName).Set(intVal);
+      propName = wpi::StringRef{};
+    }
+  }
+
+  // Print settings
+  wpi::SmallString<64> buf;
+  wpi::outs() << "Properties:\n";
+  for (const auto& prop : camera.EnumerateProperties()) {
+    wpi::outs() << "  " << prop.GetName();
+    switch (prop.GetKind()) {
+      case cs::VideoProperty::kBoolean:
+        wpi::outs() << " (bool): "
+                    << "value=" << prop.Get()
+                    << " default=" << prop.GetDefault();
+        break;
+      case cs::VideoProperty::kInteger:
+        wpi::outs() << " (int): "
+                    << "value=" << prop.Get() << " min=" << prop.GetMin()
+                    << " max=" << prop.GetMax() << " step=" << prop.GetStep()
+                    << " default=" << prop.GetDefault();
+        break;
+      case cs::VideoProperty::kString:
+        wpi::outs() << " (string): " << prop.GetString(buf);
+        break;
+      case cs::VideoProperty::kEnum: {
+        wpi::outs() << " (enum): "
+                    << "value=" << prop.Get();
+        auto choices = prop.GetChoices();
+        for (size_t i = 0; i < choices.size(); ++i) {
+          if (choices[i].empty()) continue;
+          wpi::outs() << "\n    " << i << ": " << choices[i];
+        }
+        break;
+      }
+      default:
+        break;
+    }
+    wpi::outs() << '\n';
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/examples/usbcvstream/usbcvstream.cpp b/third_party/allwpilib_2019/cscore/examples/usbcvstream/usbcvstream.cpp
new file mode 100644
index 0000000..68796b4
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/examples/usbcvstream/usbcvstream.cpp
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <cstdio>
+#include <iostream>
+
+#include <opencv2/core/core.hpp>
+
+#include "cscore.h"
+
+int main() {
+  cs::UsbCamera camera{"usbcam", 0};
+  camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30);
+  cs::MjpegServer mjpegServer{"httpserver", 8081};
+  mjpegServer.SetSource(camera);
+  cs::CvSink cvsink{"cvsink"};
+  cvsink.SetSource(camera);
+  cs::CvSource cvsource{"cvsource", cs::VideoMode::kMJPEG, 320, 240, 30};
+  cs::MjpegServer cvMjpegServer{"cvhttpserver", 8082};
+  cvMjpegServer.SetSource(cvsource);
+
+  cv::Mat test;
+  cv::Mat flip;
+  for (;;) {
+    uint64_t time = cvsink.GrabFrame(test);
+    if (time == 0) {
+      std::cout << "error: " << cvsink.GetError() << std::endl;
+      continue;
+    }
+    std::cout << "got frame at time " << time << " size " << test.size()
+              << std::endl;
+    cv::flip(test, flip, 0);
+    cvsource.PutFrame(flip);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/examples/usbstream/usbstream.cpp b/third_party/allwpilib_2019/cscore/examples/usbstream/usbstream.cpp
new file mode 100644
index 0000000..2f23151
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/examples/usbstream/usbstream.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <cstdio>
+
+#include <wpi/raw_ostream.h>
+
+#include "cscore.h"
+
+int main() {
+  wpi::outs() << "hostname: " << cs::GetHostname() << '\n';
+  wpi::outs() << "IPv4 network addresses:\n";
+  for (const auto& addr : cs::GetNetworkInterfaces())
+    wpi::outs() << "  " << addr << '\n';
+  cs::UsbCamera camera{"usbcam", 0};
+  camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30);
+  cs::MjpegServer mjpegServer{"httpserver", 8081};
+  mjpegServer.SetSource(camera);
+
+  CS_Status status = 0;
+  cs::AddListener(
+      [&](const cs::RawEvent& event) {
+        wpi::outs() << "FPS=" << camera.GetActualFPS()
+                    << " MBPS=" << (camera.GetActualDataRate() / 1000000.0)
+                    << '\n';
+      },
+      cs::RawEvent::kTelemetryUpdated, false, &status);
+  cs::SetTelemetryPeriod(1.0);
+
+  std::getchar();
+}
diff --git a/third_party/allwpilib_2019/cscore/src/dev/java/edu/wpi/cscore/DevMain.java b/third_party/allwpilib_2019/cscore/src/dev/java/edu/wpi/cscore/DevMain.java
new file mode 100644
index 0000000..e7fd516
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/dev/java/edu/wpi/cscore/DevMain.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import edu.wpi.first.wpiutil.RuntimeDetector;
+
+public final class DevMain {
+  /**
+   * Main method.
+   */
+  public static void main(String[] args) {
+    System.out.println("Hello World!");
+    System.out.println(RuntimeDetector.getPlatformPath());
+    System.out.println(CameraServerJNI.getHostname());
+  }
+
+  private DevMain() {
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/cscore/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..b95de47
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/dev/native/cpp/main.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include "cscore.h"
+
+int main() { std::cout << cs::GetHostname() << std::endl; }
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/AxisCamera.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/AxisCamera.java
new file mode 100644
index 0000000..8eef0b3
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/AxisCamera.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source that represents an Axis IP camera.
+ */
+public class AxisCamera extends HttpCamera {
+  private static String hostToUrl(String host) {
+    return "http://" + host + "/mjpg/video.mjpg";
+  }
+
+  private static String[] hostToUrl(String[] hosts) {
+    String[] urls = new String[hosts.length];
+    for (int i = 0; i < hosts.length; i++) {
+      urls[i] = hostToUrl(hosts[i]);
+    }
+    return urls;
+  }
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  public AxisCamera(String name, String host) {
+    super(name, hostToUrl(host), HttpCameraKind.kAxis);
+  }
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  public AxisCamera(String name, String[] hosts) {
+    super(name, hostToUrl(hosts), HttpCameraKind.kAxis);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CameraServerJNI.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CameraServerJNI.java
new file mode 100644
index 0000000..cb6202d
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CameraServerJNI.java
@@ -0,0 +1,231 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import java.io.IOException;
+import java.util.function.Consumer;
+
+import org.opencv.core.Core;
+
+import edu.wpi.first.wpiutil.RuntimeLoader;
+
+public class CameraServerJNI {
+  static boolean libraryLoaded = false;
+  static boolean cvLibraryLoaded = false;
+
+  static RuntimeLoader<CameraServerJNI> loader = null;
+  static RuntimeLoader<Core> cvLoader = null;
+
+  static {
+    if (!libraryLoaded) {
+      try {
+        loader = new RuntimeLoader<>("cscorejni", RuntimeLoader.getDefaultExtractionRoot(), CameraServerJNI.class);
+        loader.loadLibrary();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      libraryLoaded = true;
+    }
+
+    String opencvName = Core.NATIVE_LIBRARY_NAME;
+    if (!cvLibraryLoaded) {
+      try {
+        cvLoader = new RuntimeLoader<>(opencvName, RuntimeLoader.getDefaultExtractionRoot(), Core.class);
+        cvLoader.loadLibraryHashed();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      cvLibraryLoaded = true;
+    }
+  }
+
+  public static void forceLoad() {}
+
+  //
+  // Property Functions
+  //
+  public static native int getPropertyKind(int property);
+  public static native String getPropertyName(int property);
+  public static native int getProperty(int property);
+  public static native void setProperty(int property, int value);
+  public static native int getPropertyMin(int property);
+  public static native int getPropertyMax(int property);
+  public static native int getPropertyStep(int property);
+  public static native int getPropertyDefault(int property);
+  public static native String getStringProperty(int property);
+  public static native void setStringProperty(int property, String value);
+  public static native String[] getEnumPropertyChoices(int property);
+
+  //
+  // Source Creation Functions
+  //
+  public static native int createUsbCameraDev(String name, int dev);
+  public static native int createUsbCameraPath(String name, String path);
+  public static native int createHttpCamera(String name, String url, int kind);
+  public static native int createHttpCameraMulti(String name, String[] urls, int kind);
+  public static native int createCvSource(String name, int pixelFormat, int width, int height, int fps);
+
+  //
+  // Source Functions
+  //
+  public static native int getSourceKind(int source);
+  public static native String getSourceName(int source);
+  public static native String getSourceDescription(int source);
+  public static native long getSourceLastFrameTime(int source);
+  public static native void setSourceConnectionStrategy(int source, int strategy);
+  public static native boolean isSourceConnected(int source);
+  public static native boolean isSourceEnabled(int source);
+  public static native int getSourceProperty(int source, String name);
+  public static native int[] enumerateSourceProperties(int source);
+  public static native VideoMode getSourceVideoMode(int source);
+  public static native boolean setSourceVideoMode(int source, int pixelFormat, int width, int height, int fps);
+  public static native boolean setSourcePixelFormat(int source, int pixelFormat);
+  public static native boolean setSourceResolution(int source, int width, int height);
+  public static native boolean setSourceFPS(int source, int fps);
+  public static native boolean setSourceConfigJson(int source, String config);
+  public static native String getSourceConfigJson(int source);
+  public static native VideoMode[] enumerateSourceVideoModes(int source);
+  public static native int[] enumerateSourceSinks(int source);
+  public static native int copySource(int source);
+  public static native void releaseSource(int source);
+
+  //
+  // Camera Source Common Property Fuctions
+  //
+  public static native void setCameraBrightness(int source, int brightness);
+  public static native int getCameraBrightness(int source);
+  public static native void setCameraWhiteBalanceAuto(int source);
+  public static native void setCameraWhiteBalanceHoldCurrent(int source);
+  public static native void setCameraWhiteBalanceManual(int source, int value);
+  public static native void setCameraExposureAuto(int source);
+  public static native void setCameraExposureHoldCurrent(int source);
+  public static native void setCameraExposureManual(int source, int value);
+
+  //
+  // UsbCamera Source Functions
+  //
+  public static native String getUsbCameraPath(int source);
+  public static native UsbCameraInfo getUsbCameraInfo(int source);
+
+  //
+  // HttpCamera Source Functions
+  //
+  public static native int getHttpCameraKind(int source);
+  public static native void setHttpCameraUrls(int source, String[] urls);
+  public static native String[] getHttpCameraUrls(int source);
+
+  //
+  // OpenCV Source Functions
+  //
+  public static native void putSourceFrame(int source, long imageNativeObj);
+  public static native void notifySourceError(int source, String msg);
+  public static native void setSourceConnected(int source, boolean connected);
+  public static native void setSourceDescription(int source, String description);
+  public static native int createSourceProperty(int source, String name, int kind, int minimum, int maximum, int step, int defaultValue, int value);
+  public static native void setSourceEnumPropertyChoices(int source, int property, String[] choices);
+
+  //
+  // Sink Creation Functions
+  //
+  public static native int createMjpegServer(String name, String listenAddress, int port);
+  public static native int createCvSink(String name);
+  //public static native int createCvSinkCallback(String name,
+  //                            void (*processFrame)(long time));
+
+  //
+  // Sink Functions
+  //
+  public static native int getSinkKind(int sink);
+  public static native String getSinkName(int sink);
+  public static native String getSinkDescription(int sink);
+  public static native int getSinkProperty(int sink, String name);
+  public static native int[] enumerateSinkProperties(int sink);
+  public static native boolean setSinkConfigJson(int sink, String config);
+  public static native String getSinkConfigJson(int sink);
+  public static native void setSinkSource(int sink, int source);
+  public static native int getSinkSourceProperty(int sink, String name);
+  public static native int getSinkSource(int sink);
+  public static native int copySink(int sink);
+  public static native void releaseSink(int sink);
+
+  //
+  // MjpegServer Sink Functions
+  //
+  public static native String getMjpegServerListenAddress(int sink);
+  public static native int getMjpegServerPort(int sink);
+
+  //
+  // OpenCV Sink Functions
+  //
+  public static native void setSinkDescription(int sink, String description);
+  public static native long grabSinkFrame(int sink, long imageNativeObj);
+  public static native long grabSinkFrameTimeout(int sink, long imageNativeObj, double timeout);
+  public static native String getSinkError(int sink);
+  public static native void setSinkEnabled(int sink, boolean enabled);
+
+  //
+  // Listener Functions
+  //
+  public static native int addListener(Consumer<VideoEvent> listener,
+                                       int eventMask, boolean immediateNotify);
+
+  public static native void removeListener(int handle);
+
+  //
+  // Telemetry Functions
+  //
+  public enum TelemetryKind {
+    kSourceBytesReceived(1),
+    kSourceFramesReceived(2);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    TelemetryKind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+  public static native void setTelemetryPeriod(double seconds);
+  public static native double getTelemetryElapsedTime();
+  public static native long getTelemetryValue(int handle, int kind);
+  public static long getTelemetryValue(int handle, TelemetryKind kind) {
+    return getTelemetryValue(handle, kind.getValue());
+  }
+  public static native double getTelemetryAverageValue(int handle, int kind);
+  public static double getTelemetryAverageValue(int handle, TelemetryKind kind) {
+    return getTelemetryAverageValue(handle, kind.getValue());
+  }
+
+  //
+  // Logging Functions
+  //
+  @FunctionalInterface
+  public interface LoggerFunction {
+    void apply(int level, String file, int line, String msg);
+  }
+  public static native void setLogger(LoggerFunction func, int minLevel);
+
+  //
+  // Utility Functions
+  //
+  public static native UsbCameraInfo[] enumerateUsbCameras();
+
+  public static native int[] enumerateSources();
+
+  public static native int[] enumerateSinks();
+
+  public static native String getHostname();
+
+  public static native String[] getNetworkInterfaces();
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CvSink.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CvSink.java
new file mode 100644
index 0000000..c2c7d0e
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CvSink.java
@@ -0,0 +1,101 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import org.opencv.core.Mat;
+
+/**
+ * A sink for user code to accept video frames as OpenCV images.
+ */
+public class CvSink extends VideoSink {
+  /**
+   * Create a sink for accepting OpenCV images.
+   * WaitForFrame() must be called on the created sink to get each new
+   * image.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   */
+  public CvSink(String name) {
+    super(CameraServerJNI.createCvSink(name));
+  }
+
+  /// Create a sink for accepting OpenCV images in a separate thread.
+  /// A thread will be created that calls WaitForFrame() and calls the
+  /// processFrame() callback each time a new frame arrives.
+  /// @param name Source name (arbitrary unique identifier)
+  /// @param processFrame Frame processing function; will be called with a
+  ///        time=0 if an error occurred.  processFrame should call GetImage()
+  ///        or GetError() as needed, but should not call (except in very
+  ///        unusual circumstances) WaitForImage().
+  //public CvSink(wpi::StringRef name,
+  //       std::function<void(uint64_t time)> processFrame) {
+  //  super(CameraServerJNI.createCvSinkCallback(name, processFrame));
+  //}
+
+  /**
+   * Set sink description.
+   *
+   * @param description Description
+   */
+  public void setDescription(String description) {
+    CameraServerJNI.setSinkDescription(m_handle, description);
+  }
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after 0.225 seconds.
+   * The provided image will have three 3-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message)
+   */
+  public long grabFrame(Mat image) {
+    return grabFrame(image, 0.225);
+  }
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 3-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in 1 us increments.
+   */
+  public long grabFrame(Mat image, double timeout) {
+    return CameraServerJNI.grabSinkFrameTimeout(m_handle, image.nativeObj, timeout);
+  }
+
+  /**
+   * Wait for the next frame and get the image.  May block forever.
+   * The provided image will have three 3-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in 1 us increments.
+   */
+  public long grabFrameNoTimeout(Mat image) {
+    return CameraServerJNI.grabSinkFrame(m_handle, image.nativeObj);
+  }
+
+  /**
+   * Get error string.  Call this if WaitForFrame() returns 0 to determine
+   * what the error is.
+   */
+  public String getError() {
+    return CameraServerJNI.getSinkError(m_handle);
+  }
+
+  /**
+   * Enable or disable getting new frames.
+   * Disabling will cause processFrame (for callback-based CvSinks) to not
+   * be called and WaitForFrame() to not return.  This can be used to save
+   * processor resources when frames are not needed.
+   */
+  public void setEnabled(boolean enabled) {
+    CameraServerJNI.setSinkEnabled(m_handle, enabled);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CvSource.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CvSource.java
new file mode 100644
index 0000000..47cd409
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/CvSource.java
@@ -0,0 +1,203 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import org.opencv.core.Mat;
+
+/**
+ * A source that represents a video camera.
+ */
+public class CvSource extends VideoSource {
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param mode Video mode being generated
+   */
+  public CvSource(String name, VideoMode mode) {
+    super(CameraServerJNI.createCvSource(name,
+        mode.pixelFormat.getValue(),
+        mode.width,
+        mode.height,
+        mode.fps));
+  }
+
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param pixelFormat Pixel format
+   * @param width width
+   * @param height height
+   * @param fps fps
+   */
+  public CvSource(String name, VideoMode.PixelFormat pixelFormat, int width, int height, int fps) {
+    super(CameraServerJNI.createCvSource(name, pixelFormat.getValue(), width, height, fps));
+  }
+
+  /**
+   * Put an OpenCV image and notify sinks.
+   *
+   * <p>Only 8-bit single-channel or 3-channel (with BGR channel order) images
+   * are supported. If the format, depth or channel order is different, use
+   * Mat.convertTo() and/or cvtColor() to convert it first.
+   *
+   * @param image OpenCV image
+   */
+  public void putFrame(Mat image) {
+    CameraServerJNI.putSourceFrame(m_handle, image.nativeObj);
+  }
+
+  /**
+   * Signal sinks that an error has occurred.  This should be called instead
+   * of NotifyFrame when an error occurs.
+   */
+  public void notifyError(String msg) {
+    CameraServerJNI.notifySourceError(m_handle, msg);
+  }
+
+  /**
+   * Set source connection status.  Defaults to true.
+   *
+   * @param connected True for connected, false for disconnected
+   */
+  public void setConnected(boolean connected) {
+    CameraServerJNI.setSourceConnected(m_handle, connected);
+  }
+
+  /**
+   * Set source description.
+   *
+   * @param description Description
+   */
+  public void setDescription(String description) {
+    CameraServerJNI.setSourceDescription(m_handle, description);
+  }
+
+  /**
+   * Create a property.
+   *
+   * @param name Property name
+   * @param kind Property kind
+   * @param minimum Minimum value
+   * @param maximum Maximum value
+   * @param step Step value
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  public VideoProperty createProperty(String name,
+                                      VideoProperty.Kind kind,
+                                      int minimum,
+                                      int maximum,
+                                      int step,
+                                      int defaultValue,
+                                      int value) {
+    return new VideoProperty(
+        CameraServerJNI.createSourceProperty(m_handle,
+            name,
+            kind.getValue(),
+            minimum,
+            maximum,
+            step,
+            defaultValue,
+            value));
+  }
+
+  /**
+   * Create an integer property.
+   *
+   * @param name Property name
+   * @param minimum Minimum value
+   * @param maximum Maximum value
+   * @param step Step value
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  public VideoProperty createIntegerProperty(String name,
+                                             int minimum,
+                                             int maximum,
+                                             int step,
+                                             int defaultValue,
+                                             int value) {
+    return new VideoProperty(
+        CameraServerJNI.createSourceProperty(m_handle,
+            name,
+            VideoProperty.Kind.kInteger.getValue(),
+            minimum,
+            maximum,
+            step,
+            defaultValue,
+            value));
+  }
+
+  /**
+   * Create a boolean property.
+   *
+   * @param name Property name
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  public VideoProperty createBooleanProperty(String name, boolean defaultValue, boolean value) {
+    return new VideoProperty(
+        CameraServerJNI.createSourceProperty(m_handle,
+            name,
+            VideoProperty.Kind.kBoolean.getValue(),
+            0,
+            1,
+            1,
+            defaultValue ? 1 : 0,
+            value ? 1 : 0));
+  }
+
+  /**
+   * Create a string property.
+   *
+   * @param name Property name
+   * @param value Current value
+   * @return Property
+   */
+  public VideoProperty createStringProperty(String name, String value) {
+    VideoProperty prop = new VideoProperty(
+        CameraServerJNI.createSourceProperty(m_handle,
+            name,
+            VideoProperty.Kind.kString.getValue(),
+            0,
+            0,
+            0,
+            0,
+            0));
+    prop.setString(value);
+    return prop;
+  }
+
+  /**
+   * Configure enum property choices.
+   *
+   * @param property Property
+   * @param choices Choices
+   */
+  public void setEnumPropertyChoices(VideoProperty property, String[] choices) {
+    CameraServerJNI.setSourceEnumPropertyChoices(m_handle, property.m_handle, choices);
+  }
+
+  /**
+   * Configure enum property choices.
+   *
+   * @param property Property
+   * @param choices Choices
+   * @deprecated Use {@code setEnumPropertyChoices} instead.
+   */
+  @Deprecated
+  @SuppressWarnings("MethodName")
+  public void SetEnumPropertyChoices(VideoProperty property, String[] choices) {
+    setEnumPropertyChoices(property, choices);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/HttpCamera.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/HttpCamera.java
new file mode 100644
index 0000000..533d00f
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/HttpCamera.java
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source that represents a MJPEG-over-HTTP (IP) camera.
+ */
+public class HttpCamera extends VideoCamera {
+  public enum HttpCameraKind {
+    kUnknown(0), kMJPGStreamer(1), kCSCore(2), kAxis(3);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    HttpCameraKind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  public static HttpCameraKind getHttpCameraKindFromInt(int kind) {
+    switch (kind) {
+      case 1: return HttpCameraKind.kMJPGStreamer;
+      case 2: return HttpCameraKind.kCSCore;
+      case 3: return HttpCameraKind.kAxis;
+      default: return HttpCameraKind.kUnknown;
+    }
+  }
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   */
+  public HttpCamera(String name, String url) {
+    super(CameraServerJNI.createHttpCamera(name, url, HttpCameraKind.kUnknown.getValue()));
+  }
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  public HttpCamera(String name, String url, HttpCameraKind kind) {
+    super(CameraServerJNI.createHttpCamera(name, url, kind.getValue()));
+  }
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param urls Array of Camera URLs
+   */
+  public HttpCamera(String name, String[] urls) {
+    super(CameraServerJNI.createHttpCameraMulti(name, urls, HttpCameraKind.kUnknown.getValue()));
+  }
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param urls Array of Camera URLs
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  public HttpCamera(String name, String[] urls, HttpCameraKind kind) {
+    super(CameraServerJNI.createHttpCameraMulti(name, urls, kind.getValue()));
+  }
+
+  /**
+   * Get the kind of HTTP camera.
+   *
+   * <p>Autodetection can result in returning a different value than the camera
+   * was created with.
+   */
+  public HttpCameraKind getHttpCameraKind() {
+    return getHttpCameraKindFromInt(CameraServerJNI.getHttpCameraKind(m_handle));
+  }
+
+  /**
+   * Change the URLs used to connect to the camera.
+   */
+  public void setUrls(String[] urls) {
+    CameraServerJNI.setHttpCameraUrls(m_handle, urls);
+  }
+
+  /**
+   * Get the URLs used to connect to the camera.
+   */
+  public String[] getUrls() {
+    return CameraServerJNI.getHttpCameraUrls(m_handle);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/MjpegServer.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/MjpegServer.java
new file mode 100644
index 0000000..fbbddf8
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/MjpegServer.java
@@ -0,0 +1,104 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A sink that acts as a MJPEG-over-HTTP network server.
+ */
+public class MjpegServer extends VideoSink {
+  /**
+   * Create a MJPEG-over-HTTP server sink.
+   *
+   * @param name Sink name (arbitrary unique identifier)
+   * @param listenAddress TCP listen address (empty string for all addresses)
+   * @param port TCP port number
+   */
+  public MjpegServer(String name, String listenAddress, int port) {
+    super(CameraServerJNI.createMjpegServer(name, listenAddress, port));
+  }
+
+  /**
+   * Create a MJPEG-over-HTTP server sink.
+   *
+   * @param name Sink name (arbitrary unique identifier)
+   * @param port TCP port number
+   */
+  public MjpegServer(String name, int port) {
+    this(name, "", port);
+  }
+
+  /**
+   * Get the listen address of the server.
+   */
+  public String getListenAddress() {
+    return CameraServerJNI.getMjpegServerListenAddress(m_handle);
+  }
+
+  /**
+   * Get the port number of the server.
+   */
+  public int getPort() {
+    return CameraServerJNI.getMjpegServerPort(m_handle);
+  }
+
+  /**
+   * Set the stream resolution for clients that don't specify it.
+   *
+   * <p>It is not necessary to set this if it is the same as the source
+   * resolution.
+   *
+   * <p>Setting this different than the source resolution will result in
+   * increased CPU usage, particularly for MJPEG source cameras, as it will
+   * decompress, resize, and recompress the image, instead of using the
+   * camera's MJPEG image directly.
+   *
+   * @param width width, 0 for unspecified
+   * @param height height, 0 for unspecified
+   */
+  public void setResolution(int width, int height) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "width"), width);
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "height"), height);
+  }
+
+  /**
+   * Set the stream frames per second (FPS) for clients that don't specify it.
+   *
+   * <p>It is not necessary to set this if it is the same as the source FPS.
+   *
+   * @param fps FPS, 0 for unspecified
+   */
+  public void setFPS(int fps) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "fps"), fps);
+  }
+
+  /**
+   * Set the compression for clients that don't specify it.
+   *
+   * <p>Setting this will result in increased CPU usage for MJPEG source cameras
+   * as it will decompress and recompress the image instead of using the
+   * camera's MJPEG image directly.
+   *
+   * @param quality JPEG compression quality (0-100), -1 for unspecified
+   */
+  public void setCompression(int quality) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "compression"),
+                                quality);
+  }
+
+  /**
+   * Set the default compression used for non-MJPEG sources.  If not set,
+   * 80 is used.  This function has no effect on MJPEG source cameras; use
+   * SetCompression() instead to force recompression of MJPEG source images.
+   *
+   * @param quality JPEG compression quality (0-100)
+   */
+  public void setDefaultCompression(int quality) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSinkProperty(m_handle, "default_compression"),
+                                quality);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/UsbCamera.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/UsbCamera.java
new file mode 100644
index 0000000..fc80047
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/UsbCamera.java
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source that represents a USB camera.
+ */
+public class UsbCamera extends VideoCamera {
+  /**
+   * Create a source for a USB camera based on device number.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param dev Device number (e.g. 0 for /dev/video0)
+   */
+  public UsbCamera(String name, int dev) {
+    super(CameraServerJNI.createUsbCameraDev(name, dev));
+  }
+
+  /**
+   * Create a source for a USB camera based on device path.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param path Path to device (e.g. "/dev/video0" on Linux)
+   */
+  public UsbCamera(String name, String path) {
+    super(CameraServerJNI.createUsbCameraPath(name, path));
+  }
+
+  /**
+   * Enumerate USB cameras on the local system.
+   *
+   * @return Vector of USB camera information (one for each camera)
+   */
+  public static UsbCameraInfo[] enumerateUsbCameras() {
+    return CameraServerJNI.enumerateUsbCameras();
+  }
+
+  /**
+   * Get the path to the device.
+   */
+  public String getPath() {
+    return CameraServerJNI.getUsbCameraPath(m_handle);
+  }
+
+  /**
+   * Get the full camera information for the device.
+   */
+  public UsbCameraInfo getInfo() {
+    return CameraServerJNI.getUsbCameraInfo(m_handle);
+  }
+
+  /**
+   * Set how verbose the camera connection messages are.
+   *
+   * @param level 0=don't display Connecting message, 1=do display message
+   */
+  public void setConnectVerbose(int level) {
+    CameraServerJNI.setProperty(CameraServerJNI.getSourceProperty(m_handle, "connect_verbose"),
+                                level);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/UsbCameraInfo.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/UsbCameraInfo.java
new file mode 100644
index 0000000..42ef466
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/UsbCameraInfo.java
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * USB camera information.
+ */
+public class UsbCameraInfo {
+  /**
+   * Create a new set of UsbCameraInfo.
+   *
+   * @param dev Device number (e.g. N in '/dev/videoN' on Linux)
+   * @param path Path to device if available (e.g. '/dev/video0' on Linux)
+   * @param name Vendor/model name of the camera as provided by the USB driver
+   * @param otherPaths Other path aliases to device
+   */
+  @SuppressWarnings("PMD.ArrayIsStoredDirectly")
+  public UsbCameraInfo(int dev, String path, String name, String[] otherPaths) {
+    this.dev = dev;
+    this.path = path;
+    this.name = name;
+    this.otherPaths = otherPaths;
+  }
+
+  /**
+   * Device number (e.g. N in '/dev/videoN' on Linux).
+   */
+  @SuppressWarnings("MemberName")
+  public int dev;
+
+  /**
+   * Path to device if available (e.g. '/dev/video0' on Linux).
+   */
+  @SuppressWarnings("MemberName")
+  public String path;
+
+  /**
+   * Vendor/model name of the camera as provided by the USB driver.
+   */
+  @SuppressWarnings("MemberName")
+  public String name;
+
+  /**
+   * Other path aliases to device (e.g. '/dev/v4l/by-id/...' etc on Linux).
+   */
+  @SuppressWarnings("MemberName")
+  public String[] otherPaths;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoCamera.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoCamera.java
new file mode 100644
index 0000000..0ab95f1
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoCamera.java
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source that represents a video camera.
+ */
+public class VideoCamera extends VideoSource {
+  public static class WhiteBalance {
+    public static final int kFixedIndoor = 3000;
+    public static final int kFixedOutdoor1 = 4000;
+    public static final int kFixedOutdoor2 = 5000;
+    public static final int kFixedFluorescent1 = 5100;
+    public static final int kFixedFlourescent2 = 5200;
+  }
+
+  protected VideoCamera(int handle) {
+    super(handle);
+  }
+
+  /**
+   * Set the brightness, as a percentage (0-100).
+   */
+  public synchronized void setBrightness(int brightness) {
+    CameraServerJNI.setCameraBrightness(m_handle, brightness);
+  }
+
+  /**
+   * Get the brightness, as a percentage (0-100).
+   */
+  public synchronized int getBrightness() {
+    return CameraServerJNI.getCameraBrightness(m_handle);
+  }
+
+  /**
+   * Set the white balance to auto.
+   */
+  public synchronized void setWhiteBalanceAuto() {
+    CameraServerJNI.setCameraWhiteBalanceAuto(m_handle);
+  }
+
+  /**
+   * Set the white balance to hold current.
+   */
+  public synchronized void setWhiteBalanceHoldCurrent() {
+    CameraServerJNI.setCameraWhiteBalanceHoldCurrent(m_handle);
+  }
+
+  /**
+   * Set the white balance to manual, with specified color temperature.
+   */
+  public synchronized void setWhiteBalanceManual(int value) {
+    CameraServerJNI.setCameraWhiteBalanceManual(m_handle, value);
+  }
+
+  /**
+   * Set the exposure to auto aperture.
+   */
+  public synchronized void setExposureAuto() {
+    CameraServerJNI.setCameraExposureAuto(m_handle);
+  }
+
+  /**
+   * Set the exposure to hold current.
+   */
+  public synchronized void setExposureHoldCurrent() {
+    CameraServerJNI.setCameraExposureHoldCurrent(m_handle);
+  }
+
+  /**
+   * Set the exposure to manual, as a percentage (0-100).
+   */
+  public synchronized void setExposureManual(int value) {
+    CameraServerJNI.setCameraExposureManual(m_handle, value);
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoEvent.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoEvent.java
new file mode 100644
index 0000000..7f4599d
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoEvent.java
@@ -0,0 +1,133 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * Video event.
+ */
+public class VideoEvent {
+  public enum Kind {
+    kUnknown(0x0000),
+    kSourceCreated(0x0001),
+    kSourceDestroyed(0x0002),
+    kSourceConnected(0x0004),
+    kSourceDisconnected(0x0008),
+    kSourceVideoModesUpdated(0x0010),
+    kSourceVideoModeChanged(0x0020),
+    kSourcePropertyCreated(0x0040),
+    kSourcePropertyValueUpdated(0x0080),
+    kSourcePropertyChoicesUpdated(0x0100),
+    kSinkSourceChanged(0x0200),
+    kSinkCreated(0x0400),
+    kSinkDestroyed(0x0800),
+    kSinkEnabled(0x1000),
+    kSinkDisabled(0x2000),
+    kNetworkInterfacesChanged(0x4000),
+    kTelemetryUpdated(0x8000),
+    kSinkPropertyCreated(0x10000),
+    kSinkPropertyValueUpdated(0x20000),
+    kSinkPropertyChoicesUpdated(0x40000);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  @SuppressWarnings("PMD.CyclomaticComplexity")
+  public static Kind getKindFromInt(int kind) {
+    switch (kind) {
+      case 0x0001: return Kind.kSourceCreated;
+      case 0x0002: return Kind.kSourceDestroyed;
+      case 0x0004: return Kind.kSourceConnected;
+      case 0x0008: return Kind.kSourceDisconnected;
+      case 0x0010: return Kind.kSourceVideoModesUpdated;
+      case 0x0020: return Kind.kSourceVideoModeChanged;
+      case 0x0040: return Kind.kSourcePropertyCreated;
+      case 0x0080: return Kind.kSourcePropertyValueUpdated;
+      case 0x0100: return Kind.kSourcePropertyChoicesUpdated;
+      case 0x0200: return Kind.kSinkSourceChanged;
+      case 0x0400: return Kind.kSinkCreated;
+      case 0x0800: return Kind.kSinkDestroyed;
+      case 0x1000: return Kind.kSinkEnabled;
+      case 0x2000: return Kind.kSinkDisabled;
+      case 0x4000: return Kind.kNetworkInterfacesChanged;
+      case 0x10000: return Kind.kSinkPropertyCreated;
+      case 0x20000: return Kind.kSinkPropertyValueUpdated;
+      case 0x40000: return Kind.kSinkPropertyChoicesUpdated;
+      default: return Kind.kUnknown;
+    }
+  }
+
+  @SuppressWarnings("PMD.ExcessiveParameterList")
+  VideoEvent(int kind, int source, int sink, String name, int pixelFormat,
+             int width, int height, int fps, int property, int propertyKind,
+             int value, String valueStr) {
+    this.kind = getKindFromInt(kind);
+    this.sourceHandle = source;
+    this.sinkHandle = sink;
+    this.name = name;
+    this.mode = new VideoMode(pixelFormat, width, height, fps);
+    this.propertyHandle = property;
+    this.propertyKind = VideoProperty.getKindFromInt(propertyKind);
+    this.value = value;
+    this.valueStr = valueStr;
+  }
+
+  @SuppressWarnings("MemberName")
+  public Kind kind;
+
+  // Valid for kSource* and kSink* respectively
+  @SuppressWarnings("MemberName")
+  public int sourceHandle;
+  @SuppressWarnings("MemberName")
+  public int sinkHandle;
+
+  // Source/sink/property name
+  @SuppressWarnings("MemberName")
+  public String name;
+
+  // Fields for kSourceVideoModeChanged event
+  @SuppressWarnings("MemberName")
+  public VideoMode mode;
+
+  // Fields for kSourceProperty* events
+  @SuppressWarnings("MemberName")
+  public int propertyHandle;
+  @SuppressWarnings("MemberName")
+  public VideoProperty.Kind propertyKind;
+  @SuppressWarnings("MemberName")
+  public int value;
+  @SuppressWarnings("MemberName")
+  public String valueStr;
+
+  public VideoSource getSource() {
+    return new VideoSource(CameraServerJNI.copySource(sourceHandle));
+  }
+
+  public VideoSink getSink() {
+    return new VideoSink(CameraServerJNI.copySink(sinkHandle));
+  }
+
+  public VideoProperty getProperty() {
+    return new VideoProperty(propertyHandle, propertyKind);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoException.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoException.java
new file mode 100644
index 0000000..8c35517
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoException.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * An exception raised by the camera server.
+ */
+public class VideoException extends RuntimeException {
+  private static final long serialVersionUID = -9155939328084105145L;
+
+  public VideoException(String msg) {
+    super(msg);
+  }
+
+  @Override
+  public String toString() {
+    return "VideoException [" + super.toString() + "]";
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoListener.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoListener.java
new file mode 100644
index 0000000..8dd62fa
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoListener.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import java.util.function.Consumer;
+
+/**
+ * An event listener.  This calls back to a desigated callback function when
+ * an event matching the specified mask is generated by the library.
+ */
+public class VideoListener implements AutoCloseable {
+  /**
+   * Create an event listener.
+   *
+   * @param listener Listener function
+   * @param eventMask Bitmask of VideoEvent.Type values
+   * @param immediateNotify Whether callback should be immediately called with
+   *        a representative set of events for the current library state.
+   */
+  public VideoListener(Consumer<VideoEvent> listener, int eventMask,
+                       boolean immediateNotify) {
+    m_handle = CameraServerJNI.addListener(listener, eventMask, immediateNotify);
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      CameraServerJNI.removeListener(m_handle);
+    }
+    m_handle = 0;
+  }
+
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  private int m_handle;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoMode.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoMode.java
new file mode 100644
index 0000000..dec4686
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoMode.java
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * Video mode.
+ */
+public class VideoMode {
+  public enum PixelFormat {
+    kUnknown(0), kMJPEG(1), kYUYV(2), kRGB565(3), kBGR(4), kGray(5);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    PixelFormat(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  private static final PixelFormat[] m_pixelFormatValues = PixelFormat.values();
+
+  public static PixelFormat getPixelFormatFromInt(int pixelFormat) {
+    return m_pixelFormatValues[pixelFormat];
+  }
+
+  /**
+   * Create a new video mode.
+   */
+  public VideoMode(int pixelFormat, int width, int height, int fps) {
+    this.pixelFormat = getPixelFormatFromInt(pixelFormat);
+    this.width = width;
+    this.height = height;
+    this.fps = fps;
+  }
+
+  /**
+   * Create a new video mode.
+   */
+  public VideoMode(PixelFormat pixelFormat, int width, int height, int fps) {
+    this.pixelFormat = pixelFormat;
+    this.width = width;
+    this.height = height;
+    this.fps = fps;
+  }
+
+  /**
+   * Pixel format.
+   */
+  @SuppressWarnings("MemberName")
+  public PixelFormat pixelFormat;
+
+  /**
+   * Width in pixels.
+   */
+  @SuppressWarnings("MemberName")
+  public int width;
+
+  /**
+   * Height in pixels.
+   */
+  @SuppressWarnings("MemberName")
+  public int height;
+
+  /**
+   * Frames per second.
+   */
+  @SuppressWarnings("MemberName")
+  public int fps;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoProperty.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoProperty.java
new file mode 100644
index 0000000..407e107
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoProperty.java
@@ -0,0 +1,124 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source or sink property.
+ */
+public class VideoProperty {
+  public enum Kind {
+    kNone(0), kBoolean(1), kInteger(2), kString(4), kEnum(8);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  public static Kind getKindFromInt(int kind) {
+    switch (kind) {
+      case 1: return Kind.kBoolean;
+      case 2: return Kind.kInteger;
+      case 4: return Kind.kString;
+      case 8: return Kind.kEnum;
+      default: return Kind.kNone;
+    }
+  }
+
+  public String getName() {
+    return CameraServerJNI.getPropertyName(m_handle);
+  }
+
+  public Kind getKind() {
+    return m_kind;
+  }
+
+  public boolean isValid() {
+    return m_kind != Kind.kNone;
+  }
+
+  // Kind checkers
+  public boolean isBoolean() {
+    return m_kind == Kind.kBoolean;
+  }
+
+  public boolean isInteger() {
+    return m_kind == Kind.kInteger;
+  }
+
+  public boolean isString() {
+    return m_kind == Kind.kString;
+  }
+
+  public boolean isEnum() {
+    return m_kind == Kind.kEnum;
+  }
+
+  public int get() {
+    return CameraServerJNI.getProperty(m_handle);
+  }
+
+  public void set(int value) {
+    CameraServerJNI.setProperty(m_handle, value);
+  }
+
+  public int getMin() {
+    return CameraServerJNI.getPropertyMin(m_handle);
+  }
+
+  public int getMax() {
+    return CameraServerJNI.getPropertyMax(m_handle);
+  }
+
+  public int getStep() {
+    return CameraServerJNI.getPropertyStep(m_handle);
+  }
+
+  public int getDefault() {
+    return CameraServerJNI.getPropertyDefault(m_handle);
+  }
+
+  // String-specific functions
+  public String getString() {
+    return CameraServerJNI.getStringProperty(m_handle);
+  }
+
+  public void setString(String value) {
+    CameraServerJNI.setStringProperty(m_handle, value);
+  }
+
+  // Enum-specific functions
+  public String[] getChoices() {
+    return CameraServerJNI.getEnumPropertyChoices(m_handle);
+  }
+
+  VideoProperty(int handle) {
+    m_handle = handle;
+    m_kind = getKindFromInt(CameraServerJNI.getPropertyKind(handle));
+  }
+
+  VideoProperty(int handle, Kind kind) {
+    m_handle = handle;
+    m_kind = kind;
+  }
+
+  int m_handle;
+  private Kind m_kind;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoSink.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoSink.java
new file mode 100644
index 0000000..a59a952
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoSink.java
@@ -0,0 +1,222 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source for video that provides a sequence of frames.  Each frame may
+ * consist of multiple images (e.g. from a stereo or depth camera); these
+ * are called channels.
+ */
+public class VideoSink implements AutoCloseable {
+  public enum Kind {
+    kUnknown(0), kMjpeg(2), kCv(4);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  public static Kind getKindFromInt(int kind) {
+    switch (kind) {
+      case 2: return Kind.kMjpeg;
+      case 4: return Kind.kCv;
+      default: return Kind.kUnknown;
+    }
+  }
+
+  protected VideoSink(int handle) {
+    m_handle = handle;
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      CameraServerJNI.releaseSink(m_handle);
+    }
+    m_handle = 0;
+  }
+
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  public int getHandle() {
+    return m_handle;
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (this == other) {
+      return true;
+    }
+    if (other == null) {
+      return false;
+    }
+    if (getClass() != other.getClass()) {
+      return false;
+    }
+    VideoSink sink = (VideoSink) other;
+    return m_handle == sink.m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  /**
+   * Get the kind of the sink.
+   */
+  public Kind getKind() {
+    return getKindFromInt(CameraServerJNI.getSinkKind(m_handle));
+  }
+
+  /**
+   * Get the name of the sink.  The name is an arbitrary identifier
+   * provided when the sink is created, and should be unique.
+   */
+  public String getName() {
+    return CameraServerJNI.getSinkName(m_handle);
+  }
+
+  /**
+   * Get the sink description.  This is sink-kind specific.
+   */
+  public String getDescription() {
+    return CameraServerJNI.getSinkDescription(m_handle);
+  }
+
+  /**
+   * Get a property of the sink.
+   *
+   * @param name Property name
+   * @return Property (kind Property::kNone if no property with
+   *         the given name exists)
+   */
+  public VideoProperty getProperty(String name) {
+    return new VideoProperty(CameraServerJNI.getSinkProperty(m_handle, name));
+  }
+
+  /**
+   * Enumerate all properties of this sink.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public VideoProperty[] enumerateProperties() {
+    int[] handles = CameraServerJNI.enumerateSinkProperties(m_handle);
+    VideoProperty[] rv = new VideoProperty[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoProperty(handles[i]);
+    }
+    return rv;
+  }
+
+  /**
+   * Set properties from a JSON configuration string.
+   *
+   * <p>The format of the JSON input is:
+   *
+   * <pre>
+   * {
+   *     "properties": [
+   *         {
+   *             "name": property name
+   *             "value": property value
+   *         }
+   *     ]
+   * }
+   * </pre>
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  public boolean setConfigJson(String config) {
+    return CameraServerJNI.setSinkConfigJson(m_handle, config);
+  }
+
+  /**
+   * Get a JSON configuration string.
+   *
+   * @return JSON configuration string
+   */
+  public String getConfigJson() {
+    return CameraServerJNI.getSinkConfigJson(m_handle);
+  }
+
+  /**
+   * Configure which source should provide frames to this sink.  Each sink
+   * can accept frames from only a single source, but a single source can
+   * provide frames to multiple clients.
+   *
+   * @param source Source
+   */
+  public void setSource(VideoSource source) {
+    if (source == null) {
+      CameraServerJNI.setSinkSource(m_handle, 0);
+    } else {
+      CameraServerJNI.setSinkSource(m_handle, source.m_handle);
+    }
+  }
+
+  /**
+   * Get the connected source.
+   *
+   * @return Connected source; nullptr if no source connected.
+   */
+  public VideoSource getSource() {
+    // While VideoSource.free() will call releaseSource(), getSinkSource()
+    // increments the internal reference count so this is okay to do.
+    return new VideoSource(CameraServerJNI.getSinkSource(m_handle));
+  }
+
+  /**
+   * Get a property of the associated source.
+   *
+   * @param name Property name
+   * @return Property (kind Property::kNone if no property with
+   *         the given name exists or no source connected)
+   */
+  public VideoProperty getSourceProperty(String name) {
+    return new VideoProperty(
+        CameraServerJNI.getSinkSourceProperty(m_handle, name));
+  }
+
+  /**
+   * Enumerate all existing sinks.
+   *
+   * @return Vector of sinks.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public static VideoSink[] enumerateSinks() {
+    int[] handles = CameraServerJNI.enumerateSinks();
+    VideoSink[] rv = new VideoSink[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoSink(handles[i]);
+    }
+    return rv;
+  }
+
+  protected int m_handle;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoSource.java b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoSource.java
new file mode 100644
index 0000000..cac344c
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/java/edu/wpi/cscore/VideoSource.java
@@ -0,0 +1,376 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+/**
+ * A source for video that provides a sequence of frames.  Each frame may
+ * consist of multiple images (e.g. from a stereo or depth camera); these
+ * are called channels.
+ */
+public class VideoSource implements AutoCloseable {
+  public enum Kind {
+    kUnknown(0), kUsb(1), kHttp(2), kCv(4);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    Kind(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Connection strategy.
+   */
+  public enum ConnectionStrategy {
+    /**
+     * Automatically connect or disconnect based on whether any sinks are
+     * connected to this source.  This is the default behavior.
+     */
+    kAutoManage(0),
+
+    /**
+     * Try to keep the connection open regardless of whether any sinks are
+     * connected.
+     */
+    kKeepOpen(1),
+
+    /**
+     * Never open the connection.  If this is set when the connection is open,
+     * close the connection.
+     */
+    kForceClose(2);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    ConnectionStrategy(int value) {
+      this.value = value;
+    }
+
+    public int getValue() {
+      return value;
+    }
+  }
+
+  /**
+   * Convert from the numerical representation of kind to an enum type.
+   *
+   * @param kind The numerical representation of kind
+   * @return The kind
+   */
+  public static Kind getKindFromInt(int kind) {
+    switch (kind) {
+      case 1: return Kind.kUsb;
+      case 2: return Kind.kHttp;
+      case 4: return Kind.kCv;
+      default: return Kind.kUnknown;
+    }
+  }
+
+  protected VideoSource(int handle) {
+    m_handle = handle;
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  @Override
+  public synchronized void close() {
+    if (m_handle != 0) {
+      CameraServerJNI.releaseSource(m_handle);
+    }
+    m_handle = 0;
+  }
+
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  public int getHandle() {
+    return m_handle;
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (this == other) {
+      return true;
+    }
+    if (other == null) {
+      return false;
+    }
+    if (getClass() != other.getClass()) {
+      return false;
+    }
+    VideoSource source = (VideoSource) other;
+    return m_handle == source.m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  /**
+   * Get the kind of the source.
+   */
+  public Kind getKind() {
+    return getKindFromInt(CameraServerJNI.getSourceKind(m_handle));
+  }
+
+  /**
+   * Get the name of the source.  The name is an arbitrary identifier
+   * provided when the source is created, and should be unique.
+   */
+  public String getName() {
+    return CameraServerJNI.getSourceName(m_handle);
+  }
+
+  /**
+   * Get the source description.  This is source-kind specific.
+   */
+  public String getDescription() {
+    return CameraServerJNI.getSourceDescription(m_handle);
+  }
+
+  /**
+   * Get the last time a frame was captured.
+   * @return Time in 1 us increments.
+   */
+  public long getLastFrameTime() {
+    return CameraServerJNI.getSourceLastFrameTime(m_handle);
+  }
+
+  /**
+   * Sets the connection strategy.  By default, the source will automatically
+   * connect or disconnect based on whether any sinks are connected.
+   *
+   * <p>This function is non-blocking; look for either a connection open or
+   * close event or call {@link #isConnected()} to determine the connection
+   * state.
+   *
+   * @param strategy connection strategy (auto, keep open, or force close)
+   */
+  public void setConnectionStrategy(ConnectionStrategy strategy) {
+    CameraServerJNI.setSourceConnectionStrategy(m_handle, strategy.getValue());
+  }
+
+  /**
+   * Returns if the source currently connected to whatever is providing the images.
+   */
+  public boolean isConnected() {
+    return CameraServerJNI.isSourceConnected(m_handle);
+  }
+
+  /**
+   * Gets source enable status.  This is determined with a combination of
+   * connection strategy and the number of sinks connected.
+   *
+   * @return True if enabled, false otherwise.
+   */
+  public boolean isEnabled() {
+    return CameraServerJNI.isSourceEnabled(m_handle);
+  }
+
+  /**
+   * Get a property.
+   *
+   * @param name Property name
+   * @return Property contents (of kind Property::kNone if no property with
+   *         the given name exists)
+   */
+  public VideoProperty getProperty(String name) {
+    return new VideoProperty(CameraServerJNI.getSourceProperty(m_handle, name));
+  }
+
+  /**
+   * Enumerate all properties of this source.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public VideoProperty[] enumerateProperties() {
+    int[] handles = CameraServerJNI.enumerateSourceProperties(m_handle);
+    VideoProperty[] rv = new VideoProperty[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoProperty(handles[i]);
+    }
+    return rv;
+  }
+
+  /**
+   * Get the current video mode.
+   */
+  public VideoMode getVideoMode() {
+    return CameraServerJNI.getSourceVideoMode(m_handle);
+  }
+
+  /**
+   * Set the video mode.
+   * @param mode Video mode
+   */
+  public boolean setVideoMode(VideoMode mode) {
+    return CameraServerJNI.setSourceVideoMode(m_handle,
+        mode.pixelFormat.getValue(),
+        mode.width,
+        mode.height,
+        mode.fps);
+  }
+
+  /**
+   * Set the video mode.
+   *
+   * @param pixelFormat desired pixel format
+   * @param width desired width
+   * @param height desired height
+   * @param fps desired FPS
+   * @return True if set successfully
+   */
+  public boolean setVideoMode(VideoMode.PixelFormat pixelFormat, int width, int height, int fps) {
+    return CameraServerJNI.setSourceVideoMode(m_handle, pixelFormat.getValue(), width, height, fps);
+  }
+
+  /**
+   * Set the pixel format.
+   *
+   * @param pixelFormat desired pixel format
+   * @return True if set successfully
+   */
+  public boolean setPixelFormat(VideoMode.PixelFormat pixelFormat) {
+    return CameraServerJNI.setSourcePixelFormat(m_handle, pixelFormat.getValue());
+  }
+
+  /**
+   * Set the resolution.
+   *
+   * @param width desired width
+   * @param height desired height
+   * @return True if set successfully
+   */
+  public boolean setResolution(int width, int height) {
+    return CameraServerJNI.setSourceResolution(m_handle, width, height);
+  }
+
+  /**
+   * Set the frames per second (FPS).
+   *
+   * @param fps desired FPS
+   * @return True if set successfully
+   */
+  public boolean setFPS(int fps) {
+    return CameraServerJNI.setSourceFPS(m_handle, fps);
+  }
+
+  /**
+   * Set video mode and properties from a JSON configuration string.
+   *
+   * <p>The format of the JSON input is:
+   *
+   * <pre>
+   * {
+   *     "pixel format": "MJPEG", "YUYV", etc
+   *     "width": video mode width
+   *     "height": video mode height
+   *     "fps": video mode fps
+   *     "brightness": percentage brightness
+   *     "white balance": "auto", "hold", or value
+   *     "exposure": "auto", "hold", or value
+   *     "properties": [
+   *         {
+   *             "name": property name
+   *             "value": property value
+   *         }
+   *     ]
+   * }
+   * </pre>
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  public boolean setConfigJson(String config) {
+    return CameraServerJNI.setSourceConfigJson(m_handle, config);
+  }
+
+  /**
+   * Get a JSON configuration string.
+   *
+   * @return JSON configuration string
+   */
+  public String getConfigJson() {
+    return CameraServerJNI.getSourceConfigJson(m_handle);
+  }
+
+  /**
+   * Get the actual FPS.
+   *
+   * <p>CameraServerJNI#setTelemetryPeriod() must be called for this to be valid
+   * (throws VisionException if telemetry is not enabled).
+   *
+   * @return Actual FPS averaged over the telemetry period.
+   */
+  public double getActualFPS() {
+    return CameraServerJNI.getTelemetryAverageValue(m_handle,
+        CameraServerJNI.TelemetryKind.kSourceFramesReceived);
+  }
+
+  /**
+   * Get the data rate (in bytes per second).
+   *
+   * <p>CameraServerJNI#setTelemetryPeriod() must be called for this to be valid
+   * (throws VisionException if telemetry is not enabled).
+   *
+   * @return Data rate averaged over the telemetry period.
+   */
+  public double getActualDataRate() {
+    return CameraServerJNI.getTelemetryAverageValue(m_handle,
+        CameraServerJNI.TelemetryKind.kSourceBytesReceived);
+  }
+
+  /**
+   * Enumerate all known video modes for this source.
+   */
+  public VideoMode[] enumerateVideoModes() {
+    return CameraServerJNI.enumerateSourceVideoModes(m_handle);
+  }
+
+  /**
+   * Enumerate all sinks connected to this source.
+   *
+   * @return Vector of sinks.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public VideoSink[] enumerateSinks() {
+    int[] handles = CameraServerJNI.enumerateSourceSinks(m_handle);
+    VideoSink[] rv = new VideoSink[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoSink(handles[i]);
+    }
+    return rv;
+  }
+
+  /**
+   * Enumerate all existing sources.
+   *
+   * @return Vector of sources.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  public static VideoSource[] enumerateSources() {
+    int[] handles = CameraServerJNI.enumerateSources();
+    VideoSource[] rv = new VideoSource[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      rv[i] = new VideoSource(handles[i]);
+    }
+    return rv;
+  }
+
+  protected int m_handle;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSinkImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSinkImpl.cpp
new file mode 100644
index 0000000..17dbd18
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSinkImpl.cpp
@@ -0,0 +1,250 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "CvSinkImpl.h"
+
+#include <opencv2/core/core.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+#include <wpi/SmallString.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+CvSinkImpl::CvSinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                       Notifier& notifier, Telemetry& telemetry)
+    : SinkImpl{name, logger, notifier, telemetry} {
+  m_active = true;
+  // m_thread = std::thread(&CvSinkImpl::ThreadMain, this);
+}
+
+CvSinkImpl::CvSinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                       Notifier& notifier, Telemetry& telemetry,
+                       std::function<void(uint64_t time)> processFrame)
+    : SinkImpl{name, logger, notifier, telemetry} {}
+
+CvSinkImpl::~CvSinkImpl() { Stop(); }
+
+void CvSinkImpl::Stop() {
+  m_active = false;
+
+  // wake up any waiters by forcing an empty frame to be sent
+  if (auto source = GetSource()) source->Wakeup();
+
+  // join thread
+  if (m_thread.joinable()) m_thread.join();
+}
+
+uint64_t CvSinkImpl::GrabFrame(cv::Mat& image) {
+  SetEnabled(true);
+
+  auto source = GetSource();
+  if (!source) {
+    // Source disconnected; sleep for one second
+    std::this_thread::sleep_for(std::chrono::seconds(1));
+    return 0;
+  }
+
+  auto frame = source->GetNextFrame();  // blocks
+  if (!frame) {
+    // Bad frame; sleep for 20 ms so we don't consume all processor time.
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;  // signal error
+  }
+
+  if (!frame.GetCv(image)) {
+    // Shouldn't happen, but just in case...
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;
+  }
+
+  return frame.GetTime();
+}
+
+uint64_t CvSinkImpl::GrabFrame(cv::Mat& image, double timeout) {
+  SetEnabled(true);
+
+  auto source = GetSource();
+  if (!source) {
+    // Source disconnected; sleep for one second
+    std::this_thread::sleep_for(std::chrono::seconds(1));
+    return 0;
+  }
+
+  auto frame = source->GetNextFrame(timeout);  // blocks
+  if (!frame) {
+    // Bad frame; sleep for 20 ms so we don't consume all processor time.
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;  // signal error
+  }
+
+  if (!frame.GetCv(image)) {
+    // Shouldn't happen, but just in case...
+    std::this_thread::sleep_for(std::chrono::milliseconds(20));
+    return 0;
+  }
+
+  return frame.GetTime();
+}
+
+// Send HTTP response and a stream of JPG-frames
+void CvSinkImpl::ThreadMain() {
+  Enable();
+  while (m_active) {
+    auto source = GetSource();
+    if (!source) {
+      // Source disconnected; sleep for one second
+      std::this_thread::sleep_for(std::chrono::seconds(1));
+      continue;
+    }
+    SDEBUG4("waiting for frame");
+    Frame frame = source->GetNextFrame();  // blocks
+    if (!m_active) break;
+    if (!frame) {
+      // Bad frame; sleep for 10 ms so we don't consume all processor time.
+      std::this_thread::sleep_for(std::chrono::milliseconds(10));
+      continue;
+    }
+    // TODO m_processFrame();
+  }
+  Disable();
+}
+
+namespace cs {
+
+CS_Sink CreateCvSink(const wpi::Twine& name, CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSink(
+      CS_SINK_CV, std::make_shared<CvSinkImpl>(name, inst.logger, inst.notifier,
+                                               inst.telemetry));
+}
+
+CS_Sink CreateCvSinkCallback(const wpi::Twine& name,
+                             std::function<void(uint64_t time)> processFrame,
+                             CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSink(
+      CS_SINK_CV, std::make_shared<CvSinkImpl>(name, inst.logger, inst.notifier,
+                                               inst.telemetry, processFrame));
+}
+
+void SetSinkDescription(CS_Sink sink, const wpi::Twine& description,
+                        CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_CV) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSinkImpl&>(*data->sink).SetDescription(description);
+}
+
+uint64_t GrabSinkFrame(CS_Sink sink, cv::Mat& image, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_CV) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return static_cast<CvSinkImpl&>(*data->sink).GrabFrame(image);
+}
+
+uint64_t GrabSinkFrameTimeout(CS_Sink sink, cv::Mat& image, double timeout,
+                              CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_CV) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return static_cast<CvSinkImpl&>(*data->sink).GrabFrame(image, timeout);
+}
+
+std::string GetSinkError(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_CV) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return static_cast<CvSinkImpl&>(*data->sink).GetError();
+}
+
+wpi::StringRef GetSinkError(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                            CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_CV) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return static_cast<CvSinkImpl&>(*data->sink).GetError(buf);
+}
+
+void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_CV) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSinkImpl&>(*data->sink).SetEnabled(enabled);
+}
+
+}  // namespace cs
+
+extern "C" {
+
+CS_Sink CS_CreateCvSink(const char* name, CS_Status* status) {
+  return cs::CreateCvSink(name, status);
+}
+
+CS_Sink CS_CreateCvSinkCallback(const char* name, void* data,
+                                void (*processFrame)(void* data, uint64_t time),
+                                CS_Status* status) {
+  return cs::CreateCvSinkCallback(
+      name, [=](uint64_t time) { processFrame(data, time); }, status);
+}
+
+void CS_SetSinkDescription(CS_Sink sink, const char* description,
+                           CS_Status* status) {
+  return cs::SetSinkDescription(sink, description, status);
+}
+
+uint64_t CS_GrabSinkFrame(CS_Sink sink, struct CvMat* image,
+                          CS_Status* status) {
+  auto mat = cv::cvarrToMat(image);
+  return cs::GrabSinkFrame(sink, mat, status);
+}
+
+uint64_t CS_GrabSinkFrameTimeout(CS_Sink sink, struct CvMat* image,
+                                 double timeout, CS_Status* status) {
+  auto mat = cv::cvarrToMat(image);
+  return cs::GrabSinkFrameTimeout(sink, mat, timeout, status);
+}
+
+uint64_t CS_GrabSinkFrameCpp(CS_Sink sink, cv::Mat* image, CS_Status* status) {
+  return cs::GrabSinkFrame(sink, *image, status);
+}
+
+uint64_t CS_GrabSinkFrameTimeoutCpp(CS_Sink sink, cv::Mat* image,
+                                    double timeout, CS_Status* status) {
+  return cs::GrabSinkFrameTimeout(sink, *image, timeout, status);
+}
+
+char* CS_GetSinkError(CS_Sink sink, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkError(sink, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+void CS_SetSinkEnabled(CS_Sink sink, CS_Bool enabled, CS_Status* status) {
+  return cs::SetSinkEnabled(sink, enabled, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSinkImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSinkImpl.h
new file mode 100644
index 0000000..9b7820f
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSinkImpl.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CVSINKIMPL_H_
+#define CSCORE_CVSINKIMPL_H_
+
+#include <stdint.h>
+
+#include <atomic>
+#include <functional>
+#include <thread>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+
+#include "Frame.h"
+#include "SinkImpl.h"
+
+namespace cs {
+
+class SourceImpl;
+
+class CvSinkImpl : public SinkImpl {
+ public:
+  CvSinkImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+             Telemetry& telemetry);
+  CvSinkImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+             Telemetry& telemetry,
+             std::function<void(uint64_t time)> processFrame);
+  ~CvSinkImpl() override;
+
+  void Stop();
+
+  uint64_t GrabFrame(cv::Mat& image);
+  uint64_t GrabFrame(cv::Mat& image, double timeout);
+
+ private:
+  void ThreadMain();
+
+  std::atomic_bool m_active;  // set to false to terminate threads
+  std::thread m_thread;
+  std::function<void(uint64_t time)> m_processFrame;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_CVSINKIMPL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSourceImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSourceImpl.cpp
new file mode 100644
index 0000000..449a9ee
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSourceImpl.cpp
@@ -0,0 +1,312 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "CvSourceImpl.h"
+
+#include <opencv2/core/core.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+#include <wpi/STLExtras.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+CvSourceImpl::CvSourceImpl(const wpi::Twine& name, wpi::Logger& logger,
+                           Notifier& notifier, Telemetry& telemetry,
+                           const VideoMode& mode)
+    : SourceImpl{name, logger, notifier, telemetry} {
+  m_mode = mode;
+  m_videoModes.push_back(m_mode);
+}
+
+CvSourceImpl::~CvSourceImpl() {}
+
+void CvSourceImpl::Start() {
+  m_notifier.NotifySource(*this, CS_SOURCE_CONNECTED);
+  m_notifier.NotifySource(*this, CS_SOURCE_VIDEOMODES_UPDATED);
+  m_notifier.NotifySourceVideoMode(*this, m_mode);
+}
+
+bool CvSourceImpl::SetVideoMode(const VideoMode& mode, CS_Status* status) {
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_mode = mode;
+    m_videoModes[0] = mode;
+  }
+  m_notifier.NotifySourceVideoMode(*this, mode);
+  return true;
+}
+
+void CvSourceImpl::NumSinksChanged() {
+  // ignore
+}
+
+void CvSourceImpl::NumSinksEnabledChanged() {
+  // ignore
+}
+
+void CvSourceImpl::PutFrame(cv::Mat& image) {
+  // We only support 8-bit images; convert if necessary.
+  cv::Mat finalImage;
+  if (image.depth() == CV_8U)
+    finalImage = image;
+  else
+    image.convertTo(finalImage, CV_8U);
+
+  std::unique_ptr<Image> dest;
+  switch (image.channels()) {
+    case 1:
+      dest =
+          AllocImage(VideoMode::kGray, image.cols, image.rows, image.total());
+      finalImage.copyTo(dest->AsMat());
+      break;
+    case 3:
+      dest = AllocImage(VideoMode::kBGR, image.cols, image.rows,
+                        image.total() * 3);
+      finalImage.copyTo(dest->AsMat());
+      break;
+    case 4:
+      dest = AllocImage(VideoMode::kBGR, image.cols, image.rows,
+                        image.total() * 3);
+      cv::cvtColor(finalImage, dest->AsMat(), cv::COLOR_BGRA2BGR);
+      break;
+    default:
+      SERROR("PutFrame: " << image.channels()
+                          << "-channel images not supported");
+      return;
+  }
+  SourceImpl::PutFrame(std::move(dest), wpi::Now());
+}
+
+void CvSourceImpl::NotifyError(const wpi::Twine& msg) {
+  PutError(msg, wpi::Now());
+}
+
+int CvSourceImpl::CreateProperty(const wpi::Twine& name, CS_PropertyKind kind,
+                                 int minimum, int maximum, int step,
+                                 int defaultValue, int value) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  int ndx = CreateOrUpdateProperty(name,
+                                   [=] {
+                                     return wpi::make_unique<PropertyImpl>(
+                                         name, kind, minimum, maximum, step,
+                                         defaultValue, value);
+                                   },
+                                   [&](PropertyImpl& prop) {
+                                     // update all but value
+                                     prop.propKind = kind;
+                                     prop.minimum = minimum;
+                                     prop.maximum = maximum;
+                                     prop.step = step;
+                                     prop.defaultValue = defaultValue;
+                                     value = prop.value;
+                                   });
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CREATED, name, ndx,
+                                  kind, value, wpi::Twine{});
+  return ndx;
+}
+
+int CvSourceImpl::CreateProperty(
+    const wpi::Twine& name, CS_PropertyKind kind, int minimum, int maximum,
+    int step, int defaultValue, int value,
+    std::function<void(CS_Property property)> onChange) {
+  // TODO
+  return 0;
+}
+
+void CvSourceImpl::SetEnumPropertyChoices(int property,
+                                          wpi::ArrayRef<std::string> choices,
+                                          CS_Status* status) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return;
+  }
+  if (prop->propKind != CS_PROP_ENUM) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return;
+  }
+  prop->enumChoices = choices;
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CHOICES_UPDATED,
+                                  prop->name, property, CS_PROP_ENUM,
+                                  prop->value, wpi::Twine{});
+}
+
+namespace cs {
+
+CS_Source CreateCvSource(const wpi::Twine& name, const VideoMode& mode,
+                         CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSource(CS_SOURCE_CV, std::make_shared<CvSourceImpl>(
+                                             name, inst.logger, inst.notifier,
+                                             inst.telemetry, mode));
+}
+
+void PutSourceFrame(CS_Source source, cv::Mat& image, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_CV) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSourceImpl&>(*data->source).PutFrame(image);
+}
+
+void NotifySourceError(CS_Source source, const wpi::Twine& msg,
+                       CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_CV) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSourceImpl&>(*data->source).NotifyError(msg);
+}
+
+void SetSourceConnected(CS_Source source, bool connected, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_CV) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSourceImpl&>(*data->source).SetConnected(connected);
+}
+
+void SetSourceDescription(CS_Source source, const wpi::Twine& description,
+                          CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_CV) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<CvSourceImpl&>(*data->source).SetDescription(description);
+}
+
+CS_Property CreateSourceProperty(CS_Source source, const wpi::Twine& name,
+                                 CS_PropertyKind kind, int minimum, int maximum,
+                                 int step, int defaultValue, int value,
+                                 CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_CV) {
+    *status = CS_INVALID_HANDLE;
+    return -1;
+  }
+  int property = static_cast<CvSourceImpl&>(*data->source)
+                     .CreateProperty(name, kind, minimum, maximum, step,
+                                     defaultValue, value);
+  return Handle{source, property, Handle::kProperty};
+}
+
+CS_Property CreateSourcePropertyCallback(
+    CS_Source source, const wpi::Twine& name, CS_PropertyKind kind, int minimum,
+    int maximum, int step, int defaultValue, int value,
+    std::function<void(CS_Property property)> onChange, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_CV) {
+    *status = CS_INVALID_HANDLE;
+    return -1;
+  }
+  int property = static_cast<CvSourceImpl&>(*data->source)
+                     .CreateProperty(name, kind, minimum, maximum, step,
+                                     defaultValue, value, onChange);
+  return Handle{source, property, Handle::kProperty};
+}
+
+void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
+                                  wpi::ArrayRef<std::string> choices,
+                                  CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_CV) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+
+  // Get property index; also validate the source owns this property
+  Handle handle{property};
+  int i = handle.GetParentIndex();
+  if (i < 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  auto data2 = Instance::GetInstance().GetSource(Handle{i, Handle::kSource});
+  if (!data2 || data->source.get() != data2->source.get()) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  int propertyIndex = handle.GetIndex();
+  static_cast<CvSourceImpl&>(*data->source)
+      .SetEnumPropertyChoices(propertyIndex, choices, status);
+}
+
+}  // namespace cs
+
+extern "C" {
+
+CS_Source CS_CreateCvSource(const char* name, const CS_VideoMode* mode,
+                            CS_Status* status) {
+  return cs::CreateCvSource(name, static_cast<const cs::VideoMode&>(*mode),
+                            status);
+}
+
+void CS_PutSourceFrame(CS_Source source, struct CvMat* image,
+                       CS_Status* status) {
+  auto mat = cv::cvarrToMat(image);
+  return cs::PutSourceFrame(source, mat, status);
+}
+
+void CS_PutSourceFrameCpp(CS_Source source, cv::Mat* image, CS_Status* status) {
+  return cs::PutSourceFrame(source, *image, status);
+}
+
+void CS_NotifySourceError(CS_Source source, const char* msg,
+                          CS_Status* status) {
+  return cs::NotifySourceError(source, msg, status);
+}
+
+void CS_SetSourceConnected(CS_Source source, CS_Bool connected,
+                           CS_Status* status) {
+  return cs::SetSourceConnected(source, connected, status);
+}
+
+void CS_SetSourceDescription(CS_Source source, const char* description,
+                             CS_Status* status) {
+  return cs::SetSourceDescription(source, description, status);
+}
+
+CS_Property CS_CreateSourceProperty(CS_Source source, const char* name,
+                                    enum CS_PropertyKind kind, int minimum,
+                                    int maximum, int step, int defaultValue,
+                                    int value, CS_Status* status) {
+  return cs::CreateSourceProperty(source, name, kind, minimum, maximum, step,
+                                  defaultValue, value, status);
+}
+
+CS_Property CS_CreateSourcePropertyCallback(
+    CS_Source source, const char* name, enum CS_PropertyKind kind, int minimum,
+    int maximum, int step, int defaultValue, int value, void* data,
+    void (*onChange)(void* data, CS_Property property), CS_Status* status) {
+  return cs::CreateSourcePropertyCallback(
+      source, name, kind, minimum, maximum, step, defaultValue, value,
+      [=](CS_Property property) { onChange(data, property); }, status);
+}
+
+void CS_SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
+                                     const char** choices, int count,
+                                     CS_Status* status) {
+  wpi::SmallVector<std::string, 8> vec;
+  vec.reserve(count);
+  for (int i = 0; i < count; ++i) vec.push_back(choices[i]);
+  return cs::SetSourceEnumPropertyChoices(source, property, vec, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSourceImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSourceImpl.h
new file mode 100644
index 0000000..e1a9cd2
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/CvSourceImpl.h
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CVSOURCEIMPL_H_
+#define CSCORE_CVSOURCEIMPL_H_
+
+#include <atomic>
+#include <functional>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/ArrayRef.h>
+#include <wpi/Twine.h>
+
+#include "SourceImpl.h"
+
+namespace cs {
+
+class CvSourceImpl : public SourceImpl {
+ public:
+  CvSourceImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+               Telemetry& telemetry, const VideoMode& mode);
+  ~CvSourceImpl() override;
+
+  void Start() override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  // OpenCV-specific functions
+  void PutFrame(cv::Mat& image);
+  void NotifyError(const wpi::Twine& msg);
+  int CreateProperty(const wpi::Twine& name, CS_PropertyKind kind, int minimum,
+                     int maximum, int step, int defaultValue, int value);
+  int CreateProperty(const wpi::Twine& name, CS_PropertyKind kind, int minimum,
+                     int maximum, int step, int defaultValue, int value,
+                     std::function<void(CS_Property property)> onChange);
+  void SetEnumPropertyChoices(int property, wpi::ArrayRef<std::string> choices,
+                              CS_Status* status);
+
+ private:
+  std::atomic_bool m_connected{true};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_CVSOURCEIMPL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Frame.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Frame.cpp
new file mode 100644
index 0000000..15f9b2d
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Frame.cpp
@@ -0,0 +1,499 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "Frame.h"
+
+#include <cstdlib>
+
+#include <opencv2/core/core.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+
+#include "Instance.h"
+#include "Log.h"
+#include "SourceImpl.h"
+
+using namespace cs;
+
+Frame::Frame(SourceImpl& source, const wpi::Twine& error, Time time)
+    : m_impl{source.AllocFrameImpl().release()} {
+  m_impl->refcount = 1;
+  m_impl->error = error.str();
+  m_impl->time = time;
+}
+
+Frame::Frame(SourceImpl& source, std::unique_ptr<Image> image, Time time)
+    : m_impl{source.AllocFrameImpl().release()} {
+  m_impl->refcount = 1;
+  m_impl->error.resize(0);
+  m_impl->time = time;
+  m_impl->images.push_back(image.release());
+}
+
+Image* Frame::GetNearestImage(int width, int height) const {
+  if (!m_impl) return nullptr;
+  std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+  Image* found = nullptr;
+
+  // Ideally we want the smallest image at least width/height in size
+  for (auto i : m_impl->images) {
+    if (i->IsLarger(width, height) && (!found || (i->IsSmaller(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // Find the largest image (will be less than width/height)
+  for (auto i : m_impl->images) {
+    if (!found || (i->IsLarger(*found))) found = i;
+  }
+  if (found) return found;
+
+  // Shouldn't reach this, but just in case...
+  return m_impl->images.empty() ? nullptr : m_impl->images[0];
+}
+
+Image* Frame::GetNearestImage(int width, int height,
+                              VideoMode::PixelFormat pixelFormat,
+                              int jpegQuality) const {
+  if (!m_impl) return nullptr;
+  std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+  Image* found = nullptr;
+
+  // We want the smallest image at least width/height (or the next largest),
+  // but the primary search order is in order of conversion cost.
+  // If we don't find exactly what we want, we prefer non-JPEG source images
+  // (because JPEG source images require a decompression step).
+  // While the searching takes a little time, it pales in comparison to the
+  // image processing to come, so it's worth spending a little extra time
+  // looking for the most efficient conversion.
+
+  // 1) Same width, height, pixelFormat, and (possibly) JPEG quality
+  //    (e.g. exactly what we want)
+  for (auto i : m_impl->images) {
+    if (i->Is(width, height, pixelFormat, jpegQuality)) return i;
+  }
+
+  // 2) Same width, height, different (but non-JPEG) pixelFormat (color conv)
+  // 2a) If we want JPEG output, prefer BGR over other pixel formats
+  if (pixelFormat == VideoMode::kMJPEG) {
+    for (auto i : m_impl->images) {
+      if (i->Is(width, height, VideoMode::kBGR)) return i;
+    }
+  }
+
+  for (auto i : m_impl->images) {
+    if (i->Is(width, height) && i->pixelFormat != VideoMode::kMJPEG) return i;
+  }
+
+  // 3) Different width, height, same pixelFormat (only if non-JPEG) (resample)
+  if (pixelFormat != VideoMode::kMJPEG) {
+    // 3a) Smallest image at least width/height in size
+    for (auto i : m_impl->images) {
+      if (i->IsLarger(width, height) && i->pixelFormat == pixelFormat &&
+          (!found || (i->IsSmaller(*found))))
+        found = i;
+    }
+    if (found) return found;
+
+    // 3b) Largest image (less than width/height)
+    for (auto i : m_impl->images) {
+      if (i->pixelFormat == pixelFormat && (!found || (i->IsLarger(*found))))
+        found = i;
+    }
+    if (found) return found;
+  }
+
+  // 4) Different width, height, different (but non-JPEG) pixelFormat
+  //    (color conversion + resample)
+  // 4a) Smallest image at least width/height in size
+  for (auto i : m_impl->images) {
+    if (i->IsLarger(width, height) && i->pixelFormat != VideoMode::kMJPEG &&
+        (!found || (i->IsSmaller(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // 4b) Largest image (less than width/height)
+  for (auto i : m_impl->images) {
+    if (i->pixelFormat != VideoMode::kMJPEG &&
+        (!found || (i->IsLarger(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // 5) Same width, height, JPEG pixelFormat (decompression).  As there may be
+  //    multiple JPEG images, find the highest quality one.
+  for (auto i : m_impl->images) {
+    if (i->Is(width, height, VideoMode::kMJPEG) &&
+        (!found || i->jpegQuality > found->jpegQuality)) {
+      found = i;
+      // consider one without a quality setting to be the highest quality
+      // (e.g. directly from the camera)
+      if (i->jpegQuality == -1) break;
+    }
+  }
+  if (found) return found;
+
+  // 6) Different width, height, JPEG pixelFormat (decompression)
+  // 6a) Smallest image at least width/height in size
+  for (auto i : m_impl->images) {
+    if (i->IsLarger(width, height) && i->pixelFormat == VideoMode::kMJPEG &&
+        (!found || (i->IsSmaller(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // 6b) Largest image (less than width/height)
+  for (auto i : m_impl->images) {
+    if (i->pixelFormat != VideoMode::kMJPEG &&
+        (!found || (i->IsLarger(*found))))
+      found = i;
+  }
+  if (found) return found;
+
+  // Shouldn't reach this, but just in case...
+  return m_impl->images.empty() ? nullptr : m_impl->images[0];
+}
+
+Image* Frame::ConvertImpl(Image* image, VideoMode::PixelFormat pixelFormat,
+                          int requiredJpegQuality, int defaultJpegQuality) {
+  if (!image ||
+      image->Is(image->width, image->height, pixelFormat, requiredJpegQuality))
+    return image;
+  Image* cur = image;
+
+  // If the source image is a JPEG, we need to decode it before we can do
+  // anything else with it.  Note that if the destination format is JPEG, we
+  // still need to do this (unless it was already a JPEG, in which case we
+  // would have returned above).
+  if (cur->pixelFormat == VideoMode::kMJPEG) {
+    cur = ConvertMJPEGToBGR(cur);
+    if (pixelFormat == VideoMode::kBGR) return cur;
+  }
+
+  // Color convert
+  switch (pixelFormat) {
+    case VideoMode::kRGB565:
+      // If source is YUYV or Gray, need to convert to BGR first
+      if (cur->pixelFormat == VideoMode::kYUYV) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR))
+          cur = newImage;
+        else
+          cur = ConvertYUYVToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kGray) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR))
+          cur = newImage;
+        else
+          cur = ConvertGrayToBGR(cur);
+      }
+      return ConvertBGRToRGB565(cur);
+    case VideoMode::kGray:
+      // If source is YUYV or RGB565, need to convert to BGR first
+      if (cur->pixelFormat == VideoMode::kYUYV) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR))
+          cur = newImage;
+        else
+          cur = ConvertYUYVToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kRGB565) {
+        // Check to see if BGR version already exists...
+        if (Image* newImage =
+                GetExistingImage(cur->width, cur->height, VideoMode::kBGR))
+          cur = newImage;
+        else
+          cur = ConvertRGB565ToBGR(cur);
+      }
+      return ConvertBGRToGray(cur);
+    case VideoMode::kBGR:
+    case VideoMode::kMJPEG:
+      if (cur->pixelFormat == VideoMode::kYUYV) {
+        cur = ConvertYUYVToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kRGB565) {
+        cur = ConvertRGB565ToBGR(cur);
+      } else if (cur->pixelFormat == VideoMode::kGray) {
+        if (pixelFormat == VideoMode::kBGR)
+          return ConvertGrayToBGR(cur);
+        else
+          return ConvertGrayToMJPEG(cur, defaultJpegQuality);
+      }
+      break;
+    case VideoMode::kYUYV:
+    default:
+      return nullptr;  // Unsupported
+  }
+
+  // Compress if destination is JPEG
+  if (pixelFormat == VideoMode::kMJPEG)
+    cur = ConvertBGRToMJPEG(cur, defaultJpegQuality);
+
+  return cur;
+}
+
+Image* Frame::ConvertMJPEGToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kMJPEG) return nullptr;
+
+  // Allocate an BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Decode
+  cv::Mat newMat = newImage->AsMat();
+  cv::imdecode(image->AsInputArray(), cv::IMREAD_COLOR, &newMat);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertMJPEGToGray(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kMJPEG) return nullptr;
+
+  // Allocate an grayscale image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kGray, image->width, image->height,
+                                image->width * image->height);
+
+  // Decode
+  cv::Mat newMat = newImage->AsMat();
+  cv::imdecode(image->AsInputArray(), cv::IMREAD_GRAYSCALE, &newMat);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertYUYVToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kYUYV) return nullptr;
+
+  // Allocate a BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_YUV2BGR_YUYV);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertBGRToRGB565(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kBGR) return nullptr;
+
+  // Allocate a RGB565 image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kRGB565, image->width, image->height,
+                                image->width * image->height * 2);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_RGB2BGR565);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertRGB565ToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kRGB565) return nullptr;
+
+  // Allocate a BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_BGR5652RGB);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertBGRToGray(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kBGR) return nullptr;
+
+  // Allocate a Grayscale image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kGray, image->width, image->height,
+                                image->width * image->height);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_BGR2GRAY);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertGrayToBGR(Image* image) {
+  if (!image || image->pixelFormat != VideoMode::kBGR) return nullptr;
+
+  // Allocate a BGR image
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kBGR, image->width, image->height,
+                                image->width * image->height * 3);
+
+  // Convert
+  cv::cvtColor(image->AsMat(), newImage->AsMat(), cv::COLOR_GRAY2BGR);
+
+  // Save the result
+  Image* rv = newImage.release();
+  if (m_impl) {
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    m_impl->images.push_back(rv);
+  }
+  return rv;
+}
+
+Image* Frame::ConvertBGRToMJPEG(Image* image, int quality) {
+  if (!image || image->pixelFormat != VideoMode::kBGR) return nullptr;
+  if (!m_impl) return nullptr;
+  std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+
+  // Allocate a JPEG image.  We don't actually know what the resulting size
+  // will be; while the destination will automatically grow, doing so will
+  // cause an extra malloc, so we don't want to be too conservative here.
+  // Per Wikipedia, Q=100 on a sample image results in 8.25 bits per pixel,
+  // this is a little bit more conservative in assuming 50% space savings over
+  // the equivalent BGR image.
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kMJPEG, image->width, image->height,
+                                image->width * image->height * 1.5);
+
+  // Compress
+  if (m_impl->compressionParams.empty()) {
+    m_impl->compressionParams.push_back(CV_IMWRITE_JPEG_QUALITY);
+    m_impl->compressionParams.push_back(quality);
+  } else {
+    m_impl->compressionParams[1] = quality;
+  }
+  cv::imencode(".jpg", image->AsMat(), newImage->vec(),
+               m_impl->compressionParams);
+
+  // Save the result
+  Image* rv = newImage.release();
+  m_impl->images.push_back(rv);
+  return rv;
+}
+
+Image* Frame::ConvertGrayToMJPEG(Image* image, int quality) {
+  if (!image || image->pixelFormat != VideoMode::kGray) return nullptr;
+  if (!m_impl) return nullptr;
+  std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+
+  // Allocate a JPEG image.  We don't actually know what the resulting size
+  // will be; while the destination will automatically grow, doing so will
+  // cause an extra malloc, so we don't want to be too conservative here.
+  // Per Wikipedia, Q=100 on a sample image results in 8.25 bits per pixel,
+  // this is a little bit more conservative in assuming 25% space savings over
+  // the equivalent grayscale image.
+  auto newImage =
+      m_impl->source.AllocImage(VideoMode::kMJPEG, image->width, image->height,
+                                image->width * image->height * 0.75);
+
+  // Compress
+  if (m_impl->compressionParams.empty()) {
+    m_impl->compressionParams.push_back(CV_IMWRITE_JPEG_QUALITY);
+    m_impl->compressionParams.push_back(quality);
+  } else {
+    m_impl->compressionParams[1] = quality;
+  }
+  cv::imencode(".jpg", image->AsMat(), newImage->vec(),
+               m_impl->compressionParams);
+
+  // Save the result
+  Image* rv = newImage.release();
+  m_impl->images.push_back(rv);
+  return rv;
+}
+
+Image* Frame::GetImageImpl(int width, int height,
+                           VideoMode::PixelFormat pixelFormat,
+                           int requiredJpegQuality, int defaultJpegQuality) {
+  if (!m_impl) return nullptr;
+  std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+  Image* cur = GetNearestImage(width, height, pixelFormat, requiredJpegQuality);
+  if (!cur || cur->Is(width, height, pixelFormat, requiredJpegQuality))
+    return cur;
+
+  WPI_DEBUG4(Instance::GetInstance().logger,
+             "converting image from " << cur->width << "x" << cur->height
+                                      << " type " << cur->pixelFormat << " to "
+                                      << width << "x" << height << " type "
+                                      << pixelFormat);
+
+  // If the source image is a JPEG, we need to decode it before we can do
+  // anything else with it.  Note that if the destination format is JPEG, we
+  // still need to do this (unless the width/height/compression were the same,
+  // in which case we already returned the existing JPEG above).
+  if (cur->pixelFormat == VideoMode::kMJPEG) cur = ConvertMJPEGToBGR(cur);
+
+  // Resize
+  if (!cur->Is(width, height)) {
+    // Allocate an image.
+    auto newImage = m_impl->source.AllocImage(
+        cur->pixelFormat, width, height,
+        width * height * (cur->size() / (cur->width * cur->height)));
+
+    // Resize
+    cv::Mat newMat = newImage->AsMat();
+    cv::resize(cur->AsMat(), newMat, newMat.size(), 0, 0);
+
+    // Save the result
+    cur = newImage.release();
+    m_impl->images.push_back(cur);
+  }
+
+  // Convert to output format
+  return ConvertImpl(cur, pixelFormat, requiredJpegQuality, defaultJpegQuality);
+}
+
+bool Frame::GetCv(cv::Mat& image, int width, int height) {
+  Image* rawImage = GetImage(width, height, VideoMode::kBGR);
+  if (!rawImage) return false;
+  rawImage->AsMat().copyTo(image);
+  return true;
+}
+
+void Frame::ReleaseFrame() {
+  for (auto image : m_impl->images)
+    m_impl->source.ReleaseImage(std::unique_ptr<Image>(image));
+  m_impl->images.clear();
+  m_impl->source.ReleaseFrameImpl(std::unique_ptr<Impl>(m_impl));
+  m_impl = nullptr;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Frame.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Frame.h
new file mode 100644
index 0000000..b977f24
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Frame.h
@@ -0,0 +1,200 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_FRAME_H_
+#define CSCORE_FRAME_H_
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "Image.h"
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class SourceImpl;
+
+class Frame {
+  friend class SourceImpl;
+
+ public:
+  using Time = uint64_t;
+
+ private:
+  struct Impl {
+    explicit Impl(SourceImpl& source_) : source(source_) {}
+
+    wpi::recursive_mutex mutex;
+    std::atomic_int refcount{0};
+    Time time{0};
+    SourceImpl& source;
+    std::string error;
+    wpi::SmallVector<Image*, 4> images;
+    std::vector<int> compressionParams;
+  };
+
+ public:
+  Frame() noexcept : m_impl{nullptr} {}
+
+  Frame(SourceImpl& source, const wpi::Twine& error, Time time);
+
+  Frame(SourceImpl& source, std::unique_ptr<Image> image, Time time);
+
+  Frame(const Frame& frame) noexcept : m_impl{frame.m_impl} {
+    if (m_impl) ++m_impl->refcount;
+  }
+
+  Frame(Frame&& other) noexcept : Frame() { swap(*this, other); }
+
+  ~Frame() { DecRef(); }
+
+  Frame& operator=(Frame other) noexcept {
+    swap(*this, other);
+    return *this;
+  }
+
+  explicit operator bool() const { return m_impl && m_impl->error.empty(); }
+
+  friend void swap(Frame& first, Frame& second) noexcept {
+    using std::swap;
+    swap(first.m_impl, second.m_impl);
+  }
+
+  Time GetTime() const { return m_impl ? m_impl->time : 0; }
+
+  wpi::StringRef GetError() const {
+    if (!m_impl) return wpi::StringRef{};
+    return m_impl->error;
+  }
+
+  int GetOriginalWidth() const {
+    if (!m_impl) return 0;
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    if (m_impl->images.empty()) return 0;
+    return m_impl->images[0]->width;
+  }
+
+  int GetOriginalHeight() const {
+    if (!m_impl) return 0;
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    if (m_impl->images.empty()) return 0;
+    return m_impl->images[0]->height;
+  }
+
+  int GetOriginalPixelFormat() const {
+    if (!m_impl) return 0;
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    if (m_impl->images.empty()) return 0;
+    return m_impl->images[0]->pixelFormat;
+  }
+
+  int GetOriginalJpegQuality() const {
+    if (!m_impl) return 0;
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    if (m_impl->images.empty()) return 0;
+    return m_impl->images[0]->jpegQuality;
+  }
+
+  Image* GetExistingImage(size_t i = 0) const {
+    if (!m_impl) return nullptr;
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    if (i >= m_impl->images.size()) return nullptr;
+    return m_impl->images[i];
+  }
+
+  Image* GetExistingImage(int width, int height) const {
+    if (!m_impl) return nullptr;
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    for (auto i : m_impl->images) {
+      if (i->Is(width, height)) return i;
+    }
+    return nullptr;
+  }
+
+  Image* GetExistingImage(int width, int height,
+                          VideoMode::PixelFormat pixelFormat) const {
+    if (!m_impl) return nullptr;
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    for (auto i : m_impl->images) {
+      if (i->Is(width, height, pixelFormat)) return i;
+    }
+    return nullptr;
+  }
+
+  Image* GetExistingImage(int width, int height,
+                          VideoMode::PixelFormat pixelFormat,
+                          int jpegQuality) const {
+    if (!m_impl) return nullptr;
+    std::lock_guard<wpi::recursive_mutex> lock(m_impl->mutex);
+    for (auto i : m_impl->images) {
+      if (i->Is(width, height, pixelFormat, jpegQuality)) return i;
+    }
+    return nullptr;
+  }
+
+  Image* GetNearestImage(int width, int height) const;
+  Image* GetNearestImage(int width, int height,
+                         VideoMode::PixelFormat pixelFormat,
+                         int jpegQuality = -1) const;
+
+  Image* Convert(Image* image, VideoMode::PixelFormat pixelFormat) {
+    if (pixelFormat == VideoMode::kMJPEG) return nullptr;
+    return ConvertImpl(image, pixelFormat, -1, 80);
+  }
+  Image* ConvertToMJPEG(Image* image, int requiredQuality,
+                        int defaultQuality = 80) {
+    return ConvertImpl(image, VideoMode::kMJPEG, requiredQuality,
+                       defaultQuality);
+  }
+  Image* ConvertMJPEGToBGR(Image* image);
+  Image* ConvertMJPEGToGray(Image* image);
+  Image* ConvertYUYVToBGR(Image* image);
+  Image* ConvertBGRToRGB565(Image* image);
+  Image* ConvertRGB565ToBGR(Image* image);
+  Image* ConvertBGRToGray(Image* image);
+  Image* ConvertGrayToBGR(Image* image);
+  Image* ConvertBGRToMJPEG(Image* image, int quality);
+  Image* ConvertGrayToMJPEG(Image* image, int quality);
+
+  Image* GetImage(int width, int height, VideoMode::PixelFormat pixelFormat) {
+    if (pixelFormat == VideoMode::kMJPEG) return nullptr;
+    return GetImageImpl(width, height, pixelFormat, -1, 80);
+  }
+  Image* GetImageMJPEG(int width, int height, int requiredQuality,
+                       int defaultQuality = 80) {
+    return GetImageImpl(width, height, VideoMode::kMJPEG, requiredQuality,
+                        defaultQuality);
+  }
+
+  bool GetCv(cv::Mat& image) {
+    return GetCv(image, GetOriginalWidth(), GetOriginalHeight());
+  }
+  bool GetCv(cv::Mat& image, int width, int height);
+
+ private:
+  Image* ConvertImpl(Image* image, VideoMode::PixelFormat pixelFormat,
+                     int requiredJpegQuality, int defaultJpegQuality);
+  Image* GetImageImpl(int width, int height, VideoMode::PixelFormat pixelFormat,
+                      int requiredJpegQuality, int defaultJpegQuality);
+  void DecRef() {
+    if (m_impl && --(m_impl->refcount) == 0) ReleaseFrame();
+  }
+  void ReleaseFrame();
+
+  Impl* m_impl;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_FRAME_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Handle.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Handle.h
new file mode 100644
index 0000000..ebb3a55
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Handle.h
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_HANDLE_H_
+#define CSCORE_HANDLE_H_
+
+#include "cscore_c.h"
+
+namespace cs {
+
+// Handle data layout:
+// Bits 0-15:  Handle index
+// Bits 16-23: Parent index (property only)
+// Bits 24-30: Type
+
+class Handle {
+ public:
+  enum Type {
+    kUndefined = 0,
+    kProperty = 0x40,
+    kSource,
+    kSink,
+    kListener,
+    kSinkProperty
+  };
+  enum { kIndexMax = 0xffff };
+
+  Handle(CS_Handle handle) : m_handle(handle) {}  // NOLINT
+  operator CS_Handle() const { return m_handle; }
+
+  Handle(int index, Type type) {
+    if (index < 0) {
+      m_handle = 0;
+      return;
+    }
+    m_handle = ((static_cast<int>(type) & 0x7f) << 24) | (index & 0xffff);
+  }
+  Handle(int index, int property, Type type) {
+    if (index < 0 || property < 0) {
+      m_handle = 0;
+      return;
+    }
+    m_handle = ((static_cast<int>(type) & 0x7f) << 24) |
+               ((index & 0xff) << 16) | (property & 0xffff);
+  }
+
+  int GetIndex() const { return static_cast<int>(m_handle) & 0xffff; }
+  Type GetType() const {
+    return static_cast<Type>((static_cast<int>(m_handle) >> 24) & 0xff);
+  }
+  bool IsType(Type type) const { return type == GetType(); }
+  int GetTypedIndex(Type type) const { return IsType(type) ? GetIndex() : -1; }
+  int GetParentIndex() const {
+    return (IsType(Handle::kProperty) || IsType(Handle::kSinkProperty))
+               ? (static_cast<int>(m_handle) >> 16) & 0xff
+               : -1;
+  }
+
+ private:
+  CS_Handle m_handle;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_HANDLE_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/HttpCameraImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/HttpCameraImpl.cpp
new file mode 100644
index 0000000..f15fc5f
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/HttpCameraImpl.cpp
@@ -0,0 +1,618 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "HttpCameraImpl.h"
+
+#include <wpi/STLExtras.h>
+#include <wpi/TCPConnector.h>
+#include <wpi/memory.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "JpegUtil.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "Telemetry.h"
+#include "c_util.h"
+
+using namespace cs;
+
+HttpCameraImpl::HttpCameraImpl(const wpi::Twine& name, CS_HttpCameraKind kind,
+                               wpi::Logger& logger, Notifier& notifier,
+                               Telemetry& telemetry)
+    : SourceImpl{name, logger, notifier, telemetry}, m_kind{kind} {}
+
+HttpCameraImpl::~HttpCameraImpl() {
+  m_active = false;
+
+  // force wakeup of monitor thread
+  m_monitorCond.notify_one();
+
+  // join monitor thread
+  if (m_monitorThread.joinable()) m_monitorThread.join();
+
+  // Close file if it's open
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    if (m_streamConn) m_streamConn->stream->close();
+    if (m_settingsConn) m_settingsConn->stream->close();
+  }
+
+  // force wakeup of camera thread in case it's waiting on cv
+  m_sinkEnabledCond.notify_one();
+
+  // join camera thread
+  if (m_streamThread.joinable()) m_streamThread.join();
+
+  // force wakeup of settings thread
+  m_settingsCond.notify_one();
+
+  // join settings thread
+  if (m_settingsThread.joinable()) m_settingsThread.join();
+}
+
+void HttpCameraImpl::Start() {
+  // Kick off the stream and settings threads
+  m_streamThread = std::thread(&HttpCameraImpl::StreamThreadMain, this);
+  m_settingsThread = std::thread(&HttpCameraImpl::SettingsThreadMain, this);
+  m_monitorThread = std::thread(&HttpCameraImpl::MonitorThreadMain, this);
+}
+
+void HttpCameraImpl::MonitorThreadMain() {
+  while (m_active) {
+    std::unique_lock<wpi::mutex> lock(m_mutex);
+    // sleep for 1 second between checks
+    m_monitorCond.wait_for(lock, std::chrono::seconds(1),
+                           [=] { return !m_active; });
+
+    if (!m_active) break;
+
+    // check to see if we got any frames, and close the stream if not
+    // (this will result in an error at the read point, and ultimately
+    // a reconnect attempt)
+    if (m_streamConn && m_frameCount == 0) {
+      SWARNING("Monitor detected stream hung, disconnecting");
+      m_streamConn->stream->close();
+    }
+
+    // reset the frame counter
+    m_frameCount = 0;
+  }
+
+  SDEBUG("Monitor Thread exiting");
+}
+
+void HttpCameraImpl::StreamThreadMain() {
+  while (m_active) {
+    SetConnected(false);
+
+    // sleep between retries
+    std::this_thread::sleep_for(std::chrono::milliseconds(250));
+
+    // disconnect if not enabled
+    if (!IsEnabled()) {
+      std::unique_lock<wpi::mutex> lock(m_mutex);
+      if (m_streamConn) m_streamConn->stream->close();
+      // Wait for enable
+      m_sinkEnabledCond.wait(lock, [=] { return !m_active || IsEnabled(); });
+      if (!m_active) return;
+    }
+
+    // connect
+    wpi::SmallString<64> boundary;
+    wpi::HttpConnection* conn = DeviceStreamConnect(boundary);
+
+    if (!m_active) break;
+
+    // keep retrying
+    if (!conn) continue;
+
+    // update connected since we're actually connected
+    SetConnected(true);
+
+    // stream
+    DeviceStream(conn->is, boundary);
+    {
+      std::unique_lock<wpi::mutex> lock(m_mutex);
+      m_streamConn = nullptr;
+    }
+  }
+
+  SDEBUG("Camera Thread exiting");
+  SetConnected(false);
+}
+
+wpi::HttpConnection* HttpCameraImpl::DeviceStreamConnect(
+    wpi::SmallVectorImpl<char>& boundary) {
+  // Build the request
+  wpi::HttpRequest req;
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    if (m_locations.empty()) {
+      SERROR("locations array is empty!?");
+      std::this_thread::sleep_for(std::chrono::seconds(1));
+      return nullptr;
+    }
+    if (m_nextLocation >= m_locations.size()) m_nextLocation = 0;
+    req = wpi::HttpRequest{m_locations[m_nextLocation++], m_streamSettings};
+    m_streamSettingsUpdated = false;
+  }
+
+  // Try to connect
+  auto stream =
+      wpi::TCPConnector::connect(req.host.c_str(), req.port, m_logger, 1);
+
+  if (!m_active || !stream) return nullptr;
+
+  auto connPtr = wpi::make_unique<wpi::HttpConnection>(std::move(stream), 1);
+  wpi::HttpConnection* conn = connPtr.get();
+
+  // update m_streamConn
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_frameCount = 1;  // avoid a race with monitor thread
+    m_streamConn = std::move(connPtr);
+  }
+
+  std::string warn;
+  if (!conn->Handshake(req, &warn)) {
+    SWARNING(GetName() << ": " << warn);
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_streamConn = nullptr;
+    return nullptr;
+  }
+
+  // Parse Content-Type header to get the boundary
+  wpi::StringRef mediaType, contentType;
+  std::tie(mediaType, contentType) = conn->contentType.str().split(';');
+  mediaType = mediaType.trim();
+  if (mediaType != "multipart/x-mixed-replace") {
+    SWARNING("\"" << req.host << "\": unrecognized Content-Type \"" << mediaType
+                  << "\"");
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_streamConn = nullptr;
+    return nullptr;
+  }
+
+  // media parameters
+  boundary.clear();
+  while (!contentType.empty()) {
+    wpi::StringRef keyvalue;
+    std::tie(keyvalue, contentType) = contentType.split(';');
+    contentType = contentType.ltrim();
+    wpi::StringRef key, value;
+    std::tie(key, value) = keyvalue.split('=');
+    if (key.trim() == "boundary") {
+      value = value.trim().trim('"');  // value may be quoted
+      boundary.append(value.begin(), value.end());
+    }
+  }
+
+  if (boundary.empty()) {
+    SWARNING("\"" << req.host
+                  << "\": empty multi-part boundary or no Content-Type");
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_streamConn = nullptr;
+    return nullptr;
+  }
+
+  return conn;
+}
+
+void HttpCameraImpl::DeviceStream(wpi::raw_istream& is,
+                                  wpi::StringRef boundary) {
+  // Stored here so we reuse it from frame to frame
+  std::string imageBuf;
+
+  // keep track of number of bad images received; if we receive 3 bad images
+  // in a row, we reconnect
+  int numErrors = 0;
+
+  // streaming loop
+  while (m_active && !is.has_error() && IsEnabled() && numErrors < 3 &&
+         !m_streamSettingsUpdated) {
+    if (!FindMultipartBoundary(is, boundary, nullptr)) break;
+
+    // Read the next two characters after the boundary (normally \r\n)
+    char eol[2];
+    is.read(eol, 2);
+    if (!m_active || is.has_error()) break;
+    // End-of-stream is indicated with trailing --
+    if (eol[0] == '-' && eol[1] == '-') break;
+
+    if (!DeviceStreamFrame(is, imageBuf))
+      ++numErrors;
+    else
+      numErrors = 0;
+  }
+}
+
+bool HttpCameraImpl::DeviceStreamFrame(wpi::raw_istream& is,
+                                       std::string& imageBuf) {
+  // Read the headers
+  wpi::SmallString<64> contentTypeBuf;
+  wpi::SmallString<64> contentLengthBuf;
+  if (!ParseHttpHeaders(is, &contentTypeBuf, &contentLengthBuf)) {
+    SWARNING("disconnected during headers");
+    PutError("disconnected during headers", wpi::Now());
+    return false;
+  }
+
+  // Check the content type (if present)
+  if (!contentTypeBuf.str().empty() &&
+      !contentTypeBuf.str().startswith("image/jpeg")) {
+    wpi::SmallString<64> errBuf;
+    wpi::raw_svector_ostream errMsg{errBuf};
+    errMsg << "received unknown Content-Type \"" << contentTypeBuf << "\"";
+    SWARNING(errMsg.str());
+    PutError(errMsg.str(), wpi::Now());
+    return false;
+  }
+
+  unsigned int contentLength = 0;
+  if (contentLengthBuf.str().getAsInteger(10, contentLength)) {
+    // Ugh, no Content-Length?  Read the blocks of the JPEG file.
+    int width, height;
+    if (!ReadJpeg(is, imageBuf, &width, &height)) {
+      SWARNING("did not receive a JPEG image");
+      PutError("did not receive a JPEG image", wpi::Now());
+      return false;
+    }
+    PutFrame(VideoMode::PixelFormat::kMJPEG, width, height, imageBuf,
+             wpi::Now());
+    ++m_frameCount;
+    return true;
+  }
+
+  // We know how big it is!  Just get a frame of the right size and read
+  // the data directly into it.
+  auto image = AllocImage(VideoMode::PixelFormat::kMJPEG, 0, 0, contentLength);
+  is.read(image->data(), contentLength);
+  if (!m_active || is.has_error()) return false;
+  int width, height;
+  if (!GetJpegSize(image->str(), &width, &height)) {
+    SWARNING("did not receive a JPEG image");
+    PutError("did not receive a JPEG image", wpi::Now());
+    return false;
+  }
+  image->width = width;
+  image->height = height;
+  PutFrame(std::move(image), wpi::Now());
+  ++m_frameCount;
+  return true;
+}
+
+void HttpCameraImpl::SettingsThreadMain() {
+  for (;;) {
+    wpi::HttpRequest req;
+    {
+      std::unique_lock<wpi::mutex> lock(m_mutex);
+      m_settingsCond.wait(lock, [=] {
+        return !m_active || (m_prefLocation != -1 && !m_settings.empty());
+      });
+      if (!m_active) break;
+
+      // Build the request
+      req = wpi::HttpRequest{m_locations[m_prefLocation], m_settings};
+    }
+
+    DeviceSendSettings(req);
+  }
+
+  SDEBUG("Settings Thread exiting");
+}
+
+void HttpCameraImpl::DeviceSendSettings(wpi::HttpRequest& req) {
+  // Try to connect
+  auto stream =
+      wpi::TCPConnector::connect(req.host.c_str(), req.port, m_logger, 1);
+
+  if (!m_active || !stream) return;
+
+  auto connPtr = wpi::make_unique<wpi::HttpConnection>(std::move(stream), 1);
+  wpi::HttpConnection* conn = connPtr.get();
+
+  // update m_settingsConn
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_settingsConn = std::move(connPtr);
+  }
+
+  // Just need a handshake as settings are sent via GET parameters
+  std::string warn;
+  if (!conn->Handshake(req, &warn)) SWARNING(GetName() << ": " << warn);
+
+  conn->stream->close();
+}
+
+CS_HttpCameraKind HttpCameraImpl::GetKind() const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return m_kind;
+}
+
+bool HttpCameraImpl::SetUrls(wpi::ArrayRef<std::string> urls,
+                             CS_Status* status) {
+  std::vector<wpi::HttpLocation> locations;
+  for (const auto& url : urls) {
+    bool error = false;
+    std::string errorMsg;
+    locations.emplace_back(url, &error, &errorMsg);
+    if (error) {
+      SERROR(GetName() << ": " << errorMsg);
+      *status = CS_BAD_URL;
+      return false;
+    }
+  }
+
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_locations.swap(locations);
+  m_nextLocation = 0;
+  m_streamSettingsUpdated = true;
+  return true;
+}
+
+std::vector<std::string> HttpCameraImpl::GetUrls() const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  std::vector<std::string> urls;
+  for (const auto& loc : m_locations) urls.push_back(loc.url);
+  return urls;
+}
+
+void HttpCameraImpl::CreateProperty(const wpi::Twine& name,
+                                    const wpi::Twine& httpParam,
+                                    bool viaSettings, CS_PropertyKind kind,
+                                    int minimum, int maximum, int step,
+                                    int defaultValue, int value) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_propertyData.emplace_back(wpi::make_unique<PropertyData>(
+      name, httpParam, viaSettings, kind, minimum, maximum, step, defaultValue,
+      value));
+
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CREATED, name,
+                                  m_propertyData.size() + 1, kind, value,
+                                  wpi::Twine{});
+}
+
+template <typename T>
+void HttpCameraImpl::CreateEnumProperty(
+    const wpi::Twine& name, const wpi::Twine& httpParam, bool viaSettings,
+    int defaultValue, int value, std::initializer_list<T> choices) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_propertyData.emplace_back(wpi::make_unique<PropertyData>(
+      name, httpParam, viaSettings, CS_PROP_ENUM, 0, choices.size() - 1, 1,
+      defaultValue, value));
+
+  auto& enumChoices = m_propertyData.back()->enumChoices;
+  enumChoices.clear();
+  for (const auto& choice : choices) enumChoices.emplace_back(choice);
+
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CREATED, name,
+                                  m_propertyData.size() + 1, CS_PROP_ENUM,
+                                  value, wpi::Twine{});
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CHOICES_UPDATED,
+                                  name, m_propertyData.size() + 1, CS_PROP_ENUM,
+                                  value, wpi::Twine{});
+}
+
+std::unique_ptr<PropertyImpl> HttpCameraImpl::CreateEmptyProperty(
+    const wpi::Twine& name) const {
+  return wpi::make_unique<PropertyData>(name);
+}
+
+bool HttpCameraImpl::CacheProperties(CS_Status* status) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+
+  // Pretty typical set of video modes
+  m_videoModes.clear();
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 640, 480, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 320, 240, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 160, 120, 30);
+
+  m_properties_cached = true;
+  return true;
+}
+
+void HttpCameraImpl::SetProperty(int property, int value, CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetStringProperty(int property, const wpi::Twine& value,
+                                       CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetBrightness(int brightness, CS_Status* status) {
+  // TODO
+}
+
+int HttpCameraImpl::GetBrightness(CS_Status* status) const {
+  // TODO
+  return 0;
+}
+
+void HttpCameraImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetExposureAuto(CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetExposureHoldCurrent(CS_Status* status) {
+  // TODO
+}
+
+void HttpCameraImpl::SetExposureManual(int value, CS_Status* status) {
+  // TODO
+}
+
+bool HttpCameraImpl::SetVideoMode(const VideoMode& mode, CS_Status* status) {
+  if (mode.pixelFormat != VideoMode::kMJPEG) return false;
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_mode = mode;
+  m_streamSettingsUpdated = true;
+  return true;
+}
+
+void HttpCameraImpl::NumSinksChanged() {
+  // ignore
+}
+
+void HttpCameraImpl::NumSinksEnabledChanged() {
+  m_sinkEnabledCond.notify_one();
+}
+
+bool AxisCameraImpl::CacheProperties(CS_Status* status) const {
+  CreateProperty("brightness", "ImageSource.I0.Sensor.Brightness", true,
+                 CS_PROP_INTEGER, 0, 100, 1, 50, 50);
+  CreateEnumProperty("white_balance", "ImageSource.I0.Sensor.WhiteBalance",
+                     true, 0, 0,
+                     {"auto", "hold", "fixed_outdoor1", "fixed_outdoor2",
+                      "fixed_indoor", "fixed_fluor1", "fixed_fluor2"});
+  CreateProperty("color_level", "ImageSource.I0.Sensor.ColorLevel", true,
+                 CS_PROP_INTEGER, 0, 100, 1, 50, 50);
+  CreateEnumProperty("exposure", "ImageSource.I0.Sensor.Exposure", true, 0, 0,
+                     {"auto", "hold", "flickerfree50", "flickerfree60"});
+  CreateProperty("exposure_priority", "ImageSource.I0.Sensor.ExposurePriority",
+                 true, CS_PROP_INTEGER, 0, 100, 1, 50, 50);
+
+  // TODO: get video modes from device
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_videoModes.clear();
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 640, 480, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 480, 360, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 320, 240, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 240, 180, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 176, 144, 30);
+  m_videoModes.emplace_back(VideoMode::kMJPEG, 160, 120, 30);
+
+  m_properties_cached = true;
+  return true;
+}
+
+namespace cs {
+
+CS_Source CreateHttpCamera(const wpi::Twine& name, const wpi::Twine& url,
+                           CS_HttpCameraKind kind, CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  std::shared_ptr<HttpCameraImpl> source;
+  switch (kind) {
+    case CS_HTTP_AXIS:
+      source = std::make_shared<AxisCameraImpl>(name, inst.logger,
+                                                inst.notifier, inst.telemetry);
+      break;
+    default:
+      source = std::make_shared<HttpCameraImpl>(name, kind, inst.logger,
+                                                inst.notifier, inst.telemetry);
+      break;
+  }
+  if (!source->SetUrls(url.str(), status)) return 0;
+  return inst.CreateSource(CS_SOURCE_HTTP, source);
+}
+
+CS_Source CreateHttpCamera(const wpi::Twine& name,
+                           wpi::ArrayRef<std::string> urls,
+                           CS_HttpCameraKind kind, CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  if (urls.empty()) {
+    *status = CS_EMPTY_VALUE;
+    return 0;
+  }
+  auto source = std::make_shared<HttpCameraImpl>(name, kind, inst.logger,
+                                                 inst.notifier, inst.telemetry);
+  if (!source->SetUrls(urls, status)) return 0;
+  return inst.CreateSource(CS_SOURCE_HTTP, source);
+}
+
+CS_HttpCameraKind GetHttpCameraKind(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_HTTP) {
+    *status = CS_INVALID_HANDLE;
+    return CS_HTTP_UNKNOWN;
+  }
+  return static_cast<HttpCameraImpl&>(*data->source).GetKind();
+}
+
+void SetHttpCameraUrls(CS_Source source, wpi::ArrayRef<std::string> urls,
+                       CS_Status* status) {
+  if (urls.empty()) {
+    *status = CS_EMPTY_VALUE;
+    return;
+  }
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_HTTP) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  static_cast<HttpCameraImpl&>(*data->source).SetUrls(urls, status);
+}
+
+std::vector<std::string> GetHttpCameraUrls(CS_Source source,
+                                           CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_HTTP) {
+    *status = CS_INVALID_HANDLE;
+    return std::vector<std::string>{};
+  }
+  return static_cast<HttpCameraImpl&>(*data->source).GetUrls();
+}
+
+}  // namespace cs
+
+extern "C" {
+
+CS_Source CS_CreateHttpCamera(const char* name, const char* url,
+                              CS_HttpCameraKind kind, CS_Status* status) {
+  return cs::CreateHttpCamera(name, url, kind, status);
+}
+
+CS_Source CS_CreateHttpCameraMulti(const char* name, const char** urls,
+                                   int count, CS_HttpCameraKind kind,
+                                   CS_Status* status) {
+  wpi::SmallVector<std::string, 4> vec;
+  vec.reserve(count);
+  for (int i = 0; i < count; ++i) vec.push_back(urls[i]);
+  return cs::CreateHttpCamera(name, vec, kind, status);
+}
+
+CS_HttpCameraKind CS_GetHttpCameraKind(CS_Source source, CS_Status* status) {
+  return cs::GetHttpCameraKind(source, status);
+}
+
+void CS_SetHttpCameraUrls(CS_Source source, const char** urls, int count,
+                          CS_Status* status) {
+  wpi::SmallVector<std::string, 4> vec;
+  vec.reserve(count);
+  for (int i = 0; i < count; ++i) vec.push_back(urls[i]);
+  cs::SetHttpCameraUrls(source, vec, status);
+}
+
+char** CS_GetHttpCameraUrls(CS_Source source, int* count, CS_Status* status) {
+  auto urls = cs::GetHttpCameraUrls(source, status);
+  char** out =
+      static_cast<char**>(wpi::CheckedMalloc(urls.size() * sizeof(char*)));
+  *count = urls.size();
+  for (size_t i = 0; i < urls.size(); ++i) out[i] = cs::ConvertToC(urls[i]);
+  return out;
+}
+
+void CS_FreeHttpCameraUrls(char** urls, int count) {
+  if (!urls) return;
+  for (int i = 0; i < count; ++i) std::free(urls[i]);
+  std::free(urls);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/HttpCameraImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/HttpCameraImpl.h
new file mode 100644
index 0000000..5967015
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/HttpCameraImpl.h
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_HTTPCAMERAIMPL_H_
+#define CSCORE_HTTPCAMERAIMPL_H_
+
+#include <atomic>
+#include <functional>
+#include <initializer_list>
+#include <memory>
+#include <string>
+#include <thread>
+#include <vector>
+
+#include <wpi/HttpUtil.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/raw_istream.h>
+
+#include "SourceImpl.h"
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class HttpCameraImpl : public SourceImpl {
+ public:
+  HttpCameraImpl(const wpi::Twine& name, CS_HttpCameraKind kind,
+                 wpi::Logger& logger, Notifier& notifier, Telemetry& telemetry);
+  ~HttpCameraImpl() override;
+
+  void Start() override;
+
+  // Property functions
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, const wpi::Twine& value,
+                         CS_Status* status) override;
+
+  // Standard common camera properties
+  void SetBrightness(int brightness, CS_Status* status) override;
+  int GetBrightness(CS_Status* status) const override;
+  void SetWhiteBalanceAuto(CS_Status* status) override;
+  void SetWhiteBalanceHoldCurrent(CS_Status* status) override;
+  void SetWhiteBalanceManual(int value, CS_Status* status) override;
+  void SetExposureAuto(CS_Status* status) override;
+  void SetExposureHoldCurrent(CS_Status* status) override;
+  void SetExposureManual(int value, CS_Status* status) override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  CS_HttpCameraKind GetKind() const;
+  bool SetUrls(wpi::ArrayRef<std::string> urls, CS_Status* status);
+  std::vector<std::string> GetUrls() const;
+
+  // Property data
+  class PropertyData : public PropertyImpl {
+   public:
+    PropertyData() = default;
+    explicit PropertyData(const wpi::Twine& name_) : PropertyImpl{name_} {}
+    PropertyData(const wpi::Twine& name_, const wpi::Twine& httpParam_,
+                 bool viaSettings_, CS_PropertyKind kind_, int minimum_,
+                 int maximum_, int step_, int defaultValue_, int value_)
+        : PropertyImpl(name_, kind_, step_, defaultValue_, value_),
+          viaSettings(viaSettings_),
+          httpParam(httpParam_.str()) {
+      hasMinimum = true;
+      minimum = minimum_;
+      hasMaximum = true;
+      maximum = maximum_;
+    }
+    ~PropertyData() override = default;
+
+    bool viaSettings{false};
+    std::string httpParam;
+  };
+
+ protected:
+  std::unique_ptr<PropertyImpl> CreateEmptyProperty(
+      const wpi::Twine& name) const override;
+
+  bool CacheProperties(CS_Status* status) const override;
+
+  void CreateProperty(const wpi::Twine& name, const wpi::Twine& httpParam,
+                      bool viaSettings, CS_PropertyKind kind, int minimum,
+                      int maximum, int step, int defaultValue, int value) const;
+
+  template <typename T>
+  void CreateEnumProperty(const wpi::Twine& name, const wpi::Twine& httpParam,
+                          bool viaSettings, int defaultValue, int value,
+                          std::initializer_list<T> choices) const;
+
+ private:
+  // The camera streaming thread
+  void StreamThreadMain();
+
+  // Functions used by StreamThreadMain()
+  wpi::HttpConnection* DeviceStreamConnect(
+      wpi::SmallVectorImpl<char>& boundary);
+  void DeviceStream(wpi::raw_istream& is, wpi::StringRef boundary);
+  bool DeviceStreamFrame(wpi::raw_istream& is, std::string& imageBuf);
+
+  // The camera settings thread
+  void SettingsThreadMain();
+  void DeviceSendSettings(wpi::HttpRequest& req);
+
+  // The monitor thread
+  void MonitorThreadMain();
+
+  std::atomic_bool m_connected{false};
+  std::atomic_bool m_active{true};  // set to false to terminate thread
+  std::thread m_streamThread;
+  std::thread m_settingsThread;
+  std::thread m_monitorThread;
+
+  //
+  // Variables protected by m_mutex
+  //
+
+  // The camera connections
+  std::unique_ptr<wpi::HttpConnection> m_streamConn;
+  std::unique_ptr<wpi::HttpConnection> m_settingsConn;
+
+  CS_HttpCameraKind m_kind;
+
+  std::vector<wpi::HttpLocation> m_locations;
+  size_t m_nextLocation{0};
+  int m_prefLocation{-1};  // preferred location
+
+  std::atomic_int m_frameCount{0};
+
+  wpi::condition_variable m_sinkEnabledCond;
+
+  wpi::StringMap<wpi::SmallString<16>> m_settings;
+  wpi::condition_variable m_settingsCond;
+
+  wpi::StringMap<wpi::SmallString<16>> m_streamSettings;
+  std::atomic_bool m_streamSettingsUpdated{false};
+
+  wpi::condition_variable m_monitorCond;
+};
+
+class AxisCameraImpl : public HttpCameraImpl {
+ public:
+  AxisCameraImpl(const wpi::Twine& name, wpi::Logger& logger,
+                 Notifier& notifier, Telemetry& telemetry)
+      : HttpCameraImpl{name, CS_HTTP_AXIS, logger, notifier, telemetry} {}
+#if 0
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, const wpi::Twine& value,
+                         CS_Status* status) override;
+#endif
+ protected:
+  bool CacheProperties(CS_Status* status) const override;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_HTTPCAMERAIMPL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Image.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Image.h
new file mode 100644
index 0000000..6305d93
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Image.h
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_IMAGE_H_
+#define CSCORE_IMAGE_H_
+
+#include <vector>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/StringRef.h>
+
+#include "cscore_cpp.h"
+#include "default_init_allocator.h"
+
+namespace cs {
+
+class Frame;
+
+class Image {
+  friend class Frame;
+
+ public:
+#ifndef __linux__
+  explicit Image(size_t capacity) { m_data.reserve(capacity); }
+#else
+  explicit Image(size_t capacity)
+      : m_data{capacity, default_init_allocator<uchar>{}} {
+    m_data.resize(0);
+  }
+#endif
+
+  Image(const Image&) = delete;
+  Image& operator=(const Image&) = delete;
+
+  // Getters
+  operator wpi::StringRef() const { return str(); }
+  wpi::StringRef str() const { return wpi::StringRef(data(), size()); }
+  size_t capacity() const { return m_data.capacity(); }
+  const char* data() const {
+    return reinterpret_cast<const char*>(m_data.data());
+  }
+  char* data() { return reinterpret_cast<char*>(m_data.data()); }
+  size_t size() const { return m_data.size(); }
+
+  const std::vector<uchar>& vec() const { return m_data; }
+  std::vector<uchar>& vec() { return m_data; }
+
+  void resize(size_t size) { m_data.resize(size); }
+  void SetSize(size_t size) { m_data.resize(size); }
+
+  cv::Mat AsMat() {
+    int type;
+    switch (pixelFormat) {
+      case VideoMode::kYUYV:
+      case VideoMode::kRGB565:
+        type = CV_8UC2;
+        break;
+      case VideoMode::kBGR:
+        type = CV_8UC3;
+        break;
+      case VideoMode::kGray:
+      case VideoMode::kMJPEG:
+      default:
+        type = CV_8UC1;
+        break;
+    }
+    return cv::Mat{height, width, type, m_data.data()};
+  }
+
+  cv::_InputArray AsInputArray() { return cv::_InputArray{m_data}; }
+
+  bool Is(int width_, int height_) {
+    return width == width_ && height == height_;
+  }
+  bool Is(int width_, int height_, VideoMode::PixelFormat pixelFormat_) {
+    return width == width_ && height == height_ && pixelFormat == pixelFormat_;
+  }
+  bool Is(int width_, int height_, VideoMode::PixelFormat pixelFormat_,
+          int jpegQuality_) {
+    // Consider +/-5 on JPEG quality to be "close enough"
+    return width == width_ && height == height_ &&
+           pixelFormat == pixelFormat_ &&
+           (pixelFormat != VideoMode::kMJPEG || jpegQuality_ == -1 ||
+            (jpegQuality != -1 && std::abs(jpegQuality - jpegQuality_) <= 5));
+  }
+  bool IsLarger(int width_, int height_) {
+    return width >= width_ && height >= height_;
+  }
+  bool IsLarger(const Image& oth) {
+    return width >= oth.width && height >= oth.height;
+  }
+  bool IsSmaller(int width_, int height_) { return !IsLarger(width_, height_); }
+  bool IsSmaller(const Image& oth) { return !IsLarger(oth); }
+
+ private:
+  std::vector<uchar> m_data;
+
+ public:
+  VideoMode::PixelFormat pixelFormat{VideoMode::kUnknown};
+  int width{0};
+  int height{0};
+  int jpegQuality{-1};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_IMAGE_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Instance.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Instance.cpp
new file mode 100644
index 0000000..8dd5c26
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Instance.cpp
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "Instance.h"
+
+#include <wpi/Path.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringRef.h>
+#include <wpi/raw_ostream.h>
+
+using namespace cs;
+
+static void def_log_func(unsigned int level, const char* file,
+                         unsigned int line, const char* msg) {
+  wpi::SmallString<128> buf;
+  wpi::raw_svector_ostream oss(buf);
+  if (level == 20) {
+    oss << "CS: " << msg << '\n';
+    wpi::errs() << oss.str();
+    return;
+  }
+
+  wpi::StringRef levelmsg;
+  if (level >= 50)
+    levelmsg = "CRITICAL: ";
+  else if (level >= 40)
+    levelmsg = "ERROR: ";
+  else if (level >= 30)
+    levelmsg = "WARNING: ";
+  else
+    return;
+  oss << "CS: " << levelmsg << msg << " (" << wpi::sys::path::filename(file)
+      << ':' << line << ")\n";
+  wpi::errs() << oss.str();
+}
+
+Instance::Instance() : telemetry(notifier), networkListener(logger, notifier) {
+  SetDefaultLogger();
+}
+
+Instance::~Instance() {}
+
+Instance& Instance::GetInstance() {
+  static Instance* inst = new Instance;
+  return *inst;
+}
+
+void Instance::Shutdown() {
+  eventLoop.Stop();
+  m_sinks.FreeAll();
+  m_sources.FreeAll();
+  networkListener.Stop();
+  telemetry.Stop();
+  notifier.Stop();
+}
+
+void Instance::SetDefaultLogger() { logger.SetLogger(def_log_func); }
+
+std::pair<CS_Source, std::shared_ptr<SourceData>> Instance::FindSource(
+    const SourceImpl& source) {
+  return m_sources.FindIf(
+      [&](const SourceData& data) { return data.source.get() == &source; });
+}
+
+std::pair<CS_Sink, std::shared_ptr<SinkData>> Instance::FindSink(
+    const SinkImpl& sink) {
+  return m_sinks.FindIf(
+      [&](const SinkData& data) { return data.sink.get() == &sink; });
+}
+
+CS_Source Instance::CreateSource(CS_SourceKind kind,
+                                 std::shared_ptr<SourceImpl> source) {
+  auto handle = m_sources.Allocate(kind, source);
+  notifier.NotifySource(source->GetName(), handle, CS_SOURCE_CREATED);
+  source->Start();
+  return handle;
+}
+
+CS_Sink Instance::CreateSink(CS_SinkKind kind, std::shared_ptr<SinkImpl> sink) {
+  auto handle = m_sinks.Allocate(kind, sink);
+  notifier.NotifySink(sink->GetName(), handle, CS_SINK_CREATED);
+  return handle;
+}
+
+void Instance::DestroySource(CS_Source handle) {
+  if (auto data = m_sources.Free(handle))
+    notifier.NotifySource(data->source->GetName(), handle, CS_SOURCE_DESTROYED);
+}
+
+void Instance::DestroySink(CS_Sink handle) {
+  if (auto data = m_sinks.Free(handle))
+    notifier.NotifySink(data->sink->GetName(), handle, CS_SINK_DESTROYED);
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Instance.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Instance.h
new file mode 100644
index 0000000..0c566f3
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Instance.h
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_INSTANCE_H_
+#define CSCORE_INSTANCE_H_
+
+#include <memory>
+#include <utility>
+
+#include <wpi/EventLoopRunner.h>
+#include <wpi/Logger.h>
+
+#include "Log.h"
+#include "NetworkListener.h"
+#include "Notifier.h"
+#include "SinkImpl.h"
+#include "SourceImpl.h"
+#include "Telemetry.h"
+#include "UnlimitedHandleResource.h"
+
+namespace cs {
+
+struct SourceData {
+  SourceData(CS_SourceKind kind_, std::shared_ptr<SourceImpl> source_)
+      : kind{kind_}, refCount{0}, source{source_} {}
+
+  CS_SourceKind kind;
+  std::atomic_int refCount;
+  std::shared_ptr<SourceImpl> source;
+};
+
+struct SinkData {
+  explicit SinkData(CS_SinkKind kind_, std::shared_ptr<SinkImpl> sink_)
+      : kind{kind_}, refCount{0}, sourceHandle{0}, sink{sink_} {}
+
+  CS_SinkKind kind;
+  std::atomic_int refCount;
+  std::atomic<CS_Source> sourceHandle;
+  std::shared_ptr<SinkImpl> sink;
+};
+
+class Instance {
+ public:
+  Instance(const Instance&) = delete;
+  Instance& operator=(const Instance&) = delete;
+  ~Instance();
+
+  static Instance& GetInstance();
+
+  void Shutdown();
+
+  wpi::Logger logger;
+  Notifier notifier;
+  Telemetry telemetry;
+  NetworkListener networkListener;
+
+ private:
+  UnlimitedHandleResource<Handle, SourceData, Handle::kSource> m_sources;
+  UnlimitedHandleResource<Handle, SinkData, Handle::kSink> m_sinks;
+
+ public:
+  wpi::EventLoopRunner eventLoop;
+
+  std::pair<CS_Sink, std::shared_ptr<SinkData>> FindSink(const SinkImpl& sink);
+  std::pair<CS_Source, std::shared_ptr<SourceData>> FindSource(
+      const SourceImpl& source);
+
+  void SetDefaultLogger();
+
+  std::shared_ptr<SourceData> GetSource(CS_Source handle) {
+    return m_sources.Get(handle);
+  }
+
+  std::shared_ptr<SinkData> GetSink(CS_Sink handle) {
+    return m_sinks.Get(handle);
+  }
+
+  CS_Source CreateSource(CS_SourceKind kind,
+                         std::shared_ptr<SourceImpl> source);
+
+  CS_Sink CreateSink(CS_SinkKind kind, std::shared_ptr<SinkImpl> sink);
+
+  void DestroySource(CS_Source handle);
+  void DestroySink(CS_Sink handle);
+
+  wpi::ArrayRef<CS_Source> EnumerateSourceHandles(
+      wpi::SmallVectorImpl<CS_Source>& vec) {
+    return m_sources.GetAll(vec);
+  }
+
+  wpi::ArrayRef<CS_Sink> EnumerateSinkHandles(
+      wpi::SmallVectorImpl<CS_Sink>& vec) {
+    return m_sinks.GetAll(vec);
+  }
+
+  wpi::ArrayRef<CS_Sink> EnumerateSourceSinks(
+      CS_Source source, wpi::SmallVectorImpl<CS_Sink>& vec) {
+    vec.clear();
+    m_sinks.ForEach([&](CS_Sink sinkHandle, const SinkData& data) {
+      if (source == data.sourceHandle.load()) vec.push_back(sinkHandle);
+    });
+    return vec;
+  }
+
+ private:
+  Instance();
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_INSTANCE_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/JpegUtil.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/JpegUtil.cpp
new file mode 100644
index 0000000..35891e8
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/JpegUtil.cpp
@@ -0,0 +1,197 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "JpegUtil.h"
+
+#include <wpi/raw_istream.h>
+
+namespace cs {
+
+// DHT data for MJPEG images that don't have it.
+static const unsigned char dhtData[] = {
+    0xff, 0xc4, 0x01, 0xa2, 0x00, 0x00, 0x01, 0x05, 0x01, 0x01, 0x01, 0x01,
+    0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02,
+    0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0x01, 0x00, 0x03,
+    0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00,
+    0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09,
+    0x0a, 0x0b, 0x10, 0x00, 0x02, 0x01, 0x03, 0x03, 0x02, 0x04, 0x03, 0x05,
+    0x05, 0x04, 0x04, 0x00, 0x00, 0x01, 0x7d, 0x01, 0x02, 0x03, 0x00, 0x04,
+    0x11, 0x05, 0x12, 0x21, 0x31, 0x41, 0x06, 0x13, 0x51, 0x61, 0x07, 0x22,
+    0x71, 0x14, 0x32, 0x81, 0x91, 0xa1, 0x08, 0x23, 0x42, 0xb1, 0xc1, 0x15,
+    0x52, 0xd1, 0xf0, 0x24, 0x33, 0x62, 0x72, 0x82, 0x09, 0x0a, 0x16, 0x17,
+    0x18, 0x19, 0x1a, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x34, 0x35, 0x36,
+    0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a,
+    0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66,
+    0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a,
+    0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94, 0x95,
+    0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8,
+    0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, 0xc2,
+    0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5,
+    0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe1, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7,
+    0xe8, 0xe9, 0xea, 0xf1, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9,
+    0xfa, 0x11, 0x00, 0x02, 0x01, 0x02, 0x04, 0x04, 0x03, 0x04, 0x07, 0x05,
+    0x04, 0x04, 0x00, 0x01, 0x02, 0x77, 0x00, 0x01, 0x02, 0x03, 0x11, 0x04,
+    0x05, 0x21, 0x31, 0x06, 0x12, 0x41, 0x51, 0x07, 0x61, 0x71, 0x13, 0x22,
+    0x32, 0x81, 0x08, 0x14, 0x42, 0x91, 0xa1, 0xb1, 0xc1, 0x09, 0x23, 0x33,
+    0x52, 0xf0, 0x15, 0x62, 0x72, 0xd1, 0x0a, 0x16, 0x24, 0x34, 0xe1, 0x25,
+    0xf1, 0x17, 0x18, 0x19, 0x1a, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x35, 0x36,
+    0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a,
+    0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66,
+    0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a,
+    0x82, 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94,
+    0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7,
+    0xa8, 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba,
+    0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4,
+    0xd5, 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7,
+    0xe8, 0xe9, 0xea, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa};
+
+bool IsJpeg(wpi::StringRef data) {
+  if (data.size() < 11) return false;
+
+  // Check for valid SOI
+  auto bytes = data.bytes_begin();
+  if (bytes[0] != 0xff || bytes[1] != 0xd8) return false;
+  return true;
+}
+
+bool GetJpegSize(wpi::StringRef data, int* width, int* height) {
+  if (!IsJpeg(data)) return false;
+
+  data = data.substr(2);  // Get to the first block
+  auto bytes = data.bytes_begin();
+  for (;;) {
+    if (data.size() < 4) return false;  // EOF
+    bytes = data.bytes_begin();
+    if (bytes[0] != 0xff) return false;  // not a tag
+    if (bytes[1] == 0xd9) return false;  // EOI without finding SOF?
+    if (bytes[1] == 0xda) return false;  // SOS without finding SOF?
+    if (bytes[1] == 0xc0) {
+      // SOF contains the file size
+      if (data.size() < 9) return false;
+      *height = bytes[5] * 256 + bytes[6];
+      *width = bytes[7] * 256 + bytes[8];
+      return true;
+    }
+    // Go to the next block
+    data = data.substr(bytes[2] * 256 + bytes[3] + 2);
+  }
+}
+
+bool JpegNeedsDHT(const char* data, size_t* size, size_t* locSOF) {
+  wpi::StringRef sdata(data, *size);
+  if (!IsJpeg(sdata)) return false;
+
+  *locSOF = *size;
+
+  // Search until SOS for DHT tag
+  sdata = sdata.substr(2);  // Get to the first block
+  auto bytes = sdata.bytes_begin();
+  for (;;) {
+    if (sdata.size() < 4) return false;  // EOF
+    bytes = sdata.bytes_begin();
+    if (bytes[0] != 0xff) return false;                   // not a tag
+    if (bytes[1] == 0xda) break;                          // SOS
+    if (bytes[1] == 0xc4) return false;                   // DHT
+    if (bytes[1] == 0xc0) *locSOF = sdata.data() - data;  // SOF
+    // Go to the next block
+    sdata = sdata.substr(bytes[2] * 256 + bytes[3] + 2);
+  }
+
+  // Only add DHT if we also found SOF (insertion point)
+  if (*locSOF != *size) {
+    *size += sizeof(dhtData);
+    return true;
+  }
+  return false;
+}
+
+wpi::StringRef JpegGetDHT() {
+  return wpi::StringRef(reinterpret_cast<const char*>(dhtData),
+                        sizeof(dhtData));
+}
+
+static inline void ReadInto(wpi::raw_istream& is, std::string& buf,
+                            size_t len) {
+  size_t oldSize = buf.size();
+  buf.resize(oldSize + len);
+  is.read(&(*buf.begin()) + oldSize, len);
+}
+
+bool ReadJpeg(wpi::raw_istream& is, std::string& buf, int* width, int* height) {
+  // in case we don't get a SOF
+  *width = 0;
+  *height = 0;
+
+  // read SOI and first marker
+  buf.resize(4);
+  is.read(&(*buf.begin()), 4);
+  if (is.has_error()) return false;
+
+  // Check for valid SOI
+  auto bytes = reinterpret_cast<const unsigned char*>(buf.data());
+  if (bytes[0] != 0xff || bytes[1] != 0xd8) return false;
+  size_t pos = 2;  // point to first marker
+  for (;;) {
+    bytes = reinterpret_cast<const unsigned char*>(buf.data() + pos);
+    if (bytes[0] != 0xff) return false;  // not a marker
+    unsigned char marker = bytes[1];
+
+    if (marker == 0xd9) return true;  // EOI, we're done
+
+    if (marker == 0xda) {
+      // SOS: need to keep reading until we reach a normal marker.
+      // Byte stuffing ensures we don't get false markers.
+      // Have to read a byte at a time as we don't want to overread.
+      pos += 2;  // point after SOS marker
+      bool maybeMarker = false;
+      for (;;) {
+        ReadInto(is, buf, 1);
+        if (is.has_error()) return false;
+        bytes = reinterpret_cast<const unsigned char*>(buf.data() + pos);
+        if (maybeMarker) {
+          if (bytes[0] != 0x00 && bytes[0] != 0xff &&
+              (bytes[0] < 0xd0 || bytes[0] > 0xd7))
+            break;
+          maybeMarker = false;
+        } else if (bytes[0] == 0xff) {
+          maybeMarker = true;
+        }
+        ++pos;  // point after byte we finished reading
+      }
+      --pos;  // point back to start of marker
+      continue;
+    }
+
+    // A normal block. Read the length
+    ReadInto(is, buf, 2);  // read length
+    if (is.has_error()) return false;
+
+    // Point to length
+    pos += 2;
+    bytes = reinterpret_cast<const unsigned char*>(buf.data() + pos);
+
+    // Read the block and the next marker
+    size_t blockLength = bytes[0] * 256 + bytes[1];
+    ReadInto(is, buf, blockLength);
+    if (is.has_error()) return false;
+    bytes = reinterpret_cast<const unsigned char*>(buf.data() + pos);
+
+    // Special block processing
+    if (marker == 0xc0) {
+      // SOF: contains the file size; make sure we actually read enough bytes
+      if (blockLength >= 7) {
+        *height = bytes[3] * 256 + bytes[4];
+        *width = bytes[5] * 256 + bytes[6];
+      }
+    }
+
+    // Point to next marker
+    pos += blockLength;
+  }
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/JpegUtil.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/JpegUtil.h
new file mode 100644
index 0000000..082fdc4
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/JpegUtil.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_JPEGUTIL_H_
+#define CSCORE_JPEGUTIL_H_
+
+#include <string>
+
+#include <wpi/StringRef.h>
+
+namespace wpi {
+class raw_istream;
+}  // namespace wpi
+
+namespace cs {
+
+bool IsJpeg(wpi::StringRef data);
+
+bool GetJpegSize(wpi::StringRef data, int* width, int* height);
+
+bool JpegNeedsDHT(const char* data, size_t* size, size_t* locSOF);
+
+wpi::StringRef JpegGetDHT();
+
+bool ReadJpeg(wpi::raw_istream& is, std::string& buf, int* width, int* height);
+
+}  // namespace cs
+
+#endif  // CSCORE_JPEGUTIL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Log.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Log.h
new file mode 100644
index 0000000..9ca0e1b
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Log.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_LOG_H_
+#define CSCORE_LOG_H_
+
+#include <wpi/Logger.h>
+
+#define LOG(level, x) WPI_LOG(m_logger, level, x)
+
+#undef ERROR
+#define ERROR(x) WPI_ERROR(m_logger, x)
+#define WARNING(x) WPI_WARNING(m_logger, x)
+#define INFO(x) WPI_INFO(m_logger, x)
+
+#define DEBUG(x) WPI_DEBUG(m_logger, x)
+#define DEBUG1(x) WPI_DEBUG1(m_logger, x)
+#define DEBUG2(x) WPI_DEBUG2(m_logger, x)
+#define DEBUG3(x) WPI_DEBUG3(m_logger, x)
+#define DEBUG4(x) WPI_DEBUG4(m_logger, x)
+
+#define SERROR(x) ERROR(GetName() << ": " << x)
+#define SWARNING(x) WARNING(GetName() << ": " << x)
+#define SINFO(x) INFO(GetName() << ": " << x)
+
+#define SDEBUG(x) DEBUG(GetName() << ": " << x)
+#define SDEBUG1(x) DEBUG1(GetName() << ": " << x)
+#define SDEBUG2(x) DEBUG2(GetName() << ": " << x)
+#define SDEBUG3(x) DEBUG3(GetName() << ": " << x)
+#define SDEBUG4(x) DEBUG4(GetName() << ": " << x)
+
+#endif  // CSCORE_LOG_H_
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
new file mode 100644
index 0000000..9dd6f33
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/MjpegServerImpl.cpp
@@ -0,0 +1,1005 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "MjpegServerImpl.h"
+
+#include <chrono>
+
+#include <wpi/HttpUtil.h>
+#include <wpi/SmallString.h>
+#include <wpi/TCPAcceptor.h>
+#include <wpi/raw_socket_istream.h>
+#include <wpi/raw_socket_ostream.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "JpegUtil.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "SourceImpl.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+// The boundary used for the M-JPEG stream.
+// It separates the multipart stream of pictures
+#define BOUNDARY "boundarydonotcross"
+
+// A bare-bones HTML webpage for user friendliness.
+static const char* emptyRootPage =
+    "</head><body>"
+    "<img src=\"/stream.mjpg\" /><p />"
+    "<a href=\"/settings.json\">Settings JSON</a>"
+    "</body></html>";
+
+// An HTML page to be sent when a source exists
+static const char* startRootPage =
+    "<script>\n"
+    "function httpGetAsync(name, val)\n"
+    "{\n"
+    "    var host = location.protocol + '//' + location.host + "
+    "'/?action=command&' + name + '=' + val;\n"
+    "    var xmlHttp = new XMLHttpRequest();\n"
+    "    xmlHttp.open(\"GET\", host, true);\n"
+    "    xmlHttp.send(null);\n"
+    "}\n"
+    "function updateInt(prop, name, val) {\n"
+    "    document.querySelector(prop).value = val;\n"
+    "    httpGetAsync(name, val);\n"
+    "}\n"
+    "function update(name, val) {\n"
+    "    httpGetAsync(name, val);\n"
+    "}\n"
+    "</script>\n"
+    "<style>\n"
+    "table, th, td {\n"
+    "    border: 1px solid black;\n"
+    "    border-collapse: collapse;\n"
+    "}\n"
+    ".settings { float: left; }\n"
+    ".stream { display: inline-block; margin-left: 10px; }\n"
+    "</style>\n"
+    "</head><body>\n"
+    "<div class=\"stream\">\n"
+    "<img src=\"/stream.mjpg\" /><p />\n"
+    "<a href=\"/settings.json\">Settings JSON</a> |\n"
+    "<a href=\"/config.json\">Source Config JSON</a>\n"
+    "</div>\n"
+    "<div class=\"settings\">\n";
+static const char* endRootPage = "</div></body></html>";
+
+class MjpegServerImpl::ConnThread : public wpi::SafeThread {
+ public:
+  explicit ConnThread(const wpi::Twine& name, wpi::Logger& logger)
+      : m_name(name.str()), m_logger(logger) {}
+
+  void Main();
+
+  bool ProcessCommand(wpi::raw_ostream& os, SourceImpl& source,
+                      wpi::StringRef parameters, bool respond);
+  void SendJSON(wpi::raw_ostream& os, SourceImpl& source, bool header);
+  void SendHTMLHeadTitle(wpi::raw_ostream& os) const;
+  void SendHTML(wpi::raw_ostream& os, SourceImpl& source, bool header);
+  void SendStream(wpi::raw_socket_ostream& os);
+  void ProcessRequest();
+
+  std::unique_ptr<wpi::NetworkStream> m_stream;
+  std::shared_ptr<SourceImpl> m_source;
+  bool m_streaming = false;
+  bool m_noStreaming = false;
+  int m_width = 0;
+  int m_height = 0;
+  int m_compression = -1;
+  int m_defaultCompression = 80;
+  int m_fps = 0;
+
+ private:
+  std::string m_name;
+  wpi::Logger& m_logger;
+
+  wpi::StringRef GetName() { return m_name; }
+
+  std::shared_ptr<SourceImpl> GetSource() {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    return m_source;
+  }
+
+  void StartStream() {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_source->EnableSink();
+    m_streaming = true;
+  }
+
+  void StopStream() {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_source->DisableSink();
+    m_streaming = false;
+  }
+};
+
+// Standard header to send along with other header information like mimetype.
+//
+// The parameters should ensure the browser does not cache our answer.
+// A browser should connect for each file and not serve files from its cache.
+// Using cached pictures would lead to showing old/outdated pictures.
+// Many browsers seem to ignore, or at least not always obey, those headers.
+static void SendHeader(wpi::raw_ostream& os, int code,
+                       const wpi::Twine& codeText,
+                       const wpi::Twine& contentType,
+                       const wpi::Twine& extra = wpi::Twine{}) {
+  os << "HTTP/1.0 " << code << ' ' << codeText << "\r\n";
+  os << "Connection: close\r\n"
+        "Server: CameraServer/1.0\r\n"
+        "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
+        "post-check=0, max-age=0\r\n"
+        "Pragma: no-cache\r\n"
+        "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n";
+  os << "Content-Type: " << contentType << "\r\n";
+  os << "Access-Control-Allow-Origin: *\r\nAccess-Control-Allow-Methods: *\r\n";
+  wpi::SmallString<128> extraBuf;
+  wpi::StringRef extraStr = extra.toStringRef(extraBuf);
+  if (!extraStr.empty()) os << extraStr << "\r\n";
+  os << "\r\n";  // header ends with a blank line
+}
+
+// Send error header and message
+// @param code HTTP error code (e.g. 404)
+// @param message Additional message text
+static void SendError(wpi::raw_ostream& os, int code,
+                      const wpi::Twine& message) {
+  wpi::StringRef codeText, extra, baseMessage;
+  switch (code) {
+    case 401:
+      codeText = "Unauthorized";
+      extra = "WWW-Authenticate: Basic realm=\"CameraServer\"";
+      baseMessage = "401: Not Authenticated!";
+      break;
+    case 404:
+      codeText = "Not Found";
+      baseMessage = "404: Not Found!";
+      break;
+    case 500:
+      codeText = "Internal Server Error";
+      baseMessage = "500: Internal Server Error!";
+      break;
+    case 400:
+      codeText = "Bad Request";
+      baseMessage = "400: Not Found!";
+      break;
+    case 403:
+      codeText = "Forbidden";
+      baseMessage = "403: Forbidden!";
+      break;
+    case 503:
+      codeText = "Service Unavailable";
+      baseMessage = "503: Service Unavailable";
+      break;
+    default:
+      code = 501;
+      codeText = "Not Implemented";
+      baseMessage = "501: Not Implemented!";
+      break;
+  }
+  SendHeader(os, code, codeText, "text/plain", extra);
+  os << baseMessage << "\r\n" << message;
+}
+
+// Perform a command specified by HTTP GET parameters.
+bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os,
+                                                 SourceImpl& source,
+                                                 wpi::StringRef parameters,
+                                                 bool respond) {
+  wpi::SmallString<256> responseBuf;
+  wpi::raw_svector_ostream response{responseBuf};
+  // command format: param1=value1&param2=value2...
+  while (!parameters.empty()) {
+    // split out next param and value
+    wpi::StringRef rawParam, rawValue;
+    std::tie(rawParam, parameters) = parameters.split('&');
+    if (rawParam.empty()) continue;  // ignore "&&"
+    std::tie(rawParam, rawValue) = rawParam.split('=');
+    if (rawParam.empty() || rawValue.empty()) continue;  // ignore "param="
+    SDEBUG4("HTTP parameter \"" << rawParam << "\" value \"" << rawValue
+                                << "\"");
+
+    // unescape param
+    bool error = false;
+    wpi::SmallString<64> paramBuf;
+    wpi::StringRef param = wpi::UnescapeURI(rawParam, paramBuf, &error);
+    if (error) {
+      wpi::SmallString<128> error;
+      wpi::raw_svector_ostream oss{error};
+      oss << "could not unescape parameter \"" << rawParam << "\"";
+      SendError(os, 500, error.str());
+      SDEBUG(error.str());
+      return false;
+    }
+
+    // unescape value
+    wpi::SmallString<64> valueBuf;
+    wpi::StringRef value = wpi::UnescapeURI(rawValue, valueBuf, &error);
+    if (error) {
+      wpi::SmallString<128> error;
+      wpi::raw_svector_ostream oss{error};
+      oss << "could not unescape value \"" << rawValue << "\"";
+      SendError(os, 500, error.str());
+      SDEBUG(error.str());
+      return false;
+    }
+
+    // Handle resolution, compression, and FPS.  These are handled locally
+    // rather than passed to the source.
+    if (param == "resolution") {
+      wpi::StringRef widthStr, heightStr;
+      std::tie(widthStr, heightStr) = value.split('x');
+      int width, height;
+      if (widthStr.getAsInteger(10, width)) {
+        response << param << ": \"width is not an integer\"\r\n";
+        SWARNING("HTTP parameter \"" << param << "\" width \"" << widthStr
+                                     << "\" is not an integer");
+        continue;
+      }
+      if (heightStr.getAsInteger(10, height)) {
+        response << param << ": \"height is not an integer\"\r\n";
+        SWARNING("HTTP parameter \"" << param << "\" height \"" << heightStr
+                                     << "\" is not an integer");
+        continue;
+      }
+      m_width = width;
+      m_height = height;
+      response << param << ": \"ok\"\r\n";
+      continue;
+    }
+
+    if (param == "fps") {
+      int fps;
+      if (value.getAsInteger(10, fps)) {
+        response << param << ": \"invalid integer\"\r\n";
+        SWARNING("HTTP parameter \"" << param << "\" value \"" << value
+                                     << "\" is not an integer");
+        continue;
+      } else {
+        m_fps = fps;
+        response << param << ": \"ok\"\r\n";
+      }
+      continue;
+    }
+
+    if (param == "compression") {
+      int compression;
+      if (value.getAsInteger(10, compression)) {
+        response << param << ": \"invalid integer\"\r\n";
+        SWARNING("HTTP parameter \"" << param << "\" value \"" << value
+                                     << "\" is not an integer");
+        continue;
+      } else {
+        m_compression = compression;
+        response << param << ": \"ok\"\r\n";
+      }
+      continue;
+    }
+
+    // ignore name parameter
+    if (param == "name") continue;
+
+    // try to assign parameter
+    auto prop = source.GetPropertyIndex(param);
+    if (!prop) {
+      response << param << ": \"ignored\"\r\n";
+      SWARNING("ignoring HTTP parameter \"" << param << "\"");
+      continue;
+    }
+
+    CS_Status status = 0;
+    auto kind = source.GetPropertyKind(prop);
+    switch (kind) {
+      case CS_PROP_BOOLEAN:
+      case CS_PROP_INTEGER:
+      case CS_PROP_ENUM: {
+        int val = 0;
+        if (value.getAsInteger(10, val)) {
+          response << param << ": \"invalid integer\"\r\n";
+          SWARNING("HTTP parameter \"" << param << "\" value \"" << value
+                                       << "\" is not an integer");
+        } else {
+          response << param << ": " << val << "\r\n";
+          SDEBUG4("HTTP parameter \"" << param << "\" value " << value);
+          source.SetProperty(prop, val, &status);
+        }
+        break;
+      }
+      case CS_PROP_STRING: {
+        response << param << ": \"ok\"\r\n";
+        SDEBUG4("HTTP parameter \"" << param << "\" value \"" << value << "\"");
+        source.SetStringProperty(prop, value, &status);
+        break;
+      }
+      default:
+        break;
+    }
+  }
+
+  // Send HTTP response
+  if (respond) {
+    SendHeader(os, 200, "OK", "text/plain");
+    os << response.str() << "\r\n";
+  }
+
+  return true;
+}
+
+void MjpegServerImpl::ConnThread::SendHTMLHeadTitle(
+    wpi::raw_ostream& os) const {
+  os << "<html><head><title>" << m_name << " CameraServer</title>"
+     << "<meta charset=\"UTF-8\">";
+}
+
+// Send the root html file with controls for all the settable properties.
+void MjpegServerImpl::ConnThread::SendHTML(wpi::raw_ostream& os,
+                                           SourceImpl& source, bool header) {
+  if (header) SendHeader(os, 200, "OK", "text/html");
+
+  SendHTMLHeadTitle(os);
+  os << startRootPage;
+  wpi::SmallVector<int, 32> properties_vec;
+  CS_Status status = 0;
+  for (auto prop : source.EnumerateProperties(properties_vec, &status)) {
+    wpi::SmallString<128> name_buf;
+    auto name = source.GetPropertyName(prop, name_buf, &status);
+    if (name.startswith("raw_")) continue;
+    auto kind = source.GetPropertyKind(prop);
+    os << "<p />"
+       << "<label for=\"" << name << "\">" << name << "</label>\n";
+    switch (kind) {
+      case CS_PROP_BOOLEAN:
+        os << "<input id=\"" << name
+           << "\" type=\"checkbox\" onclick=\"update('" << name
+           << "', this.checked ? 1 : 0)\" ";
+        if (source.GetProperty(prop, &status) != 0)
+          os << "checked />\n";
+        else
+          os << " />\n";
+        break;
+      case CS_PROP_INTEGER: {
+        auto valI = source.GetProperty(prop, &status);
+        auto min = source.GetPropertyMin(prop, &status);
+        auto max = source.GetPropertyMax(prop, &status);
+        auto step = source.GetPropertyStep(prop, &status);
+        os << "<input type=\"range\" min=\"" << min << "\" max=\"" << max
+           << "\" value=\"" << valI << "\" id=\"" << name << "\" step=\""
+           << step << "\" oninput=\"updateInt('#" << name << "op', '" << name
+           << "', value)\" />\n";
+        os << "<output for=\"" << name << "\" id=\"" << name << "op\">" << valI
+           << "</output>\n";
+        break;
+      }
+      case CS_PROP_ENUM: {
+        auto valE = source.GetProperty(prop, &status);
+        auto choices = source.GetEnumPropertyChoices(prop, &status);
+        int j = 0;
+        for (auto choice = choices.begin(), end = choices.end(); choice != end;
+             ++j, ++choice) {
+          if (choice->empty()) continue;  // skip empty choices
+          // replace any non-printable characters in name with spaces
+          wpi::SmallString<128> ch_name;
+          for (char ch : *choice)
+            ch_name.push_back(std::isprint(ch) ? ch : ' ');
+          os << "<input id=\"" << name << j << "\" type=\"radio\" name=\""
+             << name << "\" value=\"" << ch_name << "\" onclick=\"update('"
+             << name << "', " << j << ")\"";
+          if (j == valE) {
+            os << " checked";
+          }
+          os << " /><label for=\"" << name << j << "\">" << ch_name
+             << "</label>\n";
+        }
+        break;
+      }
+      case CS_PROP_STRING: {
+        wpi::SmallString<128> strval_buf;
+        os << "<input type=\"text\" id=\"" << name << "box\" name=\"" << name
+           << "\" value=\""
+           << source.GetStringProperty(prop, strval_buf, &status) << "\" />\n";
+        os << "<input type=\"button\" value =\"Submit\" onclick=\"update('"
+           << name << "', " << name << "box.value)\" />\n";
+        break;
+      }
+      default:
+        break;
+    }
+  }
+
+  status = 0;
+  auto info = GetUsbCameraInfo(Instance::GetInstance().FindSource(source).first,
+                               &status);
+  if (status == CS_OK) {
+    os << "<p>USB device path: " << info.path << '\n';
+    for (auto&& path : info.otherPaths)
+      os << "<p>Alternate device path: " << path << '\n';
+  }
+
+  os << "<p>Supported Video Modes:</p>\n";
+  os << "<table cols=\"4\" style=\"border: 1px solid black\">\n";
+  os << "<tr><th>Pixel Format</th>"
+     << "<th>Width</th>"
+     << "<th>Height</th>"
+     << "<th>FPS</th></tr>";
+  for (auto mode : source.EnumerateVideoModes(&status)) {
+    os << "<tr><td>";
+    switch (mode.pixelFormat) {
+      case VideoMode::kMJPEG:
+        os << "MJPEG";
+        break;
+      case VideoMode::kYUYV:
+        os << "YUYV";
+        break;
+      case VideoMode::kRGB565:
+        os << "RGB565";
+        break;
+      case VideoMode::kBGR:
+        os << "BGR";
+        break;
+      case VideoMode::kGray:
+        os << "gray";
+        break;
+      default:
+        os << "unknown";
+        break;
+    }
+    os << "</td><td>" << mode.width;
+    os << "</td><td>" << mode.height;
+    os << "</td><td>" << mode.fps;
+    os << "</td></tr>";
+  }
+  os << "</table>\n";
+  os << endRootPage << "\r\n";
+  os.flush();
+}
+
+// Send a JSON file which is contains information about the source parameters.
+void MjpegServerImpl::ConnThread::SendJSON(wpi::raw_ostream& os,
+                                           SourceImpl& source, bool header) {
+  if (header) SendHeader(os, 200, "OK", "application/json");
+
+  os << "{\n\"controls\": [\n";
+  wpi::SmallVector<int, 32> properties_vec;
+  bool first = true;
+  CS_Status status = 0;
+  for (auto prop : source.EnumerateProperties(properties_vec, &status)) {
+    if (first)
+      first = false;
+    else
+      os << ",\n";
+    os << '{';
+    wpi::SmallString<128> name_buf;
+    auto name = source.GetPropertyName(prop, name_buf, &status);
+    auto kind = source.GetPropertyKind(prop);
+    os << "\n\"name\": \"" << name << '"';
+    os << ",\n\"id\": \"" << prop << '"';
+    os << ",\n\"type\": \"" << kind << '"';
+    os << ",\n\"min\": \"" << source.GetPropertyMin(prop, &status) << '"';
+    os << ",\n\"max\": \"" << source.GetPropertyMax(prop, &status) << '"';
+    os << ",\n\"step\": \"" << source.GetPropertyStep(prop, &status) << '"';
+    os << ",\n\"default\": \"" << source.GetPropertyDefault(prop, &status)
+       << '"';
+    os << ",\n\"value\": \"";
+    switch (kind) {
+      case CS_PROP_BOOLEAN:
+      case CS_PROP_INTEGER:
+      case CS_PROP_ENUM:
+        os << source.GetProperty(prop, &status);
+        break;
+      case CS_PROP_STRING: {
+        wpi::SmallString<128> strval_buf;
+        os << source.GetStringProperty(prop, strval_buf, &status);
+        break;
+      }
+      default:
+        break;
+    }
+    os << '"';
+    // os << ",\n\"dest\": \"0\"";
+    // os << ",\n\"flags\": \"" << param->flags << '"';
+    // os << ",\n\"group\": \"" << param->group << '"';
+
+    // append the menu object to the menu typecontrols
+    if (source.GetPropertyKind(prop) == CS_PROP_ENUM) {
+      os << ",\n\"menu\": {";
+      auto choices = source.GetEnumPropertyChoices(prop, &status);
+      int j = 0;
+      for (auto choice = choices.begin(), end = choices.end(); choice != end;
+           ++j, ++choice) {
+        if (j != 0) os << ", ";
+        // replace any non-printable characters in name with spaces
+        wpi::SmallString<128> ch_name;
+        for (char ch : *choice) ch_name.push_back(std::isprint(ch) ? ch : ' ');
+        os << '"' << j << "\": \"" << ch_name << '"';
+      }
+      os << "}\n";
+    }
+    os << '}';
+  }
+  os << "\n],\n\"modes\": [\n";
+  first = true;
+  for (auto mode : source.EnumerateVideoModes(&status)) {
+    if (first)
+      first = false;
+    else
+      os << ",\n";
+    os << '{';
+    os << "\n\"pixelFormat\": \"";
+    switch (mode.pixelFormat) {
+      case VideoMode::kMJPEG:
+        os << "MJPEG";
+        break;
+      case VideoMode::kYUYV:
+        os << "YUYV";
+        break;
+      case VideoMode::kRGB565:
+        os << "RGB565";
+        break;
+      case VideoMode::kBGR:
+        os << "BGR";
+        break;
+      case VideoMode::kGray:
+        os << "gray";
+        break;
+      default:
+        os << "unknown";
+        break;
+    }
+    os << "\",\n\"width\": \"" << mode.width << '"';
+    os << ",\n\"height\": \"" << mode.height << '"';
+    os << ",\n\"fps\": \"" << mode.fps << '"';
+    os << '}';
+  }
+  os << "\n]\n}\n";
+  os.flush();
+}
+
+MjpegServerImpl::MjpegServerImpl(const wpi::Twine& name, wpi::Logger& logger,
+                                 Notifier& notifier, Telemetry& telemetry,
+                                 const wpi::Twine& listenAddress, int port,
+                                 std::unique_ptr<wpi::NetworkAcceptor> acceptor)
+    : SinkImpl{name, logger, notifier, telemetry},
+      m_listenAddress(listenAddress.str()),
+      m_port(port),
+      m_acceptor{std::move(acceptor)} {
+  m_active = true;
+
+  wpi::SmallString<128> descBuf;
+  wpi::raw_svector_ostream desc{descBuf};
+  desc << "HTTP Server on port " << port;
+  SetDescription(desc.str());
+
+  // Create properties
+  m_widthProp = CreateProperty("width", [] {
+    return std::make_unique<PropertyImpl>("width", CS_PROP_INTEGER, 1, 0, 0);
+  });
+  m_heightProp = CreateProperty("height", [] {
+    return std::make_unique<PropertyImpl>("height", CS_PROP_INTEGER, 1, 0, 0);
+  });
+  m_compressionProp = CreateProperty("compression", [] {
+    return std::make_unique<PropertyImpl>("compression", CS_PROP_INTEGER, -1,
+                                          100, 1, -1, -1);
+  });
+  m_defaultCompressionProp = CreateProperty("default_compression", [] {
+    return std::make_unique<PropertyImpl>("default_compression",
+                                          CS_PROP_INTEGER, 0, 100, 1, 80, 80);
+  });
+  m_fpsProp = CreateProperty("fps", [] {
+    return std::make_unique<PropertyImpl>("fps", CS_PROP_INTEGER, 1, 0, 0);
+  });
+
+  m_serverThread = std::thread(&MjpegServerImpl::ServerThreadMain, this);
+}
+
+MjpegServerImpl::~MjpegServerImpl() { Stop(); }
+
+void MjpegServerImpl::Stop() {
+  m_active = false;
+
+  // wake up server thread by shutting down the socket
+  m_acceptor->shutdown();
+
+  // join server thread
+  if (m_serverThread.joinable()) m_serverThread.join();
+
+  // close streams
+  for (auto& connThread : m_connThreads) {
+    if (auto thr = connThread.GetThread()) {
+      if (thr->m_stream) thr->m_stream->close();
+    }
+    connThread.Stop();
+  }
+
+  // wake up connection threads by forcing an empty frame to be sent
+  if (auto source = GetSource()) source->Wakeup();
+}
+
+// Send HTTP response and a stream of JPG-frames
+void MjpegServerImpl::ConnThread::SendStream(wpi::raw_socket_ostream& os) {
+  if (m_noStreaming) {
+    SERROR("Too many simultaneous client streams");
+    SendError(os, 503, "Too many simultaneous streams");
+    return;
+  }
+
+  os.SetUnbuffered();
+
+  wpi::SmallString<256> header;
+  wpi::raw_svector_ostream oss{header};
+
+  SendHeader(oss, 200, "OK", "multipart/x-mixed-replace;boundary=" BOUNDARY);
+  os << oss.str();
+
+  SDEBUG("Headers send, sending stream now");
+
+  Frame::Time lastFrameTime = 0;
+  Frame::Time timePerFrame = 0;
+  if (m_fps != 0) timePerFrame = 1000000.0 / m_fps;
+  Frame::Time averageFrameTime = 0;
+  Frame::Time averagePeriod = 1000000;  // 1 second window
+  if (averagePeriod < timePerFrame) averagePeriod = timePerFrame * 10;
+
+  StartStream();
+  while (m_active && !os.has_error()) {
+    auto source = GetSource();
+    if (!source) {
+      // Source disconnected; sleep so we don't consume all processor time.
+      os << "\r\n";  // Keep connection alive
+      std::this_thread::sleep_for(std::chrono::milliseconds(200));
+      continue;
+    }
+    SDEBUG4("waiting for frame");
+    Frame frame = source->GetNextFrame(0.225);  // blocks
+    if (!m_active) break;
+    if (!frame) {
+      // Bad frame; sleep for 20 ms so we don't consume all processor time.
+      os << "\r\n";  // Keep connection alive
+      std::this_thread::sleep_for(std::chrono::milliseconds(20));
+      continue;
+    }
+
+    auto thisFrameTime = frame.GetTime();
+    if (thisFrameTime != 0 && timePerFrame != 0 && lastFrameTime != 0) {
+      Frame::Time deltaTime = thisFrameTime - lastFrameTime;
+
+      // drop frame if it is early compared to the desired frame rate AND
+      // the current average is higher than the desired average
+      if (deltaTime < timePerFrame && averageFrameTime < timePerFrame) {
+        // sleep for 1 ms so we don't consume all processor time
+        std::this_thread::sleep_for(std::chrono::milliseconds(1));
+        continue;
+      }
+
+      // update average
+      if (averageFrameTime != 0) {
+        averageFrameTime =
+            averageFrameTime * (averagePeriod - timePerFrame) / averagePeriod +
+            deltaTime * timePerFrame / averagePeriod;
+      } else {
+        averageFrameTime = deltaTime;
+      }
+    }
+
+    int width = m_width != 0 ? m_width : frame.GetOriginalWidth();
+    int height = m_height != 0 ? m_height : frame.GetOriginalHeight();
+    Image* image = frame.GetImageMJPEG(
+        width, height, m_compression,
+        m_compression == -1 ? m_defaultCompression : m_compression);
+    if (!image) {
+      // Shouldn't happen, but just in case...
+      std::this_thread::sleep_for(std::chrono::milliseconds(20));
+      continue;
+    }
+
+    const char* data = image->data();
+    size_t size = image->size();
+    bool addDHT = false;
+    size_t locSOF = size;
+    switch (image->pixelFormat) {
+      case VideoMode::kMJPEG:
+        // Determine if we need to add DHT to it, and allocate enough space
+        // for adding it if required.
+        addDHT = JpegNeedsDHT(data, &size, &locSOF);
+        break;
+      case VideoMode::kYUYV:
+      case VideoMode::kRGB565:
+      default:
+        // Bad frame; sleep for 10 ms so we don't consume all processor time.
+        std::this_thread::sleep_for(std::chrono::milliseconds(10));
+        continue;
+    }
+
+    SDEBUG4("sending frame size=" << size << " addDHT=" << addDHT);
+
+    // print the individual mimetype and the length
+    // sending the content-length fixes random stream disruption observed
+    // with firefox
+    lastFrameTime = thisFrameTime;
+    double timestamp = lastFrameTime / 1000000.0;
+    header.clear();
+    oss << "\r\n--" BOUNDARY "\r\n"
+        << "Content-Type: image/jpeg\r\n"
+        << "Content-Length: " << size << "\r\n"
+        << "X-Timestamp: " << timestamp << "\r\n"
+        << "\r\n";
+    os << oss.str();
+    if (addDHT) {
+      // Insert DHT data immediately before SOF
+      os << wpi::StringRef(data, locSOF);
+      os << JpegGetDHT();
+      os << wpi::StringRef(data + locSOF, image->size() - locSOF);
+    } else {
+      os << wpi::StringRef(data, size);
+    }
+    // os.flush();
+  }
+  StopStream();
+}
+
+void MjpegServerImpl::ConnThread::ProcessRequest() {
+  wpi::raw_socket_istream is{*m_stream};
+  wpi::raw_socket_ostream os{*m_stream, true};
+
+  // Read the request string from the stream
+  wpi::SmallString<128> reqBuf;
+  wpi::StringRef req = is.getline(reqBuf, 4096);
+  if (is.has_error()) {
+    SDEBUG("error getting request string");
+    return;
+  }
+
+  enum { kCommand, kStream, kGetSettings, kGetSourceConfig, kRootPage } kind;
+  wpi::StringRef parameters;
+  size_t pos;
+
+  SDEBUG("HTTP request: '" << req << "'\n");
+
+  // Determine request kind.  Most of these are for mjpgstreamer
+  // compatibility, others are for Axis camera compatibility.
+  if ((pos = req.find("POST /stream")) != wpi::StringRef::npos) {
+    kind = kStream;
+    parameters = req.substr(req.find('?', pos + 12)).substr(1);
+  } else if ((pos = req.find("GET /?action=stream")) != wpi::StringRef::npos) {
+    kind = kStream;
+    parameters = req.substr(req.find('&', pos + 19)).substr(1);
+  } else if ((pos = req.find("GET /stream.mjpg")) != wpi::StringRef::npos) {
+    kind = kStream;
+    parameters = req.substr(req.find('?', pos + 16)).substr(1);
+  } else if (req.find("GET /settings") != wpi::StringRef::npos &&
+             req.find(".json") != wpi::StringRef::npos) {
+    kind = kGetSettings;
+  } else if (req.find("GET /config") != wpi::StringRef::npos &&
+             req.find(".json") != wpi::StringRef::npos) {
+    kind = kGetSourceConfig;
+  } else if (req.find("GET /input") != wpi::StringRef::npos &&
+             req.find(".json") != wpi::StringRef::npos) {
+    kind = kGetSettings;
+  } else if (req.find("GET /output") != wpi::StringRef::npos &&
+             req.find(".json") != wpi::StringRef::npos) {
+    kind = kGetSettings;
+  } else if ((pos = req.find("GET /?action=command")) != wpi::StringRef::npos) {
+    kind = kCommand;
+    parameters = req.substr(req.find('&', pos + 20)).substr(1);
+  } else if (req.find("GET / ") != wpi::StringRef::npos || req == "GET /\n") {
+    kind = kRootPage;
+  } else {
+    SDEBUG("HTTP request resource not found");
+    SendError(os, 404, "Resource not found");
+    return;
+  }
+
+  // Parameter can only be certain characters.  This also strips the EOL.
+  pos = parameters.find_first_not_of(
+      "abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ_"
+      "-=&1234567890%./");
+  parameters = parameters.substr(0, pos);
+  SDEBUG("command parameters: \"" << parameters << "\"");
+
+  // Read the rest of the HTTP request.
+  // The end of the request is marked by a single, empty line
+  wpi::SmallString<128> lineBuf;
+  for (;;) {
+    if (is.getline(lineBuf, 4096).startswith("\n")) break;
+    if (is.has_error()) return;
+  }
+
+  // Send response
+  switch (kind) {
+    case kStream:
+      if (auto source = GetSource()) {
+        SDEBUG("request for stream " << source->GetName());
+        if (!ProcessCommand(os, *source, parameters, false)) return;
+      }
+      SendStream(os);
+      break;
+    case kCommand:
+      if (auto source = GetSource()) {
+        ProcessCommand(os, *source, parameters, true);
+      } else {
+        SendHeader(os, 200, "OK", "text/plain");
+        os << "Ignored due to no connected source."
+           << "\r\n";
+        SDEBUG("Ignored due to no connected source.");
+      }
+      break;
+    case kGetSettings:
+      SDEBUG("request for JSON file");
+      if (auto source = GetSource())
+        SendJSON(os, *source, true);
+      else
+        SendError(os, 404, "Resource not found");
+      break;
+    case kGetSourceConfig:
+      SDEBUG("request for JSON file");
+      if (auto source = GetSource()) {
+        SendHeader(os, 200, "OK", "application/json");
+        CS_Status status = CS_OK;
+        os << source->GetConfigJson(&status);
+        os.flush();
+      } else {
+        SendError(os, 404, "Resource not found");
+      }
+      break;
+    case kRootPage:
+      SDEBUG("request for root page");
+      SendHeader(os, 200, "OK", "text/html");
+      if (auto source = GetSource()) {
+        SendHTML(os, *source, false);
+      } else {
+        SendHTMLHeadTitle(os);
+        os << emptyRootPage << "\r\n";
+      }
+      break;
+  }
+
+  SDEBUG("leaving HTTP client thread");
+}
+
+// worker thread for clients that connected to this server
+void MjpegServerImpl::ConnThread::Main() {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  while (m_active) {
+    while (!m_stream) {
+      m_cond.wait(lock);
+      if (!m_active) return;
+    }
+    lock.unlock();
+    ProcessRequest();
+    lock.lock();
+    m_stream = nullptr;
+  }
+}
+
+// Main server thread
+void MjpegServerImpl::ServerThreadMain() {
+  if (m_acceptor->start() != 0) {
+    m_active = false;
+    return;
+  }
+
+  SDEBUG("waiting for clients to connect");
+  while (m_active) {
+    auto stream = m_acceptor->accept();
+    if (!stream) {
+      m_active = false;
+      return;
+    }
+    if (!m_active) return;
+
+    SDEBUG("client connection from " << stream->getPeerIP());
+
+    auto source = GetSource();
+
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    // Find unoccupied worker thread, or create one if necessary
+    auto it = std::find_if(m_connThreads.begin(), m_connThreads.end(),
+                           [](const wpi::SafeThreadOwner<ConnThread>& owner) {
+                             auto thr = owner.GetThread();
+                             return !thr || !thr->m_stream;
+                           });
+    if (it == m_connThreads.end()) {
+      m_connThreads.emplace_back();
+      it = std::prev(m_connThreads.end());
+    }
+
+    // Start it if not already started
+    it->Start(GetName(), m_logger);
+
+    auto nstreams =
+        std::count_if(m_connThreads.begin(), m_connThreads.end(),
+                      [](const wpi::SafeThreadOwner<ConnThread>& owner) {
+                        auto thr = owner.GetThread();
+                        return thr && thr->m_streaming;
+                      });
+
+    // Hand off connection to it
+    auto thr = it->GetThread();
+    thr->m_stream = std::move(stream);
+    thr->m_source = source;
+    thr->m_noStreaming = nstreams >= 10;
+    thr->m_width = GetProperty(m_widthProp)->value;
+    thr->m_height = GetProperty(m_heightProp)->value;
+    thr->m_compression = GetProperty(m_compressionProp)->value;
+    thr->m_defaultCompression = GetProperty(m_defaultCompressionProp)->value;
+    thr->m_fps = GetProperty(m_fpsProp)->value;
+    thr->m_cond.notify_one();
+  }
+
+  SDEBUG("leaving server thread");
+}
+
+void MjpegServerImpl::SetSourceImpl(std::shared_ptr<SourceImpl> source) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  for (auto& connThread : m_connThreads) {
+    if (auto thr = connThread.GetThread()) {
+      if (thr->m_source != source) {
+        bool streaming = thr->m_streaming;
+        if (thr->m_source && streaming) thr->m_source->DisableSink();
+        thr->m_source = source;
+        if (source && streaming) thr->m_source->EnableSink();
+      }
+    }
+  }
+}
+
+namespace cs {
+
+CS_Sink CreateMjpegServer(const wpi::Twine& name,
+                          const wpi::Twine& listenAddress, int port,
+                          CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  wpi::SmallString<128> listenAddressBuf;
+  return inst.CreateSink(
+      CS_SINK_MJPEG,
+      std::make_shared<MjpegServerImpl>(
+          name, inst.logger, inst.notifier, inst.telemetry, listenAddress, port,
+          std::unique_ptr<wpi::NetworkAcceptor>(new wpi::TCPAcceptor(
+              port,
+              listenAddress.toNullTerminatedStringRef(listenAddressBuf).data(),
+              inst.logger))));
+}
+
+std::string GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_MJPEG) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return static_cast<MjpegServerImpl&>(*data->sink).GetListenAddress();
+}
+
+int GetMjpegServerPort(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data || data->kind != CS_SINK_MJPEG) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return static_cast<MjpegServerImpl&>(*data->sink).GetPort();
+}
+
+}  // namespace cs
+
+extern "C" {
+
+CS_Sink CS_CreateMjpegServer(const char* name, const char* listenAddress,
+                             int port, CS_Status* status) {
+  return cs::CreateMjpegServer(name, listenAddress, port, status);
+}
+
+char* CS_GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status) {
+  return ConvertToC(cs::GetMjpegServerListenAddress(sink, status));
+}
+
+int CS_GetMjpegServerPort(CS_Sink sink, CS_Status* status) {
+  return cs::GetMjpegServerPort(sink, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/MjpegServerImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/MjpegServerImpl.h
new file mode 100644
index 0000000..db60b86
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/MjpegServerImpl.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_MJPEGSERVERIMPL_H_
+#define CSCORE_MJPEGSERVERIMPL_H_
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <thread>
+#include <vector>
+
+#include <wpi/NetworkAcceptor.h>
+#include <wpi/NetworkStream.h>
+#include <wpi/SafeThread.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/raw_socket_ostream.h>
+
+#include "SinkImpl.h"
+
+namespace cs {
+
+class SourceImpl;
+
+class MjpegServerImpl : public SinkImpl {
+ public:
+  MjpegServerImpl(const wpi::Twine& name, wpi::Logger& logger,
+                  Notifier& notifier, Telemetry& telemetry,
+                  const wpi::Twine& listenAddress, int port,
+                  std::unique_ptr<wpi::NetworkAcceptor> acceptor);
+  ~MjpegServerImpl() override;
+
+  void Stop();
+  std::string GetListenAddress() { return m_listenAddress; }
+  int GetPort() { return m_port; }
+
+ private:
+  void SetSourceImpl(std::shared_ptr<SourceImpl> source) override;
+
+  void ServerThreadMain();
+
+  class ConnThread;
+
+  // Never changed, so not protected by mutex
+  std::string m_listenAddress;
+  int m_port;
+
+  std::unique_ptr<wpi::NetworkAcceptor> m_acceptor;
+  std::atomic_bool m_active;  // set to false to terminate threads
+  std::thread m_serverThread;
+
+  std::vector<wpi::SafeThreadOwner<ConnThread>> m_connThreads;
+
+  // property indices
+  int m_widthProp;
+  int m_heightProp;
+  int m_compressionProp;
+  int m_defaultCompressionProp;
+  int m_fpsProp;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_MJPEGSERVERIMPL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/NetworkListener.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/NetworkListener.h
new file mode 100644
index 0000000..6d49adc
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/NetworkListener.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_NETWORKLISTENER_H_
+#define CSCORE_NETWORKLISTENER_H_
+
+#include <memory>
+
+#include <wpi/Logger.h>
+
+namespace cs {
+
+class Notifier;
+
+class NetworkListener {
+ public:
+  NetworkListener(wpi::Logger& logger, Notifier& notifier);
+  ~NetworkListener();
+
+  void Start();
+  void Stop();
+
+ private:
+  class Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_NETWORKLISTENER_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Notifier.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Notifier.cpp
new file mode 100644
index 0000000..45bd050
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Notifier.cpp
@@ -0,0 +1,248 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "Notifier.h"
+
+#include <queue>
+#include <vector>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "SinkImpl.h"
+#include "SourceImpl.h"
+
+using namespace cs;
+
+bool Notifier::s_destroyed = false;
+
+namespace {
+// Vector which provides an integrated freelist for removal and reuse of
+// individual elements.
+template <typename T>
+class UidVector {
+ public:
+  using size_type = typename std::vector<T>::size_type;
+
+  size_type size() const { return m_vector.size(); }
+  T& operator[](size_type i) { return m_vector[i]; }
+  const T& operator[](size_type i) const { return m_vector[i]; }
+
+  // Add a new T to the vector.  If there are elements on the freelist,
+  // reuses the last one; otherwise adds to the end of the vector.
+  // Returns the resulting element index (+1).
+  template <class... Args>
+  unsigned int emplace_back(Args&&... args) {
+    unsigned int uid;
+    if (m_free.empty()) {
+      uid = m_vector.size();
+      m_vector.emplace_back(std::forward<Args>(args)...);
+    } else {
+      uid = m_free.back();
+      m_free.pop_back();
+      m_vector[uid] = T(std::forward<Args>(args)...);
+    }
+    return uid + 1;
+  }
+
+  // Removes the identified element by replacing it with a default-constructed
+  // one.  The element is added to the freelist for later reuse.
+  void erase(unsigned int uid) {
+    --uid;
+    if (uid >= m_vector.size() || !m_vector[uid]) return;
+    m_free.push_back(uid);
+    m_vector[uid] = T();
+  }
+
+ private:
+  std::vector<T> m_vector;
+  std::vector<unsigned int> m_free;
+};
+
+}  // namespace
+
+class Notifier::Thread : public wpi::SafeThread {
+ public:
+  Thread(std::function<void()> on_start, std::function<void()> on_exit)
+      : m_on_start(on_start), m_on_exit(on_exit) {}
+
+  void Main();
+
+  struct Listener {
+    Listener() = default;
+    Listener(std::function<void(const RawEvent& event)> callback_,
+             int eventMask_)
+        : callback(callback_), eventMask(eventMask_) {}
+
+    explicit operator bool() const { return static_cast<bool>(callback); }
+
+    std::string prefix;
+    std::function<void(const RawEvent& event)> callback;
+    int eventMask;
+  };
+  UidVector<Listener> m_listeners;
+
+  std::queue<RawEvent> m_notifications;
+
+  std::function<void()> m_on_start;
+  std::function<void()> m_on_exit;
+};
+
+Notifier::Notifier() { s_destroyed = false; }
+
+Notifier::~Notifier() { s_destroyed = true; }
+
+void Notifier::Start() { m_owner.Start(m_on_start, m_on_exit); }
+
+void Notifier::Stop() { m_owner.Stop(); }
+
+void Notifier::Thread::Main() {
+  if (m_on_start) m_on_start();
+
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  while (m_active) {
+    while (m_notifications.empty()) {
+      m_cond.wait(lock);
+      if (!m_active) goto done;
+    }
+
+    while (!m_notifications.empty()) {
+      if (!m_active) goto done;
+      auto item = std::move(m_notifications.front());
+      m_notifications.pop();
+
+      // Use index because iterator might get invalidated.
+      for (size_t i = 0; i < m_listeners.size(); ++i) {
+        if (!m_listeners[i]) continue;  // removed
+
+        // Event type must be within requested set for this listener.
+        if ((item.kind & m_listeners[i].eventMask) == 0) continue;
+
+        // make a copy of the callback so we can safely release the mutex
+        auto callback = m_listeners[i].callback;
+
+        // Don't hold mutex during callback execution!
+        lock.unlock();
+        callback(item);
+        lock.lock();
+      }
+    }
+  }
+
+done:
+  if (m_on_exit) m_on_exit();
+}
+
+int Notifier::AddListener(std::function<void(const RawEvent& event)> callback,
+                          int eventMask) {
+  Start();
+  auto thr = m_owner.GetThread();
+  return thr->m_listeners.emplace_back(callback, eventMask);
+}
+
+void Notifier::RemoveListener(int uid) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  thr->m_listeners.erase(uid);
+}
+
+void Notifier::NotifySource(const wpi::Twine& name, CS_Source source,
+                            CS_EventKind kind) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  thr->m_notifications.emplace(name, source, static_cast<RawEvent::Kind>(kind));
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySource(const SourceImpl& source, CS_EventKind kind) {
+  auto handleData = Instance::GetInstance().FindSource(source);
+  NotifySource(source.GetName(), handleData.first, kind);
+}
+
+void Notifier::NotifySourceVideoMode(const SourceImpl& source,
+                                     const VideoMode& mode) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  auto handleData = Instance::GetInstance().FindSource(source);
+
+  thr->m_notifications.emplace(source.GetName(), handleData.first, mode);
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySourceProperty(const SourceImpl& source, CS_EventKind kind,
+                                    const wpi::Twine& propertyName,
+                                    int property, CS_PropertyKind propertyKind,
+                                    int value, const wpi::Twine& valueStr) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  auto handleData = Instance::GetInstance().FindSource(source);
+
+  thr->m_notifications.emplace(
+      propertyName, handleData.first, static_cast<RawEvent::Kind>(kind),
+      Handle{handleData.first, property, Handle::kProperty}, propertyKind,
+      value, valueStr);
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySink(const wpi::Twine& name, CS_Sink sink,
+                          CS_EventKind kind) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  thr->m_notifications.emplace(name, sink, static_cast<RawEvent::Kind>(kind));
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySink(const SinkImpl& sink, CS_EventKind kind) {
+  auto handleData = Instance::GetInstance().FindSink(sink);
+  NotifySink(sink.GetName(), handleData.first, kind);
+}
+
+void Notifier::NotifySinkSourceChanged(const wpi::Twine& name, CS_Sink sink,
+                                       CS_Source source) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  RawEvent event{name, sink, RawEvent::kSinkSourceChanged};
+  event.sourceHandle = source;
+
+  thr->m_notifications.emplace(std::move(event));
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifySinkProperty(const SinkImpl& sink, CS_EventKind kind,
+                                  const wpi::Twine& propertyName, int property,
+                                  CS_PropertyKind propertyKind, int value,
+                                  const wpi::Twine& valueStr) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  auto handleData = Instance::GetInstance().FindSink(sink);
+
+  thr->m_notifications.emplace(
+      propertyName, handleData.first, static_cast<RawEvent::Kind>(kind),
+      Handle{handleData.first, property, Handle::kSinkProperty}, propertyKind,
+      value, valueStr);
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifyNetworkInterfacesChanged() {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  thr->m_notifications.emplace(RawEvent::kNetworkInterfacesChanged);
+  thr->m_cond.notify_one();
+}
+
+void Notifier::NotifyTelemetryUpdated() {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+
+  thr->m_notifications.emplace(RawEvent::kTelemetryUpdated);
+  thr->m_cond.notify_one();
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Notifier.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Notifier.h
new file mode 100644
index 0000000..526cea8
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Notifier.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_NOTIFIER_H_
+#define CSCORE_NOTIFIER_H_
+
+#include <functional>
+
+#include <wpi/SafeThread.h>
+
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class SinkImpl;
+class SourceImpl;
+
+class Notifier {
+  friend class NotifierTest;
+
+ public:
+  Notifier();
+  ~Notifier();
+
+  void Start();
+  void Stop();
+
+  static bool destroyed() { return s_destroyed; }
+
+  void SetOnStart(std::function<void()> on_start) { m_on_start = on_start; }
+  void SetOnExit(std::function<void()> on_exit) { m_on_exit = on_exit; }
+
+  int AddListener(std::function<void(const RawEvent& event)> callback,
+                  int eventMask);
+  void RemoveListener(int uid);
+
+  // Notification events
+  void NotifySource(const wpi::Twine& name, CS_Source source,
+                    CS_EventKind kind);
+  void NotifySource(const SourceImpl& source, CS_EventKind kind);
+  void NotifySourceVideoMode(const SourceImpl& source, const VideoMode& mode);
+  void NotifySourceProperty(const SourceImpl& source, CS_EventKind kind,
+                            const wpi::Twine& propertyName, int property,
+                            CS_PropertyKind propertyKind, int value,
+                            const wpi::Twine& valueStr);
+  void NotifySink(const wpi::Twine& name, CS_Sink sink, CS_EventKind kind);
+  void NotifySink(const SinkImpl& sink, CS_EventKind kind);
+  void NotifySinkSourceChanged(const wpi::Twine& name, CS_Sink sink,
+                               CS_Source source);
+  void NotifySinkProperty(const SinkImpl& sink, CS_EventKind kind,
+                          const wpi::Twine& propertyName, int property,
+                          CS_PropertyKind propertyKind, int value,
+                          const wpi::Twine& valueStr);
+  void NotifyNetworkInterfacesChanged();
+  void NotifyTelemetryUpdated();
+
+ private:
+  class Thread;
+  wpi::SafeThreadOwner<Thread> m_owner;
+
+  std::function<void()> m_on_start;
+  std::function<void()> m_on_exit;
+  static bool s_destroyed;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_NOTIFIER_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyContainer.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyContainer.cpp
new file mode 100644
index 0000000..46ea77d
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyContainer.cpp
@@ -0,0 +1,282 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "PropertyContainer.h"
+
+#include <wpi/Logger.h>
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/json.h>
+
+using namespace cs;
+
+int PropertyContainer::GetPropertyIndex(const wpi::Twine& name) const {
+  // We can't fail, so instead we create a new index if caching fails.
+  CS_Status status = 0;
+  if (!m_properties_cached) CacheProperties(&status);
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  wpi::SmallVector<char, 64> nameBuf;
+  int& ndx = m_properties[name.toStringRef(nameBuf)];
+  if (ndx == 0) {
+    // create a new index
+    ndx = m_propertyData.size() + 1;
+    m_propertyData.emplace_back(CreateEmptyProperty(name));
+  }
+  return ndx;
+}
+
+wpi::ArrayRef<int> PropertyContainer::EnumerateProperties(
+    wpi::SmallVectorImpl<int>& vec, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status))
+    return wpi::ArrayRef<int>{};
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  for (int i = 0; i < static_cast<int>(m_propertyData.size()); ++i) {
+    if (m_propertyData[i]) vec.push_back(i + 1);
+  }
+  return vec;
+}
+
+CS_PropertyKind PropertyContainer::GetPropertyKind(int property) const {
+  CS_Status status = 0;
+  if (!m_properties_cached && !CacheProperties(&status)) return CS_PROP_NONE;
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) return CS_PROP_NONE;
+  return prop->propKind;
+}
+
+wpi::StringRef PropertyContainer::GetPropertyName(
+    int property, wpi::SmallVectorImpl<char>& buf, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return wpi::StringRef{};
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return wpi::StringRef{};
+  }
+  // safe to not copy because we never modify it after caching
+  return prop->name;
+}
+
+int PropertyContainer::GetProperty(int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  if ((prop->propKind & (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) ==
+      0) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return 0;
+  }
+  return prop->value;
+}
+
+void PropertyContainer::SetProperty(int property, int value,
+                                    CS_Status* status) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return;
+  }
+
+  // Guess it's integer if we've set before get
+  if (prop->propKind == CS_PROP_NONE) prop->propKind = CS_PROP_INTEGER;
+
+  if ((prop->propKind & (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) ==
+      0) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return;
+  }
+
+  UpdatePropertyValue(property, false, value, wpi::Twine{});
+}
+
+int PropertyContainer::GetPropertyMin(int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  return prop->minimum;
+}
+
+int PropertyContainer::GetPropertyMax(int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  return prop->maximum;
+}
+
+int PropertyContainer::GetPropertyStep(int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  return prop->step;
+}
+
+int PropertyContainer::GetPropertyDefault(int property,
+                                          CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return 0;
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return 0;
+  }
+  return prop->defaultValue;
+}
+
+wpi::StringRef PropertyContainer::GetStringProperty(
+    int property, wpi::SmallVectorImpl<char>& buf, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return wpi::StringRef{};
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return wpi::StringRef{};
+  }
+  if (prop->propKind != CS_PROP_STRING) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return wpi::StringRef{};
+  }
+  buf.clear();
+  buf.append(prop->valueStr.begin(), prop->valueStr.end());
+  return wpi::StringRef(buf.data(), buf.size());
+}
+
+void PropertyContainer::SetStringProperty(int property, const wpi::Twine& value,
+                                          CS_Status* status) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return;
+  }
+
+  // Guess it's string if we've set before get
+  if (prop->propKind == CS_PROP_NONE) prop->propKind = CS_PROP_STRING;
+
+  if (prop->propKind != CS_PROP_STRING) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return;
+  }
+
+  UpdatePropertyValue(property, true, 0, value);
+}
+
+std::vector<std::string> PropertyContainer::GetEnumPropertyChoices(
+    int property, CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status))
+    return std::vector<std::string>{};
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto prop = GetProperty(property);
+  if (!prop) {
+    *status = CS_INVALID_PROPERTY;
+    return std::vector<std::string>{};
+  }
+  if (prop->propKind != CS_PROP_ENUM) {
+    *status = CS_WRONG_PROPERTY_TYPE;
+    return std::vector<std::string>{};
+  }
+  return prop->enumChoices;
+}
+
+std::unique_ptr<PropertyImpl> PropertyContainer::CreateEmptyProperty(
+    const wpi::Twine& name) const {
+  return wpi::make_unique<PropertyImpl>(name);
+}
+
+bool PropertyContainer::CacheProperties(CS_Status* status) const {
+  // Doesn't need to do anything.
+  m_properties_cached = true;
+  return true;
+}
+
+bool PropertyContainer::SetPropertiesJson(const wpi::json& config,
+                                          wpi::Logger& logger,
+                                          wpi::StringRef logName,
+                                          CS_Status* status) {
+  for (auto&& prop : config) {
+    std::string name;
+    try {
+      name = prop.at("name").get<std::string>();
+    } catch (const wpi::json::exception& e) {
+      WPI_WARNING(logger,
+                  logName << ": SetConfigJson: could not read property name: "
+                          << e.what());
+      continue;
+    }
+    int n = GetPropertyIndex(name);
+    try {
+      auto& v = prop.at("value");
+      if (v.is_string()) {
+        std::string val = v.get<std::string>();
+        WPI_INFO(logger, logName << ": SetConfigJson: setting property '"
+                                 << name << "' to '" << val << '\'');
+        SetStringProperty(n, val, status);
+      } else if (v.is_boolean()) {
+        bool val = v.get<bool>();
+        WPI_INFO(logger, logName << ": SetConfigJson: setting property '"
+                                 << name << "' to " << val);
+        SetProperty(n, val, status);
+      } else {
+        int val = v.get<int>();
+        WPI_INFO(logger, logName << ": SetConfigJson: setting property '"
+                                 << name << "' to " << val);
+        SetProperty(n, val, status);
+      }
+    } catch (const wpi::json::exception& e) {
+      WPI_WARNING(logger,
+                  logName << ": SetConfigJson: could not read property value: "
+                          << e.what());
+      continue;
+    }
+  }
+
+  return true;
+}
+
+wpi::json PropertyContainer::GetPropertiesJsonObject(CS_Status* status) {
+  wpi::json j;
+  wpi::SmallVector<int, 32> propVec;
+  for (int p : EnumerateProperties(propVec, status)) {
+    wpi::json prop;
+    wpi::SmallString<128> strBuf;
+    prop.emplace("name", GetPropertyName(p, strBuf, status));
+    switch (GetPropertyKind(p)) {
+      case CS_PROP_BOOLEAN:
+        prop.emplace("value", static_cast<bool>(GetProperty(p, status)));
+        break;
+      case CS_PROP_INTEGER:
+      case CS_PROP_ENUM:
+        prop.emplace("value", GetProperty(p, status));
+        break;
+      case CS_PROP_STRING:
+        prop.emplace("value", GetStringProperty(p, strBuf, status));
+        break;
+      default:
+        continue;
+    }
+    j.emplace_back(prop);
+  }
+
+  return j;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyContainer.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyContainer.h
new file mode 100644
index 0000000..19197b2
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyContainer.h
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_PROPERTYCONTAINER_H_
+#define CSCORE_PROPERTYCONTAINER_H_
+
+#include <atomic>
+#include <cstddef>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringMap.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "PropertyImpl.h"
+#include "cscore_cpp.h"
+
+namespace wpi {
+class Logger;
+class json;
+}  // namespace wpi
+
+namespace cs {
+
+class PropertyContainer {
+ public:
+  virtual ~PropertyContainer() = default;
+
+  int GetPropertyIndex(const wpi::Twine& name) const;
+  wpi::ArrayRef<int> EnumerateProperties(wpi::SmallVectorImpl<int>& vec,
+                                         CS_Status* status) const;
+  CS_PropertyKind GetPropertyKind(int property) const;
+  wpi::StringRef GetPropertyName(int property, wpi::SmallVectorImpl<char>& buf,
+                                 CS_Status* status) const;
+  int GetProperty(int property, CS_Status* status) const;
+  virtual void SetProperty(int property, int value, CS_Status* status);
+  int GetPropertyMin(int property, CS_Status* status) const;
+  int GetPropertyMax(int property, CS_Status* status) const;
+  int GetPropertyStep(int property, CS_Status* status) const;
+  int GetPropertyDefault(int property, CS_Status* status) const;
+  wpi::StringRef GetStringProperty(int property,
+                                   wpi::SmallVectorImpl<char>& buf,
+                                   CS_Status* status) const;
+  virtual void SetStringProperty(int property, const wpi::Twine& value,
+                                 CS_Status* status);
+  std::vector<std::string> GetEnumPropertyChoices(int property,
+                                                  CS_Status* status) const;
+
+  bool SetPropertiesJson(const wpi::json& config, wpi::Logger& logger,
+                         wpi::StringRef logName, CS_Status* status);
+  wpi::json GetPropertiesJsonObject(CS_Status* status);
+
+ protected:
+  // Get a property; must be called with m_mutex held.
+  PropertyImpl* GetProperty(int property) {
+    if (property <= 0 || static_cast<size_t>(property) > m_propertyData.size())
+      return nullptr;
+    return m_propertyData[property - 1].get();
+  }
+  const PropertyImpl* GetProperty(int property) const {
+    if (property <= 0 || static_cast<size_t>(property) > m_propertyData.size())
+      return nullptr;
+    return m_propertyData[property - 1].get();
+  }
+  // Create or update a property; must be called with m_mutex held.
+  // @tparam NewFunc functor that returns a std::unique_ptr<PropertyImpl>
+  // @tparam UpdateFunc functor that takes a PropertyImpl&.
+  template <typename NewFunc, typename UpdateFunc>
+  int CreateOrUpdateProperty(const wpi::Twine& name, NewFunc newFunc,
+                             UpdateFunc updateFunc) {
+    wpi::SmallVector<char, 64> nameBuf;
+    int& ndx = m_properties[name.toStringRef(nameBuf)];
+    if (ndx == 0) {
+      // create a new index
+      ndx = m_propertyData.size() + 1;
+      m_propertyData.emplace_back(newFunc());
+    } else {
+      // update existing
+      updateFunc(*GetProperty(ndx));
+    }
+    return ndx;
+  }
+  template <typename NewFunc>
+  int CreateProperty(const wpi::Twine& name, NewFunc newFunc) {
+    return CreateOrUpdateProperty(name, newFunc, [](PropertyImpl&) {});
+  }
+
+  // Create an "empty" property.  This is called by GetPropertyIndex to create
+  // properties that don't exist (as GetPropertyIndex can't fail).
+  // Note: called with m_mutex held.
+  // The default implementation simply creates a PropertyImpl object.
+  virtual std::unique_ptr<PropertyImpl> CreateEmptyProperty(
+      const wpi::Twine& name) const;
+
+  // Cache properties.  Implementations must return false and set status to
+  // CS_SOURCE_IS_DISCONNECTED if not possible to cache.
+  // The default implementation simply sets m_property_cached to true.
+  virtual bool CacheProperties(CS_Status* status) const;
+
+  virtual void NotifyPropertyCreated(int propIndex, PropertyImpl& prop) = 0;
+
+  // Update property value; must be called with m_mutex held.
+  virtual void UpdatePropertyValue(int property, bool setString, int value,
+                                   const wpi::Twine& valueStr) = 0;
+
+  // Whether CacheProperties() has been successful at least once (and thus
+  // should not be called again)
+  mutable std::atomic_bool m_properties_cached{false};
+
+  mutable wpi::mutex m_mutex;
+
+  // Cached properties (protected with m_mutex)
+  mutable std::vector<std::unique_ptr<PropertyImpl>> m_propertyData;
+  mutable wpi::StringMap<int> m_properties;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_PROPERTYCONTAINER_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyImpl.cpp
new file mode 100644
index 0000000..4f1602e
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyImpl.cpp
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "PropertyImpl.h"
+
+using namespace cs;
+
+PropertyImpl::PropertyImpl(const wpi::Twine& name_) : name{name_.str()} {}
+PropertyImpl::PropertyImpl(const wpi::Twine& name_, CS_PropertyKind kind_,
+                           int step_, int defaultValue_, int value_)
+    : name{name_.str()},
+      propKind{kind_},
+      step{step_},
+      defaultValue{defaultValue_},
+      value{value_} {}
+PropertyImpl::PropertyImpl(const wpi::Twine& name_, CS_PropertyKind kind_,
+                           int minimum_, int maximum_, int step_,
+                           int defaultValue_, int value_)
+    : name{name_.str()},
+      propKind{kind_},
+      hasMinimum{true},
+      hasMaximum{true},
+      minimum{minimum_},
+      maximum{maximum_},
+      step{step_},
+      defaultValue{defaultValue_},
+      value{value_} {}
+
+void PropertyImpl::SetValue(int v) {
+  int oldValue = value;
+  if (hasMinimum && v < minimum)
+    value = minimum;
+  else if (hasMaximum && v > maximum)
+    value = maximum;
+  else
+    value = v;
+  bool wasValueSet = valueSet;
+  valueSet = true;
+  if (!wasValueSet || value != oldValue) changed();
+}
+
+void PropertyImpl::SetValue(const wpi::Twine& v) {
+  bool valueChanged = false;
+  std::string vStr = v.str();
+  if (valueStr != vStr) {
+    valueStr = vStr;
+    valueChanged = true;
+  }
+  bool wasValueSet = valueSet;
+  valueSet = true;
+  if (!wasValueSet || valueChanged) changed();
+}
+
+void PropertyImpl::SetDefaultValue(int v) {
+  if (hasMinimum && v < minimum)
+    defaultValue = minimum;
+  else if (hasMaximum && v > maximum)
+    defaultValue = maximum;
+  else
+    defaultValue = v;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyImpl.h
new file mode 100644
index 0000000..d932132
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/PropertyImpl.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_PROPERTYIMPL_H_
+#define CSCORE_PROPERTYIMPL_H_
+
+#include <string>
+#include <vector>
+
+#include <wpi/Signal.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "cscore_c.h"
+
+namespace cs {
+
+// Property data
+class PropertyImpl {
+ public:
+  PropertyImpl() = default;
+  explicit PropertyImpl(const wpi::Twine& name_);
+  PropertyImpl(const wpi::Twine& name_, CS_PropertyKind kind_, int step_,
+               int defaultValue_, int value_);
+  PropertyImpl(const wpi::Twine& name_, CS_PropertyKind kind_, int minimum_,
+               int maximum_, int step_, int defaultValue_, int value_);
+  virtual ~PropertyImpl() = default;
+  PropertyImpl(const PropertyImpl& oth) = delete;
+  PropertyImpl& operator=(const PropertyImpl& oth) = delete;
+
+  void SetValue(int v);
+  void SetValue(const wpi::Twine& v);
+  void SetDefaultValue(int v);
+
+  std::string name;
+  CS_PropertyKind propKind{CS_PROP_NONE};
+  bool hasMinimum{false};
+  bool hasMaximum{false};
+  int minimum{0};
+  int maximum{100};
+  int step{1};
+  int defaultValue{0};
+  int value{0};
+  std::string valueStr;
+  std::vector<std::string> enumChoices;
+  bool valueSet{false};
+
+  // emitted when value changes
+  wpi::sig::Signal<> changed;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_PROPERTYIMPL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/SinkImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/SinkImpl.cpp
new file mode 100644
index 0000000..637b407
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/SinkImpl.cpp
@@ -0,0 +1,173 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "SinkImpl.h"
+
+#include <wpi/json.h>
+
+#include "Instance.h"
+#include "Notifier.h"
+#include "SourceImpl.h"
+
+using namespace cs;
+
+SinkImpl::SinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                   Notifier& notifier, Telemetry& telemetry)
+    : m_logger(logger),
+      m_notifier(notifier),
+      m_telemetry(telemetry),
+      m_name{name.str()} {}
+
+SinkImpl::~SinkImpl() {
+  if (m_source) {
+    if (m_enabledCount > 0) m_source->DisableSink();
+    m_source->RemoveSink();
+  }
+}
+
+void SinkImpl::SetDescription(const wpi::Twine& description) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_description = description.str();
+}
+
+wpi::StringRef SinkImpl::GetDescription(wpi::SmallVectorImpl<char>& buf) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  buf.append(m_description.begin(), m_description.end());
+  return wpi::StringRef{buf.data(), buf.size()};
+}
+
+void SinkImpl::Enable() {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  ++m_enabledCount;
+  if (m_enabledCount == 1) {
+    if (m_source) m_source->EnableSink();
+    m_notifier.NotifySink(*this, CS_SINK_ENABLED);
+  }
+}
+
+void SinkImpl::Disable() {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  --m_enabledCount;
+  if (m_enabledCount == 0) {
+    if (m_source) m_source->DisableSink();
+    m_notifier.NotifySink(*this, CS_SINK_DISABLED);
+  }
+}
+
+void SinkImpl::SetEnabled(bool enabled) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (enabled && m_enabledCount == 0) {
+    if (m_source) m_source->EnableSink();
+    m_enabledCount = 1;
+    m_notifier.NotifySink(*this, CS_SINK_ENABLED);
+  } else if (!enabled && m_enabledCount > 0) {
+    if (m_source) m_source->DisableSink();
+    m_enabledCount = 0;
+    m_notifier.NotifySink(*this, CS_SINK_DISABLED);
+  }
+}
+
+void SinkImpl::SetSource(std::shared_ptr<SourceImpl> source) {
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    if (m_source == source) return;
+    if (m_source) {
+      if (m_enabledCount > 0) m_source->DisableSink();
+      m_source->RemoveSink();
+    }
+    m_source = source;
+    if (m_source) {
+      m_source->AddSink();
+      if (m_enabledCount > 0) m_source->EnableSink();
+    }
+  }
+  SetSourceImpl(source);
+}
+
+std::string SinkImpl::GetError() const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (!m_source) return "no source connected";
+  return m_source->GetCurFrame().GetError();
+}
+
+wpi::StringRef SinkImpl::GetError(wpi::SmallVectorImpl<char>& buf) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (!m_source) return "no source connected";
+  // Make a copy as it's shared data
+  wpi::StringRef error = m_source->GetCurFrame().GetError();
+  buf.clear();
+  buf.append(error.data(), error.data() + error.size());
+  return wpi::StringRef{buf.data(), buf.size()};
+}
+
+bool SinkImpl::SetConfigJson(wpi::StringRef config, CS_Status* status) {
+  wpi::json j;
+  try {
+    j = wpi::json::parse(config);
+  } catch (const wpi::json::parse_error& e) {
+    SWARNING("SetConfigJson: parse error at byte " << e.byte << ": "
+                                                   << e.what());
+    *status = CS_PROPERTY_WRITE_FAILED;
+    return false;
+  }
+  return SetConfigJson(j, status);
+}
+
+bool SinkImpl::SetConfigJson(const wpi::json& config, CS_Status* status) {
+  if (config.count("properties") != 0)
+    SetPropertiesJson(config.at("properties"), m_logger, GetName(), status);
+
+  return true;
+}
+
+std::string SinkImpl::GetConfigJson(CS_Status* status) {
+  std::string rv;
+  wpi::raw_string_ostream os(rv);
+  GetConfigJsonObject(status).dump(os, 4);
+  os.flush();
+  return rv;
+}
+
+wpi::json SinkImpl::GetConfigJsonObject(CS_Status* status) {
+  wpi::json j;
+
+  wpi::json props = GetPropertiesJsonObject(status);
+  if (props.is_array()) j.emplace("properties", props);
+
+  return j;
+}
+
+void SinkImpl::NotifyPropertyCreated(int propIndex, PropertyImpl& prop) {
+  m_notifier.NotifySinkProperty(*this, CS_SINK_PROPERTY_CREATED, prop.name,
+                                propIndex, prop.propKind, prop.value,
+                                prop.valueStr);
+  // also notify choices updated event for enum types
+  if (prop.propKind == CS_PROP_ENUM)
+    m_notifier.NotifySinkProperty(*this, CS_SINK_PROPERTY_CHOICES_UPDATED,
+                                  prop.name, propIndex, prop.propKind,
+                                  prop.value, wpi::Twine{});
+}
+
+void SinkImpl::UpdatePropertyValue(int property, bool setString, int value,
+                                   const wpi::Twine& valueStr) {
+  auto prop = GetProperty(property);
+  if (!prop) return;
+
+  if (setString)
+    prop->SetValue(valueStr);
+  else
+    prop->SetValue(value);
+
+  // Only notify updates after we've notified created
+  if (m_properties_cached) {
+    m_notifier.NotifySinkProperty(*this, CS_SINK_PROPERTY_VALUE_UPDATED,
+                                  prop->name, property, prop->propKind,
+                                  prop->value, prop->valueStr);
+  }
+}
+
+void SinkImpl::SetSourceImpl(std::shared_ptr<SourceImpl> source) {}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/SinkImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/SinkImpl.h
new file mode 100644
index 0000000..147268f
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/SinkImpl.h
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_SINKIMPL_H_
+#define CSCORE_SINKIMPL_H_
+
+#include <memory>
+#include <string>
+
+#include <wpi/Logger.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "SourceImpl.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace cs {
+
+class Frame;
+class Notifier;
+class Telemetry;
+
+class SinkImpl : public PropertyContainer {
+ public:
+  explicit SinkImpl(const wpi::Twine& name, wpi::Logger& logger,
+                    Notifier& notifier, Telemetry& telemetry);
+  virtual ~SinkImpl();
+  SinkImpl(const SinkImpl& queue) = delete;
+  SinkImpl& operator=(const SinkImpl& queue) = delete;
+
+  wpi::StringRef GetName() const { return m_name; }
+
+  void SetDescription(const wpi::Twine& description);
+  wpi::StringRef GetDescription(wpi::SmallVectorImpl<char>& buf) const;
+
+  void Enable();
+  void Disable();
+  void SetEnabled(bool enabled);
+
+  void SetSource(std::shared_ptr<SourceImpl> source);
+
+  std::shared_ptr<SourceImpl> GetSource() const {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    return m_source;
+  }
+
+  std::string GetError() const;
+  wpi::StringRef GetError(wpi::SmallVectorImpl<char>& buf) const;
+
+  bool SetConfigJson(wpi::StringRef config, CS_Status* status);
+  virtual bool SetConfigJson(const wpi::json& config, CS_Status* status);
+  std::string GetConfigJson(CS_Status* status);
+  virtual wpi::json GetConfigJsonObject(CS_Status* status);
+
+ protected:
+  // PropertyContainer implementation
+  void NotifyPropertyCreated(int propIndex, PropertyImpl& prop) override;
+  void UpdatePropertyValue(int property, bool setString, int value,
+                           const wpi::Twine& valueStr) override;
+
+  virtual void SetSourceImpl(std::shared_ptr<SourceImpl> source);
+
+ protected:
+  wpi::Logger& m_logger;
+  Notifier& m_notifier;
+  Telemetry& m_telemetry;
+
+ private:
+  std::string m_name;
+  std::string m_description;
+  std::shared_ptr<SourceImpl> m_source;
+  int m_enabledCount{0};
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_SINKIMPL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/SourceImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/SourceImpl.cpp
new file mode 100644
index 0000000..e646eb6
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/SourceImpl.cpp
@@ -0,0 +1,528 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "SourceImpl.h"
+
+#include <algorithm>
+#include <cstring>
+
+#include <wpi/STLExtras.h>
+#include <wpi/json.h>
+#include <wpi/timestamp.h>
+
+#include "Log.h"
+#include "Notifier.h"
+#include "Telemetry.h"
+
+using namespace cs;
+
+static constexpr size_t kMaxImagesAvail = 32;
+
+SourceImpl::SourceImpl(const wpi::Twine& name, wpi::Logger& logger,
+                       Notifier& notifier, Telemetry& telemetry)
+    : m_logger(logger),
+      m_notifier(notifier),
+      m_telemetry(telemetry),
+      m_name{name.str()} {
+  m_frame = Frame{*this, wpi::StringRef{}, 0};
+}
+
+SourceImpl::~SourceImpl() {
+  // Wake up anyone who is waiting.  This also clears the current frame,
+  // which is good because its destructor will call back into the class.
+  Wakeup();
+  // Set a flag so ReleaseFrame() doesn't re-add them to m_framesAvail.
+  // Put in a block so we destroy before the destructor ends.
+  {
+    m_destroyFrames = true;
+    auto frames = std::move(m_framesAvail);
+  }
+  // Everything else can clean up itself.
+}
+
+void SourceImpl::SetDescription(const wpi::Twine& description) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_description = description.str();
+}
+
+wpi::StringRef SourceImpl::GetDescription(
+    wpi::SmallVectorImpl<char>& buf) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  buf.append(m_description.begin(), m_description.end());
+  return wpi::StringRef{buf.data(), buf.size()};
+}
+
+void SourceImpl::SetConnected(bool connected) {
+  bool wasConnected = m_connected.exchange(connected);
+  if (wasConnected && !connected)
+    m_notifier.NotifySource(*this, CS_SOURCE_DISCONNECTED);
+  else if (!wasConnected && connected)
+    m_notifier.NotifySource(*this, CS_SOURCE_CONNECTED);
+}
+
+uint64_t SourceImpl::GetCurFrameTime() {
+  std::unique_lock<wpi::mutex> lock{m_frameMutex};
+  return m_frame.GetTime();
+}
+
+Frame SourceImpl::GetCurFrame() {
+  std::unique_lock<wpi::mutex> lock{m_frameMutex};
+  return m_frame;
+}
+
+Frame SourceImpl::GetNextFrame() {
+  std::unique_lock<wpi::mutex> lock{m_frameMutex};
+  auto oldTime = m_frame.GetTime();
+  m_frameCv.wait(lock, [=] { return m_frame.GetTime() != oldTime; });
+  return m_frame;
+}
+
+Frame SourceImpl::GetNextFrame(double timeout) {
+  std::unique_lock<wpi::mutex> lock{m_frameMutex};
+  auto oldTime = m_frame.GetTime();
+  if (!m_frameCv.wait_for(
+          lock, std::chrono::milliseconds(static_cast<int>(timeout * 1000)),
+          [=] { return m_frame.GetTime() != oldTime; })) {
+    m_frame = Frame{*this, "timed out getting frame", wpi::Now()};
+  }
+  return m_frame;
+}
+
+void SourceImpl::Wakeup() {
+  {
+    std::lock_guard<wpi::mutex> lock{m_frameMutex};
+    m_frame = Frame{*this, wpi::StringRef{}, 0};
+  }
+  m_frameCv.notify_all();
+}
+
+void SourceImpl::SetBrightness(int brightness, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+int SourceImpl::GetBrightness(CS_Status* status) const {
+  *status = CS_INVALID_HANDLE;
+  return 0;
+}
+
+void SourceImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetExposureAuto(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetExposureHoldCurrent(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+void SourceImpl::SetExposureManual(int value, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+}
+
+VideoMode SourceImpl::GetVideoMode(CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status)) return VideoMode{};
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return m_mode;
+}
+
+bool SourceImpl::SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                                CS_Status* status) {
+  auto mode = GetVideoMode(status);
+  if (!mode) return false;
+  mode.pixelFormat = pixelFormat;
+  return SetVideoMode(mode, status);
+}
+
+bool SourceImpl::SetResolution(int width, int height, CS_Status* status) {
+  auto mode = GetVideoMode(status);
+  if (!mode) return false;
+  mode.width = width;
+  mode.height = height;
+  return SetVideoMode(mode, status);
+}
+
+bool SourceImpl::SetFPS(int fps, CS_Status* status) {
+  auto mode = GetVideoMode(status);
+  if (!mode) return false;
+  mode.fps = fps;
+  return SetVideoMode(mode, status);
+}
+
+bool SourceImpl::SetConfigJson(wpi::StringRef config, CS_Status* status) {
+  wpi::json j;
+  try {
+    j = wpi::json::parse(config);
+  } catch (const wpi::json::parse_error& e) {
+    SWARNING("SetConfigJson: parse error at byte " << e.byte << ": "
+                                                   << e.what());
+    *status = CS_PROPERTY_WRITE_FAILED;
+    return false;
+  }
+  return SetConfigJson(j, status);
+}
+
+bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) {
+  VideoMode mode;
+
+  // pixel format
+  if (config.count("pixel format") != 0) {
+    try {
+      auto str = config.at("pixel format").get<std::string>();
+      wpi::StringRef s(str);
+      if (s.equals_lower("mjpeg")) {
+        mode.pixelFormat = cs::VideoMode::kMJPEG;
+      } else if (s.equals_lower("yuyv")) {
+        mode.pixelFormat = cs::VideoMode::kYUYV;
+      } else if (s.equals_lower("rgb565")) {
+        mode.pixelFormat = cs::VideoMode::kRGB565;
+      } else if (s.equals_lower("bgr")) {
+        mode.pixelFormat = cs::VideoMode::kBGR;
+      } else if (s.equals_lower("gray")) {
+        mode.pixelFormat = cs::VideoMode::kGray;
+      } else {
+        SWARNING("SetConfigJson: could not understand pixel format value '"
+                 << str << '\'');
+      }
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read pixel format: " << e.what());
+    }
+  }
+
+  // width
+  if (config.count("width") != 0) {
+    try {
+      mode.width = config.at("width").get<unsigned int>();
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read width: " << e.what());
+    }
+  }
+
+  // height
+  if (config.count("height") != 0) {
+    try {
+      mode.height = config.at("height").get<unsigned int>();
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read height: " << e.what());
+    }
+  }
+
+  // fps
+  if (config.count("fps") != 0) {
+    try {
+      mode.fps = config.at("fps").get<unsigned int>();
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read fps: " << e.what());
+    }
+  }
+
+  // if all of video mode is set, use SetVideoMode, otherwise piecemeal it
+  if (mode.pixelFormat != VideoMode::kUnknown && mode.width != 0 &&
+      mode.height != 0 && mode.fps != 0) {
+    SINFO("SetConfigJson: setting video mode to pixelFormat "
+          << mode.pixelFormat << ", width " << mode.width << ", height "
+          << mode.height << ", fps " << mode.fps);
+    SetVideoMode(mode, status);
+  } else {
+    if (mode.pixelFormat != cs::VideoMode::kUnknown) {
+      SINFO("SetConfigJson: setting pixelFormat " << mode.pixelFormat);
+      SetPixelFormat(static_cast<cs::VideoMode::PixelFormat>(mode.pixelFormat),
+                     status);
+    }
+    if (mode.width != 0 && mode.height != 0) {
+      SINFO("SetConfigJson: setting width " << mode.width << ", height "
+                                            << mode.height);
+      SetResolution(mode.width, mode.height, status);
+    }
+    if (mode.fps != 0) {
+      SINFO("SetConfigJson: setting fps " << mode.fps);
+      SetFPS(mode.fps, status);
+    }
+  }
+
+  // brightness
+  if (config.count("brightness") != 0) {
+    try {
+      int val = config.at("brightness").get<int>();
+      SINFO("SetConfigJson: setting brightness to " << val);
+      SetBrightness(val, status);
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read brightness: " << e.what());
+    }
+  }
+
+  // white balance
+  if (config.count("white balance") != 0) {
+    try {
+      auto& setting = config.at("white balance");
+      if (setting.is_string()) {
+        auto str = setting.get<std::string>();
+        wpi::StringRef s(str);
+        if (s.equals_lower("auto")) {
+          SINFO("SetConfigJson: setting white balance to auto");
+          SetWhiteBalanceAuto(status);
+        } else if (s.equals_lower("hold")) {
+          SINFO("SetConfigJson: setting white balance to hold current");
+          SetWhiteBalanceHoldCurrent(status);
+        } else {
+          SWARNING("SetConfigJson: could not understand white balance value '"
+                   << str << '\'');
+        }
+      } else {
+        int val = setting.get<int>();
+        SINFO("SetConfigJson: setting white balance to " << val);
+        SetWhiteBalanceManual(val, status);
+      }
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read white balance: " << e.what());
+    }
+  }
+
+  // exposure
+  if (config.count("exposure") != 0) {
+    try {
+      auto& setting = config.at("exposure");
+      if (setting.is_string()) {
+        auto str = setting.get<std::string>();
+        wpi::StringRef s(str);
+        if (s.equals_lower("auto")) {
+          SINFO("SetConfigJson: setting exposure to auto");
+          SetExposureAuto(status);
+        } else if (s.equals_lower("hold")) {
+          SINFO("SetConfigJson: setting exposure to hold current");
+          SetExposureHoldCurrent(status);
+        } else {
+          SWARNING("SetConfigJson: could not understand exposure value '"
+                   << str << '\'');
+        }
+      } else {
+        int val = setting.get<int>();
+        SINFO("SetConfigJson: setting exposure to " << val);
+        SetExposureManual(val, status);
+      }
+    } catch (const wpi::json::exception& e) {
+      SWARNING("SetConfigJson: could not read exposure: " << e.what());
+    }
+  }
+
+  // properties
+  if (config.count("properties") != 0)
+    SetPropertiesJson(config.at("properties"), m_logger, GetName(), status);
+
+  return true;
+}
+
+std::string SourceImpl::GetConfigJson(CS_Status* status) {
+  std::string rv;
+  wpi::raw_string_ostream os(rv);
+  GetConfigJsonObject(status).dump(os, 4);
+  os.flush();
+  return rv;
+}
+
+wpi::json SourceImpl::GetConfigJsonObject(CS_Status* status) {
+  wpi::json j;
+
+  // pixel format
+  wpi::StringRef pixelFormat;
+  switch (m_mode.pixelFormat) {
+    case VideoMode::kMJPEG:
+      pixelFormat = "mjpeg";
+      break;
+    case VideoMode::kYUYV:
+      pixelFormat = "yuyv";
+      break;
+    case VideoMode::kRGB565:
+      pixelFormat = "rgb565";
+      break;
+    case VideoMode::kBGR:
+      pixelFormat = "bgr";
+      break;
+    case VideoMode::kGray:
+      pixelFormat = "gray";
+      break;
+    default:
+      break;
+  }
+  if (!pixelFormat.empty()) j.emplace("pixel format", pixelFormat);
+
+  // width
+  if (m_mode.width != 0) j.emplace("width", m_mode.width);
+
+  // height
+  if (m_mode.height != 0) j.emplace("height", m_mode.height);
+
+  // fps
+  if (m_mode.fps != 0) j.emplace("fps", m_mode.fps);
+
+  // TODO: output brightness, white balance, and exposure?
+
+  // properties
+  wpi::json props = GetPropertiesJsonObject(status);
+  if (props.is_array()) j.emplace("properties", props);
+
+  return j;
+}
+
+std::vector<VideoMode> SourceImpl::EnumerateVideoModes(
+    CS_Status* status) const {
+  if (!m_properties_cached && !CacheProperties(status))
+    return std::vector<VideoMode>{};
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return m_videoModes;
+}
+
+std::unique_ptr<Image> SourceImpl::AllocImage(
+    VideoMode::PixelFormat pixelFormat, int width, int height, size_t size) {
+  std::unique_ptr<Image> image;
+  {
+    std::lock_guard<wpi::mutex> lock{m_poolMutex};
+    // find the smallest existing frame that is at least big enough.
+    int found = -1;
+    for (size_t i = 0; i < m_imagesAvail.size(); ++i) {
+      // is it big enough?
+      if (m_imagesAvail[i] && m_imagesAvail[i]->capacity() >= size) {
+        // is it smaller than the last found?
+        if (found < 0 ||
+            m_imagesAvail[i]->capacity() < m_imagesAvail[found]->capacity()) {
+          // yes, update
+          found = i;
+        }
+      }
+    }
+
+    // if nothing found, allocate a new buffer
+    if (found < 0)
+      image.reset(new Image{size});
+    else
+      image = std::move(m_imagesAvail[found]);
+  }
+
+  // Initialize image
+  image->SetSize(size);
+  image->pixelFormat = pixelFormat;
+  image->width = width;
+  image->height = height;
+
+  return image;
+}
+
+void SourceImpl::PutFrame(VideoMode::PixelFormat pixelFormat, int width,
+                          int height, wpi::StringRef data, Frame::Time time) {
+  auto image = AllocImage(pixelFormat, width, height, data.size());
+
+  // Copy in image data
+  SDEBUG4("Copying data to "
+          << reinterpret_cast<const void*>(image->data()) << " from "
+          << reinterpret_cast<const void*>(data.data()) << " (" << data.size()
+          << " bytes)");
+  std::memcpy(image->data(), data.data(), data.size());
+
+  PutFrame(std::move(image), time);
+}
+
+void SourceImpl::PutFrame(std::unique_ptr<Image> image, Frame::Time time) {
+  // Update telemetry
+  m_telemetry.RecordSourceFrames(*this, 1);
+  m_telemetry.RecordSourceBytes(*this, static_cast<int>(image->size()));
+
+  // Update frame
+  {
+    std::lock_guard<wpi::mutex> lock{m_frameMutex};
+    m_frame = Frame{*this, std::move(image), time};
+  }
+
+  // Signal listeners
+  m_frameCv.notify_all();
+}
+
+void SourceImpl::PutError(const wpi::Twine& msg, Frame::Time time) {
+  // Update frame
+  {
+    std::lock_guard<wpi::mutex> lock{m_frameMutex};
+    m_frame = Frame{*this, msg, time};
+  }
+
+  // Signal listeners
+  m_frameCv.notify_all();
+}
+
+void SourceImpl::NotifyPropertyCreated(int propIndex, PropertyImpl& prop) {
+  m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CREATED, prop.name,
+                                  propIndex, prop.propKind, prop.value,
+                                  prop.valueStr);
+  // also notify choices updated event for enum types
+  if (prop.propKind == CS_PROP_ENUM)
+    m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_CHOICES_UPDATED,
+                                    prop.name, propIndex, prop.propKind,
+                                    prop.value, wpi::Twine{});
+}
+
+void SourceImpl::UpdatePropertyValue(int property, bool setString, int value,
+                                     const wpi::Twine& valueStr) {
+  auto prop = GetProperty(property);
+  if (!prop) return;
+
+  if (setString)
+    prop->SetValue(valueStr);
+  else
+    prop->SetValue(value);
+
+  // Only notify updates after we've notified created
+  if (m_properties_cached) {
+    m_notifier.NotifySourceProperty(*this, CS_SOURCE_PROPERTY_VALUE_UPDATED,
+                                    prop->name, property, prop->propKind,
+                                    prop->value, prop->valueStr);
+  }
+}
+
+void SourceImpl::ReleaseImage(std::unique_ptr<Image> image) {
+  std::lock_guard<wpi::mutex> lock{m_poolMutex};
+  if (m_destroyFrames) return;
+  // Return the frame to the pool.  First try to find an empty slot, otherwise
+  // add it to the end.
+  auto it = std::find(m_imagesAvail.begin(), m_imagesAvail.end(), nullptr);
+  if (it != m_imagesAvail.end()) {
+    *it = std::move(image);
+  } else if (m_imagesAvail.size() > kMaxImagesAvail) {
+    // Replace smallest buffer; don't need to check for null because the above
+    // find would have found it.
+    auto it2 = std::min_element(
+        m_imagesAvail.begin(), m_imagesAvail.end(),
+        [](const std::unique_ptr<Image>& a, const std::unique_ptr<Image>& b) {
+          return a->capacity() < b->capacity();
+        });
+    if ((*it2)->capacity() < image->capacity()) *it2 = std::move(image);
+  } else {
+    m_imagesAvail.emplace_back(std::move(image));
+  }
+}
+
+std::unique_ptr<Frame::Impl> SourceImpl::AllocFrameImpl() {
+  std::lock_guard<wpi::mutex> lock{m_poolMutex};
+
+  if (m_framesAvail.empty()) return wpi::make_unique<Frame::Impl>(*this);
+
+  auto impl = std::move(m_framesAvail.back());
+  m_framesAvail.pop_back();
+  return impl;
+}
+
+void SourceImpl::ReleaseFrameImpl(std::unique_ptr<Frame::Impl> impl) {
+  std::lock_guard<wpi::mutex> lock{m_poolMutex};
+  if (m_destroyFrames) return;
+  m_framesAvail.push_back(std::move(impl));
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/SourceImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/SourceImpl.h
new file mode 100644
index 0000000..d74d8fa
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/SourceImpl.h
@@ -0,0 +1,202 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_SOURCEIMPL_H_
+#define CSCORE_SOURCEIMPL_H_
+
+#include <atomic>
+#include <cstddef>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/Logger.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "Frame.h"
+#include "Handle.h"
+#include "Image.h"
+#include "PropertyContainer.h"
+#include "cscore_cpp.h"
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+namespace cs {
+
+class Notifier;
+class Telemetry;
+
+class SourceImpl : public PropertyContainer {
+  friend class Frame;
+
+ public:
+  SourceImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+             Telemetry& telemetry);
+  virtual ~SourceImpl();
+  SourceImpl(const SourceImpl& oth) = delete;
+  SourceImpl& operator=(const SourceImpl& oth) = delete;
+
+  virtual void Start() = 0;
+
+  wpi::StringRef GetName() const { return m_name; }
+
+  void SetDescription(const wpi::Twine& description);
+  wpi::StringRef GetDescription(wpi::SmallVectorImpl<char>& buf) const;
+
+  void SetConnectionStrategy(CS_ConnectionStrategy strategy) {
+    m_strategy = static_cast<int>(strategy);
+  }
+  bool IsEnabled() const {
+    return m_strategy == CS_CONNECTION_KEEP_OPEN ||
+           (m_strategy == CS_CONNECTION_AUTO_MANAGE && m_numSinksEnabled > 0);
+  }
+
+  // User-visible connection status
+  void SetConnected(bool connected);
+  bool IsConnected() const { return m_connected; }
+
+  // Functions to keep track of the overall number of sinks connected to this
+  // source.  Primarily used by sinks to determine if other sinks are using
+  // the same source.
+  int GetNumSinks() const { return m_numSinks; }
+  void AddSink() {
+    ++m_numSinks;
+    NumSinksChanged();
+  }
+  void RemoveSink() {
+    --m_numSinks;
+    NumSinksChanged();
+  }
+
+  // Functions to keep track of the number of sinks connected to this source
+  // that are "enabled", in other words, listening for new images.  Primarily
+  // used by sources to determine whether they should actually bother trying
+  // to get source frames.
+  int GetNumSinksEnabled() const { return m_numSinksEnabled; }
+
+  void EnableSink() {
+    ++m_numSinksEnabled;
+    NumSinksEnabledChanged();
+  }
+
+  void DisableSink() {
+    --m_numSinksEnabled;
+    NumSinksEnabledChanged();
+  }
+
+  // Gets the current frame time (without waiting for a new one).
+  uint64_t GetCurFrameTime();
+
+  // Gets the current frame (without waiting for a new one).
+  Frame GetCurFrame();
+
+  // Blocking function that waits for the next frame and returns it.
+  Frame GetNextFrame();
+
+  // Blocking function that waits for the next frame and returns it (with
+  // timeout in seconds).  If timeout expires, returns empty frame.
+  Frame GetNextFrame(double timeout);
+
+  // Force a wakeup of all GetNextFrame() callers by sending an empty frame.
+  void Wakeup();
+
+  // Standard common camera properties
+  virtual void SetBrightness(int brightness, CS_Status* status);
+  virtual int GetBrightness(CS_Status* status) const;
+  virtual void SetWhiteBalanceAuto(CS_Status* status);
+  virtual void SetWhiteBalanceHoldCurrent(CS_Status* status);
+  virtual void SetWhiteBalanceManual(int value, CS_Status* status);
+  virtual void SetExposureAuto(CS_Status* status);
+  virtual void SetExposureHoldCurrent(CS_Status* status);
+  virtual void SetExposureManual(int value, CS_Status* status);
+
+  // Video mode functions
+  VideoMode GetVideoMode(CS_Status* status) const;
+  virtual bool SetVideoMode(const VideoMode& mode, CS_Status* status) = 0;
+
+  // These have default implementations but can be overridden for custom
+  // or optimized behavior.
+  virtual bool SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                              CS_Status* status);
+  virtual bool SetResolution(int width, int height, CS_Status* status);
+  virtual bool SetFPS(int fps, CS_Status* status);
+
+  bool SetConfigJson(wpi::StringRef config, CS_Status* status);
+  virtual bool SetConfigJson(const wpi::json& config, CS_Status* status);
+  std::string GetConfigJson(CS_Status* status);
+  virtual wpi::json GetConfigJsonObject(CS_Status* status);
+
+  std::vector<VideoMode> EnumerateVideoModes(CS_Status* status) const;
+
+  std::unique_ptr<Image> AllocImage(VideoMode::PixelFormat pixelFormat,
+                                    int width, int height, size_t size);
+
+ protected:
+  void NotifyPropertyCreated(int propIndex, PropertyImpl& prop) override;
+  void UpdatePropertyValue(int property, bool setString, int value,
+                           const wpi::Twine& valueStr) override;
+
+  void PutFrame(VideoMode::PixelFormat pixelFormat, int width, int height,
+                wpi::StringRef data, Frame::Time time);
+  void PutFrame(std::unique_ptr<Image> image, Frame::Time time);
+  void PutError(const wpi::Twine& msg, Frame::Time time);
+
+  // Notification functions for corresponding atomics
+  virtual void NumSinksChanged() = 0;
+  virtual void NumSinksEnabledChanged() = 0;
+
+  std::atomic_int m_numSinks{0};
+
+ protected:
+  // Cached video modes (protected with m_mutex)
+  mutable std::vector<VideoMode> m_videoModes;
+  // Current video mode
+  mutable VideoMode m_mode;
+
+  wpi::Logger& m_logger;
+  Notifier& m_notifier;
+  Telemetry& m_telemetry;
+
+ private:
+  void ReleaseImage(std::unique_ptr<Image> image);
+  std::unique_ptr<Frame::Impl> AllocFrameImpl();
+  void ReleaseFrameImpl(std::unique_ptr<Frame::Impl> data);
+
+  std::string m_name;
+  std::string m_description;
+
+  std::atomic_int m_strategy{CS_CONNECTION_AUTO_MANAGE};
+  std::atomic_int m_numSinksEnabled{0};
+
+  wpi::mutex m_frameMutex;
+  wpi::condition_variable m_frameCv;
+
+  bool m_destroyFrames{false};
+
+  // Pool of frames/images to reduce malloc traffic.
+  wpi::mutex m_poolMutex;
+  std::vector<std::unique_ptr<Frame::Impl>> m_framesAvail;
+  std::vector<std::unique_ptr<Image>> m_imagesAvail;
+
+  std::atomic_bool m_connected{false};
+
+  // Most recent frame (returned to callers of GetNextFrame)
+  // Access protected by m_frameMutex.
+  // MUST be located below m_poolMutex as the Frame destructor calls back
+  // into SourceImpl::ReleaseImage, which locks m_poolMutex.
+  Frame m_frame;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_SOURCEIMPL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Telemetry.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Telemetry.cpp
new file mode 100644
index 0000000..fa6c93c
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Telemetry.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "Telemetry.h"
+
+#include <chrono>
+#include <limits>
+
+#include <wpi/DenseMap.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Notifier.h"
+#include "SourceImpl.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+class Telemetry::Thread : public wpi::SafeThread {
+ public:
+  explicit Thread(Notifier& notifier) : m_notifier(notifier) {}
+
+  void Main();
+
+  Notifier& m_notifier;
+  wpi::DenseMap<std::pair<CS_Handle, int>, int64_t> m_user;
+  wpi::DenseMap<std::pair<CS_Handle, int>, int64_t> m_current;
+  double m_period = 0.0;
+  double m_elapsed = 0.0;
+  bool m_updated = false;
+  int64_t GetValue(CS_Handle handle, CS_TelemetryKind kind, CS_Status* status);
+};
+
+int64_t Telemetry::Thread::GetValue(CS_Handle handle, CS_TelemetryKind kind,
+                                    CS_Status* status) {
+  auto it = m_user.find(std::make_pair(handle, static_cast<int>(kind)));
+  if (it == m_user.end()) {
+    *status = CS_EMPTY_VALUE;
+    return 0;
+  }
+  return it->getSecond();
+}
+
+Telemetry::~Telemetry() {}
+
+void Telemetry::Start() { m_owner.Start(m_notifier); }
+
+void Telemetry::Stop() { m_owner.Stop(); }
+
+void Telemetry::Thread::Main() {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  auto prevTime = std::chrono::steady_clock::now();
+  while (m_active) {
+    double period = m_period;
+    if (period == 0) period = 1000.0;
+    auto timeoutTime = prevTime + std::chrono::duration<double>(period);
+    while (m_active && !m_updated) {
+      if (m_cond.wait_until(lock, timeoutTime) == std::cv_status::timeout)
+        break;
+    }
+    if (!m_active) break;
+    if (m_updated) {
+      m_updated = false;
+      continue;
+    }
+
+    // move to user and clear current, as we don't keep around old values
+    m_user = std::move(m_current);
+    m_current.clear();
+    auto curTime = std::chrono::steady_clock::now();
+    m_elapsed = std::chrono::duration<double>(curTime - prevTime).count();
+    prevTime = curTime;
+
+    // notify
+    m_notifier.NotifyTelemetryUpdated();
+  }
+}
+
+void Telemetry::SetPeriod(double seconds) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  if (thr->m_period == seconds) return;  // no change
+  thr->m_period = seconds;
+  thr->m_updated = true;
+  thr->m_cond.notify_one();
+}
+
+double Telemetry::GetElapsedTime() {
+  auto thr = m_owner.GetThread();
+  if (!thr) return 0;
+  return thr->m_elapsed;
+}
+
+int64_t Telemetry::GetValue(CS_Handle handle, CS_TelemetryKind kind,
+                            CS_Status* status) {
+  auto thr = m_owner.GetThread();
+  if (!thr) {
+    *status = CS_TELEMETRY_NOT_ENABLED;
+    return 0;
+  }
+  return thr->GetValue(handle, kind, status);
+}
+
+double Telemetry::GetAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                                  CS_Status* status) {
+  auto thr = m_owner.GetThread();
+  if (!thr) {
+    *status = CS_TELEMETRY_NOT_ENABLED;
+    return 0;
+  }
+  if (thr->m_elapsed == 0) return 0.0;
+  return thr->GetValue(handle, kind, status) / thr->m_elapsed;
+}
+
+void Telemetry::RecordSourceBytes(const SourceImpl& source, int quantity) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  auto handleData = Instance::GetInstance().FindSource(source);
+  thr->m_current[std::make_pair(Handle{handleData.first, Handle::kSource},
+                                static_cast<int>(CS_SOURCE_BYTES_RECEIVED))] +=
+      quantity;
+}
+
+void Telemetry::RecordSourceFrames(const SourceImpl& source, int quantity) {
+  auto thr = m_owner.GetThread();
+  if (!thr) return;
+  auto handleData = Instance::GetInstance().FindSource(source);
+  thr->m_current[std::make_pair(Handle{handleData.first, Handle::kSource},
+                                static_cast<int>(CS_SOURCE_FRAMES_RECEIVED))] +=
+      quantity;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/Telemetry.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Telemetry.h
new file mode 100644
index 0000000..8729704
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/Telemetry.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_TELEMETRY_H_
+#define CSCORE_TELEMETRY_H_
+
+#include <wpi/SafeThread.h>
+
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class Notifier;
+class SourceImpl;
+
+class Telemetry {
+  friend class TelemetryTest;
+
+ public:
+  explicit Telemetry(Notifier& notifier) : m_notifier(notifier) {}
+  ~Telemetry();
+
+  void Start();
+  void Stop();
+
+  // User interface
+  void SetPeriod(double seconds);
+  double GetElapsedTime();
+  int64_t GetValue(CS_Handle handle, CS_TelemetryKind kind, CS_Status* status);
+  double GetAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                         CS_Status* status);
+
+  // Telemetry events
+  void RecordSourceBytes(const SourceImpl& source, int quantity);
+  void RecordSourceFrames(const SourceImpl& source, int quantity);
+
+ private:
+  Notifier& m_notifier;
+
+  class Thread;
+  wpi::SafeThreadOwner<Thread> m_owner;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_TELEMETRY_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/UnlimitedHandleResource.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/UnlimitedHandleResource.h
new file mode 100644
index 0000000..c297cfa
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/UnlimitedHandleResource.h
@@ -0,0 +1,182 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_UNLIMITEDHANDLERESOURCE_H_
+#define CSCORE_UNLIMITEDHANDLERESOURCE_H_
+
+#include <memory>
+#include <utility>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+namespace cs {
+
+// The UnlimitedHandleResource class is a way to track handles. This version
+// allows an unlimted number of handles that are allocated sequentially. When
+// possible, indices are reused to save memory usage and keep the array length
+// down.
+// However, automatic array management has not been implemented, but might be in
+// the future.
+// Because we have to loop through the allocator, we must use a global mutex.
+//
+// THandle needs to have the following attributes:
+//  Type : enum or typedef
+//  kIndexMax : static, constexpr, or enum value for the maximum index value
+//  int GetTypedIndex() const : function that returns the index of the handle
+//  THandle(int index, HandleType[int] type) : constructor for index and type
+//
+// @tparam THandle The Handle Type
+// @tparam TStruct The struct type held by this resource
+// @tparam typeValue The type value stored in the handle
+// @tparam TMutex The mutex type to use
+template <typename THandle, typename TStruct, int typeValue,
+          typename TMutex = wpi::mutex>
+class UnlimitedHandleResource {
+ public:
+  UnlimitedHandleResource(const UnlimitedHandleResource&) = delete;
+  UnlimitedHandleResource operator=(const UnlimitedHandleResource&) = delete;
+  UnlimitedHandleResource() = default;
+
+  template <typename... Args>
+  THandle Allocate(Args&&... args);
+  THandle Allocate(std::shared_ptr<THandle> structure);
+
+  std::shared_ptr<TStruct> Get(THandle handle);
+
+  std::shared_ptr<TStruct> Free(THandle handle);
+
+  template <typename T>
+  wpi::ArrayRef<T> GetAll(wpi::SmallVectorImpl<T>& vec);
+
+  std::vector<std::shared_ptr<TStruct>> FreeAll();
+
+  // @param func functor with (THandle, const TStruct&) parameters
+  template <typename F>
+  void ForEach(F func);
+
+  // @pram func functor with (const TStruct&) parameter and bool return value
+  template <typename F>
+  std::pair<THandle, std::shared_ptr<TStruct>> FindIf(F func);
+
+ private:
+  THandle MakeHandle(size_t i) {
+    return THandle{static_cast<int>(i),
+                   static_cast<typename THandle::Type>(typeValue)};
+  }
+  std::vector<std::shared_ptr<TStruct>> m_structures;
+  TMutex m_handleMutex;
+};
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+template <typename... Args>
+THandle UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::Allocate(
+    Args&&... args) {
+  std::lock_guard<TMutex> sync(m_handleMutex);
+  size_t i;
+  for (i = 0; i < m_structures.size(); i++) {
+    if (m_structures[i] == nullptr) {
+      m_structures[i] = std::make_shared<TStruct>(std::forward<Args>(args)...);
+      return MakeHandle(i);
+    }
+  }
+  if (i >= THandle::kIndexMax) return 0;
+
+  m_structures.emplace_back(
+      std::make_shared<TStruct>(std::forward<Args>(args)...));
+  return MakeHandle(i);
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+THandle UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::Allocate(
+    std::shared_ptr<THandle> structure) {
+  std::lock_guard<TMutex> sync(m_handleMutex);
+  size_t i;
+  for (i = 0; i < m_structures.size(); i++) {
+    if (m_structures[i] == nullptr) {
+      m_structures[i] = structure;
+      return MakeHandle(i);
+    }
+  }
+  if (i >= THandle::kIndexMax) return 0;
+
+  m_structures.push_back(structure);
+  return MakeHandle(i);
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+inline std::shared_ptr<TStruct>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::Get(
+    THandle handle) {
+  auto index =
+      handle.GetTypedIndex(static_cast<typename THandle::Type>(typeValue));
+  if (index < 0) return nullptr;
+  std::lock_guard<TMutex> sync(m_handleMutex);
+  if (index >= static_cast<int>(m_structures.size())) return nullptr;
+  return m_structures[index];
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+inline std::shared_ptr<TStruct>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::Free(
+    THandle handle) {
+  auto index =
+      handle.GetTypedIndex(static_cast<typename THandle::Type>(typeValue));
+  if (index < 0) return nullptr;
+  std::lock_guard<TMutex> sync(m_handleMutex);
+  if (index >= static_cast<int>(m_structures.size())) return nullptr;
+  auto rv = std::move(m_structures[index]);
+  m_structures[index].reset();
+  return rv;
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+template <typename T>
+inline wpi::ArrayRef<T>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::GetAll(
+    wpi::SmallVectorImpl<T>& vec) {
+  ForEach([&](THandle handle, const TStruct& data) { vec.push_back(handle); });
+  return vec;
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+inline std::vector<std::shared_ptr<TStruct>>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::FreeAll() {
+  std::lock_guard<TMutex> sync(m_handleMutex);
+  auto rv = std::move(m_structures);
+  m_structures.clear();
+  return rv;
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+template <typename F>
+inline void
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::ForEach(F func) {
+  std::lock_guard<TMutex> sync(m_handleMutex);
+  for (size_t i = 0; i < m_structures.size(); i++) {
+    if (m_structures[i] != nullptr) func(MakeHandle(i), *(m_structures[i]));
+  }
+}
+
+template <typename THandle, typename TStruct, int typeValue, typename TMutex>
+template <typename F>
+inline std::pair<THandle, std::shared_ptr<TStruct>>
+UnlimitedHandleResource<THandle, TStruct, typeValue, TMutex>::FindIf(F func) {
+  std::lock_guard<TMutex> sync(m_handleMutex);
+  for (size_t i = 0; i < m_structures.size(); i++) {
+    auto& structure = m_structures[i];
+    if (structure != nullptr && func(*structure))
+      return std::make_pair(MakeHandle(i), structure);
+  }
+  return std::make_pair(0, nullptr);
+}
+
+}  // namespace cs
+
+#endif  // CSCORE_UNLIMITEDHANDLERESOURCE_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp
new file mode 100644
index 0000000..082e398
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "cscore_c.h"  // NOLINT(build/include_order)
+
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+static void ConvertToC(CS_UsbCameraInfo* out, const UsbCameraInfo& in) {
+  out->dev = in.dev;
+  out->path = ConvertToC(in.path);
+  out->name = ConvertToC(in.name);
+  out->otherPaths = static_cast<char**>(
+      wpi::CheckedMalloc(in.otherPaths.size() * sizeof(char*)));
+  out->otherPathsCount = in.otherPaths.size();
+  for (size_t i = 0; i < in.otherPaths.size(); ++i)
+    out->otherPaths[i] = cs::ConvertToC(in.otherPaths[i]);
+}
+
+static void FreeUsbCameraInfo(CS_UsbCameraInfo* info) {
+  std::free(info->path);
+  std::free(info->name);
+  for (int i = 0; i < info->otherPathsCount; ++i)
+    std::free(info->otherPaths[i]);
+  std::free(info->otherPaths);
+}
+
+extern "C" {
+
+CS_Source CS_CreateUsbCameraDev(const char* name, int dev, CS_Status* status) {
+  return cs::CreateUsbCameraDev(name, dev, status);
+}
+
+CS_Source CS_CreateUsbCameraPath(const char* name, const char* path,
+                                 CS_Status* status) {
+  return cs::CreateUsbCameraPath(name, path, status);
+}
+
+char* CS_GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  return ConvertToC(cs::GetUsbCameraPath(source, status));
+}
+
+CS_UsbCameraInfo* CS_GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  auto info = cs::GetUsbCameraInfo(source, status);
+  if (*status != CS_OK) return nullptr;
+  CS_UsbCameraInfo* out = static_cast<CS_UsbCameraInfo*>(
+      wpi::CheckedMalloc(sizeof(CS_UsbCameraInfo)));
+  ConvertToC(out, info);
+  return out;
+}
+
+CS_UsbCameraInfo* CS_EnumerateUsbCameras(int* count, CS_Status* status) {
+  auto cameras = cs::EnumerateUsbCameras(status);
+  CS_UsbCameraInfo* out = static_cast<CS_UsbCameraInfo*>(
+      wpi::CheckedMalloc(cameras.size() * sizeof(CS_UsbCameraInfo)));
+  *count = cameras.size();
+  for (size_t i = 0; i < cameras.size(); ++i) ConvertToC(&out[i], cameras[i]);
+  return out;
+}
+
+void CS_FreeEnumeratedUsbCameras(CS_UsbCameraInfo* cameras, int count) {
+  if (!cameras) return;
+  for (int i = 0; i < count; ++i) FreeUsbCameraInfo(&cameras[i]);
+  std::free(cameras);
+}
+
+void CS_FreeUsbCameraInfo(CS_UsbCameraInfo* info) {
+  if (!info) return;
+  FreeUsbCameraInfo(info);
+  std::free(info);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/c_util.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/c_util.h
new file mode 100644
index 0000000..6264e1f
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/c_util.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_C_UTIL_H_
+#define CSCORE_C_UTIL_H_
+
+#include <cstdlib>
+#include <cstring>
+
+#include <wpi/StringRef.h>
+#include <wpi/memory.h>
+
+namespace cs {
+
+inline char* ConvertToC(wpi::StringRef in) {
+  char* out = static_cast<char*>(wpi::CheckedMalloc(in.size() + 1));
+  std::memmove(out, in.data(), in.size());
+  out[in.size()] = '\0';
+  return out;
+}
+
+}  // namespace cs
+
+#endif  // CSCORE_C_UTIL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_c.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_c.cpp
new file mode 100644
index 0000000..1819d13
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_c.cpp
@@ -0,0 +1,443 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "cscore_c.h"
+
+#include <cstddef>
+#include <cstdlib>
+
+#include <opencv2/core/core.hpp>
+#include <wpi/SmallString.h>
+#include <wpi/memory.h>
+
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+extern "C" {
+
+CS_PropertyKind CS_GetPropertyKind(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyKind(property, status);
+}
+
+char* CS_GetPropertyName(CS_Property property, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetPropertyName(property, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+int CS_GetProperty(CS_Property property, CS_Status* status) {
+  return cs::GetProperty(property, status);
+}
+
+void CS_SetProperty(CS_Property property, int value, CS_Status* status) {
+  return cs::SetProperty(property, value, status);
+}
+
+int CS_GetPropertyMin(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyMin(property, status);
+}
+
+int CS_GetPropertyMax(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyMax(property, status);
+}
+
+int CS_GetPropertyStep(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyStep(property, status);
+}
+
+int CS_GetPropertyDefault(CS_Property property, CS_Status* status) {
+  return cs::GetPropertyDefault(property, status);
+}
+
+char* CS_GetStringProperty(CS_Property property, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetStringProperty(property, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+void CS_SetStringProperty(CS_Property property, const char* value,
+                          CS_Status* status) {
+  return cs::SetStringProperty(property, value, status);
+}
+
+char** CS_GetEnumPropertyChoices(CS_Property property, int* count,
+                                 CS_Status* status) {
+  auto choices = cs::GetEnumPropertyChoices(property, status);
+  char** out =
+      static_cast<char**>(wpi::CheckedMalloc(choices.size() * sizeof(char*)));
+  *count = choices.size();
+  for (size_t i = 0; i < choices.size(); ++i)
+    out[i] = cs::ConvertToC(choices[i]);
+  return out;
+}
+
+CS_SourceKind CS_GetSourceKind(CS_Source source, CS_Status* status) {
+  return cs::GetSourceKind(source, status);
+}
+
+char* CS_GetSourceName(CS_Source source, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSourceName(source, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+char* CS_GetSourceDescription(CS_Source source, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSourceDescription(source, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+uint64_t CS_GetSourceLastFrameTime(CS_Source source, CS_Status* status) {
+  return cs::GetSourceLastFrameTime(source, status);
+}
+
+void CS_SetSourceConnectionStrategy(CS_Source source,
+                                    CS_ConnectionStrategy strategy,
+                                    CS_Status* status) {
+  cs::SetSourceConnectionStrategy(source, strategy, status);
+}
+
+CS_Bool CS_IsSourceConnected(CS_Source source, CS_Status* status) {
+  return cs::IsSourceConnected(source, status);
+}
+
+CS_Bool CS_IsSourceEnabled(CS_Source source, CS_Status* status) {
+  return cs::IsSourceEnabled(source, status);
+}
+
+CS_Property CS_GetSourceProperty(CS_Source source, const char* name,
+                                 CS_Status* status) {
+  return cs::GetSourceProperty(source, name, status);
+}
+
+CS_Property* CS_EnumerateSourceProperties(CS_Source source, int* count,
+                                          CS_Status* status) {
+  wpi::SmallVector<CS_Property, 32> buf;
+  auto vec = cs::EnumerateSourceProperties(source, buf, status);
+  CS_Property* out = static_cast<CS_Property*>(
+      wpi::CheckedMalloc(vec.size() * sizeof(CS_Property)));
+  *count = vec.size();
+  std::copy(vec.begin(), vec.end(), out);
+  return out;
+}
+
+void CS_GetSourceVideoMode(CS_Source source, CS_VideoMode* mode,
+                           CS_Status* status) {
+  *mode = cs::GetSourceVideoMode(source, status);
+}
+
+CS_Bool CS_SetSourceVideoMode(CS_Source source, const CS_VideoMode* mode,
+                              CS_Status* status) {
+  return cs::SetSourceVideoMode(
+      source, static_cast<const cs::VideoMode&>(*mode), status);
+}
+
+CS_Bool CS_SetSourceVideoModeDiscrete(CS_Source source,
+                                      enum CS_PixelFormat pixelFormat,
+                                      int width, int height, int fps,
+                                      CS_Status* status) {
+  return cs::SetSourceVideoMode(
+      source,
+      cs::VideoMode{static_cast<cs::VideoMode::PixelFormat>(
+                        static_cast<int>(pixelFormat)),
+                    width, height, fps},
+      status);
+}
+
+CS_Bool CS_SetSourcePixelFormat(CS_Source source,
+                                enum CS_PixelFormat pixelFormat,
+                                CS_Status* status) {
+  return cs::SetSourcePixelFormat(
+      source,
+      static_cast<cs::VideoMode::PixelFormat>(static_cast<int>(pixelFormat)),
+      status);
+}
+
+CS_Bool CS_SetSourceResolution(CS_Source source, int width, int height,
+                               CS_Status* status) {
+  return cs::SetSourceResolution(source, width, height, status);
+}
+
+CS_Bool CS_SetSourceFPS(CS_Source source, int fps, CS_Status* status) {
+  return cs::SetSourceFPS(source, fps, status);
+}
+
+CS_Bool CS_SetSourceConfigJson(CS_Source source, const char* config,
+                               CS_Status* status) {
+  return cs::SetSourceConfigJson(source, config, status);
+}
+
+char* CS_GetSourceConfigJson(CS_Source source, CS_Status* status) {
+  return cs::ConvertToC(cs::GetSourceConfigJson(source, status));
+}
+
+CS_VideoMode* CS_EnumerateSourceVideoModes(CS_Source source, int* count,
+                                           CS_Status* status) {
+  auto vec = cs::EnumerateSourceVideoModes(source, status);
+  CS_VideoMode* out = static_cast<CS_VideoMode*>(
+      wpi::CheckedMalloc(vec.size() * sizeof(CS_VideoMode)));
+  *count = vec.size();
+  std::copy(vec.begin(), vec.end(), out);
+  return out;
+}
+
+CS_Sink* CS_EnumerateSourceSinks(CS_Source source, int* count,
+                                 CS_Status* status) {
+  wpi::SmallVector<CS_Sink, 32> buf;
+  auto handles = cs::EnumerateSourceSinks(source, buf, status);
+  CS_Sink* sinks = static_cast<CS_Sink*>(
+      wpi::CheckedMalloc(handles.size() * sizeof(CS_Sink)));
+  *count = handles.size();
+  std::copy(handles.begin(), handles.end(), sinks);
+  return sinks;
+}
+
+CS_Source CS_CopySource(CS_Source source, CS_Status* status) {
+  return cs::CopySource(source, status);
+}
+
+void CS_ReleaseSource(CS_Source source, CS_Status* status) {
+  return cs::ReleaseSource(source, status);
+}
+
+void CS_SetCameraBrightness(CS_Source source, int brightness,
+                            CS_Status* status) {
+  return cs::SetCameraBrightness(source, brightness, status);
+}
+
+int CS_GetCameraBrightness(CS_Source source, CS_Status* status) {
+  return cs::GetCameraBrightness(source, status);
+}
+
+void CS_SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status) {
+  return cs::SetCameraWhiteBalanceAuto(source, status);
+}
+
+void CS_SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status) {
+  return cs::SetCameraWhiteBalanceHoldCurrent(source, status);
+}
+
+void CS_SetCameraWhiteBalanceManual(CS_Source source, int value,
+                                    CS_Status* status) {
+  return cs::SetCameraWhiteBalanceManual(source, value, status);
+}
+
+void CS_SetCameraExposureAuto(CS_Source source, CS_Status* status) {
+  return cs::SetCameraExposureAuto(source, status);
+}
+
+void CS_SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status) {
+  return cs::SetCameraExposureHoldCurrent(source, status);
+}
+
+void CS_SetCameraExposureManual(CS_Source source, int value,
+                                CS_Status* status) {
+  return cs::SetCameraExposureManual(source, value, status);
+}
+
+CS_SinkKind CS_GetSinkKind(CS_Sink sink, CS_Status* status) {
+  return cs::GetSinkKind(sink, status);
+}
+
+char* CS_GetSinkName(CS_Sink sink, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkName(sink, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+char* CS_GetSinkDescription(CS_Sink sink, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkDescription(sink, buf, status);
+  if (*status != 0) return nullptr;
+  return cs::ConvertToC(str);
+}
+
+CS_Property CS_GetSinkProperty(CS_Sink sink, const char* name,
+                               CS_Status* status) {
+  return cs::GetSinkProperty(sink, name, status);
+}
+
+CS_Property* CS_EnumerateSinkProperties(CS_Sink sink, int* count,
+                                        CS_Status* status) {
+  wpi::SmallVector<CS_Property, 32> buf;
+  auto vec = cs::EnumerateSinkProperties(sink, buf, status);
+  CS_Property* out = static_cast<CS_Property*>(
+      wpi::CheckedMalloc(vec.size() * sizeof(CS_Property)));
+  *count = vec.size();
+  std::copy(vec.begin(), vec.end(), out);
+  return out;
+}
+
+CS_Bool CS_SetSinkConfigJson(CS_Sink sink, const char* config,
+                             CS_Status* status) {
+  return cs::SetSinkConfigJson(sink, config, status);
+}
+
+char* CS_GetSinkConfigJson(CS_Sink sink, CS_Status* status) {
+  return cs::ConvertToC(cs::GetSinkConfigJson(sink, status));
+}
+
+void CS_SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status) {
+  return cs::SetSinkSource(sink, source, status);
+}
+
+CS_Source CS_GetSinkSource(CS_Sink sink, CS_Status* status) {
+  return cs::GetSinkSource(sink, status);
+}
+
+CS_Property CS_GetSinkSourceProperty(CS_Sink sink, const char* name,
+                                     CS_Status* status) {
+  return cs::GetSinkSourceProperty(sink, name, status);
+}
+
+CS_Sink CS_CopySink(CS_Sink sink, CS_Status* status) {
+  return cs::CopySink(sink, status);
+}
+
+void CS_ReleaseSink(CS_Sink sink, CS_Status* status) {
+  return cs::ReleaseSink(sink, status);
+}
+
+void CS_SetListenerOnStart(void (*onStart)(void* data), void* data) {
+  cs::SetListenerOnStart([=]() { onStart(data); });
+}
+
+void CS_SetListenerOnExit(void (*onExit)(void* data), void* data) {
+  cs::SetListenerOnExit([=]() { onExit(data); });
+}
+
+CS_Listener CS_AddListener(void* data,
+                           void (*callback)(void* data, const CS_Event* event),
+                           int eventMask, int immediateNotify,
+                           CS_Status* status) {
+  return cs::AddListener(
+      [=](const cs::RawEvent& rawEvent) {
+        CS_Event event;
+        event.kind = static_cast<CS_EventKind>(static_cast<int>(rawEvent.kind));
+        event.source = rawEvent.sourceHandle;
+        event.sink = rawEvent.sinkHandle;
+        event.name = rawEvent.name.c_str();
+        event.mode = rawEvent.mode;
+        event.property = rawEvent.propertyHandle;
+        event.propertyKind = rawEvent.propertyKind;
+        event.value = rawEvent.value;
+        event.valueStr = rawEvent.valueStr.c_str();
+        callback(data, &event);
+      },
+      eventMask, immediateNotify, status);
+}
+
+void CS_RemoveListener(CS_Listener handle, CS_Status* status) {
+  return cs::RemoveListener(handle, status);
+}
+
+int CS_NotifierDestroyed(void) { return cs::NotifierDestroyed(); }
+
+void CS_SetTelemetryPeriod(double seconds) { cs::SetTelemetryPeriod(seconds); }
+
+double CS_GetTelemetryElapsedTime(void) {
+  return cs::GetTelemetryElapsedTime();
+}
+
+int64_t CS_GetTelemetryValue(CS_Handle handle, CS_TelemetryKind kind,
+                             CS_Status* status) {
+  return cs::GetTelemetryValue(handle, kind, status);
+}
+
+double CS_GetTelemetryAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                                   CS_Status* status) {
+  return cs::GetTelemetryAverageValue(handle, kind, status);
+}
+
+void CS_SetLogger(CS_LogFunc func, unsigned int min_level) {
+  cs::SetLogger(func, min_level);
+}
+
+void CS_SetDefaultLogger(unsigned int min_level) {
+  cs::SetDefaultLogger(min_level);
+}
+
+void CS_Shutdown(void) { cs::Shutdown(); }
+
+CS_Source* CS_EnumerateSources(int* count, CS_Status* status) {
+  wpi::SmallVector<CS_Source, 32> buf;
+  auto handles = cs::EnumerateSourceHandles(buf, status);
+  CS_Source* sources = static_cast<CS_Source*>(
+      wpi::CheckedMalloc(handles.size() * sizeof(CS_Source)));
+  *count = handles.size();
+  std::copy(handles.begin(), handles.end(), sources);
+  return sources;
+}
+
+void CS_ReleaseEnumeratedSources(CS_Source* sources, int count) {
+  if (!sources) return;
+  for (int i = 0; i < count; ++i) {
+    CS_Status status = 0;
+    if (sources[i] != 0) cs::ReleaseSource(sources[i], &status);
+  }
+  std::free(sources);
+}
+
+CS_Sink* CS_EnumerateSinks(int* count, CS_Status* status) {
+  wpi::SmallVector<CS_Sink, 32> buf;
+  auto handles = cs::EnumerateSinkHandles(buf, status);
+  CS_Sink* sinks = static_cast<CS_Sink*>(
+      wpi::CheckedMalloc(handles.size() * sizeof(CS_Sink)));
+  *count = handles.size();
+  std::copy(handles.begin(), handles.end(), sinks);
+  return sinks;
+}
+
+void CS_ReleaseEnumeratedSinks(CS_Sink* sinks, int count) {
+  if (!sinks) return;
+  for (int i = 0; i < count; ++i) {
+    CS_Status status = 0;
+    if (sinks[i] != 0) cs::ReleaseSink(sinks[i], &status);
+  }
+  std::free(sinks);
+}
+
+void CS_FreeString(char* str) { std::free(str); }
+
+void CS_FreeEnumPropertyChoices(char** choices, int count) {
+  if (!choices) return;
+  for (int i = 0; i < count; ++i) std::free(choices[i]);
+  std::free(choices);
+}
+
+void CS_FreeEnumeratedProperties(CS_Property* properties, int count) {
+  std::free(properties);
+}
+
+void CS_FreeEnumeratedVideoModes(CS_VideoMode* modes, int count) {
+  std::free(modes);
+}
+
+char* CS_GetHostname() { return cs::ConvertToC(cs::GetHostname()); }
+
+char** CS_GetNetworkInterfaces(int* count) {
+  auto interfaces = cs::GetNetworkInterfaces();
+  char** out = static_cast<char**>(
+      wpi::CheckedMalloc(interfaces.size() * sizeof(char*)));
+  *count = interfaces.size();
+  for (size_t i = 0; i < interfaces.size(); ++i)
+    out[i] = cs::ConvertToC(interfaces[i]);
+  return out;
+}
+
+void CS_FreeNetworkInterfaces(char** interfaces, int count) {
+  if (!interfaces) return;
+  for (int i = 0; i < count; ++i) std::free(interfaces[i]);
+  std::free(interfaces);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_cpp.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_cpp.cpp
new file mode 100644
index 0000000..83b4e87
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_cpp.cpp
@@ -0,0 +1,765 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "cscore_cpp.h"
+
+#include <wpi/SmallString.h>
+#include <wpi/hostname.h>
+#include <wpi/json.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "Log.h"
+#include "NetworkListener.h"
+#include "Notifier.h"
+#include "PropertyContainer.h"
+#include "SinkImpl.h"
+#include "SourceImpl.h"
+#include "Telemetry.h"
+
+using namespace cs;
+
+static std::shared_ptr<PropertyContainer> GetPropertyContainer(
+    CS_Property propertyHandle, int* propertyIndex, CS_Status* status) {
+  std::shared_ptr<PropertyContainer> container;
+  Handle handle{propertyHandle};
+  if (handle.IsType(Handle::kProperty)) {
+    int i = handle.GetParentIndex();
+    auto data = Instance::GetInstance().GetSource(Handle{i, Handle::kSource});
+    if (!data) {
+      *status = CS_INVALID_HANDLE;
+      return nullptr;
+    }
+    container = data->source;
+  } else if (handle.IsType(Handle::kSinkProperty)) {
+    int i = handle.GetParentIndex();
+    auto data = Instance::GetInstance().GetSink(Handle{i, Handle::kSink});
+    if (!data) {
+      *status = CS_INVALID_HANDLE;
+      return nullptr;
+    }
+    container = data->sink;
+  } else {
+    *status = CS_INVALID_HANDLE;
+    return nullptr;
+  }
+  *propertyIndex = handle.GetIndex();
+  return container;
+}
+
+namespace cs {
+
+//
+// Property Functions
+//
+
+CS_PropertyKind GetPropertyKind(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return CS_PROP_NONE;
+  return container->GetPropertyKind(propertyIndex);
+}
+
+std::string GetPropertyName(CS_Property property, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return std::string{};
+  return container->GetPropertyName(propertyIndex, buf, status);
+}
+
+wpi::StringRef GetPropertyName(CS_Property property,
+                               wpi::SmallVectorImpl<char>& buf,
+                               CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return wpi::StringRef{};
+  return container->GetPropertyName(propertyIndex, buf, status);
+}
+
+int GetProperty(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return false;
+  return container->GetProperty(propertyIndex, status);
+}
+
+void SetProperty(CS_Property property, int value, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return;
+  container->SetProperty(propertyIndex, value, status);
+}
+
+int GetPropertyMin(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return 0.0;
+  return container->GetPropertyMin(propertyIndex, status);
+}
+
+int GetPropertyMax(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return 0.0;
+  return container->GetPropertyMax(propertyIndex, status);
+}
+
+int GetPropertyStep(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return 0.0;
+  return container->GetPropertyStep(propertyIndex, status);
+}
+
+int GetPropertyDefault(CS_Property property, CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return 0.0;
+  return container->GetPropertyDefault(propertyIndex, status);
+}
+
+std::string GetStringProperty(CS_Property property, CS_Status* status) {
+  wpi::SmallString<128> buf;
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return std::string{};
+  return container->GetStringProperty(propertyIndex, buf, status);
+}
+
+wpi::StringRef GetStringProperty(CS_Property property,
+                                 wpi::SmallVectorImpl<char>& buf,
+                                 CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return wpi::StringRef{};
+  return container->GetStringProperty(propertyIndex, buf, status);
+}
+
+void SetStringProperty(CS_Property property, const wpi::Twine& value,
+                       CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return;
+  container->SetStringProperty(propertyIndex, value, status);
+}
+
+std::vector<std::string> GetEnumPropertyChoices(CS_Property property,
+                                                CS_Status* status) {
+  int propertyIndex;
+  auto container = GetPropertyContainer(property, &propertyIndex, status);
+  if (!container) return std::vector<std::string>{};
+  return container->GetEnumPropertyChoices(propertyIndex, status);
+}
+
+//
+// Source Functions
+//
+
+CS_SourceKind GetSourceKind(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return CS_SOURCE_UNKNOWN;
+  }
+  return data->kind;
+}
+
+std::string GetSourceName(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return data->source->GetName();
+}
+
+wpi::StringRef GetSourceName(CS_Source source, wpi::SmallVectorImpl<char>& buf,
+                             CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return data->source->GetName();
+}
+
+std::string GetSourceDescription(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  wpi::SmallString<128> buf;
+  return data->source->GetDescription(buf);
+}
+
+wpi::StringRef GetSourceDescription(CS_Source source,
+                                    wpi::SmallVectorImpl<char>& buf,
+                                    CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return data->source->GetDescription(buf);
+}
+
+uint64_t GetSourceLastFrameTime(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return data->source->GetCurFrameTime();
+}
+
+void SetSourceConnectionStrategy(CS_Source source,
+                                 CS_ConnectionStrategy strategy,
+                                 CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetConnectionStrategy(strategy);
+}
+
+bool IsSourceConnected(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->IsConnected();
+}
+
+bool IsSourceEnabled(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->IsEnabled();
+}
+
+CS_Property GetSourceProperty(CS_Source source, const wpi::Twine& name,
+                              CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  int property = data->source->GetPropertyIndex(name);
+  if (property < 0) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return Handle{source, property, Handle::kProperty};
+}
+
+wpi::ArrayRef<CS_Property> EnumerateSourceProperties(
+    CS_Source source, wpi::SmallVectorImpl<CS_Property>& vec,
+    CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  wpi::SmallVector<int, 32> properties_buf;
+  for (auto property :
+       data->source->EnumerateProperties(properties_buf, status))
+    vec.push_back(Handle{source, property, Handle::kProperty});
+  return vec;
+}
+
+VideoMode GetSourceVideoMode(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return VideoMode{};
+  }
+  return data->source->GetVideoMode(status);
+}
+
+bool SetSourceVideoMode(CS_Source source, const VideoMode& mode,
+                        CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetVideoMode(mode, status);
+}
+
+bool SetSourcePixelFormat(CS_Source source, VideoMode::PixelFormat pixelFormat,
+                          CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetPixelFormat(pixelFormat, status);
+}
+
+bool SetSourceResolution(CS_Source source, int width, int height,
+                         CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetResolution(width, height, status);
+}
+
+bool SetSourceFPS(CS_Source source, int fps, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetFPS(fps, status);
+}
+
+bool SetSourceConfigJson(CS_Source source, wpi::StringRef config,
+                         CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetConfigJson(config, status);
+}
+
+bool SetSourceConfigJson(CS_Source source, const wpi::json& config,
+                         CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->source->SetConfigJson(config, status);
+}
+
+std::string GetSourceConfigJson(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return data->source->GetConfigJson(status);
+}
+
+wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::json{};
+  }
+  return data->source->GetConfigJsonObject(status);
+}
+
+std::vector<VideoMode> EnumerateSourceVideoModes(CS_Source source,
+                                                 CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::vector<VideoMode>{};
+  }
+  return data->source->EnumerateVideoModes(status);
+}
+
+wpi::ArrayRef<CS_Sink> EnumerateSourceSinks(CS_Source source,
+                                            wpi::SmallVectorImpl<CS_Sink>& vec,
+                                            CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  auto data = inst.GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::ArrayRef<CS_Sink>{};
+  }
+  return inst.EnumerateSourceSinks(source, vec);
+}
+
+CS_Source CopySource(CS_Source source, CS_Status* status) {
+  if (source == 0) return 0;
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  data->refCount++;
+  return source;
+}
+
+void ReleaseSource(CS_Source source, CS_Status* status) {
+  if (source == 0) return;
+  auto& inst = Instance::GetInstance();
+  auto data = inst.GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  if (data->refCount-- == 0) inst.DestroySource(source);
+}
+
+//
+// Camera Source Common Property Fuctions
+//
+
+void SetCameraBrightness(CS_Source source, int brightness, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetBrightness(brightness, status);
+}
+
+int GetCameraBrightness(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return data->source->GetBrightness(status);
+}
+
+void SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetWhiteBalanceAuto(status);
+}
+
+void SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetWhiteBalanceHoldCurrent(status);
+}
+
+void SetCameraWhiteBalanceManual(CS_Source source, int value,
+                                 CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetWhiteBalanceManual(value, status);
+}
+
+void SetCameraExposureAuto(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetExposureAuto(status);
+}
+
+void SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetExposureHoldCurrent(status);
+}
+
+void SetCameraExposureManual(CS_Source source, int value, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  data->source->SetExposureManual(value, status);
+}
+
+//
+// Sink Functions
+//
+
+CS_SinkKind GetSinkKind(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return CS_SINK_UNKNOWN;
+  }
+  return data->kind;
+}
+
+std::string GetSinkName(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return data->sink->GetName();
+}
+
+wpi::StringRef GetSinkName(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                           CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return data->sink->GetName();
+}
+
+std::string GetSinkDescription(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  wpi::SmallString<128> buf;
+  return data->sink->GetDescription(buf);
+}
+
+wpi::StringRef GetSinkDescription(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                                  CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::StringRef{};
+  }
+  return data->sink->GetDescription(buf);
+}
+
+CS_Property GetSinkProperty(CS_Sink sink, const wpi::Twine& name,
+                            CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  int property = data->sink->GetPropertyIndex(name);
+  if (property < 0) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return Handle{sink, property, Handle::kSinkProperty};
+}
+
+wpi::ArrayRef<CS_Property> EnumerateSinkProperties(
+    CS_Sink sink, wpi::SmallVectorImpl<CS_Property>& vec, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  wpi::SmallVector<int, 32> properties_buf;
+  for (auto property : data->sink->EnumerateProperties(properties_buf, status))
+    vec.push_back(Handle{sink, property, Handle::kSinkProperty});
+  return vec;
+}
+
+bool SetSinkConfigJson(CS_Sink sink, wpi::StringRef config, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->sink->SetConfigJson(config, status);
+}
+
+bool SetSinkConfigJson(CS_Sink sink, const wpi::json& config,
+                       CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return false;
+  }
+  return data->sink->SetConfigJson(config, status);
+}
+
+std::string GetSinkConfigJson(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return data->sink->GetConfigJson(status);
+}
+
+wpi::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return wpi::json{};
+  }
+  return data->sink->GetConfigJsonObject(status);
+}
+
+void SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  if (source == 0) {
+    data->sink->SetSource(nullptr);
+  } else {
+    auto sourceData = Instance::GetInstance().GetSource(source);
+    if (!sourceData) {
+      *status = CS_INVALID_HANDLE;
+      return;
+    }
+    data->sink->SetSource(sourceData->source);
+  }
+  data->sourceHandle.store(source);
+  Instance::GetInstance().notifier.NotifySinkSourceChanged(
+      data->sink->GetName(), sink, source);
+}
+
+CS_Source GetSinkSource(CS_Sink sink, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return data->sourceHandle.load();
+}
+
+CS_Property GetSinkSourceProperty(CS_Sink sink, const wpi::Twine& name,
+                                  CS_Status* status) {
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  return GetSourceProperty(data->sourceHandle.load(), name, status);
+}
+
+CS_Sink CopySink(CS_Sink sink, CS_Status* status) {
+  if (sink == 0) return 0;
+  auto data = Instance::GetInstance().GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return 0;
+  }
+  data->refCount++;
+  return sink;
+}
+
+void ReleaseSink(CS_Sink sink, CS_Status* status) {
+  if (sink == 0) return;
+  auto& inst = Instance::GetInstance();
+  auto data = inst.GetSink(sink);
+  if (!data) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  if (data->refCount-- == 0) inst.DestroySink(sink);
+}
+
+//
+// Listener Functions
+//
+
+void SetListenerOnStart(std::function<void()> onStart) {
+  Instance::GetInstance().notifier.SetOnStart(onStart);
+}
+
+void SetListenerOnExit(std::function<void()> onExit) {
+  Instance::GetInstance().notifier.SetOnExit(onExit);
+}
+
+CS_Listener AddListener(std::function<void(const RawEvent& event)> callback,
+                        int eventMask, bool immediateNotify,
+                        CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  int uid = inst.notifier.AddListener(callback, eventMask);
+  if ((eventMask & CS_NETWORK_INTERFACES_CHANGED) != 0) {
+    // start network interface event listener
+    inst.networkListener.Start();
+    if (immediateNotify) inst.notifier.NotifyNetworkInterfacesChanged();
+  }
+  if (immediateNotify) {
+    // TODO
+  }
+  return Handle{uid, Handle::kListener};
+}
+
+void RemoveListener(CS_Listener handle, CS_Status* status) {
+  int uid = Handle{handle}.GetTypedIndex(Handle::kListener);
+  if (uid < 0) {
+    *status = CS_INVALID_HANDLE;
+    return;
+  }
+  Instance::GetInstance().notifier.RemoveListener(uid);
+}
+
+bool NotifierDestroyed() { return Notifier::destroyed(); }
+
+//
+// Telemetry Functions
+//
+void SetTelemetryPeriod(double seconds) {
+  auto& inst = Instance::GetInstance();
+  inst.telemetry.Start();
+  inst.telemetry.SetPeriod(seconds);
+}
+
+double GetTelemetryElapsedTime() {
+  return Instance::GetInstance().telemetry.GetElapsedTime();
+}
+
+int64_t GetTelemetryValue(CS_Handle handle, CS_TelemetryKind kind,
+                          CS_Status* status) {
+  return Instance::GetInstance().telemetry.GetValue(handle, kind, status);
+}
+
+double GetTelemetryAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                                CS_Status* status) {
+  return Instance::GetInstance().telemetry.GetAverageValue(handle, kind,
+                                                           status);
+}
+
+//
+// Logging Functions
+//
+void SetLogger(LogFunc func, unsigned int min_level) {
+  auto& logger = Instance::GetInstance().logger;
+  logger.SetLogger(func);
+  logger.set_min_level(min_level);
+}
+
+void SetDefaultLogger(unsigned int min_level) {
+  auto& inst = Instance::GetInstance();
+  inst.SetDefaultLogger();
+  inst.logger.set_min_level(min_level);
+}
+
+//
+// Shutdown Function
+//
+void Shutdown() { Instance::GetInstance().Shutdown(); }
+
+//
+// Utility Functions
+//
+
+wpi::ArrayRef<CS_Source> EnumerateSourceHandles(
+    wpi::SmallVectorImpl<CS_Source>& vec, CS_Status* status) {
+  return Instance::GetInstance().EnumerateSourceHandles(vec);
+}
+
+wpi::ArrayRef<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec,
+                                            CS_Status* status) {
+  return Instance::GetInstance().EnumerateSinkHandles(vec);
+}
+
+std::string GetHostname() { return wpi::GetHostname(); }
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_oo.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_oo.cpp
new file mode 100644
index 0000000..f455273
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/cscore_oo.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "cscore_oo.h"
+
+#include <wpi/json.h>
+
+using namespace cs;
+
+wpi::json VideoSource::GetConfigJsonObject() const {
+  m_status = 0;
+  return GetSourceConfigJsonObject(m_handle, &m_status);
+}
+
+wpi::json VideoSink::GetConfigJsonObject() const {
+  m_status = 0;
+  return GetSinkConfigJsonObject(m_handle, &m_status);
+}
+
+std::vector<VideoProperty> VideoSource::EnumerateProperties() const {
+  wpi::SmallVector<CS_Property, 32> handles_buf;
+  CS_Status status = 0;
+  auto handles = EnumerateSourceProperties(m_handle, handles_buf, &status);
+
+  std::vector<VideoProperty> properties;
+  properties.reserve(handles.size());
+  for (CS_Property handle : handles)
+    properties.emplace_back(VideoProperty{handle});
+  return properties;
+}
+
+std::vector<VideoSink> VideoSource::EnumerateSinks() {
+  wpi::SmallVector<CS_Sink, 16> handles_buf;
+  CS_Status status = 0;
+  auto handles = EnumerateSourceSinks(m_handle, handles_buf, &status);
+
+  std::vector<VideoSink> sinks;
+  sinks.reserve(handles.size());
+  for (int handle : handles) sinks.emplace_back(VideoSink{handle});
+  return sinks;
+}
+
+std::vector<VideoSource> VideoSource::EnumerateSources() {
+  wpi::SmallVector<CS_Source, 16> handles_buf;
+  CS_Status status = 0;
+  auto handles = ::cs::EnumerateSourceHandles(handles_buf, &status);
+
+  std::vector<VideoSource> sources;
+  sources.reserve(handles.size());
+  for (int handle : handles) sources.emplace_back(VideoSource{handle});
+  return sources;
+}
+
+std::vector<VideoProperty> VideoSink::EnumerateProperties() const {
+  wpi::SmallVector<CS_Property, 32> handles_buf;
+  CS_Status status = 0;
+  auto handles = EnumerateSinkProperties(m_handle, handles_buf, &status);
+
+  std::vector<VideoProperty> properties;
+  properties.reserve(handles.size());
+  for (CS_Property handle : handles)
+    properties.emplace_back(VideoProperty{handle});
+  return properties;
+}
+
+std::vector<VideoSink> VideoSink::EnumerateSinks() {
+  wpi::SmallVector<CS_Sink, 16> handles_buf;
+  CS_Status status = 0;
+  auto handles = ::cs::EnumerateSinkHandles(handles_buf, &status);
+
+  std::vector<VideoSink> sinks;
+  sinks.reserve(handles.size());
+  for (int handle : handles) sinks.emplace_back(VideoSink{handle});
+  return sinks;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/default_init_allocator.h b/third_party/allwpilib_2019/cscore/src/main/native/cpp/default_init_allocator.h
new file mode 100644
index 0000000..089cac7
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/default_init_allocator.h
@@ -0,0 +1,41 @@
+// From:
+// http://stackoverflow.com/questions/21028299/is-this-behavior-of-vectorresizesize-type-n-under-c11-and-boost-container
+// Credits: Casey and Howard Hinnant
+
+#ifndef CSCORE_DEFAULT_INIT_ALLOCATOR_H_
+#define CSCORE_DEFAULT_INIT_ALLOCATOR_H_
+
+#include <memory>
+#include <utility>
+
+namespace cs {
+
+// Allocator adaptor that interposes construct() calls to
+// convert value initialization into default initialization.
+template <typename T, typename A = std::allocator<T>>
+class default_init_allocator : public A {
+  using a_t = std::allocator_traits<A>;
+
+ public:
+  template <typename U>
+  struct rebind {
+    using other =
+        default_init_allocator<U, typename a_t::template rebind_alloc<U>>;
+  };
+
+  using A::A;
+
+  template <typename U>
+  void construct(U* ptr) noexcept(
+      std::is_nothrow_default_constructible<U>::value) {
+    ::new (static_cast<void*>(ptr)) U;
+  }
+  template <typename U, typename... Args>
+  void construct(U* ptr, Args&&... args) {
+    a_t::construct(static_cast<A&>(*this), ptr, std::forward<Args>(args)...);
+  }
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_DEFAULT_INIT_ALLOCATOR_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp b/third_party/allwpilib_2019/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp
new file mode 100644
index 0000000..528d5e4
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp
@@ -0,0 +1,1784 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "cscore_cpp.h"
+#include "edu_wpi_cscore_CameraServerJNI.h"
+
+using namespace wpi::java;
+
+//
+// Globals and load/unload
+//
+
+// Used for callback.
+static JavaVM* jvm = nullptr;
+static JClass usbCameraInfoCls;
+static JClass videoModeCls;
+static JClass videoEventCls;
+static JException videoEx;
+static JException nullPointerEx;
+static JException unsupportedEx;
+// Thread-attached environment for listener callbacks.
+static JNIEnv* listenerEnv = nullptr;
+
+static const JClassInit classes[] = {
+    {"edu/wpi/cscore/UsbCameraInfo", &usbCameraInfoCls},
+    {"edu/wpi/cscore/VideoMode", &videoModeCls},
+    {"edu/wpi/cscore/VideoEvent", &videoEventCls}};
+
+static const JExceptionInit exceptions[] = {
+    {"edu/wpi/cscore/VideoException", &videoEx},
+    {"java/lang/NullPointerException", &nullPointerEx},
+    {"java/lang/UnsupportedOperationException", &unsupportedEx}};
+
+static void ListenerOnStart() {
+  if (!jvm) return;
+  JNIEnv* env;
+  JavaVMAttachArgs args;
+  args.version = JNI_VERSION_1_2;
+  args.name = const_cast<char*>("CSListener");
+  args.group = nullptr;
+  if (jvm->AttachCurrentThreadAsDaemon(reinterpret_cast<void**>(&env), &args) !=
+      JNI_OK)
+    return;
+  if (!env || !env->functions) return;
+  listenerEnv = env;
+}
+
+static void ListenerOnExit() {
+  listenerEnv = nullptr;
+  if (!jvm) return;
+  jvm->DetachCurrentThread();
+}
+
+extern "C" {
+
+JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) {
+  jvm = vm;
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return JNI_ERR;
+
+  // Cache references to classes
+  for (auto& c : classes) {
+    *c.cls = JClass(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  for (auto& c : exceptions) {
+    *c.cls = JException(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  // Initial configuration of listener start/exit
+  cs::SetListenerOnStart(ListenerOnStart);
+  cs::SetListenerOnExit(ListenerOnExit);
+
+  return JNI_VERSION_1_6;
+}
+
+JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) {
+  cs::Shutdown();
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return;
+  // Delete global references
+  for (auto& c : classes) {
+    c.cls->free(env);
+  }
+  for (auto& c : exceptions) {
+    c.cls->free(env);
+  }
+  jvm = nullptr;
+}
+
+}  // extern "C"
+
+//
+// Helper class to create and clean up a global reference
+//
+template <typename T>
+class JCSGlobal {
+ public:
+  JCSGlobal(JNIEnv* env, T obj)
+      : m_obj(static_cast<T>(env->NewGlobalRef(obj))) {}
+  ~JCSGlobal() {
+    if (!jvm || cs::NotifierDestroyed()) return;
+    JNIEnv* env;
+    bool attached = false;
+    // don't attach and de-attach if already attached to a thread.
+    if (jvm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) ==
+        JNI_EDETACHED) {
+      if (jvm->AttachCurrentThread(reinterpret_cast<void**>(&env), nullptr) !=
+          JNI_OK)
+        return;
+      attached = true;
+    }
+    if (!env || !env->functions) return;
+    env->DeleteGlobalRef(m_obj);
+    if (attached) jvm->DetachCurrentThread();
+  }
+  operator T() { return m_obj; }
+  T obj() { return m_obj; }
+
+ private:
+  T m_obj;
+};
+
+static void ReportError(JNIEnv* env, CS_Status status) {
+  if (status == CS_OK) return;
+  wpi::SmallString<64> msg;
+  switch (status) {
+    case CS_PROPERTY_WRITE_FAILED:
+      msg = "property write failed";
+      break;
+    case CS_INVALID_HANDLE:
+      msg = "invalid handle";
+      break;
+    case CS_WRONG_HANDLE_SUBTYPE:
+      msg = "wrong handle subtype";
+      break;
+    case CS_INVALID_PROPERTY:
+      msg = "invalid property";
+      break;
+    case CS_WRONG_PROPERTY_TYPE:
+      msg = "wrong property type";
+      break;
+    case CS_READ_FAILED:
+      msg = "read failed";
+      break;
+    case CS_SOURCE_IS_DISCONNECTED:
+      msg = "source is disconnected";
+      break;
+    case CS_EMPTY_VALUE:
+      msg = "empty value";
+      break;
+    case CS_BAD_URL:
+      msg = "bad URL";
+      break;
+    case CS_TELEMETRY_NOT_ENABLED:
+      msg = "telemetry not enabled";
+      break;
+    default: {
+      wpi::raw_svector_ostream oss{msg};
+      oss << "unknown error code=" << status;
+      break;
+    }
+  }
+  videoEx.Throw(env, msg);
+}
+
+static inline bool CheckStatus(JNIEnv* env, CS_Status status) {
+  if (status != CS_OK) ReportError(env, status);
+  return status == CS_OK;
+}
+
+static jobject MakeJObject(JNIEnv* env, const cs::UsbCameraInfo& info) {
+  static jmethodID constructor = env->GetMethodID(
+      usbCameraInfoCls, "<init>",
+      "(ILjava/lang/String;Ljava/lang/String;[Ljava/lang/String;)V");
+  JLocal<jstring> path(env, MakeJString(env, info.path));
+  JLocal<jstring> name(env, MakeJString(env, info.name));
+  JLocal<jobjectArray> otherPaths(env, MakeJStringArray(env, info.otherPaths));
+  return env->NewObject(usbCameraInfoCls, constructor,
+                        static_cast<jint>(info.dev), path.obj(), name.obj(),
+                        otherPaths.obj());
+}
+
+static jobject MakeJObject(JNIEnv* env, const cs::VideoMode& videoMode) {
+  static jmethodID constructor =
+      env->GetMethodID(videoModeCls, "<init>", "(IIII)V");
+  return env->NewObject(
+      videoModeCls, constructor, static_cast<jint>(videoMode.pixelFormat),
+      static_cast<jint>(videoMode.width), static_cast<jint>(videoMode.height),
+      static_cast<jint>(videoMode.fps));
+}
+
+static jobject MakeJObject(JNIEnv* env, const cs::RawEvent& event) {
+  static jmethodID constructor =
+      env->GetMethodID(videoEventCls, "<init>",
+                       "(IIILjava/lang/String;IIIIIIILjava/lang/String;)V");
+  JLocal<jstring> name(env, MakeJString(env, event.name));
+  JLocal<jstring> valueStr(env, MakeJString(env, event.valueStr));
+  // clang-format off
+  return env->NewObject(
+      videoEventCls,
+      constructor,
+      static_cast<jint>(event.kind),
+      static_cast<jint>(event.sourceHandle),
+      static_cast<jint>(event.sinkHandle),
+      name.obj(),
+      static_cast<jint>(event.mode.pixelFormat),
+      static_cast<jint>(event.mode.width),
+      static_cast<jint>(event.mode.height),
+      static_cast<jint>(event.mode.fps),
+      static_cast<jint>(event.propertyHandle),
+      static_cast<jint>(event.propertyKind),
+      static_cast<jint>(event.value),
+      valueStr.obj());
+  // clang-format on
+}
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyKind
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyKind
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyKind(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyName
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyName
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetPropertyName(property, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getProperty
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getProperty
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetProperty(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setProperty
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setProperty
+  (JNIEnv* env, jclass, jint property, jint value)
+{
+  CS_Status status = 0;
+  cs::SetProperty(property, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyMin
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyMin
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyMin(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyMax
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyMax
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyMax(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyStep
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyStep
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyStep(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getPropertyDefault
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getPropertyDefault
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto val = cs::GetPropertyDefault(property, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getStringProperty
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getStringProperty
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetStringProperty(property, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setStringProperty
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setStringProperty
+  (JNIEnv* env, jclass, jint property, jstring value)
+{
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return;
+  }
+  CS_Status status = 0;
+  cs::SetStringProperty(property, JStringRef{env, value}.str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getEnumPropertyChoices
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getEnumPropertyChoices
+  (JNIEnv* env, jclass, jint property)
+{
+  CS_Status status = 0;
+  auto arr = cs::GetEnumPropertyChoices(property, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJStringArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createUsbCameraDev
+ * Signature: (Ljava/lang/String;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createUsbCameraDev
+  (JNIEnv* env, jclass, jstring name, jint dev)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateUsbCameraDev(JStringRef{env, name}.str(), dev, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createUsbCameraPath
+ * Signature: (Ljava/lang/String;Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createUsbCameraPath
+  (JNIEnv* env, jclass, jstring name, jstring path)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  if (!path) {
+    nullPointerEx.Throw(env, "path cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateUsbCameraPath(JStringRef{env, name}.str(),
+                                     JStringRef{env, path}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createHttpCamera
+ * Signature: (Ljava/lang/String;Ljava/lang/String;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createHttpCamera
+  (JNIEnv* env, jclass, jstring name, jstring url, jint kind)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  if (!url) {
+    nullPointerEx.Throw(env, "url cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateHttpCamera(
+      JStringRef{env, name}.str(), JStringRef{env, url}.str(),
+      static_cast<CS_HttpCameraKind>(kind), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createHttpCameraMulti
+ * Signature: (Ljava/lang/String;[Ljava/lang/Object;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createHttpCameraMulti
+  (JNIEnv* env, jclass, jstring name, jobjectArray urls, jint kind)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  if (!urls) {
+    nullPointerEx.Throw(env, "urls cannot be null");
+    return 0;
+  }
+  size_t len = env->GetArrayLength(urls);
+  wpi::SmallVector<std::string, 8> vec;
+  vec.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(urls, i))};
+    if (!elem) {
+      // TODO
+      return 0;
+    }
+    vec.push_back(JStringRef{env, elem}.str());
+  }
+  CS_Status status = 0;
+  auto val =
+      cs::CreateHttpCamera(JStringRef{env, name}.str(), vec,
+                           static_cast<CS_HttpCameraKind>(kind), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createCvSource
+ * Signature: (Ljava/lang/String;IIII)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createCvSource
+  (JNIEnv* env, jclass, jstring name, jint pixelFormat, jint width, jint height,
+   jint fps)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateCvSource(
+      JStringRef{env, name}.str(),
+      cs::VideoMode{static_cast<cs::VideoMode::PixelFormat>(pixelFormat),
+                    static_cast<int>(width), static_cast<int>(height),
+                    static_cast<int>(fps)},
+      &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceKind
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceKind
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSourceKind(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceName
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceName
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSourceName(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceDescription
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceDescription
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSourceDescription(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceLastFrameTime
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceLastFrameTime
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSourceLastFrameTime(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceConnectionStrategy
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceConnectionStrategy
+  (JNIEnv* env, jclass, jint source, jint strategy)
+{
+  CS_Status status = 0;
+  cs::SetSourceConnectionStrategy(
+      source, static_cast<CS_ConnectionStrategy>(strategy), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    isSourceConnected
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_isSourceConnected
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::IsSourceConnected(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    isSourceEnabled
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_isSourceEnabled
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::IsSourceEnabled(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceProperty
+ * Signature: (ILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceProperty
+  (JNIEnv* env, jclass, jint source, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val =
+      cs::GetSourceProperty(source, JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSourceProperties
+ * Signature: (I)[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSourceProperties
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Property, 32> buf;
+  auto arr = cs::EnumerateSourceProperties(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceVideoMode
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceVideoMode
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSourceVideoMode(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJObject(env, val);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceVideoMode
+ * Signature: (IIIII)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceVideoMode
+  (JNIEnv* env, jclass, jint source, jint pixelFormat, jint width, jint height,
+   jint fps)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourceVideoMode(
+      source,
+      cs::VideoMode(static_cast<cs::VideoMode::PixelFormat>(pixelFormat), width,
+                    height, fps),
+      &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourcePixelFormat
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourcePixelFormat
+  (JNIEnv* env, jclass, jint source, jint pixelFormat)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourcePixelFormat(
+      source, static_cast<cs::VideoMode::PixelFormat>(pixelFormat), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceResolution
+ * Signature: (III)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceResolution
+  (JNIEnv* env, jclass, jint source, jint width, jint height)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourceResolution(source, width, height, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceFPS
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceFPS
+  (JNIEnv* env, jclass, jint source, jint fps)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourceFPS(source, fps, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceConfigJson
+ * Signature: (ILjava/lang/String;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceConfigJson
+  (JNIEnv* env, jclass, jint source, jstring config)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSourceConfigJson(source, JStringRef{env, config}, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSourceConfigJson
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSourceConfigJson
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSourceConfigJson(source, &status);
+  CheckStatus(env, status);
+  return MakeJString(env, val);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSourceVideoModes
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSourceVideoModes
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto arr = cs::EnumerateSourceVideoModes(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  jobjectArray jarr = env->NewObjectArray(arr.size(), videoModeCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> jelem{env, MakeJObject(env, arr[i])};
+    env->SetObjectArrayElement(jarr, i, jelem);
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSourceSinks
+ * Signature: (I)[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSourceSinks
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Sink, 16> buf;
+  auto arr = cs::EnumerateSourceSinks(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    copySource
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_copySource
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::CopySource(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    releaseSource
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_releaseSource
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::ReleaseSource(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraBrightness
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraBrightness
+  (JNIEnv* env, jclass, jint source, jint brightness)
+{
+  CS_Status status = 0;
+  cs::SetCameraBrightness(source, brightness, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getCameraBrightness
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getCameraBrightness
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetCameraBrightness(source, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraWhiteBalanceAuto
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraWhiteBalanceAuto
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::SetCameraWhiteBalanceAuto(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraWhiteBalanceHoldCurrent
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraWhiteBalanceHoldCurrent
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::SetCameraWhiteBalanceHoldCurrent(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraWhiteBalanceManual
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraWhiteBalanceManual
+  (JNIEnv* env, jclass, jint source, jint value)
+{
+  CS_Status status = 0;
+  cs::SetCameraWhiteBalanceManual(source, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraExposureAuto
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraExposureAuto
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::SetCameraExposureAuto(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraExposureHoldCurrent
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraExposureHoldCurrent
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  cs::SetCameraExposureHoldCurrent(source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setCameraExposureManual
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setCameraExposureManual
+  (JNIEnv* env, jclass, jint source, jint value)
+{
+  CS_Status status = 0;
+  cs::SetCameraExposureManual(source, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getUsbCameraPath
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getUsbCameraPath
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto str = cs::GetUsbCameraPath(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getUsbCameraInfo
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getUsbCameraInfo
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto info = cs::GetUsbCameraInfo(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJObject(env, info);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getHttpCameraKind
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getHttpCameraKind
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto kind = cs::GetHttpCameraKind(source, &status);
+  if (!CheckStatus(env, status)) return 0;
+  return kind;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setHttpCameraUrls
+ * Signature: (I[Ljava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setHttpCameraUrls
+  (JNIEnv* env, jclass, jint source, jobjectArray urls)
+{
+  if (!urls) {
+    nullPointerEx.Throw(env, "urls cannot be null");
+    return;
+  }
+  size_t len = env->GetArrayLength(urls);
+  wpi::SmallVector<std::string, 8> vec;
+  vec.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(urls, i))};
+    if (!elem) {
+      // TODO
+      return;
+    }
+    vec.push_back(JStringRef{env, elem}.str());
+  }
+  CS_Status status = 0;
+  cs::SetHttpCameraUrls(source, vec, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getHttpCameraUrls
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getHttpCameraUrls
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto arr = cs::GetHttpCameraUrls(source, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJStringArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    putSourceFrame
+ * Signature: (IJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_putSourceFrame
+  (JNIEnv* env, jclass, jint source, jlong imageNativeObj)
+{
+  cv::Mat& image = *((cv::Mat*)imageNativeObj);
+  CS_Status status = 0;
+  cs::PutSourceFrame(source, image, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    notifySourceError
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_notifySourceError
+  (JNIEnv* env, jclass, jint source, jstring msg)
+{
+  if (!msg) {
+    nullPointerEx.Throw(env, "msg cannot be null");
+    return;
+  }
+  CS_Status status = 0;
+  cs::NotifySourceError(source, JStringRef{env, msg}.str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceConnected
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceConnected
+  (JNIEnv* env, jclass, jint source, jboolean connected)
+{
+  CS_Status status = 0;
+  cs::SetSourceConnected(source, connected, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceDescription
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceDescription
+  (JNIEnv* env, jclass, jint source, jstring description)
+{
+  if (!description) {
+    nullPointerEx.Throw(env, "description cannot be null");
+    return;
+  }
+  CS_Status status = 0;
+  cs::SetSourceDescription(source, JStringRef{env, description}.str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createSourceProperty
+ * Signature: (ILjava/lang/String;IIIIII)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createSourceProperty
+  (JNIEnv* env, jclass, jint source, jstring name, jint kind, jint minimum,
+   jint maximum, jint step, jint defaultValue, jint value)
+{
+  CS_Status status = 0;
+  auto val = cs::CreateSourceProperty(
+      source, JStringRef{env, name}.str(), static_cast<CS_PropertyKind>(kind),
+      minimum, maximum, step, defaultValue, value, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSourceEnumPropertyChoices
+ * Signature: (II[Ljava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSourceEnumPropertyChoices
+  (JNIEnv* env, jclass, jint source, jint property, jobjectArray choices)
+{
+  if (!choices) {
+    nullPointerEx.Throw(env, "choices cannot be null");
+    return;
+  }
+  size_t len = env->GetArrayLength(choices);
+  wpi::SmallVector<std::string, 8> vec;
+  vec.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(choices, i))};
+    if (!elem) {
+      // TODO
+      return;
+    }
+    vec.push_back(JStringRef{env, elem}.str());
+  }
+  CS_Status status = 0;
+  cs::SetSourceEnumPropertyChoices(source, property, vec, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createMjpegServer
+ * Signature: (Ljava/lang/String;Ljava/lang/String;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createMjpegServer
+  (JNIEnv* env, jclass, jstring name, jstring listenAddress, jint port)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  if (!listenAddress) {
+    nullPointerEx.Throw(env, "listenAddress cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateMjpegServer(JStringRef{env, name}.str(),
+                                   JStringRef{env, listenAddress}.str(), port,
+                                   &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    createCvSink
+ * Signature: (Ljava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_createCvSink
+  (JNIEnv* env, jclass, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::CreateCvSink(JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkKind
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkKind
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSinkKind(sink, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkName
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkName
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkName(sink, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkDescription
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkDescription
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkDescription(sink, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkProperty
+ * Signature: (ILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkProperty
+  (JNIEnv* env, jclass, jint sink, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val = cs::GetSinkProperty(sink, JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSinkProperties
+ * Signature: (I)[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSinkProperties
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Property, 32> buf;
+  auto arr = cs::EnumerateSinkProperties(source, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSinkConfigJson
+ * Signature: (ILjava/lang/String;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSinkConfigJson
+  (JNIEnv* env, jclass, jint source, jstring config)
+{
+  CS_Status status = 0;
+  auto val = cs::SetSinkConfigJson(source, JStringRef{env, config}, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkConfigJson
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkConfigJson
+  (JNIEnv* env, jclass, jint source)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSinkConfigJson(source, &status);
+  CheckStatus(env, status);
+  return MakeJString(env, val);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSinkSource
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSinkSource
+  (JNIEnv* env, jclass, jint sink, jint source)
+{
+  CS_Status status = 0;
+  cs::SetSinkSource(sink, source, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkSourceProperty
+ * Signature: (ILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkSourceProperty
+  (JNIEnv* env, jclass, jint sink, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return 0;
+  }
+  CS_Status status = 0;
+  auto val =
+      cs::GetSinkSourceProperty(sink, JStringRef{env, name}.str(), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkSource
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkSource
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto val = cs::GetSinkSource(sink, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    copySink
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_copySink
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto val = cs::CopySink(sink, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    releaseSink
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_releaseSink
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  cs::ReleaseSink(sink, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getMjpegServerListenAddress
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getMjpegServerListenAddress
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto str = cs::GetMjpegServerListenAddress(sink, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getMjpegServerPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getMjpegServerPort
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  auto val = cs::GetMjpegServerPort(sink, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSinkDescription
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSinkDescription
+  (JNIEnv* env, jclass, jint sink, jstring description)
+{
+  if (!description) {
+    nullPointerEx.Throw(env, "description cannot be null");
+    return;
+  }
+  CS_Status status = 0;
+  cs::SetSinkDescription(sink, JStringRef{env, description}.str(), &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    grabSinkFrame
+ * Signature: (IJ)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_grabSinkFrame
+  (JNIEnv* env, jclass, jint sink, jlong imageNativeObj)
+{
+  cv::Mat& image = *((cv::Mat*)imageNativeObj);
+  CS_Status status = 0;
+  auto rv = cs::GrabSinkFrame(sink, image, &status);
+  CheckStatus(env, status);
+  return rv;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    grabSinkFrameTimeout
+ * Signature: (IJD)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_grabSinkFrameTimeout
+  (JNIEnv* env, jclass, jint sink, jlong imageNativeObj, jdouble timeout)
+{
+  cv::Mat& image = *((cv::Mat*)imageNativeObj);
+  CS_Status status = 0;
+  auto rv = cs::GrabSinkFrameTimeout(sink, image, timeout, &status);
+  CheckStatus(env, status);
+  return rv;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getSinkError
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getSinkError
+  (JNIEnv* env, jclass, jint sink)
+{
+  CS_Status status = 0;
+  wpi::SmallString<128> buf;
+  auto str = cs::GetSinkError(sink, buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJString(env, str);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setSinkEnabled
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setSinkEnabled
+  (JNIEnv* env, jclass, jint sink, jboolean enabled)
+{
+  CS_Status status = 0;
+  cs::SetSinkEnabled(sink, enabled, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    addListener
+ * Signature: (Ljava/lang/Object;IZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_addListener
+  (JNIEnv* envouter, jclass, jobject listener, jint eventMask,
+   jboolean immediateNotify)
+{
+  if (!listener) {
+    nullPointerEx.Throw(envouter, "listener cannot be null");
+    return 0;
+  }
+  // the shared pointer to the weak global will keep it around until the
+  // entry listener is destroyed
+  auto listener_global =
+      std::make_shared<JCSGlobal<jobject>>(envouter, listener);
+
+  // cls is a temporary here; cannot be used within callback functor
+  jclass cls = envouter->GetObjectClass(listener);
+  if (!cls) return 0;
+
+  // method ids, on the other hand, are safe to retain
+  jmethodID mid = envouter->GetMethodID(cls, "accept", "(Ljava/lang/Object;)V");
+  if (!mid) return 0;
+
+  CS_Status status = 0;
+  CS_Listener handle = cs::AddListener(
+      [=](const cs::RawEvent& event) {
+        JNIEnv* env = listenerEnv;
+        if (!env || !env->functions) return;
+
+        // get the handler
+        auto handler = listener_global->obj();
+
+        // convert into the appropriate Java type
+        JLocal<jobject> jobj{env, MakeJObject(env, event)};
+        if (env->ExceptionCheck()) {
+          env->ExceptionDescribe();
+          env->ExceptionClear();
+          return;
+        }
+        if (!jobj) return;
+
+        env->CallVoidMethod(handler, mid, jobj.obj());
+        if (env->ExceptionCheck()) {
+          env->ExceptionDescribe();
+          env->ExceptionClear();
+        }
+      },
+      eventMask, immediateNotify != JNI_FALSE, &status);
+  CheckStatus(envouter, status);
+  return handle;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    removeListener
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_removeListener
+  (JNIEnv* env, jclass, jint handle)
+{
+  CS_Status status = 0;
+  cs::RemoveListener(handle, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setTelemetryPeriod
+ * Signature: (D)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setTelemetryPeriod
+  (JNIEnv* env, jclass, jdouble seconds)
+{
+  cs::SetTelemetryPeriod(seconds);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getTelemetryElapsedTime
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getTelemetryElapsedTime
+  (JNIEnv* env, jclass)
+{
+  return cs::GetTelemetryElapsedTime();
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getTelemetryValue
+ * Signature: (II)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getTelemetryValue
+  (JNIEnv* env, jclass, jint handle, jint kind)
+{
+  CS_Status status = 0;
+  auto val = cs::GetTelemetryValue(handle, static_cast<CS_TelemetryKind>(kind),
+                                   &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getTelemetryAverageValue
+ * Signature: (II)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getTelemetryAverageValue
+  (JNIEnv* env, jclass, jint handle, jint kind)
+{
+  CS_Status status = 0;
+  auto val = cs::GetTelemetryAverageValue(
+      handle, static_cast<CS_TelemetryKind>(kind), &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateUsbCameras
+ * Signature: ()[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateUsbCameras
+  (JNIEnv* env, jclass)
+{
+  CS_Status status = 0;
+  auto arr = cs::EnumerateUsbCameras(&status);
+  if (!CheckStatus(env, status)) return nullptr;
+  jobjectArray jarr =
+      env->NewObjectArray(arr.size(), usbCameraInfoCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> jelem{env, MakeJObject(env, arr[i])};
+    env->SetObjectArrayElement(jarr, i, jelem);
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSources
+ * Signature: ()[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSources
+  (JNIEnv* env, jclass)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Source, 16> buf;
+  auto arr = cs::EnumerateSourceHandles(buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    enumerateSinks
+ * Signature: ()[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_enumerateSinks
+  (JNIEnv* env, jclass)
+{
+  CS_Status status = 0;
+  wpi::SmallVector<CS_Sink, 16> buf;
+  auto arr = cs::EnumerateSinkHandles(buf, &status);
+  if (!CheckStatus(env, status)) return nullptr;
+  return MakeJIntArray(env, arr);
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getHostname
+ * Signature: ()Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getHostname
+  (JNIEnv* env, jclass)
+{
+  return MakeJString(env, cs::GetHostname());
+}
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    getNetworkInterfaces
+ * Signature: ()[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_getNetworkInterfaces
+  (JNIEnv* env, jclass)
+{
+  return MakeJStringArray(env, cs::GetNetworkInterfaces());
+}
+
+}  // extern "C"
+
+namespace {
+
+struct LogMessage {
+ public:
+  LogMessage(unsigned int level, const char* file, unsigned int line,
+             const char* msg)
+      : m_level(level), m_file(file), m_line(line), m_msg(msg) {}
+
+  void CallJava(JNIEnv* env, jobject func, jmethodID mid) {
+    JLocal<jstring> file{env, MakeJString(env, m_file)};
+    JLocal<jstring> msg{env, MakeJString(env, m_msg)};
+    env->CallVoidMethod(func, mid, (jint)m_level, file.obj(), (jint)m_line,
+                        msg.obj());
+  }
+
+  static const char* GetName() { return "CSLogger"; }
+  static JavaVM* GetJVM() { return jvm; }
+
+ private:
+  unsigned int m_level;
+  const char* m_file;
+  unsigned int m_line;
+  std::string m_msg;
+};
+
+typedef JSingletonCallbackManager<LogMessage> LoggerJNI;
+
+}  // namespace
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_cscore_CameraServerJNI
+ * Method:    setLogger
+ * Signature: (Ljava/lang/Object;I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_cscore_CameraServerJNI_setLogger
+  (JNIEnv* env, jclass, jobject func, jint minLevel)
+{
+  if (!func) {
+    nullPointerEx.Throw(env, "func cannot be null");
+    return;
+  }
+  // cls is a temporary here; cannot be used within callback functor
+  jclass cls = env->GetObjectClass(func);
+  if (!cls) return;
+
+  // method ids, on the other hand, are safe to retain
+  jmethodID mid = env->GetMethodID(cls, "apply",
+                                   "(ILjava/lang/String;ILjava/lang/String;)V");
+  if (!mid) return;
+
+  auto& logger = LoggerJNI::GetInstance();
+  logger.Start();
+  logger.SetFunc(env, func, mid);
+
+  cs::SetLogger(
+      [](unsigned int level, const char* file, unsigned int line,
+         const char* msg) {
+        LoggerJNI::GetInstance().Send(level, file, line, msg);
+      },
+      minLevel);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/include/cscore.h b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore.h
new file mode 100644
index 0000000..eff3856
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_H_
+#define CSCORE_CSCORE_H_
+
+/* C API */
+#include "cscore_c.h"
+
+#ifdef __cplusplus
+/* C++ API */
+#include "cscore_cpp.h"
+#include "cscore_oo.h"
+#endif /* __cplusplus */
+
+#endif  // CSCORE_CSCORE_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_c.h b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_c.h
new file mode 100644
index 0000000..182b9b2
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_c.h
@@ -0,0 +1,503 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_C_H_
+#define CSCORE_CSCORE_C_H_
+
+#include <stdint.h>
+
+#ifdef __cplusplus
+#include <cstddef>
+#else
+#include <stddef.h>
+#endif
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+struct CvMat;
+
+/**
+ * @defgroup cscore_c_api cscore C API
+ *
+ * Handle-based interface for C.
+ *
+ * <p>Sources and sinks are reference counted internally to the library.
+ * Any time a source or sink handle is returned or provided to a callback,
+ * the reference count is incremented.
+ *
+ * <p>Calling CS_ReleaseSource() or CS_ReleaseSink() decrements the reference
+ * count, and when the reference count reaches zero, the object is destroyed.
+ *
+ * <p>Connecting a source to a sink increments the reference count of the
+ * source, and when the sink is destroyed (its reference count reaches zero),
+ * the source reference count is decremented.
+ *
+ * @{
+ */
+
+/**
+ * @defgroup cscore_typedefs Typedefs
+ * @{
+ */
+typedef int CS_Bool;
+typedef int CS_Status;
+
+typedef int CS_Handle;
+typedef CS_Handle CS_Property;
+typedef CS_Handle CS_Listener;
+typedef CS_Handle CS_Sink;
+typedef CS_Handle CS_Source;
+/** @} */
+
+/**
+ * Status values
+ */
+enum CS_StatusValue {
+  CS_PROPERTY_WRITE_FAILED = 2000,
+  CS_OK = 0,
+  CS_INVALID_HANDLE = -2000,  // handle was invalid (does not exist)
+  CS_WRONG_HANDLE_SUBTYPE = -2001,
+  CS_INVALID_PROPERTY = -2002,
+  CS_WRONG_PROPERTY_TYPE = -2003,
+  CS_READ_FAILED = -2004,
+  CS_SOURCE_IS_DISCONNECTED = -2005,
+  CS_EMPTY_VALUE = -2006,
+  CS_BAD_URL = -2007,
+  CS_TELEMETRY_NOT_ENABLED = -2008,
+  CS_UNSUPPORTED_MODE = -2009
+};
+
+/**
+ * Logging levels
+ */
+enum CS_LogLevel {
+  CS_LOG_CRITICAL = 50,
+  CS_LOG_ERROR = 40,
+  CS_LOG_WARNING = 30,
+  CS_LOG_INFO = 20,
+  CS_LOG_DEBUG = 10,
+  CS_LOG_DEBUG1 = 9,
+  CS_LOG_DEBUG2 = 8,
+  CS_LOG_DEBUG3 = 7,
+  CS_LOG_DEBUG4 = 6
+};
+
+/**
+ * Pixel formats
+ */
+enum CS_PixelFormat {
+  CS_PIXFMT_UNKNOWN = 0,
+  CS_PIXFMT_MJPEG,
+  CS_PIXFMT_YUYV,
+  CS_PIXFMT_RGB565,
+  CS_PIXFMT_BGR,
+  CS_PIXFMT_GRAY
+};
+
+/**
+ * Video mode
+ */
+typedef struct CS_VideoMode {
+  int pixelFormat;
+  int width;
+  int height;
+  int fps;
+} CS_VideoMode;
+
+/**
+ * Property kinds
+ */
+enum CS_PropertyKind {
+  CS_PROP_NONE = 0,
+  CS_PROP_BOOLEAN = 1,
+  CS_PROP_INTEGER = 2,
+  CS_PROP_STRING = 4,
+  CS_PROP_ENUM = 8
+};
+
+/**
+ * Source kinds
+ */
+enum CS_SourceKind {
+  CS_SOURCE_UNKNOWN = 0,
+  CS_SOURCE_USB = 1,
+  CS_SOURCE_HTTP = 2,
+  CS_SOURCE_CV = 4
+};
+
+/**
+ * HTTP Camera kinds
+ */
+enum CS_HttpCameraKind {
+  CS_HTTP_UNKNOWN = 0,
+  CS_HTTP_MJPGSTREAMER = 1,
+  CS_HTTP_CSCORE = 2,
+  CS_HTTP_AXIS = 3
+};
+
+/**
+ * Sink kinds
+ */
+enum CS_SinkKind { CS_SINK_UNKNOWN = 0, CS_SINK_MJPEG = 2, CS_SINK_CV = 4 };
+
+/**
+ * Listener event kinds
+ */
+enum CS_EventKind {
+  CS_SOURCE_CREATED = 0x0001,
+  CS_SOURCE_DESTROYED = 0x0002,
+  CS_SOURCE_CONNECTED = 0x0004,
+  CS_SOURCE_DISCONNECTED = 0x0008,
+  CS_SOURCE_VIDEOMODES_UPDATED = 0x0010,
+  CS_SOURCE_VIDEOMODE_CHANGED = 0x0020,
+  CS_SOURCE_PROPERTY_CREATED = 0x0040,
+  CS_SOURCE_PROPERTY_VALUE_UPDATED = 0x0080,
+  CS_SOURCE_PROPERTY_CHOICES_UPDATED = 0x0100,
+  CS_SINK_SOURCE_CHANGED = 0x0200,
+  CS_SINK_CREATED = 0x0400,
+  CS_SINK_DESTROYED = 0x0800,
+  CS_SINK_ENABLED = 0x1000,
+  CS_SINK_DISABLED = 0x2000,
+  CS_NETWORK_INTERFACES_CHANGED = 0x4000,
+  CS_TELEMETRY_UPDATED = 0x8000,
+  CS_SINK_PROPERTY_CREATED = 0x10000,
+  CS_SINK_PROPERTY_VALUE_UPDATED = 0x20000,
+  CS_SINK_PROPERTY_CHOICES_UPDATED = 0x40000
+};
+
+/**
+ * Telemetry kinds
+ */
+enum CS_TelemetryKind {
+  CS_SOURCE_BYTES_RECEIVED = 1,
+  CS_SOURCE_FRAMES_RECEIVED = 2
+};
+
+/** Connection strategy */
+enum CS_ConnectionStrategy {
+  /**
+   * Automatically connect or disconnect based on whether any sinks are
+   * connected to this source.  This is the default behavior.
+   */
+  CS_CONNECTION_AUTO_MANAGE = 0,
+
+  /**
+   * Try to keep the connection open regardless of whether any sinks are
+   * connected.
+   */
+  CS_CONNECTION_KEEP_OPEN,
+
+  /**
+   * Never open the connection.  If this is set when the connection is open,
+   * close the connection.
+   */
+  CS_CONNECTION_FORCE_CLOSE
+};
+
+/**
+ * Listener event
+ */
+struct CS_Event {
+  enum CS_EventKind kind;
+
+  // Valid for CS_SOURCE_* and CS_SINK_* respectively
+  CS_Source source;
+  CS_Sink sink;
+
+  // Source/sink/property name
+  const char* name;
+
+  // Fields for CS_SOURCE_VIDEOMODE_CHANGED event
+  CS_VideoMode mode;
+
+  // Fields for CS_SOURCE_PROPERTY_* events
+  CS_Property property;
+  enum CS_PropertyKind propertyKind;
+  int value;
+  const char* valueStr;
+};
+
+/**
+ * USB camera infomation
+ */
+typedef struct CS_UsbCameraInfo {
+  int dev;
+  char* path;
+  char* name;
+  int otherPathsCount;
+  char** otherPaths;
+} CS_UsbCameraInfo;
+
+/**
+ * @defgroup cscore_property_cfunc Property Functions
+ * @{
+ */
+enum CS_PropertyKind CS_GetPropertyKind(CS_Property property,
+                                        CS_Status* status);
+char* CS_GetPropertyName(CS_Property property, CS_Status* status);
+int CS_GetProperty(CS_Property property, CS_Status* status);
+void CS_SetProperty(CS_Property property, int value, CS_Status* status);
+int CS_GetPropertyMin(CS_Property property, CS_Status* status);
+int CS_GetPropertyMax(CS_Property property, CS_Status* status);
+int CS_GetPropertyStep(CS_Property property, CS_Status* status);
+int CS_GetPropertyDefault(CS_Property property, CS_Status* status);
+char* CS_GetStringProperty(CS_Property property, CS_Status* status);
+void CS_SetStringProperty(CS_Property property, const char* value,
+                          CS_Status* status);
+char** CS_GetEnumPropertyChoices(CS_Property property, int* count,
+                                 CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_create_cfunc Source Creation Functions
+ * @{
+ */
+CS_Source CS_CreateUsbCameraDev(const char* name, int dev, CS_Status* status);
+CS_Source CS_CreateUsbCameraPath(const char* name, const char* path,
+                                 CS_Status* status);
+CS_Source CS_CreateHttpCamera(const char* name, const char* url,
+                              enum CS_HttpCameraKind kind, CS_Status* status);
+CS_Source CS_CreateHttpCameraMulti(const char* name, const char** urls,
+                                   int count, enum CS_HttpCameraKind kind,
+                                   CS_Status* status);
+CS_Source CS_CreateCvSource(const char* name, const CS_VideoMode* mode,
+                            CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_cfunc Source Functions
+ * @{
+ */
+enum CS_SourceKind CS_GetSourceKind(CS_Source source, CS_Status* status);
+char* CS_GetSourceName(CS_Source source, CS_Status* status);
+char* CS_GetSourceDescription(CS_Source source, CS_Status* status);
+uint64_t CS_GetSourceLastFrameTime(CS_Source source, CS_Status* status);
+void CS_SetSourceConnectionStrategy(CS_Source source,
+                                    enum CS_ConnectionStrategy strategy,
+                                    CS_Status* status);
+CS_Bool CS_IsSourceConnected(CS_Source source, CS_Status* status);
+CS_Bool CS_IsSourceEnabled(CS_Source source, CS_Status* status);
+CS_Property CS_GetSourceProperty(CS_Source source, const char* name,
+                                 CS_Status* status);
+CS_Property* CS_EnumerateSourceProperties(CS_Source source, int* count,
+                                          CS_Status* status);
+void CS_GetSourceVideoMode(CS_Source source, CS_VideoMode* mode,
+                           CS_Status* status);
+CS_Bool CS_SetSourceVideoMode(CS_Source source, const CS_VideoMode* mode,
+                              CS_Status* status);
+CS_Bool CS_SetSourceVideoModeDiscrete(CS_Source source,
+                                      enum CS_PixelFormat pixelFormat,
+                                      int width, int height, int fps,
+                                      CS_Status* status);
+CS_Bool CS_SetSourcePixelFormat(CS_Source source,
+                                enum CS_PixelFormat pixelFormat,
+                                CS_Status* status);
+CS_Bool CS_SetSourceResolution(CS_Source source, int width, int height,
+                               CS_Status* status);
+CS_Bool CS_SetSourceFPS(CS_Source source, int fps, CS_Status* status);
+CS_Bool CS_SetSourceConfigJson(CS_Source source, const char* config,
+                               CS_Status* status);
+char* CS_GetSourceConfigJson(CS_Source source, CS_Status* status);
+CS_VideoMode* CS_EnumerateSourceVideoModes(CS_Source source, int* count,
+                                           CS_Status* status);
+CS_Sink* CS_EnumerateSourceSinks(CS_Source source, int* count,
+                                 CS_Status* status);
+CS_Source CS_CopySource(CS_Source source, CS_Status* status);
+void CS_ReleaseSource(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_prop_cfunc Camera Source Common Property Fuctions
+ * @{
+ */
+void CS_SetCameraBrightness(CS_Source source, int brightness,
+                            CS_Status* status);
+int CS_GetCameraBrightness(CS_Source source, CS_Status* status);
+void CS_SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status);
+void CS_SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status);
+void CS_SetCameraWhiteBalanceManual(CS_Source source, int value,
+                                    CS_Status* status);
+void CS_SetCameraExposureAuto(CS_Source source, CS_Status* status);
+void CS_SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status);
+void CS_SetCameraExposureManual(CS_Source source, int value, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_usbcamera_cfunc UsbCamera Source Functions
+ * @{
+ */
+char* CS_GetUsbCameraPath(CS_Source source, CS_Status* status);
+CS_UsbCameraInfo* CS_GetUsbCameraInfo(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_httpcamera_cfunc HttpCamera Source Functions
+ * @{
+ */
+enum CS_HttpCameraKind CS_GetHttpCameraKind(CS_Source source,
+                                            CS_Status* status);
+void CS_SetHttpCameraUrls(CS_Source source, const char** urls, int count,
+                          CS_Status* status);
+char** CS_GetHttpCameraUrls(CS_Source source, int* count, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_opencv_source_cfunc OpenCV Source Functions
+ * @{
+ */
+void CS_PutSourceFrame(CS_Source source, struct CvMat* image,
+                       CS_Status* status);
+void CS_NotifySourceError(CS_Source source, const char* msg, CS_Status* status);
+void CS_SetSourceConnected(CS_Source source, CS_Bool connected,
+                           CS_Status* status);
+void CS_SetSourceDescription(CS_Source source, const char* description,
+                             CS_Status* status);
+CS_Property CS_CreateSourceProperty(CS_Source source, const char* name,
+                                    enum CS_PropertyKind kind, int minimum,
+                                    int maximum, int step, int defaultValue,
+                                    int value, CS_Status* status);
+void CS_SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
+                                     const char** choices, int count,
+                                     CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_sink_create_cfunc Sink Creation Functions
+ * @{
+ */
+CS_Sink CS_CreateMjpegServer(const char* name, const char* listenAddress,
+                             int port, CS_Status* status);
+CS_Sink CS_CreateCvSink(const char* name, CS_Status* status);
+CS_Sink CS_CreateCvSinkCallback(const char* name, void* data,
+                                void (*processFrame)(void* data, uint64_t time),
+                                CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_sink_cfunc Sink Functions
+ * @{
+ */
+enum CS_SinkKind CS_GetSinkKind(CS_Sink sink, CS_Status* status);
+char* CS_GetSinkName(CS_Sink sink, CS_Status* status);
+char* CS_GetSinkDescription(CS_Sink sink, CS_Status* status);
+CS_Property CS_GetSinkProperty(CS_Sink sink, const char* name,
+                               CS_Status* status);
+CS_Property* CS_EnumerateSinkProperties(CS_Sink sink, int* count,
+                                        CS_Status* status);
+void CS_SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status);
+CS_Property CS_GetSinkSourceProperty(CS_Sink sink, const char* name,
+                                     CS_Status* status);
+CS_Bool CS_SetSinkConfigJson(CS_Sink sink, const char* config,
+                             CS_Status* status);
+char* CS_GetSinkConfigJson(CS_Sink sink, CS_Status* status);
+CS_Source CS_GetSinkSource(CS_Sink sink, CS_Status* status);
+CS_Sink CS_CopySink(CS_Sink sink, CS_Status* status);
+void CS_ReleaseSink(CS_Sink sink, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_mjpegserver_cfunc MjpegServer Sink Functions
+ * @{
+ */
+char* CS_GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status);
+int CS_GetMjpegServerPort(CS_Sink sink, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_opencv_sink_cfunc OpenCV Sink Functions
+ * @{
+ */
+void CS_SetSinkDescription(CS_Sink sink, const char* description,
+                           CS_Status* status);
+uint64_t CS_GrabSinkFrame(CS_Sink sink, struct CvMat* image, CS_Status* status);
+uint64_t CS_GrabSinkFrameTimeout(CS_Sink sink, struct CvMat* image,
+                                 double timeout, CS_Status* status);
+char* CS_GetSinkError(CS_Sink sink, CS_Status* status);
+void CS_SetSinkEnabled(CS_Sink sink, CS_Bool enabled, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_listener_cfunc Listener Functions
+ * @{
+ */
+void CS_SetListenerOnStart(void (*onStart)(void* data), void* data);
+void CS_SetListenerOnExit(void (*onExit)(void* data), void* data);
+CS_Listener CS_AddListener(
+    void* data, void (*callback)(void* data, const struct CS_Event* event),
+    int eventMask, int immediateNotify, CS_Status* status);
+
+void CS_RemoveListener(CS_Listener handle, CS_Status* status);
+/** @} */
+
+int CS_NotifierDestroyed(void);
+
+/**
+ * @defgroup cscore_telemetry_cfunc Telemetry Functions
+ * @{
+ */
+void CS_SetTelemetryPeriod(double seconds);
+double CS_GetTelemetryElapsedTime(void);
+int64_t CS_GetTelemetryValue(CS_Handle handle, enum CS_TelemetryKind kind,
+                             CS_Status* status);
+double CS_GetTelemetryAverageValue(CS_Handle handle, enum CS_TelemetryKind kind,
+                                   CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_logging_cfunc Logging Functions
+ * @{
+ */
+typedef void (*CS_LogFunc)(unsigned int level, const char* file,
+                           unsigned int line, const char* msg);
+void CS_SetLogger(CS_LogFunc func, unsigned int min_level);
+void CS_SetDefaultLogger(unsigned int min_level);
+/** @} */
+
+/**
+ * @defgroup cscore_shutdown_cfunc Library Shutdown Function
+ * @{
+ */
+void CS_Shutdown(void);
+/** @} */
+
+/**
+ * @defgroup cscore_utility_cfunc Utility Functions
+ * @{
+ */
+
+CS_UsbCameraInfo* CS_EnumerateUsbCameras(int* count, CS_Status* status);
+void CS_FreeEnumeratedUsbCameras(CS_UsbCameraInfo* cameras, int count);
+
+CS_Source* CS_EnumerateSources(int* count, CS_Status* status);
+void CS_ReleaseEnumeratedSources(CS_Source* sources, int count);
+
+CS_Sink* CS_EnumerateSinks(int* count, CS_Status* status);
+void CS_ReleaseEnumeratedSinks(CS_Sink* sinks, int count);
+
+void CS_FreeString(char* str);
+void CS_FreeEnumPropertyChoices(char** choices, int count);
+void CS_FreeUsbCameraInfo(CS_UsbCameraInfo* info);
+void CS_FreeHttpCameraUrls(char** urls, int count);
+
+void CS_FreeEnumeratedProperties(CS_Property* properties, int count);
+void CS_FreeEnumeratedVideoModes(CS_VideoMode* modes, int count);
+
+char* CS_GetHostname();
+
+char** CS_GetNetworkInterfaces(int* count);
+void CS_FreeNetworkInterfaces(char** interfaces, int count);
+/** @} */
+
+/** @} */
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif  // CSCORE_CSCORE_C_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_cpp.h b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_cpp.h
new file mode 100644
index 0000000..a400b78
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_cpp.h
@@ -0,0 +1,446 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_CPP_H_
+#define CSCORE_CSCORE_CPP_H_
+
+#include <stdint.h>
+
+#include <functional>
+#include <string>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "cscore_c.h"
+
+namespace cv {
+class Mat;
+}  // namespace cv
+
+namespace wpi {
+class json;
+}  // namespace wpi
+
+/** CameraServer (cscore) namespace */
+namespace cs {
+
+/**
+ * @defgroup cscore_cpp_api cscore C++ function API
+ *
+ * Handle-based interface for C++.  Users are encouraged to use the
+ * object oriented interface instead; this interface is intended for use
+ * in applications such as JNI which require handle-based access.
+ *
+ * @{
+ */
+
+/**
+ * USB camera information
+ */
+struct UsbCameraInfo {
+  /** Device number (e.g. N in '/dev/videoN' on Linux) */
+  int dev = -1;
+  /** Path to device if available (e.g. '/dev/video0' on Linux) */
+  std::string path;
+  /** Vendor/model name of the camera as provided by the USB driver */
+  std::string name;
+  /** Other path aliases to device (e.g. '/dev/v4l/by-id/...' etc on Linux) */
+  std::vector<std::string> otherPaths;
+};
+
+/**
+ * Video mode
+ */
+struct VideoMode : public CS_VideoMode {
+  enum PixelFormat {
+    kUnknown = CS_PIXFMT_UNKNOWN,
+    kMJPEG = CS_PIXFMT_MJPEG,
+    kYUYV = CS_PIXFMT_YUYV,
+    kRGB565 = CS_PIXFMT_RGB565,
+    kBGR = CS_PIXFMT_BGR,
+    kGray = CS_PIXFMT_GRAY
+  };
+  VideoMode() {
+    pixelFormat = 0;
+    width = 0;
+    height = 0;
+    fps = 0;
+  }
+  VideoMode(PixelFormat pixelFormat_, int width_, int height_, int fps_) {
+    pixelFormat = pixelFormat_;
+    width = width_;
+    height = height_;
+    fps = fps_;
+  }
+  explicit operator bool() const { return pixelFormat == kUnknown; }
+
+  bool operator==(const VideoMode& other) const {
+    return pixelFormat == other.pixelFormat && width == other.width &&
+           height == other.height && fps == other.fps;
+  }
+
+  bool operator!=(const VideoMode& other) const { return !(*this == other); }
+};
+
+/**
+ * Listener event
+ */
+struct RawEvent {
+  enum Kind {
+    kSourceCreated = CS_SOURCE_CREATED,
+    kSourceDestroyed = CS_SOURCE_DESTROYED,
+    kSourceConnected = CS_SOURCE_CONNECTED,
+    kSourceDisconnected = CS_SOURCE_DISCONNECTED,
+    kSourceVideoModesUpdated = CS_SOURCE_VIDEOMODES_UPDATED,
+    kSourceVideoModeChanged = CS_SOURCE_VIDEOMODE_CHANGED,
+    kSourcePropertyCreated = CS_SOURCE_PROPERTY_CREATED,
+    kSourcePropertyValueUpdated = CS_SOURCE_PROPERTY_VALUE_UPDATED,
+    kSourcePropertyChoicesUpdated = CS_SOURCE_PROPERTY_CHOICES_UPDATED,
+    kSinkSourceChanged = CS_SINK_SOURCE_CHANGED,
+    kSinkCreated = CS_SINK_CREATED,
+    kSinkDestroyed = CS_SINK_DESTROYED,
+    kSinkEnabled = CS_SINK_ENABLED,
+    kSinkDisabled = CS_SINK_DISABLED,
+    kNetworkInterfacesChanged = CS_NETWORK_INTERFACES_CHANGED,
+    kTelemetryUpdated = CS_TELEMETRY_UPDATED,
+    kSinkPropertyCreated = CS_SINK_PROPERTY_CREATED,
+    kSinkPropertyValueUpdated = CS_SINK_PROPERTY_VALUE_UPDATED,
+    kSinkPropertyChoicesUpdated = CS_SINK_PROPERTY_CHOICES_UPDATED
+  };
+
+  RawEvent() = default;
+  explicit RawEvent(RawEvent::Kind kind_) : kind{kind_} {}
+  RawEvent(const wpi::Twine& name_, CS_Handle handle_, RawEvent::Kind kind_)
+      : kind{kind_}, name{name_.str()} {
+    if (kind_ == kSinkCreated || kind_ == kSinkDestroyed ||
+        kind_ == kSinkEnabled || kind_ == kSinkDisabled)
+      sinkHandle = handle_;
+    else
+      sourceHandle = handle_;
+  }
+  RawEvent(const wpi::Twine& name_, CS_Source source_, const VideoMode& mode_)
+      : kind{kSourceVideoModeChanged},
+        sourceHandle{source_},
+        name{name_.str()},
+        mode{mode_} {}
+  RawEvent(const wpi::Twine& name_, CS_Source source_, RawEvent::Kind kind_,
+           CS_Property property_, CS_PropertyKind propertyKind_, int value_,
+           const wpi::Twine& valueStr_)
+      : kind{kind_},
+        sourceHandle{source_},
+        name{name_.str()},
+        propertyHandle{property_},
+        propertyKind{propertyKind_},
+        value{value_},
+        valueStr{valueStr_.str()} {}
+
+  Kind kind;
+
+  // Valid for kSource* and kSink* respectively
+  CS_Source sourceHandle = CS_INVALID_HANDLE;
+  CS_Sink sinkHandle = CS_INVALID_HANDLE;
+
+  // Source/sink/property name
+  std::string name;
+
+  // Fields for kSourceVideoModeChanged event
+  VideoMode mode;
+
+  // Fields for kSourceProperty* events
+  CS_Property propertyHandle;
+  CS_PropertyKind propertyKind;
+  int value;
+  std::string valueStr;
+};
+
+/**
+ * @defgroup cscore_property_func Property Functions
+ * @{
+ */
+CS_PropertyKind GetPropertyKind(CS_Property property, CS_Status* status);
+std::string GetPropertyName(CS_Property property, CS_Status* status);
+wpi::StringRef GetPropertyName(CS_Property property,
+                               wpi::SmallVectorImpl<char>& buf,
+                               CS_Status* status);
+int GetProperty(CS_Property property, CS_Status* status);
+void SetProperty(CS_Property property, int value, CS_Status* status);
+int GetPropertyMin(CS_Property property, CS_Status* status);
+int GetPropertyMax(CS_Property property, CS_Status* status);
+int GetPropertyStep(CS_Property property, CS_Status* status);
+int GetPropertyDefault(CS_Property property, CS_Status* status);
+std::string GetStringProperty(CS_Property property, CS_Status* status);
+wpi::StringRef GetStringProperty(CS_Property property,
+                                 wpi::SmallVectorImpl<char>& buf,
+                                 CS_Status* status);
+void SetStringProperty(CS_Property property, const wpi::Twine& value,
+                       CS_Status* status);
+std::vector<std::string> GetEnumPropertyChoices(CS_Property property,
+                                                CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_create_func Source Creation Functions
+ * @{
+ */
+CS_Source CreateUsbCameraDev(const wpi::Twine& name, int dev,
+                             CS_Status* status);
+CS_Source CreateUsbCameraPath(const wpi::Twine& name, const wpi::Twine& path,
+                              CS_Status* status);
+CS_Source CreateHttpCamera(const wpi::Twine& name, const wpi::Twine& url,
+                           CS_HttpCameraKind kind, CS_Status* status);
+CS_Source CreateHttpCamera(const wpi::Twine& name,
+                           wpi::ArrayRef<std::string> urls,
+                           CS_HttpCameraKind kind, CS_Status* status);
+CS_Source CreateCvSource(const wpi::Twine& name, const VideoMode& mode,
+                         CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_source_func Source Functions
+ * @{
+ */
+CS_SourceKind GetSourceKind(CS_Source source, CS_Status* status);
+std::string GetSourceName(CS_Source source, CS_Status* status);
+wpi::StringRef GetSourceName(CS_Source source, wpi::SmallVectorImpl<char>& buf,
+                             CS_Status* status);
+std::string GetSourceDescription(CS_Source source, CS_Status* status);
+wpi::StringRef GetSourceDescription(CS_Source source,
+                                    wpi::SmallVectorImpl<char>& buf,
+                                    CS_Status* status);
+uint64_t GetSourceLastFrameTime(CS_Source source, CS_Status* status);
+void SetSourceConnectionStrategy(CS_Source source,
+                                 CS_ConnectionStrategy strategy,
+                                 CS_Status* status);
+bool IsSourceConnected(CS_Source source, CS_Status* status);
+bool IsSourceEnabled(CS_Source source, CS_Status* status);
+CS_Property GetSourceProperty(CS_Source source, const wpi::Twine& name,
+                              CS_Status* status);
+wpi::ArrayRef<CS_Property> EnumerateSourceProperties(
+    CS_Source source, wpi::SmallVectorImpl<CS_Property>& vec,
+    CS_Status* status);
+VideoMode GetSourceVideoMode(CS_Source source, CS_Status* status);
+bool SetSourceVideoMode(CS_Source source, const VideoMode& mode,
+                        CS_Status* status);
+bool SetSourcePixelFormat(CS_Source source, VideoMode::PixelFormat pixelFormat,
+                          CS_Status* status);
+bool SetSourceResolution(CS_Source source, int width, int height,
+                         CS_Status* status);
+bool SetSourceFPS(CS_Source source, int fps, CS_Status* status);
+bool SetSourceConfigJson(CS_Source source, wpi::StringRef config,
+                         CS_Status* status);
+bool SetSourceConfigJson(CS_Source source, const wpi::json& config,
+                         CS_Status* status);
+std::string GetSourceConfigJson(CS_Source source, CS_Status* status);
+wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status);
+std::vector<VideoMode> EnumerateSourceVideoModes(CS_Source source,
+                                                 CS_Status* status);
+wpi::ArrayRef<CS_Sink> EnumerateSourceSinks(CS_Source source,
+                                            wpi::SmallVectorImpl<CS_Sink>& vec,
+                                            CS_Status* status);
+CS_Source CopySource(CS_Source source, CS_Status* status);
+void ReleaseSource(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_camera_property_func Camera Source Common Property Fuctions
+ * @{
+ */
+void SetCameraBrightness(CS_Source source, int brightness, CS_Status* status);
+int GetCameraBrightness(CS_Source source, CS_Status* status);
+void SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status);
+void SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status);
+void SetCameraWhiteBalanceManual(CS_Source source, int value,
+                                 CS_Status* status);
+void SetCameraExposureAuto(CS_Source source, CS_Status* status);
+void SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status);
+void SetCameraExposureManual(CS_Source source, int value, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_usbcamera_func UsbCamera Source Functions
+ * @{
+ */
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status);
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_httpcamera_func HttpCamera Source Functions
+ * @{
+ */
+CS_HttpCameraKind GetHttpCameraKind(CS_Source source, CS_Status* status);
+void SetHttpCameraUrls(CS_Source source, wpi::ArrayRef<std::string> urls,
+                       CS_Status* status);
+std::vector<std::string> GetHttpCameraUrls(CS_Source source, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_opencv_source_func OpenCV Source Functions
+ * @{
+ */
+void PutSourceFrame(CS_Source source, cv::Mat& image, CS_Status* status);
+void NotifySourceError(CS_Source source, const wpi::Twine& msg,
+                       CS_Status* status);
+void SetSourceConnected(CS_Source source, bool connected, CS_Status* status);
+void SetSourceDescription(CS_Source source, const wpi::Twine& description,
+                          CS_Status* status);
+CS_Property CreateSourceProperty(CS_Source source, const wpi::Twine& name,
+                                 CS_PropertyKind kind, int minimum, int maximum,
+                                 int step, int defaultValue, int value,
+                                 CS_Status* status);
+void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property,
+                                  wpi::ArrayRef<std::string> choices,
+                                  CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_sink_create_func Sink Creation Functions
+ * @{
+ */
+CS_Sink CreateMjpegServer(const wpi::Twine& name,
+                          const wpi::Twine& listenAddress, int port,
+                          CS_Status* status);
+CS_Sink CreateCvSink(const wpi::Twine& name, CS_Status* status);
+CS_Sink CreateCvSinkCallback(const wpi::Twine& name,
+                             std::function<void(uint64_t time)> processFrame,
+                             CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_sink_func Sink Functions
+ * @{
+ */
+CS_SinkKind GetSinkKind(CS_Sink sink, CS_Status* status);
+std::string GetSinkName(CS_Sink sink, CS_Status* status);
+wpi::StringRef GetSinkName(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                           CS_Status* status);
+std::string GetSinkDescription(CS_Sink sink, CS_Status* status);
+wpi::StringRef GetSinkDescription(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                                  CS_Status* status);
+CS_Property GetSinkProperty(CS_Sink sink, const wpi::Twine& name,
+                            CS_Status* status);
+wpi::ArrayRef<CS_Property> EnumerateSinkProperties(
+    CS_Sink sink, wpi::SmallVectorImpl<CS_Property>& vec, CS_Status* status);
+void SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status);
+CS_Property GetSinkSourceProperty(CS_Sink sink, const wpi::Twine& name,
+                                  CS_Status* status);
+bool SetSinkConfigJson(CS_Sink sink, wpi::StringRef config, CS_Status* status);
+bool SetSinkConfigJson(CS_Sink sink, const wpi::json& config,
+                       CS_Status* status);
+std::string GetSinkConfigJson(CS_Sink sink, CS_Status* status);
+wpi::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status* status);
+CS_Source GetSinkSource(CS_Sink sink, CS_Status* status);
+CS_Sink CopySink(CS_Sink sink, CS_Status* status);
+void ReleaseSink(CS_Sink sink, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_mjpegserver_func MjpegServer Sink Functions
+ * @{
+ */
+std::string GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status);
+int GetMjpegServerPort(CS_Sink sink, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_opencv_sink_func OpenCV Sink Functions
+ * @{
+ */
+void SetSinkDescription(CS_Sink sink, const wpi::Twine& description,
+                        CS_Status* status);
+uint64_t GrabSinkFrame(CS_Sink sink, cv::Mat& image, CS_Status* status);
+uint64_t GrabSinkFrameTimeout(CS_Sink sink, cv::Mat& image, double timeout,
+                              CS_Status* status);
+std::string GetSinkError(CS_Sink sink, CS_Status* status);
+wpi::StringRef GetSinkError(CS_Sink sink, wpi::SmallVectorImpl<char>& buf,
+                            CS_Status* status);
+void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_listener_func Listener Functions
+ * @{
+ */
+void SetListenerOnStart(std::function<void()> onStart);
+void SetListenerOnExit(std::function<void()> onExit);
+
+CS_Listener AddListener(std::function<void(const RawEvent& event)> callback,
+                        int eventMask, bool immediateNotify, CS_Status* status);
+
+void RemoveListener(CS_Listener handle, CS_Status* status);
+/** @} */
+
+bool NotifierDestroyed();
+
+/**
+ * @defgroup cscore_telemetry_func Telemetry Functions
+ * @{
+ */
+void SetTelemetryPeriod(double seconds);
+double GetTelemetryElapsedTime();
+int64_t GetTelemetryValue(CS_Handle handle, CS_TelemetryKind kind,
+                          CS_Status* status);
+double GetTelemetryAverageValue(CS_Handle handle, CS_TelemetryKind kind,
+                                CS_Status* status);
+/** @} */
+
+/**
+ * @defgroup cscore_logging_func Logging Functions
+ * @{
+ */
+using LogFunc = std::function<void(unsigned int level, const char* file,
+                                   unsigned int line, const char* msg)>;
+void SetLogger(LogFunc func, unsigned int min_level);
+void SetDefaultLogger(unsigned int min_level);
+/** @} */
+
+/**
+ * @defgroup cscore_shutdown_func Library Shutdown Function
+ * @{
+ */
+void Shutdown();
+/** @} */
+
+/**
+ * @defgroup cscore_utility_func Utility Functions
+ * @{
+ */
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status);
+
+wpi::ArrayRef<CS_Source> EnumerateSourceHandles(
+    wpi::SmallVectorImpl<CS_Source>& vec, CS_Status* status);
+wpi::ArrayRef<CS_Sink> EnumerateSinkHandles(wpi::SmallVectorImpl<CS_Sink>& vec,
+                                            CS_Status* status);
+
+std::string GetHostname();
+
+std::vector<std::string> GetNetworkInterfaces();
+/** @} */
+
+/** @} */
+
+}  // namespace cs
+
+/**
+ * @defgroup cscore_cpp_opencv_special cscore C functions taking a cv::Mat*
+ *
+ * These are needed for specific interop implementations.
+ * @{
+ */
+extern "C" {
+uint64_t CS_GrabSinkFrameCpp(CS_Sink sink, cv::Mat* image, CS_Status* status);
+uint64_t CS_GrabSinkFrameTimeoutCpp(CS_Sink sink, cv::Mat* image,
+                                    double timeout, CS_Status* status);
+void CS_PutSourceFrameCpp(CS_Source source, cv::Mat* image, CS_Status* status);
+}  // extern "C"
+/** @} */
+
+#endif  // CSCORE_CSCORE_CPP_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_oo.h b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_oo.h
new file mode 100644
index 0000000..7e0cb9f
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_oo.h
@@ -0,0 +1,1118 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_CSCORE_OO_H_
+#define CSCORE_CSCORE_OO_H_
+
+#include <initializer_list>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include "cscore_cpp.h"
+
+namespace cs {
+
+/**
+ * @defgroup cscore_oo cscore C++ object-oriented API
+ *
+ * Recommended interface for C++, identical to Java API.
+ *
+ * <p>The classes are RAII and handle reference counting internally.
+ *
+ * @{
+ */
+
+// Forward declarations so friend declarations work correctly
+class CvSource;
+class VideoEvent;
+class VideoSink;
+class VideoSource;
+
+/**
+ * A source or sink property.
+ */
+class VideoProperty {
+  friend class CvSource;
+  friend class VideoEvent;
+  friend class VideoSink;
+  friend class VideoSource;
+
+ public:
+  enum Kind {
+    kNone = CS_PROP_NONE,
+    kBoolean = CS_PROP_BOOLEAN,
+    kInteger = CS_PROP_INTEGER,
+    kString = CS_PROP_STRING,
+    kEnum = CS_PROP_ENUM
+  };
+
+  VideoProperty() : m_handle(0), m_kind(kNone) {}
+
+  std::string GetName() const;
+
+  Kind GetKind() const { return m_kind; }
+
+  explicit operator bool() const { return m_kind != kNone; }
+
+  // Kind checkers
+  bool IsBoolean() const { return m_kind == kBoolean; }
+  bool IsInteger() const { return m_kind == kInteger; }
+  bool IsString() const { return m_kind == kString; }
+  bool IsEnum() const { return m_kind == kEnum; }
+
+  int Get() const;
+  void Set(int value);
+  int GetMin() const;
+  int GetMax() const;
+  int GetStep() const;
+  int GetDefault() const;
+
+  // String-specific functions
+  std::string GetString() const;
+  wpi::StringRef GetString(wpi::SmallVectorImpl<char>& buf) const;
+  void SetString(const wpi::Twine& value);
+
+  // Enum-specific functions
+  std::vector<std::string> GetChoices() const;
+
+  CS_Status GetLastStatus() const { return m_status; }
+
+ private:
+  explicit VideoProperty(CS_Property handle);
+  VideoProperty(CS_Property handle, Kind kind);
+
+  mutable CS_Status m_status;
+  CS_Property m_handle;
+  Kind m_kind;
+};
+
+/**
+ * A source for video that provides a sequence of frames.
+ */
+class VideoSource {
+  friend class VideoEvent;
+  friend class VideoSink;
+
+ public:
+  enum Kind {
+    kUnknown = CS_SOURCE_UNKNOWN,
+    kUsb = CS_SOURCE_USB,
+    kHttp = CS_SOURCE_HTTP,
+    kCv = CS_SOURCE_CV
+  };
+
+  /** Connection strategy.  Used for SetConnectionStrategy(). */
+  enum ConnectionStrategy {
+    /**
+     * Automatically connect or disconnect based on whether any sinks are
+     * connected to this source.  This is the default behavior.
+     */
+    kConnectionAutoManage = CS_CONNECTION_AUTO_MANAGE,
+
+    /**
+     * Try to keep the connection open regardless of whether any sinks are
+     * connected.
+     */
+    kConnectionKeepOpen = CS_CONNECTION_KEEP_OPEN,
+
+    /**
+     * Never open the connection.  If this is set when the connection is open,
+     * close the connection.
+     */
+    kConnectionForceClose = CS_CONNECTION_FORCE_CLOSE
+  };
+
+  VideoSource() noexcept : m_handle(0) {}
+  VideoSource(const VideoSource& source);
+  VideoSource(VideoSource&& other) noexcept;
+  VideoSource& operator=(VideoSource other) noexcept;
+  ~VideoSource();
+
+  explicit operator bool() const { return m_handle != 0; }
+
+  int GetHandle() const { return m_handle; }
+
+  bool operator==(const VideoSource& other) const {
+    return m_handle == other.m_handle;
+  }
+
+  bool operator!=(const VideoSource& other) const { return !(*this == other); }
+
+  /**
+   * Get the kind of the source.
+   */
+  Kind GetKind() const;
+
+  /**
+   * Get the name of the source.  The name is an arbitrary identifier
+   * provided when the source is created, and should be unique.
+   */
+  std::string GetName() const;
+
+  /**
+   * Get the source description.  This is source-kind specific.
+   */
+  std::string GetDescription() const;
+
+  /**
+   * Get the last time a frame was captured.
+   * This uses the same time base as wpi::Now().
+   *
+   * @return Time in 1 us increments.
+   */
+  uint64_t GetLastFrameTime() const;
+
+  /**
+   * Sets the connection strategy.  By default, the source will automatically
+   * connect or disconnect based on whether any sinks are connected.
+   *
+   * <p>This function is non-blocking; look for either a connection open or
+   * close event or call IsConnected() to determine the connection state.
+   *
+   * @param strategy connection strategy (auto, keep open, or force close)
+   */
+  void SetConnectionStrategy(ConnectionStrategy strategy);
+
+  /**
+   * Is the source currently connected to whatever is providing the images?
+   */
+  bool IsConnected() const;
+
+  /**
+   * Gets source enable status.  This is determined with a combination of
+   * connection strategy and the number of sinks connected.
+   *
+   * @return True if enabled, false otherwise.
+   */
+  bool IsEnabled() const;
+
+  /** Get a property.
+   *
+   * @param name Property name
+   * @return Property contents (of kind Property::kNone if no property with
+   *         the given name exists)
+   */
+  VideoProperty GetProperty(const wpi::Twine& name);
+
+  /**
+   * Enumerate all properties of this source.
+   */
+  std::vector<VideoProperty> EnumerateProperties() const;
+
+  /**
+   * Get the current video mode.
+   */
+  VideoMode GetVideoMode() const;
+
+  /**
+   * Set the video mode.
+   *
+   * @param mode Video mode
+   */
+  bool SetVideoMode(const VideoMode& mode);
+
+  /**
+   * Set the video mode.
+   *
+   * @param pixelFormat desired pixel format
+   * @param width desired width
+   * @param height desired height
+   * @param fps desired FPS
+   * @return True if set successfully
+   */
+  bool SetVideoMode(VideoMode::PixelFormat pixelFormat, int width, int height,
+                    int fps);
+
+  /**
+   * Set the pixel format.
+   *
+   * @param pixelFormat desired pixel format
+   * @return True if set successfully
+   */
+  bool SetPixelFormat(VideoMode::PixelFormat pixelFormat);
+
+  /**
+   * Set the resolution.
+   *
+   * @param width desired width
+   * @param height desired height
+   * @return True if set successfully
+   */
+  bool SetResolution(int width, int height);
+
+  /**
+   * Set the frames per second (FPS).
+   *
+   * @param fps desired FPS
+   * @return True if set successfully
+   */
+  bool SetFPS(int fps);
+
+  /**
+   * Set video mode and properties from a JSON configuration string.
+   *
+   * The format of the JSON input is:
+   *
+   * <pre>
+   * {
+   *     "pixel format": "MJPEG", "YUYV", etc
+   *     "width": video mode width
+   *     "height": video mode height
+   *     "fps": video mode fps
+   *     "brightness": percentage brightness
+   *     "white balance": "auto", "hold", or value
+   *     "exposure": "auto", "hold", or value
+   *     "properties": [
+   *         {
+   *             "name": property name
+   *             "value": property value
+   *         }
+   *     ]
+   * }
+   * </pre>
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  bool SetConfigJson(wpi::StringRef config);
+
+  /**
+   * Set video mode and properties from a JSON configuration object.
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  bool SetConfigJson(const wpi::json& config);
+
+  /**
+   * Get a JSON configuration string.
+   *
+   * @return JSON configuration string
+   */
+  std::string GetConfigJson() const;
+
+  /**
+   * Get a JSON configuration object.
+   *
+   * @return JSON configuration object
+   */
+  wpi::json GetConfigJsonObject() const;
+
+  /**
+   * Get the actual FPS.
+   *
+   * <p>SetTelemetryPeriod() must be called for this to be valid.
+   *
+   * @return Actual FPS averaged over the telemetry period.
+   */
+  double GetActualFPS() const;
+
+  /**
+   * Get the data rate (in bytes per second).
+   *
+   * <p>SetTelemetryPeriod() must be called for this to be valid.
+   *
+   * @return Data rate averaged over the telemetry period.
+   */
+  double GetActualDataRate() const;
+
+  /**
+   * Enumerate all known video modes for this source.
+   */
+  std::vector<VideoMode> EnumerateVideoModes() const;
+
+  CS_Status GetLastStatus() const { return m_status; }
+
+  /**
+   * Enumerate all sinks connected to this source.
+   *
+   * @return Vector of sinks.
+   */
+  std::vector<VideoSink> EnumerateSinks();
+
+  /**
+   * Enumerate all existing sources.
+   *
+   * @return Vector of sources.
+   */
+  static std::vector<VideoSource> EnumerateSources();
+
+  friend void swap(VideoSource& first, VideoSource& second) noexcept {
+    using std::swap;
+    swap(first.m_status, second.m_status);
+    swap(first.m_handle, second.m_handle);
+  }
+
+ protected:
+  explicit VideoSource(CS_Source handle) : m_handle(handle) {}
+
+  mutable CS_Status m_status = 0;
+  CS_Source m_handle;
+};
+
+/**
+ * A source that represents a video camera.
+ */
+class VideoCamera : public VideoSource {
+ public:
+  enum WhiteBalance {
+    kFixedIndoor = 3000,
+    kFixedOutdoor1 = 4000,
+    kFixedOutdoor2 = 5000,
+    kFixedFluorescent1 = 5100,
+    kFixedFlourescent2 = 5200
+  };
+
+  VideoCamera() = default;
+
+  /**
+   * Set the brightness, as a percentage (0-100).
+   */
+  void SetBrightness(int brightness);
+
+  /**
+   * Get the brightness, as a percentage (0-100).
+   */
+  int GetBrightness();
+
+  /**
+   * Set the white balance to auto.
+   */
+  void SetWhiteBalanceAuto();
+
+  /**
+   * Set the white balance to hold current.
+   */
+  void SetWhiteBalanceHoldCurrent();
+
+  /**
+   * Set the white balance to manual, with specified color temperature.
+   */
+  void SetWhiteBalanceManual(int value);
+
+  /**
+   * Set the exposure to auto aperature.
+   */
+  void SetExposureAuto();
+
+  /**
+   * Set the exposure to hold current.
+   */
+  void SetExposureHoldCurrent();
+
+  /**
+   * Set the exposure to manual, as a percentage (0-100).
+   */
+  void SetExposureManual(int value);
+
+ protected:
+  explicit VideoCamera(CS_Source handle) : VideoSource(handle) {}
+};
+
+/**
+ * A source that represents a USB camera.
+ */
+class UsbCamera : public VideoCamera {
+ public:
+  UsbCamera() = default;
+
+  /**
+   * Create a source for a USB camera based on device number.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param dev Device number (e.g. 0 for /dev/video0)
+   */
+  UsbCamera(const wpi::Twine& name, int dev);
+
+  /**
+   * Create a source for a USB camera based on device path.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param path Path to device (e.g. "/dev/video0" on Linux)
+   */
+  UsbCamera(const wpi::Twine& name, const wpi::Twine& path);
+
+  /**
+   * Enumerate USB cameras on the local system.
+   *
+   * @return Vector of USB camera information (one for each camera)
+   */
+  static std::vector<UsbCameraInfo> EnumerateUsbCameras();
+
+  /**
+   * Get the path to the device.
+   */
+  std::string GetPath() const;
+
+  /**
+   * Get the full camera information for the device.
+   */
+  UsbCameraInfo GetInfo() const;
+
+  /**
+   * Set how verbose the camera connection messages are.
+   *
+   * @param level 0=don't display Connecting message, 1=do display message
+   */
+  void SetConnectVerbose(int level);
+};
+
+/**
+ * A source that represents a MJPEG-over-HTTP (IP) camera.
+ */
+class HttpCamera : public VideoCamera {
+ public:
+  enum HttpCameraKind {
+    kUnknown = CS_HTTP_UNKNOWN,
+    kMJPGStreamer = CS_HTTP_MJPGSTREAMER,
+    kCSCore = CS_HTTP_CSCORE,
+    kAxis = CS_HTTP_AXIS
+  };
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  HttpCamera(const wpi::Twine& name, const wpi::Twine& url,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  HttpCamera(const wpi::Twine& name, const char* url,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param url Camera URL (e.g. "http://10.x.y.11/video/stream.mjpg")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  HttpCamera(const wpi::Twine& name, const std::string& url,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param urls Array of Camera URLs
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  HttpCamera(const wpi::Twine& name, wpi::ArrayRef<std::string> urls,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Create a source for a MJPEG-over-HTTP (IP) camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param urls Array of Camera URLs
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  template <typename T>
+  HttpCamera(const wpi::Twine& name, std::initializer_list<T> urls,
+             HttpCameraKind kind = kUnknown);
+
+  /**
+   * Get the kind of HTTP camera.
+   *
+   * <p>Autodetection can result in returning a different value than the camera
+   * was created with.
+   */
+  HttpCameraKind GetHttpCameraKind() const;
+
+  /**
+   * Change the URLs used to connect to the camera.
+   */
+  void SetUrls(wpi::ArrayRef<std::string> urls);
+
+  /**
+   * Change the URLs used to connect to the camera.
+   */
+  template <typename T>
+  void SetUrls(std::initializer_list<T> urls);
+
+  /**
+   * Get the URLs used to connect to the camera.
+   */
+  std::vector<std::string> GetUrls() const;
+};
+
+/**
+ * A source that represents an Axis IP camera.
+ */
+class AxisCamera : public HttpCamera {
+  static std::string HostToUrl(const wpi::Twine& host);
+  static std::vector<std::string> HostToUrl(wpi::ArrayRef<std::string> hosts);
+  template <typename T>
+  static std::vector<std::string> HostToUrl(std::initializer_list<T> hosts);
+
+ public:
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, const wpi::Twine& host);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, const char* host);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, const std::string& host);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, wpi::StringRef host);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param hosts Array of Camera host IPs/DNS names
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  AxisCamera(const wpi::Twine& name, wpi::ArrayRef<std::string> hosts);
+
+  /**
+   * Create a source for an Axis IP camera.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param hosts Array of Camera host IPs/DNS names
+   * @param kind Camera kind (e.g. kAxis)
+   */
+  template <typename T>
+  AxisCamera(const wpi::Twine& name, std::initializer_list<T> hosts);
+};
+
+/**
+ * A source for user code to provide OpenCV images as video frames.
+ */
+class CvSource : public VideoSource {
+ public:
+  CvSource() = default;
+
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param mode Video mode being generated
+   */
+  CvSource(const wpi::Twine& name, const VideoMode& mode);
+
+  /**
+   * Create an OpenCV source.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param pixelFormat Pixel format
+   * @param width width
+   * @param height height
+   * @param fps fps
+   */
+  CvSource(const wpi::Twine& name, VideoMode::PixelFormat pixelFormat,
+           int width, int height, int fps);
+
+  /**
+   * Put an OpenCV image and notify sinks.
+   *
+   * <p>Only 8-bit single-channel or 3-channel (with BGR channel order) images
+   * are supported. If the format, depth or channel order is different, use
+   * cv::Mat::convertTo() and/or cv::cvtColor() to convert it first.
+   *
+   * @param image OpenCV image
+   */
+  void PutFrame(cv::Mat& image);
+
+  /**
+   * Signal sinks that an error has occurred.  This should be called instead
+   * of NotifyFrame when an error occurs.
+   */
+  void NotifyError(const wpi::Twine& msg);
+
+  /**
+   * Set source connection status.  Defaults to true.
+   *
+   * @param connected True for connected, false for disconnected
+   */
+  void SetConnected(bool connected);
+
+  /**
+   * Set source description.
+   *
+   * @param description Description
+   */
+  void SetDescription(const wpi::Twine& description);
+
+  /**
+   * Create a property.
+   *
+   * @param name Property name
+   * @param kind Property kind
+   * @param minimum Minimum value
+   * @param maximum Maximum value
+   * @param step Step value
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  VideoProperty CreateProperty(const wpi::Twine& name, VideoProperty::Kind kind,
+                               int minimum, int maximum, int step,
+                               int defaultValue, int value);
+
+  /**
+   * Create an integer property.
+   *
+   * @param name Property name
+   * @param minimum Minimum value
+   * @param maximum Maximum value
+   * @param step Step value
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  VideoProperty CreateIntegerProperty(const wpi::Twine& name, int minimum,
+                                      int maximum, int step, int defaultValue,
+                                      int value);
+
+  /**
+   * Create a boolean property.
+   *
+   * @param name Property name
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  VideoProperty CreateBooleanProperty(const wpi::Twine& name, bool defaultValue,
+                                      bool value);
+
+  /**
+   * Create a string property.
+   *
+   * @param name Property name
+   * @param defaultValue Default value
+   * @param value Current value
+   * @return Property
+   */
+  VideoProperty CreateStringProperty(const wpi::Twine& name,
+                                     const wpi::Twine& value);
+
+  /**
+   * Configure enum property choices.
+   *
+   * @param property Property
+   * @param choices Choices
+   */
+  void SetEnumPropertyChoices(const VideoProperty& property,
+                              wpi::ArrayRef<std::string> choices);
+
+  /**
+   * Configure enum property choices.
+   *
+   * @param property Property
+   * @param choices Choices
+   */
+  template <typename T>
+  void SetEnumPropertyChoices(const VideoProperty& property,
+                              std::initializer_list<T> choices);
+};
+
+/**
+ * A sink for video that accepts a sequence of frames.
+ */
+class VideoSink {
+  friend class VideoEvent;
+  friend class VideoSource;
+
+ public:
+  enum Kind {
+    kUnknown = CS_SINK_UNKNOWN,
+    kMjpeg = CS_SINK_MJPEG,
+    kCv = CS_SINK_CV
+  };
+
+  VideoSink() noexcept : m_handle(0) {}
+  VideoSink(const VideoSink& sink);
+  VideoSink(VideoSink&& sink) noexcept;
+  VideoSink& operator=(VideoSink other) noexcept;
+  ~VideoSink();
+
+  explicit operator bool() const { return m_handle != 0; }
+
+  int GetHandle() const { return m_handle; }
+
+  bool operator==(const VideoSink& other) const {
+    return m_handle == other.m_handle;
+  }
+
+  bool operator!=(const VideoSink& other) const { return !(*this == other); }
+
+  /**
+   * Get the kind of the sink.
+   */
+  Kind GetKind() const;
+
+  /**
+   * Get the name of the sink.  The name is an arbitrary identifier
+   * provided when the sink is created, and should be unique.
+   */
+  std::string GetName() const;
+
+  /**
+   * Get the sink description.  This is sink-kind specific.
+   */
+  std::string GetDescription() const;
+
+  /**
+   * Get a property of the sink.
+   *
+   * @param name Property name
+   * @return Property (kind Property::kNone if no property with
+   *         the given name exists)
+   */
+  VideoProperty GetProperty(const wpi::Twine& name);
+
+  /**
+   * Enumerate all properties of this sink.
+   */
+  std::vector<VideoProperty> EnumerateProperties() const;
+
+  /**
+   * Set properties from a JSON configuration string.
+   *
+   * The format of the JSON input is:
+   *
+   * <pre>
+   * {
+   *     "properties": [
+   *         {
+   *             "name": property name
+   *             "value": property value
+   *         }
+   *     ]
+   * }
+   * </pre>
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  bool SetConfigJson(wpi::StringRef config);
+
+  /**
+   * Set properties from a JSON configuration object.
+   *
+   * @param config configuration
+   * @return True if set successfully
+   */
+  bool SetConfigJson(const wpi::json& config);
+
+  /**
+   * Get a JSON configuration string.
+   *
+   * @return JSON configuration string
+   */
+  std::string GetConfigJson() const;
+
+  /**
+   * Get a JSON configuration object.
+   *
+   * @return JSON configuration object
+   */
+  wpi::json GetConfigJsonObject() const;
+
+  /**
+   * Configure which source should provide frames to this sink.  Each sink
+   * can accept frames from only a single source, but a single source can
+   * provide frames to multiple clients.
+   *
+   * @param source Source
+   */
+  void SetSource(VideoSource source);
+
+  /**
+   * Get the connected source.
+   *
+   * @return Connected source (empty if none connected).
+   */
+  VideoSource GetSource() const;
+
+  /**
+   * Get a property of the associated source.
+   *
+   * @param name Property name
+   * @return Property (kind Property::kNone if no property with
+   *         the given name exists or no source connected)
+   */
+  VideoProperty GetSourceProperty(const wpi::Twine& name);
+
+  CS_Status GetLastStatus() const { return m_status; }
+
+  /**
+   * Enumerate all existing sinks.
+   *
+   * @return Vector of sinks.
+   */
+  static std::vector<VideoSink> EnumerateSinks();
+
+  friend void swap(VideoSink& first, VideoSink& second) noexcept {
+    using std::swap;
+    swap(first.m_status, second.m_status);
+    swap(first.m_handle, second.m_handle);
+  }
+
+ protected:
+  explicit VideoSink(CS_Sink handle) : m_handle(handle) {}
+
+  mutable CS_Status m_status = 0;
+  CS_Sink m_handle;
+};
+
+/**
+ * A sink that acts as a MJPEG-over-HTTP network server.
+ */
+class MjpegServer : public VideoSink {
+ public:
+  MjpegServer() = default;
+
+  /**
+   * Create a MJPEG-over-HTTP server sink.
+   *
+   * @param name Sink name (arbitrary unique identifier)
+   * @param listenAddress TCP listen address (empty string for all addresses)
+   * @param port TCP port number
+   */
+  MjpegServer(const wpi::Twine& name, const wpi::Twine& listenAddress,
+              int port);
+
+  /**
+   * Create a MJPEG-over-HTTP server sink.
+   *
+   * @param name Sink name (arbitrary unique identifier)
+   * @param port TCP port number
+   */
+  MjpegServer(const wpi::Twine& name, int port) : MjpegServer(name, "", port) {}
+
+  /**
+   * Get the listen address of the server.
+   */
+  std::string GetListenAddress() const;
+
+  /**
+   * Get the port number of the server.
+   */
+  int GetPort() const;
+
+  /**
+   * Set the stream resolution for clients that don't specify it.
+   *
+   * <p>It is not necessary to set this if it is the same as the source
+   * resolution.
+   *
+   * <p>Setting this different than the source resolution will result in
+   * increased CPU usage, particularly for MJPEG source cameras, as it will
+   * decompress, resize, and recompress the image, instead of using the
+   * camera's MJPEG image directly.
+   *
+   * @param width width, 0 for unspecified
+   * @param height height, 0 for unspecified
+   */
+  void SetResolution(int width, int height);
+
+  /**
+   * Set the stream frames per second (FPS) for clients that don't specify it.
+   *
+   * <p>It is not necessary to set this if it is the same as the source FPS.
+   *
+   * @param fps FPS, 0 for unspecified
+   */
+  void SetFPS(int fps);
+
+  /**
+   * Set the compression for clients that don't specify it.
+   *
+   * <p>Setting this will result in increased CPU usage for MJPEG source cameras
+   * as it will decompress and recompress the image instead of using the
+   * camera's MJPEG image directly.
+   *
+   * @param quality JPEG compression quality (0-100), -1 for unspecified
+   */
+  void SetCompression(int quality);
+
+  /**
+   * Set the default compression used for non-MJPEG sources.  If not set,
+   * 80 is used.  This function has no effect on MJPEG source cameras; use
+   * SetCompression() instead to force recompression of MJPEG source images.
+   *
+   * @param quality JPEG compression quality (0-100)
+   */
+  void SetDefaultCompression(int quality);
+};
+
+/**
+ * A sink for user code to accept video frames as OpenCV images.
+ */
+class CvSink : public VideoSink {
+ public:
+  CvSink() = default;
+
+  /**
+   * Create a sink for accepting OpenCV images.
+   *
+   * <p>WaitForFrame() must be called on the created sink to get each new
+   * image.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   */
+  explicit CvSink(const wpi::Twine& name);
+
+  /**
+   * Create a sink for accepting OpenCV images in a separate thread.
+   *
+   * <p>A thread will be created that calls WaitForFrame() and calls the
+   * processFrame() callback each time a new frame arrives.
+   *
+   * @param name Source name (arbitrary unique identifier)
+   * @param processFrame Frame processing function; will be called with a
+   *        time=0 if an error occurred.  processFrame should call GetImage()
+   *        or GetError() as needed, but should not call (except in very
+   *        unusual circumstances) WaitForImage().
+   */
+  CvSink(const wpi::Twine& name,
+         std::function<void(uint64_t time)> processFrame);
+
+  /**
+   * Set sink description.
+   *
+   * @param description Description
+   */
+  void SetDescription(const wpi::Twine& description);
+
+  /**
+   * Wait for the next frame and get the image.
+   * Times out (returning 0) after timeout seconds.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrame(cv::Mat& image, double timeout = 0.225) const;
+
+  /**
+   * Wait for the next frame and get the image.  May block forever.
+   * The provided image will have three 8-bit channels stored in BGR order.
+   *
+   * @return Frame time, or 0 on error (call GetError() to obtain the error
+   *         message); the frame time is in the same time base as wpi::Now(),
+   *         and is in 1 us increments.
+   */
+  uint64_t GrabFrameNoTimeout(cv::Mat& image) const;
+
+  /**
+   * Get error string.  Call this if WaitForFrame() returns 0 to determine
+   * what the error is.
+   */
+  std::string GetError() const;
+
+  /**
+   * Enable or disable getting new frames.
+   *
+   * <p>Disabling will cause processFrame (for callback-based CvSinks) to not
+   * be called and WaitForFrame() to not return.  This can be used to save
+   * processor resources when frames are not needed.
+   */
+  void SetEnabled(bool enabled);
+};
+
+/**
+ * An event generated by the library and provided to event listeners.
+ */
+class VideoEvent : public RawEvent {
+ public:
+  /**
+   * Get the source associated with the event (if any).
+   */
+  VideoSource GetSource() const;
+
+  /**
+   * Get the sink associated with the event (if any).
+   */
+  VideoSink GetSink() const;
+
+  /**
+   * Get the property associated with the event (if any).
+   */
+  VideoProperty GetProperty() const;
+};
+
+/**
+ * An event listener.  This calls back to a desigated callback function when
+ * an event matching the specified mask is generated by the library.
+ */
+class VideoListener {
+ public:
+  VideoListener() : m_handle(0) {}
+
+  /**
+   * Create an event listener.
+   *
+   * @param callback Callback function
+   * @param eventMask Bitmask of VideoEvent::Kind values
+   * @param immediateNotify Whether callback should be immediately called with
+   *        a representative set of events for the current library state.
+   */
+  VideoListener(std::function<void(const VideoEvent& event)> callback,
+                int eventMask, bool immediateNotify);
+
+  VideoListener(const VideoListener&) = delete;
+  VideoListener& operator=(const VideoListener&) = delete;
+  VideoListener(VideoListener&& other) noexcept;
+  VideoListener& operator=(VideoListener&& other) noexcept;
+  ~VideoListener();
+
+  friend void swap(VideoListener& first, VideoListener& second) noexcept {
+    using std::swap;
+    swap(first.m_handle, second.m_handle);
+  }
+
+ private:
+  CS_Listener m_handle;
+};
+
+/** @} */
+
+}  // namespace cs
+
+#include "cscore_oo.inl"
+
+#endif  // CSCORE_CSCORE_OO_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_oo.inl b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_oo.inl
new file mode 100644
index 0000000..5162e1d
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/include/cscore_oo.inl
@@ -0,0 +1,655 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_OO_INL_
+#define CSCORE_OO_INL_
+
+namespace cs {
+
+inline std::string VideoProperty::GetName() const {
+  m_status = 0;
+  return GetPropertyName(m_handle, &m_status);
+}
+
+inline int VideoProperty::Get() const {
+  m_status = 0;
+  return GetProperty(m_handle, &m_status);
+}
+
+inline void VideoProperty::Set(int value) {
+  m_status = 0;
+  SetProperty(m_handle, value, &m_status);
+}
+
+inline int VideoProperty::GetMin() const {
+  m_status = 0;
+  return GetPropertyMin(m_handle, &m_status);
+}
+
+inline int VideoProperty::GetMax() const {
+  m_status = 0;
+  return GetPropertyMax(m_handle, &m_status);
+}
+
+inline int VideoProperty::GetStep() const {
+  m_status = 0;
+  return GetPropertyStep(m_handle, &m_status);
+}
+
+inline int VideoProperty::GetDefault() const {
+  m_status = 0;
+  return GetPropertyDefault(m_handle, &m_status);
+}
+
+inline std::string VideoProperty::GetString() const {
+  m_status = 0;
+  return GetStringProperty(m_handle, &m_status);
+}
+
+inline wpi::StringRef VideoProperty::GetString(
+    wpi::SmallVectorImpl<char>& buf) const {
+  m_status = 0;
+  return GetStringProperty(m_handle, buf, &m_status);
+}
+
+inline void VideoProperty::SetString(const wpi::Twine& value) {
+  m_status = 0;
+  SetStringProperty(m_handle, value, &m_status);
+}
+
+inline std::vector<std::string> VideoProperty::GetChoices() const {
+  m_status = 0;
+  return GetEnumPropertyChoices(m_handle, &m_status);
+}
+
+inline VideoProperty::VideoProperty(CS_Property handle) : m_handle(handle) {
+  m_status = 0;
+  if (handle == 0)
+    m_kind = kNone;
+  else
+    m_kind =
+        static_cast<Kind>(static_cast<int>(GetPropertyKind(handle, &m_status)));
+}
+
+inline VideoProperty::VideoProperty(CS_Property handle, Kind kind)
+  : m_handle(handle), m_kind(kind) {}
+
+inline VideoSource::VideoSource(const VideoSource& source)
+    : m_handle(source.m_handle == 0 ? 0
+                                    : CopySource(source.m_handle, &m_status)) {}
+
+inline VideoSource::VideoSource(VideoSource&& other) noexcept : VideoSource() {
+  swap(*this, other);
+}
+
+inline VideoSource& VideoSource::operator=(VideoSource other) noexcept {
+  swap(*this, other);
+  return *this;
+}
+
+inline VideoSource::~VideoSource() {
+  m_status = 0;
+  if (m_handle != 0) ReleaseSource(m_handle, &m_status);
+}
+
+inline VideoSource::Kind VideoSource::GetKind() const {
+  m_status = 0;
+  return static_cast<VideoSource::Kind>(GetSourceKind(m_handle, &m_status));
+}
+
+inline std::string VideoSource::GetName() const {
+  m_status = 0;
+  return GetSourceName(m_handle, &m_status);
+}
+
+inline std::string VideoSource::GetDescription() const {
+  m_status = 0;
+  return GetSourceDescription(m_handle, &m_status);
+}
+
+inline uint64_t VideoSource::GetLastFrameTime() const {
+  m_status = 0;
+  return GetSourceLastFrameTime(m_handle, &m_status);
+}
+
+inline void VideoSource::SetConnectionStrategy(ConnectionStrategy strategy) {
+  m_status = 0;
+  SetSourceConnectionStrategy(
+      m_handle, static_cast<CS_ConnectionStrategy>(static_cast<int>(strategy)),
+      &m_status);
+}
+
+inline bool VideoSource::IsConnected() const {
+  m_status = 0;
+  return IsSourceConnected(m_handle, &m_status);
+}
+
+inline bool VideoSource::IsEnabled() const {
+  m_status = 0;
+  return IsSourceEnabled(m_handle, &m_status);
+}
+
+inline VideoProperty VideoSource::GetProperty(const wpi::Twine& name) {
+  m_status = 0;
+  return VideoProperty{GetSourceProperty(m_handle, name, &m_status)};
+}
+
+inline VideoMode VideoSource::GetVideoMode() const {
+  m_status = 0;
+  return GetSourceVideoMode(m_handle, &m_status);
+}
+
+inline bool VideoSource::SetVideoMode(const VideoMode& mode) {
+  m_status = 0;
+  return SetSourceVideoMode(m_handle, mode, &m_status);
+}
+
+inline bool VideoSource::SetVideoMode(VideoMode::PixelFormat pixelFormat,
+                                      int width, int height, int fps) {
+  m_status = 0;
+  return SetSourceVideoMode(
+      m_handle, VideoMode{pixelFormat, width, height, fps}, &m_status);
+}
+
+inline bool VideoSource::SetPixelFormat(VideoMode::PixelFormat pixelFormat) {
+  m_status = 0;
+  return SetSourcePixelFormat(m_handle, pixelFormat, &m_status);
+}
+
+inline bool VideoSource::SetResolution(int width, int height) {
+  m_status = 0;
+  return SetSourceResolution(m_handle, width, height, &m_status);
+}
+
+inline bool VideoSource::SetFPS(int fps) {
+  m_status = 0;
+  return SetSourceFPS(m_handle, fps, &m_status);
+}
+
+inline bool VideoSource::SetConfigJson(wpi::StringRef config) {
+  m_status = 0;
+  return SetSourceConfigJson(m_handle, config, &m_status);
+}
+
+inline bool VideoSource::SetConfigJson(const wpi::json& config) {
+  m_status = 0;
+  return SetSourceConfigJson(m_handle, config, &m_status);
+}
+
+inline std::string VideoSource::GetConfigJson() const {
+  m_status = 0;
+  return GetSourceConfigJson(m_handle, &m_status);
+}
+
+inline double VideoSource::GetActualFPS() const {
+  m_status = 0;
+  return cs::GetTelemetryAverageValue(m_handle, CS_SOURCE_FRAMES_RECEIVED,
+                                      &m_status);
+}
+
+inline double VideoSource::GetActualDataRate() const {
+  m_status = 0;
+  return cs::GetTelemetryAverageValue(m_handle, CS_SOURCE_BYTES_RECEIVED,
+                                      &m_status);
+}
+
+inline std::vector<VideoMode> VideoSource::EnumerateVideoModes() const {
+  CS_Status status = 0;
+  return EnumerateSourceVideoModes(m_handle, &status);
+}
+
+inline void VideoCamera::SetBrightness(int brightness) {
+  m_status = 0;
+  SetCameraBrightness(m_handle, brightness, &m_status);
+}
+
+inline int VideoCamera::GetBrightness() {
+  m_status = 0;
+  return GetCameraBrightness(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetWhiteBalanceAuto() {
+  m_status = 0;
+  SetCameraWhiteBalanceAuto(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetWhiteBalanceHoldCurrent() {
+  m_status = 0;
+  SetCameraWhiteBalanceHoldCurrent(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetWhiteBalanceManual(int value) {
+  m_status = 0;
+  SetCameraWhiteBalanceManual(m_handle, value, &m_status);
+}
+
+inline void VideoCamera::SetExposureAuto() {
+  m_status = 0;
+  SetCameraExposureAuto(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetExposureHoldCurrent() {
+  m_status = 0;
+  SetCameraExposureHoldCurrent(m_handle, &m_status);
+}
+
+inline void VideoCamera::SetExposureManual(int value) {
+  m_status = 0;
+  SetCameraExposureManual(m_handle, value, &m_status);
+}
+
+inline UsbCamera::UsbCamera(const wpi::Twine& name, int dev) {
+  m_handle = CreateUsbCameraDev(name, dev, &m_status);
+}
+
+inline UsbCamera::UsbCamera(const wpi::Twine& name, const wpi::Twine& path) {
+  m_handle = CreateUsbCameraPath(name, path, &m_status);
+}
+
+inline std::vector<UsbCameraInfo> UsbCamera::EnumerateUsbCameras() {
+  CS_Status status = 0;
+  return ::cs::EnumerateUsbCameras(&status);
+}
+
+inline std::string UsbCamera::GetPath() const {
+  m_status = 0;
+  return ::cs::GetUsbCameraPath(m_handle, &m_status);
+}
+
+inline UsbCameraInfo UsbCamera::GetInfo() const {
+  m_status = 0;
+  return ::cs::GetUsbCameraInfo(m_handle, &m_status);
+}
+
+inline void UsbCamera::SetConnectVerbose(int level) {
+  m_status = 0;
+  SetProperty(GetSourceProperty(m_handle, "connect_verbose", &m_status), level,
+              &m_status);
+}
+
+inline HttpCamera::HttpCamera(const wpi::Twine& name, const wpi::Twine& url,
+                              HttpCameraKind kind) {
+  m_handle = CreateHttpCamera(
+      name, url, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
+      &m_status);
+}
+
+inline HttpCamera::HttpCamera(const wpi::Twine& name, const char* url,
+                              HttpCameraKind kind) {
+  m_handle = CreateHttpCamera(
+      name, url, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
+      &m_status);
+}
+
+inline HttpCamera::HttpCamera(const wpi::Twine& name, const std::string& url,
+                              HttpCameraKind kind)
+    : HttpCamera(name, wpi::Twine{url}, kind) {}
+
+inline HttpCamera::HttpCamera(const wpi::Twine& name,
+                              wpi::ArrayRef<std::string> urls,
+                              HttpCameraKind kind) {
+  m_handle = CreateHttpCamera(
+      name, urls, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
+      &m_status);
+}
+
+template <typename T>
+inline HttpCamera::HttpCamera(const wpi::Twine& name,
+                              std::initializer_list<T> urls,
+                              HttpCameraKind kind) {
+  std::vector<std::string> vec;
+  vec.reserve(urls.size());
+  for (const auto& url : urls) vec.emplace_back(url);
+  m_handle = CreateHttpCamera(
+      name, vec, static_cast<CS_HttpCameraKind>(static_cast<int>(kind)),
+      &m_status);
+}
+
+inline HttpCamera::HttpCameraKind HttpCamera::GetHttpCameraKind() const {
+  m_status = 0;
+  return static_cast<HttpCameraKind>(
+      static_cast<int>(::cs::GetHttpCameraKind(m_handle, &m_status)));
+}
+
+inline void HttpCamera::SetUrls(wpi::ArrayRef<std::string> urls) {
+  m_status = 0;
+  ::cs::SetHttpCameraUrls(m_handle, urls, &m_status);
+}
+
+template <typename T>
+inline void HttpCamera::SetUrls(std::initializer_list<T> urls) {
+  std::vector<std::string> vec;
+  vec.reserve(urls.size());
+  for (const auto& url : urls) vec.emplace_back(url);
+  m_status = 0;
+  ::cs::SetHttpCameraUrls(m_handle, vec, &m_status);
+}
+
+inline std::vector<std::string> HttpCamera::GetUrls() const {
+  m_status = 0;
+  return ::cs::GetHttpCameraUrls(m_handle, &m_status);
+}
+
+inline std::string AxisCamera::HostToUrl(const wpi::Twine& host) {
+  return ("http://" + host + "/mjpg/video.mjpg").str();
+}
+
+inline std::vector<std::string> AxisCamera::HostToUrl(
+    wpi::ArrayRef<std::string> hosts) {
+  std::vector<std::string> rv;
+  rv.reserve(hosts.size());
+  for (const auto& host : hosts)
+    rv.emplace_back(HostToUrl(wpi::StringRef{host}));
+  return rv;
+}
+
+template <typename T>
+inline std::vector<std::string> AxisCamera::HostToUrl(
+    std::initializer_list<T> hosts) {
+  std::vector<std::string> rv;
+  rv.reserve(hosts.size());
+  for (const auto& host : hosts)
+    rv.emplace_back(HostToUrl(wpi::StringRef{host}));
+  return rv;
+}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name, const wpi::Twine& host)
+    : HttpCamera(name, HostToUrl(host), kAxis) {}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name, const char* host)
+    : HttpCamera(name, HostToUrl(host), kAxis) {}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name, const std::string& host)
+    : HttpCamera(name, HostToUrl(wpi::Twine{host}), kAxis) {}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name, wpi::StringRef host)
+    : HttpCamera(name, HostToUrl(host), kAxis) {}
+
+inline AxisCamera::AxisCamera(const wpi::Twine& name,
+                              wpi::ArrayRef<std::string> hosts)
+    : HttpCamera(name, HostToUrl(hosts), kAxis) {}
+
+template <typename T>
+inline AxisCamera::AxisCamera(const wpi::Twine& name,
+                              std::initializer_list<T> hosts)
+    : HttpCamera(name, HostToUrl(hosts), kAxis) {}
+
+inline CvSource::CvSource(const wpi::Twine& name, const VideoMode& mode) {
+  m_handle = CreateCvSource(name, mode, &m_status);
+}
+
+inline CvSource::CvSource(const wpi::Twine& name, VideoMode::PixelFormat format,
+                          int width, int height, int fps) {
+  m_handle =
+      CreateCvSource(name, VideoMode{format, width, height, fps}, &m_status);
+}
+
+inline void CvSource::PutFrame(cv::Mat& image) {
+  m_status = 0;
+  PutSourceFrame(m_handle, image, &m_status);
+}
+
+inline void CvSource::NotifyError(const wpi::Twine& msg) {
+  m_status = 0;
+  NotifySourceError(m_handle, msg, &m_status);
+}
+
+inline void CvSource::SetConnected(bool connected) {
+  m_status = 0;
+  SetSourceConnected(m_handle, connected, &m_status);
+}
+
+inline void CvSource::SetDescription(const wpi::Twine& description) {
+  m_status = 0;
+  SetSourceDescription(m_handle, description, &m_status);
+}
+
+inline VideoProperty CvSource::CreateProperty(const wpi::Twine& name,
+                                              VideoProperty::Kind kind,
+                                              int minimum, int maximum,
+                                              int step, int defaultValue,
+                                              int value) {
+  m_status = 0;
+  return VideoProperty{CreateSourceProperty(
+      m_handle, name, static_cast<CS_PropertyKind>(static_cast<int>(kind)),
+      minimum, maximum, step, defaultValue, value, &m_status)};
+}
+
+inline VideoProperty CvSource::CreateIntegerProperty(const wpi::Twine& name,
+                                                    int minimum, int maximum,
+                                                    int step, int defaultValue,
+                                                    int value) {
+  m_status = 0;
+  return VideoProperty{CreateSourceProperty(
+      m_handle, name, static_cast<CS_PropertyKind>(static_cast<int>(VideoProperty::Kind::kInteger)),
+      minimum, maximum, step, defaultValue, value, &m_status)};
+}
+
+inline VideoProperty CvSource::CreateBooleanProperty(const wpi::Twine& name,
+                                                     bool defaultValue,
+                                                     bool value) {
+  m_status = 0;
+  return VideoProperty{CreateSourceProperty(
+      m_handle, name, static_cast<CS_PropertyKind>(static_cast<int>(VideoProperty::Kind::kBoolean)),
+      0, 1, 1, defaultValue ? 1 : 0, value ? 1 : 0, &m_status)};
+}
+
+inline VideoProperty CvSource::CreateStringProperty(const wpi::Twine& name,
+                                                    const wpi::Twine& value) {
+  m_status = 0;
+  auto prop = VideoProperty{CreateSourceProperty(
+      m_handle, name, static_cast<CS_PropertyKind>(static_cast<int>(VideoProperty::Kind::kString)),
+      0, 0, 0, 0, 0, &m_status)};
+  prop.SetString(value);
+  return prop;
+}
+
+
+inline void CvSource::SetEnumPropertyChoices(
+    const VideoProperty& property, wpi::ArrayRef<std::string> choices) {
+  m_status = 0;
+  SetSourceEnumPropertyChoices(m_handle, property.m_handle, choices, &m_status);
+}
+
+template <typename T>
+inline void CvSource::SetEnumPropertyChoices(const VideoProperty& property,
+                                             std::initializer_list<T> choices) {
+  std::vector<std::string> vec;
+  vec.reserve(choices.size());
+  for (const auto& choice : choices) vec.emplace_back(choice);
+  m_status = 0;
+  SetSourceEnumPropertyChoices(m_handle, property.m_handle, vec, &m_status);
+}
+
+inline VideoSink::VideoSink(const VideoSink& sink)
+    : m_handle(sink.m_handle == 0 ? 0 : CopySink(sink.m_handle, &m_status)) {}
+
+inline VideoSink::VideoSink(VideoSink&& other) noexcept : VideoSink() {
+  swap(*this, other);
+}
+
+inline VideoSink& VideoSink::operator=(VideoSink other) noexcept {
+  swap(*this, other);
+  return *this;
+}
+
+inline VideoSink::~VideoSink() {
+  m_status = 0;
+  if (m_handle != 0) ReleaseSink(m_handle, &m_status);
+}
+
+inline VideoSink::Kind VideoSink::GetKind() const {
+  m_status = 0;
+  return static_cast<VideoSink::Kind>(GetSinkKind(m_handle, &m_status));
+}
+
+inline std::string VideoSink::GetName() const {
+  m_status = 0;
+  return GetSinkName(m_handle, &m_status);
+}
+
+inline std::string VideoSink::GetDescription() const {
+  m_status = 0;
+  return GetSinkDescription(m_handle, &m_status);
+}
+
+inline VideoProperty VideoSink::GetProperty(const wpi::Twine& name) {
+  m_status = 0;
+  return VideoProperty{GetSinkProperty(m_handle, name, &m_status)};
+}
+
+inline void VideoSink::SetSource(VideoSource source) {
+  m_status = 0;
+  if (!source)
+    SetSinkSource(m_handle, 0, &m_status);
+  else
+    SetSinkSource(m_handle, source.m_handle, &m_status);
+}
+
+inline VideoSource VideoSink::GetSource() const {
+  m_status = 0;
+  auto handle = GetSinkSource(m_handle, &m_status);
+  return VideoSource{handle == 0 ? 0 : CopySource(handle, &m_status)};
+}
+
+inline VideoProperty VideoSink::GetSourceProperty(const wpi::Twine& name) {
+  m_status = 0;
+  return VideoProperty{GetSinkSourceProperty(m_handle, name, &m_status)};
+}
+
+inline bool VideoSink::SetConfigJson(wpi::StringRef config) {
+  m_status = 0;
+  return SetSinkConfigJson(m_handle, config, &m_status);
+}
+
+inline bool VideoSink::SetConfigJson(const wpi::json& config) {
+  m_status = 0;
+  return SetSinkConfigJson(m_handle, config, &m_status);
+}
+
+inline std::string VideoSink::GetConfigJson() const {
+  m_status = 0;
+  return GetSinkConfigJson(m_handle, &m_status);
+}
+
+inline MjpegServer::MjpegServer(const wpi::Twine& name,
+                                const wpi::Twine& listenAddress, int port) {
+  m_handle = CreateMjpegServer(name, listenAddress, port, &m_status);
+}
+
+inline std::string MjpegServer::GetListenAddress() const {
+  m_status = 0;
+  return cs::GetMjpegServerListenAddress(m_handle, &m_status);
+}
+
+inline int MjpegServer::GetPort() const {
+  m_status = 0;
+  return cs::GetMjpegServerPort(m_handle, &m_status);
+}
+
+inline void MjpegServer::SetResolution(int width, int height) {
+  m_status = 0;
+  SetProperty(GetSinkProperty(m_handle, "width", &m_status), width, &m_status);
+  SetProperty(GetSinkProperty(m_handle, "height", &m_status), height,
+              &m_status);
+}
+
+inline void MjpegServer::SetFPS(int fps) {
+  m_status = 0;
+  SetProperty(GetSinkProperty(m_handle, "fps", &m_status), fps, &m_status);
+}
+
+inline void MjpegServer::SetCompression(int quality) {
+  m_status = 0;
+  SetProperty(GetSinkProperty(m_handle, "compression", &m_status), quality,
+              &m_status);
+}
+
+inline void MjpegServer::SetDefaultCompression(int quality) {
+  m_status = 0;
+  SetProperty(GetSinkProperty(m_handle, "default_compression", &m_status),
+              quality, &m_status);
+}
+
+inline CvSink::CvSink(const wpi::Twine& name) {
+  m_handle = CreateCvSink(name, &m_status);
+}
+
+inline CvSink::CvSink(const wpi::Twine& name,
+                      std::function<void(uint64_t time)> processFrame) {
+  m_handle = CreateCvSinkCallback(name, processFrame, &m_status);
+}
+
+inline void CvSink::SetDescription(const wpi::Twine& description) {
+  m_status = 0;
+  SetSinkDescription(m_handle, description, &m_status);
+}
+
+inline uint64_t CvSink::GrabFrame(cv::Mat& image, double timeout) const {
+  m_status = 0;
+  return GrabSinkFrameTimeout(m_handle, image, timeout, &m_status);
+}
+
+inline uint64_t CvSink::GrabFrameNoTimeout(cv::Mat& image) const {
+  m_status = 0;
+  return GrabSinkFrame(m_handle, image, &m_status);
+}
+
+inline std::string CvSink::GetError() const {
+  m_status = 0;
+  return GetSinkError(m_handle, &m_status);
+}
+
+inline void CvSink::SetEnabled(bool enabled) {
+  m_status = 0;
+  SetSinkEnabled(m_handle, enabled, &m_status);
+}
+
+inline VideoSource VideoEvent::GetSource() const {
+  CS_Status status = 0;
+  return VideoSource{sourceHandle == 0 ? 0 : CopySource(sourceHandle, &status)};
+}
+
+inline VideoSink VideoEvent::GetSink() const {
+  CS_Status status = 0;
+  return VideoSink{sinkHandle == 0 ? 0 : CopySink(sinkHandle, &status)};
+}
+
+inline VideoProperty VideoEvent::GetProperty() const {
+  return VideoProperty{propertyHandle,
+                       static_cast<VideoProperty::Kind>(propertyKind)};
+}
+
+inline VideoListener::VideoListener(
+    std::function<void(const VideoEvent& event)> callback, int eventMask,
+    bool immediateNotify) {
+  CS_Status status = 0;
+  m_handle = AddListener(
+      [=](const RawEvent& event) {
+        callback(static_cast<const VideoEvent&>(event));
+      },
+      eventMask, immediateNotify, &status);
+}
+
+inline VideoListener::VideoListener(VideoListener&& other) noexcept
+    : VideoListener() {
+  swap(*this, other);
+}
+
+inline VideoListener& VideoListener::operator=(VideoListener&& other) noexcept {
+  swap(*this, other);
+  return *this;
+}
+
+inline VideoListener::~VideoListener() {
+  CS_Status status = 0;
+  if (m_handle != 0) RemoveListener(m_handle, &status);
+}
+
+}  // namespace cs
+
+#endif  /* CSCORE_OO_INL_ */
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/NetworkListener.cpp b/third_party/allwpilib_2019/cscore/src/main/native/linux/NetworkListener.cpp
new file mode 100644
index 0000000..ed3d966
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/NetworkListener.cpp
@@ -0,0 +1,147 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "NetworkListener.h"
+
+#include <linux/netlink.h>
+#include <linux/rtnetlink.h>
+#include <sys/eventfd.h>
+#include <sys/select.h>
+#include <sys/socket.h>
+#include <sys/time.h>
+#include <sys/types.h>
+#include <unistd.h>
+
+#include <cerrno>
+
+#include <wpi/SafeThread.h>
+
+#include "Log.h"
+#include "Notifier.h"
+
+using namespace cs;
+
+class NetworkListener::Impl {
+ public:
+  Impl(wpi::Logger& logger, Notifier& notifier)
+      : m_logger(logger), m_notifier(notifier) {}
+
+  wpi::Logger& m_logger;
+  Notifier& m_notifier;
+
+  class Thread : public wpi::SafeThread {
+   public:
+    Thread(wpi::Logger& logger, Notifier& notifier)
+        : m_logger(logger), m_notifier(notifier) {}
+    void Main();
+
+    wpi::Logger& m_logger;
+    Notifier& m_notifier;
+    int m_command_fd = -1;
+  };
+
+  wpi::SafeThreadOwner<Thread> m_owner;
+};
+
+NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier)
+    : m_impl(std::make_unique<Impl>(logger, notifier)) {}
+
+NetworkListener::~NetworkListener() { Stop(); }
+
+void NetworkListener::Start() {
+  m_impl->m_owner.Start(m_impl->m_logger, m_impl->m_notifier);
+}
+
+void NetworkListener::Stop() {
+  // Wake up thread
+  if (auto thr = m_impl->m_owner.GetThread()) {
+    thr->m_active = false;
+    if (thr->m_command_fd >= 0) eventfd_write(thr->m_command_fd, 1);
+  }
+  m_impl->m_owner.Stop();
+}
+
+void NetworkListener::Impl::Thread::Main() {
+  // Create event socket so we can be shut down
+  m_command_fd = ::eventfd(0, 0);
+  if (m_command_fd < 0) {
+    ERROR(
+        "NetworkListener: could not create eventfd: " << std::strerror(errno));
+    return;
+  }
+
+  // Create netlink socket
+  int sd = ::socket(AF_NETLINK, SOCK_RAW, NETLINK_ROUTE);
+  if (sd < 0) {
+    ERROR("NetworkListener: could not create socket: " << std::strerror(errno));
+    ::close(m_command_fd);
+    m_command_fd = -1;
+    return;
+  }
+
+  // Bind to netlink socket
+  struct sockaddr_nl addr;
+  std::memset(&addr, 0, sizeof(addr));
+  addr.nl_family = AF_NETLINK;
+  addr.nl_groups = RTMGRP_LINK | RTMGRP_IPV4_IFADDR;
+  if (bind(sd, reinterpret_cast<struct sockaddr*>(&addr), sizeof(addr)) < 0) {
+    ERROR("NetworkListener: could not create socket: " << std::strerror(errno));
+    ::close(sd);
+    ::close(m_command_fd);
+    m_command_fd = -1;
+    return;
+  }
+
+  char buf[4096];
+
+  while (m_active) {
+    // select timeout
+    struct timeval tv;
+    tv.tv_sec = 10;
+    tv.tv_usec = 0;
+
+    // select on applicable read descriptors
+    fd_set readfds;
+    FD_ZERO(&readfds);
+    FD_SET(m_command_fd, &readfds);
+    FD_SET(sd, &readfds);
+    int nfds = std::max(m_command_fd, sd) + 1;
+
+    if (::select(nfds, &readfds, nullptr, nullptr, &tv) < 0) {
+      ERROR("NetworkListener: select(): " << std::strerror(errno));
+      break;  // XXX: is this the right thing to do here?
+    }
+
+    // Double-check to see if we're shutting down
+    if (!m_active) break;
+
+    if (!FD_ISSET(sd, &readfds)) continue;
+
+    std::memset(&addr, 0, sizeof(addr));
+    struct iovec iov = {buf, sizeof(buf)};
+    struct msghdr msg = {&addr, sizeof(addr), &iov, 1, nullptr, 0, 0};
+    int len = ::recvmsg(sd, &msg, 0);
+    if (len < 0) {
+      if (errno == EWOULDBLOCK || errno == EAGAIN) continue;
+      ERROR(
+          "NetworkListener: could not read netlink: " << std::strerror(errno));
+      break;  // XXX: is this the right thing to do here?
+    }
+    if (len == 0) continue;  // EOF?
+    for (struct nlmsghdr* nh = reinterpret_cast<struct nlmsghdr*>(buf);
+         NLMSG_OK(nh, len); nh = NLMSG_NEXT(nh, len)) {
+      if (nh->nlmsg_type == NLMSG_DONE) break;
+      if (nh->nlmsg_type == RTM_NEWLINK || nh->nlmsg_type == RTM_DELLINK ||
+          nh->nlmsg_type == RTM_NEWADDR || nh->nlmsg_type == RTM_DELADDR) {
+        m_notifier.NotifyNetworkInterfacesChanged();
+      }
+    }
+  }
+  ::close(sd);
+  ::close(m_command_fd);
+  m_command_fd = -1;
+}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/NetworkUtil.cpp b/third_party/allwpilib_2019/cscore/src/main/native/linux/NetworkUtil.cpp
new file mode 100644
index 0000000..2c1f3cd
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/NetworkUtil.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "cscore_cpp.h"  // NOLINT(build/include_order)
+
+#include <arpa/inet.h>
+#include <ifaddrs.h>
+#include <sys/types.h>
+#include <unistd.h>
+
+namespace cs {
+
+std::vector<std::string> GetNetworkInterfaces() {
+  struct ifaddrs* ifa;
+  if (::getifaddrs(&ifa) != 0) return std::vector<std::string>{};
+
+  std::vector<std::string> rv;
+  char buf[256];
+  for (struct ifaddrs* i = ifa; i; i = i->ifa_next) {
+    if (!i->ifa_addr) continue;                       // no address
+    if (i->ifa_addr->sa_family != AF_INET) continue;  // only return IPv4
+    struct sockaddr_in* addr_in = reinterpret_cast<sockaddr_in*>(i->ifa_addr);
+    const char* addr =
+        ::inet_ntop(addr_in->sin_family, &addr_in->sin_addr, buf, sizeof(buf));
+    if (!addr) continue;  // error converting address
+    rv.emplace_back(addr);
+  }
+
+  ::freeifaddrs(ifa);
+  return rv;
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraBuffer.h b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraBuffer.h
new file mode 100644
index 0000000..98ac149
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraBuffer.h
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBCAMERABUFFER_H_
+#define CSCORE_USBCAMERABUFFER_H_
+
+#include <sys/mman.h>
+
+#include <utility>
+
+namespace cs {
+
+class UsbCameraBuffer {
+ public:
+  UsbCameraBuffer() noexcept : m_data{nullptr}, m_length{0} {}
+  UsbCameraBuffer(UsbCameraBuffer&& other) noexcept : UsbCameraBuffer() {
+    swap(*this, other);
+  }
+  UsbCameraBuffer& operator=(UsbCameraBuffer&& other) noexcept {
+    swap(*this, other);
+    return *this;
+  }
+  UsbCameraBuffer(const UsbCameraBuffer&) = delete;
+  UsbCameraBuffer& operator=(const UsbCameraBuffer&) = delete;
+
+  UsbCameraBuffer(int fd, size_t length, off_t offset) noexcept
+      : m_length{length} {
+    m_data =
+        mmap(nullptr, length, PROT_READ | PROT_WRITE, MAP_SHARED, fd, offset);
+    if (m_data == MAP_FAILED) {
+      m_data = nullptr;
+      m_length = 0;
+    }
+  }
+
+  ~UsbCameraBuffer() {
+    if (m_data) munmap(m_data, m_length);
+  }
+
+  friend void swap(UsbCameraBuffer& first, UsbCameraBuffer& second) noexcept {
+    using std::swap;
+    swap(first.m_data, second.m_data);
+    swap(first.m_length, second.m_length);
+  }
+
+  void* m_data;
+  size_t m_length;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_USBCAMERABUFFER_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraImpl.cpp
new file mode 100644
index 0000000..125c936
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraImpl.cpp
@@ -0,0 +1,1408 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "UsbCameraImpl.h"
+
+#include <dirent.h>
+#include <fcntl.h>
+#include <libgen.h>
+#include <linux/kernel.h>
+#include <linux/types.h>
+#include <linux/videodev2.h>
+#include <sys/eventfd.h>
+#include <sys/inotify.h>
+#include <sys/ioctl.h>
+#include <sys/select.h>
+#include <sys/stat.h>
+#include <sys/time.h>
+#include <sys/types.h>
+#include <unistd.h>
+
+#include <algorithm>
+
+#include <wpi/FileSystem.h>
+#include <wpi/Path.h>
+#include <wpi/SmallString.h>
+#include <wpi/memory.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "Instance.h"
+#include "JpegUtil.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "Telemetry.h"
+#include "UsbUtil.h"
+#include "cscore_cpp.h"
+
+using namespace cs;
+
+static constexpr char const* kPropWbAuto = "white_balance_temperature_auto";
+static constexpr char const* kPropWbValue = "white_balance_temperature";
+static constexpr char const* kPropExAuto = "exposure_auto";
+static constexpr char const* kPropExValue = "exposure_absolute";
+static constexpr char const* kPropBrValue = "brightness";
+static constexpr char const* kPropConnectVerbose = "connect_verbose";
+static constexpr unsigned kPropConnectVerboseId = 0;
+
+// Conversions v4l2_fract time per frame from/to frames per second (fps)
+static inline int FractToFPS(const struct v4l2_fract& timeperframe) {
+  return (1.0 * timeperframe.denominator) / timeperframe.numerator;
+}
+
+static inline struct v4l2_fract FPSToFract(int fps) {
+  struct v4l2_fract timeperframe;
+  timeperframe.numerator = 1;
+  timeperframe.denominator = fps;
+  return timeperframe;
+}
+
+// Conversion from v4l2_format pixelformat to VideoMode::PixelFormat
+static VideoMode::PixelFormat ToPixelFormat(__u32 pixelFormat) {
+  switch (pixelFormat) {
+    case V4L2_PIX_FMT_MJPEG:
+      return VideoMode::kMJPEG;
+    case V4L2_PIX_FMT_YUYV:
+      return VideoMode::kYUYV;
+    case V4L2_PIX_FMT_RGB565:
+      return VideoMode::kRGB565;
+    case V4L2_PIX_FMT_BGR24:
+      return VideoMode::kBGR;
+    case V4L2_PIX_FMT_GREY:
+      return VideoMode::kGray;
+    default:
+      return VideoMode::kUnknown;
+  }
+}
+
+// Conversion from VideoMode::PixelFormat to v4l2_format pixelformat
+static __u32 FromPixelFormat(VideoMode::PixelFormat pixelFormat) {
+  switch (pixelFormat) {
+    case VideoMode::kMJPEG:
+      return V4L2_PIX_FMT_MJPEG;
+    case VideoMode::kYUYV:
+      return V4L2_PIX_FMT_YUYV;
+    case VideoMode::kRGB565:
+      return V4L2_PIX_FMT_RGB565;
+    case VideoMode::kBGR:
+      return V4L2_PIX_FMT_BGR24;
+    case VideoMode::kGray:
+      return V4L2_PIX_FMT_GREY;
+    default:
+      return 0;
+  }
+}
+
+static bool IsPercentageProperty(wpi::StringRef name) {
+  if (name.startswith("raw_")) name = name.substr(4);
+  return name == "brightness" || name == "contrast" || name == "saturation" ||
+         name == "hue" || name == "sharpness" || name == "gain" ||
+         name == "exposure_absolute";
+}
+
+static constexpr const int quirkLifeCamHd3000[] = {
+    5, 10, 20, 39, 78, 156, 312, 625, 1250, 2500, 5000, 10000, 20000};
+
+int UsbCameraImpl::RawToPercentage(const UsbCameraProperty& rawProp,
+                                   int rawValue) {
+  // LifeCam exposure setting quirk
+  if (m_lifecam_exposure && rawProp.name == "raw_exposure_absolute" &&
+      rawProp.minimum == 5 && rawProp.maximum == 20000) {
+    int nelems = wpi::array_lengthof(quirkLifeCamHd3000);
+    for (int i = 0; i < nelems; ++i) {
+      if (rawValue < quirkLifeCamHd3000[i]) return 100.0 * i / nelems;
+    }
+    return 100;
+  }
+  return 100.0 * (rawValue - rawProp.minimum) /
+         (rawProp.maximum - rawProp.minimum);
+}
+
+int UsbCameraImpl::PercentageToRaw(const UsbCameraProperty& rawProp,
+                                   int percentValue) {
+  // LifeCam exposure setting quirk
+  if (m_lifecam_exposure && rawProp.name == "raw_exposure_absolute" &&
+      rawProp.minimum == 5 && rawProp.maximum == 20000) {
+    int nelems = wpi::array_lengthof(quirkLifeCamHd3000);
+    int ndx = nelems * percentValue / 100.0;
+    if (ndx < 0) ndx = 0;
+    if (ndx >= nelems) ndx = nelems - 1;
+    return quirkLifeCamHd3000[ndx];
+  }
+  return rawProp.minimum +
+         (rawProp.maximum - rawProp.minimum) * (percentValue / 100.0);
+}
+
+static bool GetDescriptionSysV4L(wpi::StringRef path, std::string* desc) {
+  wpi::SmallString<64> ifpath{"/sys/class/video4linux/"};
+  ifpath += path.substr(5);
+  ifpath += "/device/interface";
+
+  int fd = open(ifpath.c_str(), O_RDONLY);
+  if (fd < 0) return false;
+
+  char readBuf[128];
+  ssize_t n = read(fd, readBuf, sizeof(readBuf));
+  close(fd);
+
+  if (n <= 0) return false;
+
+  *desc = wpi::StringRef(readBuf, n).rtrim();
+  return true;
+}
+
+static bool GetDescriptionIoctl(const char* cpath, std::string* desc) {
+  int fd = open(cpath, O_RDWR);
+  if (fd < 0) return false;
+
+  struct v4l2_capability vcap;
+  std::memset(&vcap, 0, sizeof(vcap));
+  if (DoIoctl(fd, VIDIOC_QUERYCAP, &vcap) < 0) {
+    close(fd);
+    return false;
+  }
+  close(fd);
+
+  wpi::StringRef card{reinterpret_cast<const char*>(vcap.card)};
+  // try to convert "UVC Camera (0000:0000)" into a better name
+  int vendor = 0;
+  int product = 0;
+  if (card.startswith("UVC Camera (") &&
+      !card.substr(12, 4).getAsInteger(16, vendor) &&
+      !card.substr(17, 4).getAsInteger(16, product)) {
+    wpi::SmallString<64> card2Buf;
+    wpi::StringRef card2 = GetUsbNameFromId(vendor, product, card2Buf);
+    if (!card2.empty()) {
+      *desc = card2;
+      return true;
+    }
+  }
+
+  *desc = card;
+  return true;
+}
+
+static std::string GetDescriptionImpl(const char* cpath) {
+  wpi::StringRef path{cpath};
+  char pathBuf[128];
+  std::string rv;
+
+  // If trying to get by id or path, follow symlink
+  if (path.startswith("/dev/v4l/by-id/")) {
+    ssize_t n = readlink(cpath, pathBuf, sizeof(pathBuf));
+    if (n > 0) path = wpi::StringRef(pathBuf, n);
+  } else if (path.startswith("/dev/v4l/by-path/")) {
+    ssize_t n = readlink(cpath, pathBuf, sizeof(pathBuf));
+    if (n > 0) path = wpi::StringRef(pathBuf, n);
+  }
+
+  if (path.startswith("/dev/video")) {
+    // Sometimes the /sys tree gives a better name.
+    if (GetDescriptionSysV4L(path, &rv)) return rv;
+  }
+
+  // Otherwise use an ioctl to query the caps and get the card name
+  if (GetDescriptionIoctl(cpath, &rv)) return rv;
+
+  return std::string{};
+}
+
+UsbCameraImpl::UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             const wpi::Twine& path)
+    : SourceImpl{name, logger, notifier, telemetry},
+      m_path{path.str()},
+      m_fd{-1},
+      m_command_fd{eventfd(0, 0)},
+      m_active{true} {
+  SetDescription(GetDescriptionImpl(m_path.c_str()));
+  SetQuirks();
+
+  CreateProperty(kPropConnectVerbose, [] {
+    return std::make_unique<UsbCameraProperty>(kPropConnectVerbose,
+                                               kPropConnectVerboseId,
+                                               CS_PROP_INTEGER, 0, 1, 1, 1, 1);
+  });
+}
+
+UsbCameraImpl::~UsbCameraImpl() {
+  m_active = false;
+
+  // Just in case anyone is waiting...
+  m_responseCv.notify_all();
+
+  // Send message to wake up thread; select timeout will wake us up anyway,
+  // but this speeds shutdown.
+  Send(Message{Message::kNone});
+
+  // join camera thread
+  if (m_cameraThread.joinable()) m_cameraThread.join();
+
+  // close command fd
+  int fd = m_command_fd.exchange(-1);
+  if (fd >= 0) close(fd);
+}
+
+static inline void DoFdSet(int fd, fd_set* set, int* nfds) {
+  if (fd >= 0) {
+    FD_SET(fd, set);
+    if ((fd + 1) > *nfds) *nfds = fd + 1;
+  }
+}
+
+void UsbCameraImpl::Start() {
+  // Kick off the camera thread
+  m_cameraThread = std::thread(&UsbCameraImpl::CameraThreadMain, this);
+}
+
+void UsbCameraImpl::CameraThreadMain() {
+  // We want to be notified on file creation and deletion events in the device
+  // path.  This is used to detect disconnects and reconnects.
+  std::unique_ptr<wpi::raw_fd_istream> notify_is;
+  int notify_fd = inotify_init();
+  if (notify_fd >= 0) {
+    // need to make a copy as dirname can modify it
+    wpi::SmallString<64> pathCopy{m_path};
+    pathCopy.push_back('\0');
+    if (inotify_add_watch(notify_fd, dirname(pathCopy.data()),
+                          IN_CREATE | IN_DELETE) < 0) {
+      close(notify_fd);
+      notify_fd = -1;
+    } else {
+      notify_is.reset(new wpi::raw_fd_istream{
+          notify_fd, true, sizeof(struct inotify_event) + NAME_MAX + 1});
+    }
+  }
+  bool notified = (notify_fd < 0);  // treat as always notified if cannot notify
+
+  // Get the basename for later notify use
+  wpi::SmallString<64> pathCopy{m_path};
+  pathCopy.push_back('\0');
+  wpi::SmallString<64> base{basename(pathCopy.data())};
+
+  // Used to restart streaming on reconnect
+  bool wasStreaming = false;
+
+  // Default to not streaming
+  m_streaming = false;
+
+  while (m_active) {
+    // If not connected, try to reconnect
+    if (m_fd < 0) DeviceConnect();
+
+    // Make copies of fd's in case they go away
+    int command_fd = m_command_fd.load();
+    int fd = m_fd.load();
+    if (!m_active) break;
+
+    // Reset notified flag and restart streaming if necessary
+    if (fd >= 0) {
+      notified = (notify_fd < 0);
+      if (wasStreaming && !m_streaming) {
+        DeviceStreamOn();
+        wasStreaming = false;
+      }
+    }
+
+    // Turn off streaming if not enabled, and turn it on if enabled
+    if (m_streaming && !IsEnabled()) {
+      DeviceStreamOff();
+    } else if (!m_streaming && IsEnabled()) {
+      DeviceStreamOn();
+    }
+
+    // The select timeout can be long unless we're trying to reconnect
+    struct timeval tv;
+    if (fd < 0 && notified) {
+      tv.tv_sec = 0;
+      tv.tv_usec = 300000;
+    } else {
+      tv.tv_sec = 2;
+      tv.tv_usec = 0;
+    }
+
+    // select on applicable read descriptors
+    int nfds = 0;
+    fd_set readfds;
+    FD_ZERO(&readfds);
+    DoFdSet(command_fd, &readfds, &nfds);
+    if (m_streaming) DoFdSet(fd, &readfds, &nfds);
+    DoFdSet(notify_fd, &readfds, &nfds);
+
+    if (select(nfds, &readfds, nullptr, nullptr, &tv) < 0) {
+      SERROR("select(): " << std::strerror(errno));
+      break;  // XXX: is this the right thing to do here?
+    }
+
+    // Double-check to see if we're shutting down
+    if (!m_active) break;
+
+    // Handle notify events
+    if (notify_fd >= 0 && FD_ISSET(notify_fd, &readfds)) {
+      SDEBUG4("notify event");
+      struct inotify_event event;
+      do {
+        // Read the event structure
+        notify_is->read(&event, sizeof(event));
+        // Read the event name
+        wpi::SmallString<64> raw_name;
+        raw_name.resize(event.len);
+        notify_is->read(raw_name.data(), event.len);
+        // If the name is what we expect...
+        wpi::StringRef name{raw_name.c_str()};
+        SDEBUG4("got event on '" << name << "' (" << name.size()
+                                 << ") compare to '" << base << "' ("
+                                 << base.size() << ") mask " << event.mask);
+        if (name == base) {
+          if ((event.mask & IN_DELETE) != 0) {
+            wasStreaming = m_streaming;
+            DeviceStreamOff();
+            DeviceDisconnect();
+          } else if ((event.mask & IN_CREATE) != 0) {
+            notified = true;
+          }
+        }
+      } while (!notify_is->has_error() &&
+               notify_is->in_avail() >= sizeof(event));
+      continue;
+    }
+
+    // Handle commands
+    if (command_fd >= 0 && FD_ISSET(command_fd, &readfds)) {
+      SDEBUG4("got command");
+      // Read it to clear
+      eventfd_t val;
+      eventfd_read(command_fd, &val);
+      DeviceProcessCommands();
+      continue;
+    }
+
+    // Handle frames
+    if (m_streaming && fd >= 0 && FD_ISSET(fd, &readfds)) {
+      SDEBUG4("grabbing image");
+
+      // Dequeue buffer
+      struct v4l2_buffer buf;
+      std::memset(&buf, 0, sizeof(buf));
+      buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+      buf.memory = V4L2_MEMORY_MMAP;
+      if (DoIoctl(fd, VIDIOC_DQBUF, &buf) != 0) {
+        SWARNING("could not dequeue buffer");
+        wasStreaming = m_streaming;
+        DeviceStreamOff();
+        DeviceDisconnect();
+        notified = true;  // device wasn't deleted, just error'ed
+        continue;         // will reconnect
+      }
+
+      if ((buf.flags & V4L2_BUF_FLAG_ERROR) == 0) {
+        SDEBUG4("got image size=" << buf.bytesused << " index=" << buf.index);
+
+        if (buf.index >= kNumBuffers || !m_buffers[buf.index].m_data) {
+          SWARNING("invalid buffer" << buf.index);
+          continue;
+        }
+
+        wpi::StringRef image{
+            static_cast<const char*>(m_buffers[buf.index].m_data),
+            static_cast<size_t>(buf.bytesused)};
+        int width = m_mode.width;
+        int height = m_mode.height;
+        bool good = true;
+        if (m_mode.pixelFormat == VideoMode::kMJPEG &&
+            !GetJpegSize(image, &width, &height)) {
+          SWARNING("invalid JPEG image received from camera");
+          good = false;
+        }
+        if (good) {
+          PutFrame(static_cast<VideoMode::PixelFormat>(m_mode.pixelFormat),
+                   width, height, image, wpi::Now());  // TODO: time
+        }
+      }
+
+      // Requeue buffer
+      if (DoIoctl(fd, VIDIOC_QBUF, &buf) != 0) {
+        SWARNING("could not requeue buffer");
+        wasStreaming = m_streaming;
+        DeviceStreamOff();
+        DeviceDisconnect();
+        notified = true;  // device wasn't deleted, just error'ed
+        continue;         // will reconnect
+      }
+    }
+  }
+
+  // close camera connection
+  DeviceStreamOff();
+  DeviceDisconnect();
+}
+
+void UsbCameraImpl::DeviceDisconnect() {
+  int fd = m_fd.exchange(-1);
+  if (fd < 0) return;  // already disconnected
+
+  // Unmap buffers
+  for (int i = 0; i < kNumBuffers; ++i)
+    m_buffers[i] = std::move(UsbCameraBuffer{});
+
+  // Close device
+  close(fd);
+
+  // Notify
+  SetConnected(false);
+}
+
+void UsbCameraImpl::DeviceConnect() {
+  if (m_fd >= 0) return;
+
+  if (m_connectVerbose) SINFO("Connecting to USB camera on " << m_path);
+
+  // Try to open the device
+  SDEBUG3("opening device");
+  int fd = open(m_path.c_str(), O_RDWR);
+  if (fd < 0) return;
+  m_fd = fd;
+
+  // Get capabilities
+  SDEBUG3("getting capabilities");
+  struct v4l2_capability vcap;
+  std::memset(&vcap, 0, sizeof(vcap));
+  if (DoIoctl(fd, VIDIOC_QUERYCAP, &vcap) >= 0) {
+    m_capabilities = vcap.capabilities;
+    if (m_capabilities & V4L2_CAP_DEVICE_CAPS)
+      m_capabilities = vcap.device_caps;
+  }
+
+  // Get or restore video mode
+  if (!m_properties_cached) {
+    SDEBUG3("caching properties");
+    DeviceCacheProperties();
+    DeviceCacheVideoModes();
+    DeviceCacheMode();
+    m_properties_cached = true;
+  } else {
+    SDEBUG3("restoring video mode");
+    DeviceSetMode();
+    DeviceSetFPS();
+
+    // Restore settings
+    SDEBUG3("restoring settings");
+    std::unique_lock<wpi::mutex> lock2(m_mutex);
+    for (size_t i = 0; i < m_propertyData.size(); ++i) {
+      const auto prop =
+          static_cast<const UsbCameraProperty*>(m_propertyData[i].get());
+      if (!prop || !prop->valueSet || !prop->device || prop->percentage)
+        continue;
+      if (!prop->DeviceSet(lock2, m_fd))
+        SWARNING("failed to set property " << prop->name);
+    }
+  }
+
+  // Request buffers
+  SDEBUG3("allocating buffers");
+  struct v4l2_requestbuffers rb;
+  std::memset(&rb, 0, sizeof(rb));
+  rb.count = kNumBuffers;
+  rb.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  rb.memory = V4L2_MEMORY_MMAP;
+  if (DoIoctl(fd, VIDIOC_REQBUFS, &rb) != 0) {
+    SWARNING("could not allocate buffers");
+    close(fd);
+    m_fd = -1;
+    return;
+  }
+
+  // Map buffers
+  SDEBUG3("mapping buffers");
+  for (int i = 0; i < kNumBuffers; ++i) {
+    struct v4l2_buffer buf;
+    std::memset(&buf, 0, sizeof(buf));
+    buf.index = i;
+    buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+    buf.memory = V4L2_MEMORY_MMAP;
+    if (DoIoctl(fd, VIDIOC_QUERYBUF, &buf) != 0) {
+      SWARNING("could not query buffer " << i);
+      close(fd);
+      m_fd = -1;
+      return;
+    }
+    SDEBUG4("buf " << i << " length=" << buf.length
+                   << " offset=" << buf.m.offset);
+
+    m_buffers[i] = std::move(UsbCameraBuffer(fd, buf.length, buf.m.offset));
+    if (!m_buffers[i].m_data) {
+      SWARNING("could not map buffer " << i);
+      // release other buffers
+      for (int j = 0; j < i; ++j) m_buffers[j] = std::move(UsbCameraBuffer{});
+      close(fd);
+      m_fd = -1;
+      return;
+    }
+
+    SDEBUG4("buf " << i << " address=" << m_buffers[i].m_data);
+  }
+
+  // Update description (as it may have changed)
+  SetDescription(GetDescriptionImpl(m_path.c_str()));
+
+  // Update quirks settings
+  SetQuirks();
+
+  // Notify
+  SetConnected(true);
+}
+
+bool UsbCameraImpl::DeviceStreamOn() {
+  if (m_streaming) return false;  // ignore if already enabled
+  int fd = m_fd.load();
+  if (fd < 0) return false;
+
+  // Queue buffers
+  SDEBUG3("queuing buffers");
+  for (int i = 0; i < kNumBuffers; ++i) {
+    struct v4l2_buffer buf;
+    std::memset(&buf, 0, sizeof(buf));
+    buf.index = i;
+    buf.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+    buf.memory = V4L2_MEMORY_MMAP;
+    if (DoIoctl(fd, VIDIOC_QBUF, &buf) != 0) {
+      SWARNING("could not queue buffer " << i);
+      return false;
+    }
+  }
+
+  // Turn stream on
+  int type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (TryIoctl(fd, VIDIOC_STREAMON, &type) < 0) {
+    if (errno == ENOSPC) {
+      // indicates too much USB bandwidth requested
+      SERROR(
+          "could not start streaming due to USB bandwidth limitations; try a "
+          "lower resolution or a different pixel format (VIDIOC_STREAMON: "
+          "No space left on device)");
+    } else {
+      // some other error
+      SERROR("ioctl VIDIOC_STREAMON failed: " << std::strerror(errno));
+    }
+    return false;
+  }
+  SDEBUG4("enabled streaming");
+  m_streaming = true;
+  return true;
+}
+
+bool UsbCameraImpl::DeviceStreamOff() {
+  if (!m_streaming) return false;  // ignore if already disabled
+  int fd = m_fd.load();
+  if (fd < 0) return false;
+  int type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (DoIoctl(fd, VIDIOC_STREAMOFF, &type) != 0) return false;
+  SDEBUG4("disabled streaming");
+  m_streaming = false;
+  return true;
+}
+
+CS_StatusValue UsbCameraImpl::DeviceCmdSetMode(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  VideoMode newMode;
+  if (msg.kind == Message::kCmdSetMode) {
+    newMode.pixelFormat = msg.data[0];
+    newMode.width = msg.data[1];
+    newMode.height = msg.data[2];
+    newMode.fps = msg.data[3];
+    m_modeSetPixelFormat = true;
+    m_modeSetResolution = true;
+    m_modeSetFPS = true;
+  } else if (msg.kind == Message::kCmdSetPixelFormat) {
+    newMode = m_mode;
+    newMode.pixelFormat = msg.data[0];
+    m_modeSetPixelFormat = true;
+  } else if (msg.kind == Message::kCmdSetResolution) {
+    newMode = m_mode;
+    newMode.width = msg.data[0];
+    newMode.height = msg.data[1];
+    m_modeSetResolution = true;
+  } else if (msg.kind == Message::kCmdSetFPS) {
+    newMode = m_mode;
+    newMode.fps = msg.data[0];
+    m_modeSetFPS = true;
+  }
+
+  // If the pixel format or resolution changed, we need to disconnect and
+  // reconnect
+  if (newMode.pixelFormat != m_mode.pixelFormat ||
+      newMode.width != m_mode.width || newMode.height != m_mode.height) {
+    m_mode = newMode;
+    lock.unlock();
+    bool wasStreaming = m_streaming;
+    if (wasStreaming) DeviceStreamOff();
+    if (m_fd >= 0) {
+      DeviceDisconnect();
+      DeviceConnect();
+    }
+    if (wasStreaming) DeviceStreamOn();
+    m_notifier.NotifySourceVideoMode(*this, newMode);
+    lock.lock();
+  } else if (newMode.fps != m_mode.fps) {
+    m_mode = newMode;
+    lock.unlock();
+    // Need to stop streaming to set FPS
+    bool wasStreaming = m_streaming;
+    if (wasStreaming) DeviceStreamOff();
+    DeviceSetFPS();
+    if (wasStreaming) DeviceStreamOn();
+    m_notifier.NotifySourceVideoMode(*this, newMode);
+    lock.lock();
+  }
+
+  return CS_OK;
+}
+
+CS_StatusValue UsbCameraImpl::DeviceCmdSetProperty(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  bool setString = (msg.kind == Message::kCmdSetPropertyStr);
+  int property = msg.data[0];
+  int value = msg.data[1];
+  wpi::StringRef valueStr = msg.dataStr;
+
+  // Look up
+  auto prop = static_cast<UsbCameraProperty*>(GetProperty(property));
+  if (!prop) return CS_INVALID_PROPERTY;
+
+  // If setting before we get, guess initial type based on set
+  if (prop->propKind == CS_PROP_NONE) {
+    if (setString)
+      prop->propKind = CS_PROP_STRING;
+    else
+      prop->propKind = CS_PROP_INTEGER;
+  }
+
+  // Check kind match
+  if ((setString && prop->propKind != CS_PROP_STRING) ||
+      (!setString && (prop->propKind &
+                      (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) == 0))
+    return CS_WRONG_PROPERTY_TYPE;
+
+  // Handle percentage property
+  int percentageProperty = prop->propPair;
+  int percentageValue = value;
+  if (percentageProperty != 0) {
+    if (prop->percentage) {
+      std::swap(percentageProperty, property);
+      prop = static_cast<UsbCameraProperty*>(GetProperty(property));
+      value = PercentageToRaw(*prop, percentageValue);
+    } else {
+      percentageValue = RawToPercentage(*prop, value);
+    }
+  }
+
+  // Actually set the new value on the device (if possible)
+  if (!prop->device) {
+    if (prop->id == kPropConnectVerboseId) m_connectVerbose = value;
+  } else {
+    if (!prop->DeviceSet(lock, m_fd, value, valueStr))
+      return CS_PROPERTY_WRITE_FAILED;
+  }
+
+  // Cache the set values
+  UpdatePropertyValue(property, setString, value, valueStr);
+  if (percentageProperty != 0)
+    UpdatePropertyValue(percentageProperty, setString, percentageValue,
+                        valueStr);
+
+  return CS_OK;
+}
+
+CS_StatusValue UsbCameraImpl::DeviceProcessCommand(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  if (msg.kind == Message::kCmdSetMode ||
+      msg.kind == Message::kCmdSetPixelFormat ||
+      msg.kind == Message::kCmdSetResolution ||
+      msg.kind == Message::kCmdSetFPS) {
+    return DeviceCmdSetMode(lock, msg);
+  } else if (msg.kind == Message::kCmdSetProperty ||
+             msg.kind == Message::kCmdSetPropertyStr) {
+    return DeviceCmdSetProperty(lock, msg);
+  } else if (msg.kind == Message::kNumSinksChanged ||
+             msg.kind == Message::kNumSinksEnabledChanged) {
+    return CS_OK;
+  } else {
+    return CS_OK;
+  }
+}
+
+void UsbCameraImpl::DeviceProcessCommands() {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (m_commands.empty()) return;
+  while (!m_commands.empty()) {
+    auto msg = std::move(m_commands.back());
+    m_commands.pop_back();
+
+    CS_StatusValue status = DeviceProcessCommand(lock, msg);
+    if (msg.kind != Message::kNumSinksChanged &&
+        msg.kind != Message::kNumSinksEnabledChanged)
+      m_responses.emplace_back(msg.from, status);
+  }
+  lock.unlock();
+  m_responseCv.notify_all();
+}
+
+void UsbCameraImpl::DeviceSetMode() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+  struct v4l2_format vfmt;
+  std::memset(&vfmt, 0, sizeof(vfmt));
+#ifdef V4L2_CAP_EXT_PIX_FORMAT
+  vfmt.fmt.pix.priv = (m_capabilities & V4L2_CAP_EXT_PIX_FORMAT) != 0
+                          ? V4L2_PIX_FMT_PRIV_MAGIC
+                          : 0;
+#endif
+  vfmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  vfmt.fmt.pix.pixelformat =
+      FromPixelFormat(static_cast<VideoMode::PixelFormat>(m_mode.pixelFormat));
+  if (vfmt.fmt.pix.pixelformat == 0) {
+    SWARNING("could not set format " << m_mode.pixelFormat
+                                     << ", defaulting to MJPEG");
+    vfmt.fmt.pix.pixelformat = V4L2_PIX_FMT_MJPEG;
+  }
+  vfmt.fmt.pix.width = m_mode.width;
+  vfmt.fmt.pix.height = m_mode.height;
+  vfmt.fmt.pix.field = V4L2_FIELD_ANY;
+  if (DoIoctl(fd, VIDIOC_S_FMT, &vfmt) != 0) {
+    SWARNING("could not set format " << m_mode.pixelFormat << " res "
+                                     << m_mode.width << "x" << m_mode.height);
+  } else {
+    SINFO("set format " << m_mode.pixelFormat << " res " << m_mode.width << "x"
+                        << m_mode.height);
+  }
+}
+
+void UsbCameraImpl::DeviceSetFPS() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+  struct v4l2_streamparm parm;
+  std::memset(&parm, 0, sizeof(parm));
+  parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (DoIoctl(fd, VIDIOC_G_PARM, &parm) != 0) return;
+  if ((parm.parm.capture.capability & V4L2_CAP_TIMEPERFRAME) == 0) return;
+  std::memset(&parm, 0, sizeof(parm));
+  parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  parm.parm.capture.timeperframe = FPSToFract(m_mode.fps);
+  if (DoIoctl(fd, VIDIOC_S_PARM, &parm) != 0)
+    SWARNING("could not set FPS to " << m_mode.fps);
+  else
+    SINFO("set FPS to " << m_mode.fps);
+}
+
+void UsbCameraImpl::DeviceCacheMode() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+  // Get format
+  struct v4l2_format vfmt;
+  std::memset(&vfmt, 0, sizeof(vfmt));
+#ifdef V4L2_CAP_EXT_PIX_FORMAT
+  vfmt.fmt.pix.priv = (m_capabilities & V4L2_CAP_EXT_PIX_FORMAT) != 0
+                          ? V4L2_PIX_FMT_PRIV_MAGIC
+                          : 0;
+#endif
+  vfmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (DoIoctl(fd, VIDIOC_G_FMT, &vfmt) != 0) {
+    SERROR("could not read current video mode");
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_mode = VideoMode{VideoMode::kMJPEG, 320, 240, 30};
+    return;
+  }
+  VideoMode::PixelFormat pixelFormat = ToPixelFormat(vfmt.fmt.pix.pixelformat);
+  int width = vfmt.fmt.pix.width;
+  int height = vfmt.fmt.pix.height;
+
+  // Get FPS
+  int fps = 0;
+  struct v4l2_streamparm parm;
+  std::memset(&parm, 0, sizeof(parm));
+  parm.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  if (TryIoctl(fd, VIDIOC_G_PARM, &parm) == 0) {
+    if (parm.parm.capture.capability & V4L2_CAP_TIMEPERFRAME)
+      fps = FractToFPS(parm.parm.capture.timeperframe);
+  }
+
+  // Update format with user changes.
+  bool formatChanged = false;
+
+  if (m_modeSetPixelFormat) {
+    // User set pixel format
+    if (pixelFormat != m_mode.pixelFormat) {
+      formatChanged = true;
+      pixelFormat = static_cast<VideoMode::PixelFormat>(m_mode.pixelFormat);
+    }
+  } else {
+    // Default to MJPEG
+    if (pixelFormat != VideoMode::kMJPEG) {
+      formatChanged = true;
+      pixelFormat = VideoMode::kMJPEG;
+    }
+  }
+
+  if (m_modeSetResolution) {
+    // User set resolution
+    if (width != m_mode.width || height != m_mode.height) {
+      formatChanged = true;
+      width = m_mode.width;
+      height = m_mode.height;
+    }
+  } else {
+    // Default to lowest known resolution (based on number of total pixels)
+    int numPixels = width * height;
+    for (const auto& mode : m_videoModes) {
+      if (mode.pixelFormat != pixelFormat) continue;
+      int numPixelsHere = mode.width * mode.height;
+      if (numPixelsHere < numPixels) {
+        formatChanged = true;
+        numPixels = numPixelsHere;
+        width = mode.width;
+        height = mode.height;
+      }
+    }
+  }
+
+  // Update FPS with user changes
+  bool fpsChanged = false;
+  if (m_modeSetFPS && fps != m_mode.fps) {
+    fpsChanged = true;
+    fps = m_mode.fps;
+  }
+
+  // Save to global mode
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_mode.pixelFormat = pixelFormat;
+    m_mode.width = width;
+    m_mode.height = height;
+    m_mode.fps = fps;
+  }
+
+  if (formatChanged) DeviceSetMode();
+  if (fpsChanged) DeviceSetFPS();
+
+  m_notifier.NotifySourceVideoMode(*this, m_mode);
+}
+
+void UsbCameraImpl::DeviceCacheProperty(
+    std::unique_ptr<UsbCameraProperty> rawProp) {
+  // 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
+  // to rename this one as well as create/cache the percentage version.
+  //
+  // This is complicated by the fact that either the percentage version or the
+  // the raw version may have been set previously.  If both were previously set,
+  // the raw version wins.
+  std::unique_ptr<UsbCameraProperty> perProp;
+  if (IsPercentageProperty(rawProp->name)) {
+    perProp =
+        wpi::make_unique<UsbCameraProperty>(rawProp->name, 0, *rawProp, 0, 0);
+    rawProp->name = "raw_" + perProp->name;
+  }
+
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  int* rawIndex = &m_properties[rawProp->name];
+  bool newRaw = *rawIndex == 0;
+  UsbCameraProperty* oldRawProp =
+      newRaw ? nullptr
+             : static_cast<UsbCameraProperty*>(GetProperty(*rawIndex));
+
+  int* perIndex = perProp ? &m_properties[perProp->name] : nullptr;
+  bool newPer = !perIndex || *perIndex == 0;
+  UsbCameraProperty* oldPerProp =
+      newPer ? nullptr
+             : static_cast<UsbCameraProperty*>(GetProperty(*perIndex));
+
+  if (oldRawProp && oldRawProp->valueSet) {
+    // Merge existing raw setting and set percentage from it
+    rawProp->SetValue(oldRawProp->value);
+    rawProp->valueStr = std::move(oldRawProp->valueStr);
+
+    if (perProp) {
+      perProp->SetValue(RawToPercentage(*rawProp, rawProp->value));
+      perProp->valueStr = rawProp->valueStr;  // copy
+    }
+  } else if (oldPerProp && oldPerProp->valueSet) {
+    // Merge existing percentage setting and set raw from it
+    perProp->SetValue(oldPerProp->value);
+    perProp->valueStr = std::move(oldPerProp->valueStr);
+
+    rawProp->SetValue(PercentageToRaw(*rawProp, perProp->value));
+    rawProp->valueStr = perProp->valueStr;  // copy
+  } else {
+    // Read current raw value and set percentage from it
+    if (!rawProp->DeviceGet(lock, m_fd))
+      SWARNING("failed to get property " << rawProp->name);
+
+    if (perProp) {
+      perProp->SetValue(RawToPercentage(*rawProp, rawProp->value));
+      perProp->valueStr = rawProp->valueStr;  // copy
+    }
+  }
+
+  // Set value on device if user-configured
+  if (rawProp->valueSet) {
+    if (!rawProp->DeviceSet(lock, m_fd))
+      SWARNING("failed to set property " << rawProp->name);
+  }
+
+  // Update pointers since we released the lock
+  rawIndex = &m_properties[rawProp->name];
+  perIndex = perProp ? &m_properties[perProp->name] : nullptr;
+
+  // Get pointers before we move the std::unique_ptr values
+  auto rawPropPtr = rawProp.get();
+  auto perPropPtr = perProp.get();
+
+  if (newRaw) {
+    // create a new index
+    *rawIndex = m_propertyData.size() + 1;
+    m_propertyData.emplace_back(std::move(rawProp));
+  } else {
+    // update
+    m_propertyData[*rawIndex - 1] = std::move(rawProp);
+  }
+
+  // Finish setting up percentage property
+  if (perProp) {
+    perProp->propPair = *rawIndex;
+    perProp->defaultValue =
+        RawToPercentage(*rawPropPtr, rawPropPtr->defaultValue);
+
+    if (newPer) {
+      // create a new index
+      *perIndex = m_propertyData.size() + 1;
+      m_propertyData.emplace_back(std::move(perProp));
+    } else if (perIndex) {
+      // update
+      m_propertyData[*perIndex - 1] = std::move(perProp);
+    }
+
+    // Tell raw property where to find percentage property
+    rawPropPtr->propPair = *perIndex;
+  }
+
+  NotifyPropertyCreated(*rawIndex, *rawPropPtr);
+  if (perPropPtr) NotifyPropertyCreated(*perIndex, *perPropPtr);
+}
+
+void UsbCameraImpl::DeviceCacheProperties() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+#ifdef V4L2_CTRL_FLAG_NEXT_COMPOUND
+  constexpr __u32 nextFlags =
+      V4L2_CTRL_FLAG_NEXT_CTRL | V4L2_CTRL_FLAG_NEXT_COMPOUND;
+#else
+  constexpr __u32 nextFlags = V4L2_CTRL_FLAG_NEXT_CTRL;
+#endif
+  __u32 id = nextFlags;
+
+  while (auto prop = UsbCameraProperty::DeviceQuery(fd, &id)) {
+    DeviceCacheProperty(std::move(prop));
+    id |= nextFlags;
+  }
+
+  if (id == nextFlags) {
+    // try just enumerating standard...
+    for (id = V4L2_CID_BASE; id < V4L2_CID_LASTP1; ++id) {
+      if (auto prop = UsbCameraProperty::DeviceQuery(fd, &id))
+        DeviceCacheProperty(std::move(prop));
+    }
+    // ... and custom controls
+    std::unique_ptr<UsbCameraProperty> prop;
+    for (id = V4L2_CID_PRIVATE_BASE;
+         (prop = UsbCameraProperty::DeviceQuery(fd, &id)); ++id)
+      DeviceCacheProperty(std::move(prop));
+  }
+}
+
+void UsbCameraImpl::DeviceCacheVideoModes() {
+  int fd = m_fd.load();
+  if (fd < 0) return;
+
+  std::vector<VideoMode> modes;
+
+  // Pixel formats
+  struct v4l2_fmtdesc fmt;
+  std::memset(&fmt, 0, sizeof(fmt));
+  fmt.type = V4L2_BUF_TYPE_VIDEO_CAPTURE;
+  for (fmt.index = 0; TryIoctl(fd, VIDIOC_ENUM_FMT, &fmt) >= 0; ++fmt.index) {
+    VideoMode::PixelFormat pixelFormat = ToPixelFormat(fmt.pixelformat);
+    if (pixelFormat == VideoMode::kUnknown) continue;
+
+    // Frame sizes
+    struct v4l2_frmsizeenum frmsize;
+    std::memset(&frmsize, 0, sizeof(frmsize));
+    frmsize.pixel_format = fmt.pixelformat;
+    for (frmsize.index = 0; TryIoctl(fd, VIDIOC_ENUM_FRAMESIZES, &frmsize) >= 0;
+         ++frmsize.index) {
+      if (frmsize.type != V4L2_FRMSIZE_TYPE_DISCRETE) continue;
+
+      // Frame intervals
+      struct v4l2_frmivalenum frmival;
+      std::memset(&frmival, 0, sizeof(frmival));
+      frmival.pixel_format = fmt.pixelformat;
+      frmival.width = frmsize.discrete.width;
+      frmival.height = frmsize.discrete.height;
+      for (frmival.index = 0;
+           TryIoctl(fd, VIDIOC_ENUM_FRAMEINTERVALS, &frmival) >= 0;
+           ++frmival.index) {
+        if (frmival.type != V4L2_FRMIVAL_TYPE_DISCRETE) continue;
+
+        modes.emplace_back(pixelFormat,
+                           static_cast<int>(frmsize.discrete.width),
+                           static_cast<int>(frmsize.discrete.height),
+                           FractToFPS(frmival.discrete));
+      }
+    }
+  }
+
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_videoModes.swap(modes);
+  }
+  m_notifier.NotifySource(*this, CS_SOURCE_VIDEOMODES_UPDATED);
+}
+
+CS_StatusValue UsbCameraImpl::SendAndWait(Message&& msg) const {
+  int fd = m_command_fd.load();
+  // exit early if not possible to signal
+  if (fd < 0) return CS_SOURCE_IS_DISCONNECTED;
+
+  auto from = msg.from;
+
+  // Add the message to the command queue
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_commands.emplace_back(std::move(msg));
+  }
+
+  // Signal the camera thread
+  if (eventfd_write(fd, 1) < 0) return CS_SOURCE_IS_DISCONNECTED;
+
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  while (m_active) {
+    // Did we get a response to *our* request?
+    auto it =
+        std::find_if(m_responses.begin(), m_responses.end(),
+                     [=](const std::pair<std::thread::id, CS_StatusValue>& r) {
+                       return r.first == from;
+                     });
+    if (it != m_responses.end()) {
+      // Yes, remove it from the vector and we're done.
+      auto rv = it->second;
+      m_responses.erase(it);
+      return rv;
+    }
+    // No, keep waiting for a response
+    m_responseCv.wait(lock);
+  }
+
+  return CS_SOURCE_IS_DISCONNECTED;
+}
+
+void UsbCameraImpl::Send(Message&& msg) const {
+  int fd = m_command_fd.load();
+  // exit early if not possible to signal
+  if (fd < 0) return;
+
+  // Add the message to the command queue
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_commands.emplace_back(std::move(msg));
+  }
+
+  // Signal the camera thread
+  eventfd_write(fd, 1);
+}
+
+std::unique_ptr<PropertyImpl> UsbCameraImpl::CreateEmptyProperty(
+    const wpi::Twine& name) const {
+  return wpi::make_unique<UsbCameraProperty>(name);
+}
+
+bool UsbCameraImpl::CacheProperties(CS_Status* status) const {
+  // Wake up camera thread; this will try to reconnect
+  *status = SendAndWait(Message{Message::kNone});
+  if (*status != CS_OK) return false;
+  if (!m_properties_cached) {
+    *status = CS_SOURCE_IS_DISCONNECTED;
+    return false;
+  }
+  return true;
+}
+
+void UsbCameraImpl::SetQuirks() {
+  wpi::SmallString<128> descbuf;
+  wpi::StringRef desc = GetDescription(descbuf);
+  m_lifecam_exposure =
+      desc.endswith("LifeCam HD-3000") || desc.endswith("LifeCam Cinema (TM)");
+}
+
+void UsbCameraImpl::SetProperty(int property, int value, CS_Status* status) {
+  Message msg{Message::kCmdSetProperty};
+  msg.data[0] = property;
+  msg.data[1] = value;
+  *status = SendAndWait(std::move(msg));
+}
+
+void UsbCameraImpl::SetStringProperty(int property, const wpi::Twine& value,
+                                      CS_Status* status) {
+  Message msg{Message::kCmdSetPropertyStr};
+  msg.data[0] = property;
+  msg.dataStr = value.str();
+  *status = SendAndWait(std::move(msg));
+}
+
+void UsbCameraImpl::SetBrightness(int brightness, CS_Status* status) {
+  if (brightness > 100) {
+    brightness = 100;
+  } else if (brightness < 0) {
+    brightness = 0;
+  }
+  SetProperty(GetPropertyIndex(kPropBrValue), brightness, status);
+}
+
+int UsbCameraImpl::GetBrightness(CS_Status* status) const {
+  return GetProperty(GetPropertyIndex(kPropBrValue), status);
+}
+
+void UsbCameraImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropWbAuto), 1, status);  // auto
+}
+
+void UsbCameraImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropWbAuto), 0, status);  // manual
+}
+
+void UsbCameraImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropWbAuto), 0, status);  // manual
+  SetProperty(GetPropertyIndex(kPropWbValue), value, status);
+}
+
+void UsbCameraImpl::SetExposureAuto(CS_Status* status) {
+  // auto; this is an enum value
+  SetProperty(GetPropertyIndex(kPropExAuto), 3, status);
+}
+
+void UsbCameraImpl::SetExposureHoldCurrent(CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropExAuto), 1, status);  // manual
+}
+
+void UsbCameraImpl::SetExposureManual(int value, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropExAuto), 1, status);  // manual
+  if (value > 100) {
+    value = 100;
+  } else if (value < 0) {
+    value = 0;
+  }
+  SetProperty(GetPropertyIndex(kPropExValue), value, status);
+}
+
+bool UsbCameraImpl::SetVideoMode(const VideoMode& mode, CS_Status* status) {
+  Message msg{Message::kCmdSetMode};
+  msg.data[0] = mode.pixelFormat;
+  msg.data[1] = mode.width;
+  msg.data[2] = mode.height;
+  msg.data[3] = mode.fps;
+  *status = SendAndWait(std::move(msg));
+  return *status == CS_OK;
+}
+
+bool UsbCameraImpl::SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                                   CS_Status* status) {
+  Message msg{Message::kCmdSetPixelFormat};
+  msg.data[0] = pixelFormat;
+  *status = SendAndWait(std::move(msg));
+  return *status == CS_OK;
+}
+
+bool UsbCameraImpl::SetResolution(int width, int height, CS_Status* status) {
+  Message msg{Message::kCmdSetResolution};
+  msg.data[0] = width;
+  msg.data[1] = height;
+  *status = SendAndWait(std::move(msg));
+  return *status == CS_OK;
+}
+
+bool UsbCameraImpl::SetFPS(int fps, CS_Status* status) {
+  Message msg{Message::kCmdSetFPS};
+  msg.data[0] = fps;
+  *status = SendAndWait(std::move(msg));
+  return *status == CS_OK;
+}
+
+void UsbCameraImpl::NumSinksChanged() {
+  Send(Message{Message::kNumSinksChanged});
+}
+
+void UsbCameraImpl::NumSinksEnabledChanged() {
+  Send(Message{Message::kNumSinksEnabledChanged});
+}
+
+namespace cs {
+
+CS_Source CreateUsbCameraDev(const wpi::Twine& name, int dev,
+                             CS_Status* status) {
+  wpi::SmallString<32> path;
+  wpi::raw_svector_ostream oss{path};
+  oss << "/dev/video" << dev;
+  return CreateUsbCameraPath(name, oss.str(), status);
+}
+
+CS_Source CreateUsbCameraPath(const wpi::Twine& name, const wpi::Twine& path,
+                              CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  return inst.CreateSource(CS_SOURCE_USB, std::make_shared<UsbCameraImpl>(
+                                              name, inst.logger, inst.notifier,
+                                              inst.telemetry, path));
+}
+
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return static_cast<UsbCameraImpl&>(*data->source).GetPath();
+}
+
+static const char* symlinkDirs[] = {"/dev/v4l/by-id", "/dev/v4l/by-path"};
+
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  UsbCameraInfo info;
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return info;
+  }
+  std::string keypath = static_cast<UsbCameraImpl&>(*data->source).GetPath();
+  info.path = keypath;
+
+  // it might be a symlink; if so, find the symlink target (e.g. /dev/videoN),
+  // add that to the list and make it the keypath
+  if (wpi::sys::fs::is_symlink_file(keypath)) {
+    char* target = ::realpath(keypath.c_str(), nullptr);
+    if (target) {
+      keypath.assign(target);
+      info.otherPaths.emplace_back(keypath);
+      std::free(target);
+    }
+  }
+
+  // device number
+  wpi::StringRef fname = wpi::sys::path::filename(keypath);
+  if (fname.startswith("video")) fname.substr(5).getAsInteger(10, info.dev);
+
+  // description
+  info.name = GetDescriptionImpl(keypath.c_str());
+
+  // look through /dev/v4l/by-id and /dev/v4l/by-path for symlinks to the
+  // keypath
+  wpi::SmallString<128> path;
+  for (auto symlinkDir : symlinkDirs) {
+    if (DIR* dp = ::opendir(symlinkDir)) {
+      while (struct dirent* ep = ::readdir(dp)) {
+        if (ep->d_type == DT_LNK) {
+          path = symlinkDir;
+          path += '/';
+          path += ep->d_name;
+          char* target = ::realpath(path.c_str(), nullptr);
+          if (target) {
+            if (keypath == target) info.otherPaths.emplace_back(path.str());
+            std::free(target);
+          }
+        }
+      }
+      ::closedir(dp);
+    }
+  }
+
+  // eliminate any duplicates
+  std::sort(info.otherPaths.begin(), info.otherPaths.end());
+  info.otherPaths.erase(
+      std::unique(info.otherPaths.begin(), info.otherPaths.end()),
+      info.otherPaths.end());
+  return info;
+}
+
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status) {
+  std::vector<UsbCameraInfo> retval;
+
+  if (DIR* dp = ::opendir("/dev")) {
+    while (struct dirent* ep = ::readdir(dp)) {
+      wpi::StringRef fname{ep->d_name};
+      if (!fname.startswith("video")) continue;
+
+      unsigned int dev = 0;
+      if (fname.substr(5).getAsInteger(10, dev)) continue;
+
+      UsbCameraInfo info;
+      info.dev = dev;
+
+      wpi::SmallString<32> path{"/dev/"};
+      path += fname;
+      info.path = path.str();
+
+      info.name = GetDescriptionImpl(path.c_str());
+      if (info.name.empty()) continue;
+
+      if (dev >= retval.size()) retval.resize(info.dev + 1);
+      retval[info.dev] = std::move(info);
+    }
+    ::closedir(dp);
+  } else {
+    // *status = ;
+    WPI_ERROR(Instance::GetInstance().logger, "Could not open /dev");
+    return retval;
+  }
+
+  // look through /dev/v4l/by-id and /dev/v4l/by-path for symlinks to
+  // /dev/videoN
+  wpi::SmallString<128> path;
+  for (auto symlinkDir : symlinkDirs) {
+    if (DIR* dp = ::opendir(symlinkDir)) {
+      while (struct dirent* ep = ::readdir(dp)) {
+        if (ep->d_type == DT_LNK) {
+          path = symlinkDir;
+          path += '/';
+          path += ep->d_name;
+          char* target = ::realpath(path.c_str(), nullptr);
+          if (target) {
+            wpi::StringRef fname = wpi::sys::path::filename(target);
+            unsigned int dev = 0;
+            if (fname.startswith("video") &&
+                !fname.substr(5).getAsInteger(10, dev) && dev < retval.size()) {
+              retval[dev].otherPaths.emplace_back(path.str());
+            }
+            std::free(target);
+          }
+        }
+      }
+      ::closedir(dp);
+    }
+  }
+
+  // remove devices with empty names
+  retval.erase(
+      std::remove_if(retval.begin(), retval.end(),
+                     [](const UsbCameraInfo& x) { return x.name.empty(); }),
+      retval.end());
+
+  return retval;
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraImpl.h b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraImpl.h
new file mode 100644
index 0000000..eb4a311
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraImpl.h
@@ -0,0 +1,181 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBCAMERAIMPL_H_
+#define CSCORE_USBCAMERAIMPL_H_
+
+#include <linux/videodev2.h>
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <thread>
+#include <utility>
+#include <vector>
+
+#include <wpi/STLExtras.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+#include "SourceImpl.h"
+#include "UsbCameraBuffer.h"
+#include "UsbCameraProperty.h"
+
+namespace cs {
+
+class Notifier;
+class Telemetry;
+
+class UsbCameraImpl : public SourceImpl {
+ public:
+  UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, const wpi::Twine& path);
+  ~UsbCameraImpl() override;
+
+  void Start() override;
+
+  // Property functions
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, const wpi::Twine& value,
+                         CS_Status* status) override;
+
+  // Standard common camera properties
+  void SetBrightness(int brightness, CS_Status* status) override;
+  int GetBrightness(CS_Status* status) const override;
+  void SetWhiteBalanceAuto(CS_Status* status) override;
+  void SetWhiteBalanceHoldCurrent(CS_Status* status) override;
+  void SetWhiteBalanceManual(int value, CS_Status* status) override;
+  void SetExposureAuto(CS_Status* status) override;
+  void SetExposureHoldCurrent(CS_Status* status) override;
+  void SetExposureManual(int value, CS_Status* status) override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+  bool SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                      CS_Status* status) override;
+  bool SetResolution(int width, int height, CS_Status* status) override;
+  bool SetFPS(int fps, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  std::string GetPath() { return m_path; }
+
+  // Messages passed to/from camera thread
+  struct Message {
+    enum Kind {
+      kNone = 0,
+      kCmdSetMode,
+      kCmdSetPixelFormat,
+      kCmdSetResolution,
+      kCmdSetFPS,
+      kCmdSetProperty,
+      kCmdSetPropertyStr,
+      kNumSinksChanged,         // no response
+      kNumSinksEnabledChanged,  // no response
+      // Responses
+      kOk,
+      kError
+    };
+
+    explicit Message(Kind kind_)
+        : kind(kind_), from(std::this_thread::get_id()) {}
+
+    Kind kind;
+    int data[4];
+    std::string dataStr;
+    std::thread::id from;
+  };
+
+ protected:
+  std::unique_ptr<PropertyImpl> CreateEmptyProperty(
+      const wpi::Twine& name) const override;
+
+  // Cache properties.  Immediately successful if properties are already cached.
+  // If they are not, tries to connect to the camera to do so; returns false and
+  // sets status to CS_SOURCE_IS_DISCONNECTED if that too fails.
+  bool CacheProperties(CS_Status* status) const override;
+
+ private:
+  // Send a message to the camera thread and wait for a response (generic)
+  CS_StatusValue SendAndWait(Message&& msg) const;
+  // Send a message to the camera thread with no response
+  void Send(Message&& msg) const;
+
+  // The camera processing thread
+  void CameraThreadMain();
+
+  // Functions used by CameraThreadMain()
+  void DeviceDisconnect();
+  void DeviceConnect();
+  bool DeviceStreamOn();
+  bool DeviceStreamOff();
+  void DeviceProcessCommands();
+  void DeviceSetMode();
+  void DeviceSetFPS();
+  void DeviceCacheMode();
+  void DeviceCacheProperty(std::unique_ptr<UsbCameraProperty> rawProp);
+  void DeviceCacheProperties();
+  void DeviceCacheVideoModes();
+
+  // Command helper functions
+  CS_StatusValue DeviceProcessCommand(std::unique_lock<wpi::mutex>& lock,
+                                      const Message& msg);
+  CS_StatusValue DeviceCmdSetMode(std::unique_lock<wpi::mutex>& lock,
+                                  const Message& msg);
+  CS_StatusValue DeviceCmdSetProperty(std::unique_lock<wpi::mutex>& lock,
+                                      const Message& msg);
+
+  // Property helper functions
+  int RawToPercentage(const UsbCameraProperty& rawProp, int rawValue);
+  int PercentageToRaw(const UsbCameraProperty& rawProp, int percentValue);
+
+  void SetQuirks();
+
+  //
+  // Variables only used within camera thread
+  //
+  bool m_streaming;
+  bool m_modeSetPixelFormat{false};
+  bool m_modeSetResolution{false};
+  bool m_modeSetFPS{false};
+  int m_connectVerbose{1};
+  unsigned m_capabilities = 0;
+  // Number of buffers to ask OS for
+  static constexpr int kNumBuffers = 4;
+  std::array<UsbCameraBuffer, kNumBuffers> m_buffers;
+
+  //
+  // Path never changes, so not protected by mutex.
+  //
+  std::string m_path;
+
+  std::atomic_int m_fd;
+  std::atomic_int m_command_fd;  // for command eventfd
+
+  std::atomic_bool m_active;  // set to false to terminate thread
+  std::thread m_cameraThread;
+
+  // Quirks
+  bool m_lifecam_exposure{false};  // Microsoft LifeCam exposure
+
+  //
+  // Variables protected by m_mutex
+  //
+
+  // Message queues
+  mutable std::vector<Message> m_commands;
+  mutable std::vector<std::pair<std::thread::id, CS_StatusValue>> m_responses;
+  mutable wpi::condition_variable m_responseCv;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_USBCAMERAIMPL_H_
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
new file mode 100644
index 0000000..6976095
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.cpp
@@ -0,0 +1,322 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "UsbCameraProperty.h"
+
+#include <wpi/STLExtras.h>
+#include <wpi/SmallString.h>
+
+#include "UsbUtil.h"
+
+using namespace cs;
+
+static int GetIntCtrlIoctl(int fd, unsigned id, int type, int64_t* value) {
+  unsigned ctrl_class = V4L2_CTRL_ID2CLASS(id);
+  if (type == V4L2_CTRL_TYPE_INTEGER64 || V4L2_CTRL_DRIVER_PRIV(id) ||
+      (ctrl_class != V4L2_CTRL_CLASS_USER &&
+       ctrl_class != V4L2_CID_PRIVATE_BASE)) {
+    // Use extended control
+    struct v4l2_ext_control ctrl;
+    struct v4l2_ext_controls ctrls;
+    std::memset(&ctrl, 0, sizeof(ctrl));
+    std::memset(&ctrls, 0, sizeof(ctrls));
+    ctrl.id = id;
+    ctrls.ctrl_class = ctrl_class;
+    ctrls.count = 1;
+    ctrls.controls = &ctrl;
+    int rc = DoIoctl(fd, VIDIOC_G_EXT_CTRLS, &ctrls);
+    if (rc < 0) return rc;
+    *value = ctrl.value;
+  } else {
+    // Use normal control
+    struct v4l2_control ctrl;
+    std::memset(&ctrl, 0, sizeof(ctrl));
+    ctrl.id = id;
+    int rc = DoIoctl(fd, VIDIOC_G_CTRL, &ctrl);
+    if (rc < 0) return rc;
+    *value = ctrl.value;
+  }
+  return 0;
+}
+
+static int SetIntCtrlIoctl(int fd, unsigned id, int type, int64_t value) {
+  unsigned ctrl_class = V4L2_CTRL_ID2CLASS(id);
+  if (type == V4L2_CTRL_TYPE_INTEGER64 || V4L2_CTRL_DRIVER_PRIV(id) ||
+      (ctrl_class != V4L2_CTRL_CLASS_USER &&
+       ctrl_class != V4L2_CID_PRIVATE_BASE)) {
+    // Use extended control
+    struct v4l2_ext_control ctrl;
+    struct v4l2_ext_controls ctrls;
+    std::memset(&ctrl, 0, sizeof(ctrl));
+    std::memset(&ctrls, 0, sizeof(ctrls));
+    ctrl.id = id;
+    if (type == V4L2_CTRL_TYPE_INTEGER64)
+      ctrl.value64 = value;
+    else
+      ctrl.value = static_cast<__s32>(value);
+    ctrls.ctrl_class = ctrl_class;
+    ctrls.count = 1;
+    ctrls.controls = &ctrl;
+    return DoIoctl(fd, VIDIOC_S_EXT_CTRLS, &ctrls);
+  } else {
+    // Use normal control
+    struct v4l2_control ctrl;
+    ctrl.id = id;
+    ctrl.value = static_cast<__s32>(value);
+    return DoIoctl(fd, VIDIOC_S_CTRL, &ctrl);
+  }
+}
+
+static int GetStringCtrlIoctl(int fd, int id, int maximum, std::string* value) {
+  struct v4l2_ext_control ctrl;
+  struct v4l2_ext_controls ctrls;
+  std::memset(&ctrl, 0, sizeof(ctrl));
+  std::memset(&ctrls, 0, sizeof(ctrls));
+  ctrl.id = id;
+  ctrls.ctrl_class = V4L2_CTRL_ID2CLASS(id);
+  ctrls.count = 1;
+  ctrls.controls = &ctrl;
+  int rc = DoIoctl(fd, VIDIOC_G_EXT_CTRLS, &ctrls);
+  if (rc < 0) {
+    value->clear();
+    return rc;
+  }
+  value->assign(ctrl.string, std::strlen(ctrl.string));
+  return 0;
+}
+
+static int SetStringCtrlIoctl(int fd, int id, int maximum,
+                              const wpi::Twine& value) {
+  wpi::SmallString<64> strBuf, strBuf2;
+  wpi::StringRef str = value.toNullTerminatedStringRef(strBuf);
+  if (str.size() > static_cast<size_t>(maximum)) {
+    // don't know if strBuf was used, just recopy
+    strBuf2 = str.take_front(maximum);
+    str = strBuf2;
+    strBuf2.push_back('\0');  // null terminate
+  }
+
+  struct v4l2_ext_control ctrl;
+  struct v4l2_ext_controls ctrls;
+  std::memset(&ctrl, 0, sizeof(ctrl));
+  std::memset(&ctrls, 0, sizeof(ctrls));
+  ctrl.id = id;
+  ctrl.size = str.size();
+  ctrl.string = const_cast<char*>(str.data());
+  ctrls.ctrl_class = V4L2_CTRL_ID2CLASS(id);
+  ctrls.count = 1;
+  ctrls.controls = &ctrl;
+  return DoIoctl(fd, VIDIOC_S_EXT_CTRLS, &ctrls);
+}
+
+// Removes non-alphanumeric characters and replaces spaces with underscores.
+// e.g. "Zoom, Absolute" -> "zoom_absolute", "Pan (Absolute)" -> "pan_absolute"
+static wpi::StringRef NormalizeName(wpi::StringRef name,
+                                    wpi::SmallVectorImpl<char>& buf) {
+  bool newWord = false;
+  for (auto ch : name) {
+    if (std::isalnum(ch)) {
+      if (newWord) buf.push_back('_');
+      newWord = false;
+      buf.push_back(std::tolower(ch));
+    } else if (!buf.empty()) {
+      newWord = true;
+    }
+  }
+  return wpi::StringRef(buf.data(), buf.size());
+}
+
+#ifdef VIDIOC_QUERY_EXT_CTRL
+UsbCameraProperty::UsbCameraProperty(const struct v4l2_query_ext_ctrl& ctrl)
+    : PropertyImpl(wpi::StringRef{}, CS_PROP_NONE, ctrl.step,
+                   ctrl.default_value, 0),
+      id(ctrl.id & V4L2_CTRL_ID_MASK),
+      type(ctrl.type) {
+  hasMinimum = true;
+  minimum = ctrl.minimum;
+  hasMaximum = true;
+  maximum = ctrl.maximum;
+
+  // propKind
+  switch (ctrl.type) {
+    case V4L2_CTRL_TYPE_INTEGER:
+    case V4L2_CTRL_TYPE_INTEGER64:
+      propKind = CS_PROP_INTEGER;
+      break;
+    case V4L2_CTRL_TYPE_BOOLEAN:
+      propKind = CS_PROP_BOOLEAN;
+      break;
+    case V4L2_CTRL_TYPE_INTEGER_MENU:
+    case V4L2_CTRL_TYPE_MENU:
+      propKind = CS_PROP_ENUM;
+      break;
+    case V4L2_CTRL_TYPE_STRING:
+      propKind = CS_PROP_STRING;
+      break;
+    default:
+      return;  // others unsupported
+  }
+
+  // name
+  size_t len = 0;
+  while (len < sizeof(ctrl.name) && ctrl.name[len] != '\0') ++len;
+  wpi::SmallString<64> name_buf;
+  name = NormalizeName(wpi::StringRef(ctrl.name, len), name_buf);
+}
+#endif
+
+UsbCameraProperty::UsbCameraProperty(const struct v4l2_queryctrl& ctrl)
+    : PropertyImpl(wpi::StringRef{}, CS_PROP_NONE, ctrl.step,
+                   ctrl.default_value, 0),
+      id(ctrl.id & V4L2_CTRL_ID_MASK),
+      type(ctrl.type) {
+  hasMinimum = true;
+  minimum = ctrl.minimum;
+  hasMaximum = true;
+  maximum = ctrl.maximum;
+
+  // propKind
+  switch (ctrl.type) {
+    case V4L2_CTRL_TYPE_INTEGER:
+    case V4L2_CTRL_TYPE_INTEGER64:
+      propKind = CS_PROP_INTEGER;
+      break;
+    case V4L2_CTRL_TYPE_BOOLEAN:
+      propKind = CS_PROP_BOOLEAN;
+      break;
+    case V4L2_CTRL_TYPE_INTEGER_MENU:
+    case V4L2_CTRL_TYPE_MENU:
+      propKind = CS_PROP_ENUM;
+      break;
+    case V4L2_CTRL_TYPE_STRING:
+      propKind = CS_PROP_STRING;
+      break;
+    default:
+      return;  // others unsupported
+  }
+
+  // name
+  size_t len = 0;
+  while (len < sizeof(ctrl.name) && ctrl.name[len] != '\0') ++len;
+  wpi::SmallString<64> name_buf;
+  name = NormalizeName(
+      wpi::StringRef(reinterpret_cast<const char*>(ctrl.name), len), name_buf);
+}
+
+std::unique_ptr<UsbCameraProperty> UsbCameraProperty::DeviceQuery(int fd,
+                                                                  __u32* id) {
+  int rc;
+  std::unique_ptr<UsbCameraProperty> prop;
+#ifdef VIDIOC_QUERY_EXT_CTRL
+  v4l2_query_ext_ctrl qc_ext;
+  std::memset(&qc_ext, 0, sizeof(qc_ext));
+  qc_ext.id = *id;
+  rc = TryIoctl(fd, VIDIOC_QUERY_EXT_CTRL, &qc_ext);
+  if (rc == 0) {
+    *id = qc_ext.id;  // copy back
+    // We don't support array types
+    if (qc_ext.elems > 1 || qc_ext.nr_of_dims > 0) return nullptr;
+    prop = wpi::make_unique<UsbCameraProperty>(qc_ext);
+  }
+#endif
+  if (!prop) {
+    // Fall back to normal QUERYCTRL
+    struct v4l2_queryctrl qc;
+    std::memset(&qc, 0, sizeof(qc));
+    qc.id = *id;
+    rc = TryIoctl(fd, VIDIOC_QUERYCTRL, &qc);
+    *id = qc.id;  // copy back
+    if (rc != 0) return nullptr;
+    prop = wpi::make_unique<UsbCameraProperty>(qc);
+  }
+
+  // Cache enum property choices
+  if (prop->propKind == CS_PROP_ENUM) {
+    prop->enumChoices.resize(prop->maximum + 1);
+    v4l2_querymenu qmenu;
+    std::memset(&qmenu, 0, sizeof(qmenu));
+    qmenu.id = *id;
+    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);
+    }
+  }
+
+  return prop;
+}
+
+bool UsbCameraProperty::DeviceGet(std::unique_lock<wpi::mutex>& lock, int fd) {
+  if (fd < 0) return true;
+  unsigned idCopy = id;
+  int rv = 0;
+
+  switch (propKind) {
+    case CS_PROP_BOOLEAN:
+    case CS_PROP_INTEGER:
+    case CS_PROP_ENUM: {
+      int typeCopy = type;
+      int64_t newValue = 0;
+      lock.unlock();
+      rv = GetIntCtrlIoctl(fd, idCopy, typeCopy, &newValue);
+      lock.lock();
+      if (rv >= 0) value = newValue;
+      break;
+    }
+    case CS_PROP_STRING: {
+      int maximumCopy = maximum;
+      std::string newValueStr;
+      lock.unlock();
+      rv = GetStringCtrlIoctl(fd, idCopy, maximumCopy, &newValueStr);
+      lock.lock();
+      if (rv >= 0) valueStr = std::move(newValueStr);
+      break;
+    }
+    default:
+      break;
+  }
+
+  return rv >= 0;
+}
+
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  int fd) const {
+  // Make a copy of the string as we're about to release the lock
+  wpi::SmallString<128> valueStrCopy{valueStr};
+  return DeviceSet(lock, fd, value, valueStrCopy);
+}
+
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock, int fd,
+                                  int newValue,
+                                  const wpi::Twine& newValueStr) const {
+  if (!device || fd < 0) return true;
+  unsigned idCopy = id;
+  int rv = 0;
+
+  switch (propKind) {
+    case CS_PROP_BOOLEAN:
+    case CS_PROP_INTEGER:
+    case CS_PROP_ENUM: {
+      int typeCopy = type;
+      lock.unlock();
+      rv = SetIntCtrlIoctl(fd, idCopy, typeCopy, newValue);
+      lock.lock();
+      break;
+    }
+    case CS_PROP_STRING: {
+      int maximumCopy = maximum;
+      lock.unlock();
+      rv = SetStringCtrlIoctl(fd, idCopy, maximumCopy, newValueStr);
+      lock.lock();
+      break;
+    }
+    default:
+      break;
+  }
+
+  return rv >= 0;
+}
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
new file mode 100644
index 0000000..446deab
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbCameraProperty.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBCAMERAPROPERTY_H_
+#define CSCORE_USBCAMERAPROPERTY_H_
+
+#include <linux/videodev2.h>
+
+#include <memory>
+
+#include <wpi/mutex.h>
+
+#include "PropertyImpl.h"
+
+namespace cs {
+
+// Property data
+class UsbCameraProperty : public PropertyImpl {
+ public:
+  UsbCameraProperty() = default;
+  explicit UsbCameraProperty(const wpi::Twine& name_) : PropertyImpl{name_} {}
+
+  // Software property constructor
+  UsbCameraProperty(const wpi::Twine& name_, unsigned id_,
+                    CS_PropertyKind kind_, int minimum_, int maximum_,
+                    int step_, int defaultValue_, int value_)
+      : PropertyImpl(name_, kind_, minimum_, maximum_, step_, defaultValue_,
+                     value_),
+        device{false},
+        id{id_} {}
+
+  // Normalized property constructor
+  UsbCameraProperty(const wpi::Twine& name_, int rawIndex_,
+                    const UsbCameraProperty& rawProp, int defaultValue_,
+                    int value_)
+      : PropertyImpl(name_, rawProp.propKind, 1, defaultValue_, value_),
+        percentage{true},
+        propPair{rawIndex_},
+        id{rawProp.id},
+        type{rawProp.type} {
+    hasMinimum = true;
+    minimum = 0;
+    hasMaximum = true;
+    maximum = 100;
+  }
+
+#ifdef VIDIOC_QUERY_EXT_CTRL
+  explicit UsbCameraProperty(const struct v4l2_query_ext_ctrl& ctrl);
+#endif
+  explicit UsbCameraProperty(const struct v4l2_queryctrl& ctrl);
+
+  static std::unique_ptr<UsbCameraProperty> DeviceQuery(int fd, __u32* id);
+
+  bool DeviceGet(std::unique_lock<wpi::mutex>& lock, int fd);
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock, int fd) const;
+  bool DeviceSet(std::unique_lock<wpi::mutex>& lock, int fd, int newValue,
+                 const wpi::Twine& newValueStr) const;
+
+  // If this is a device (rather than software) property
+  bool device{true};
+
+  // If this is a percentage (rather than raw) property
+  bool percentage{false};
+
+  // If not 0, index of corresponding raw/percentage property
+  int propPair{0};
+
+  unsigned id{0};  // implementation-level id
+  int type{0};     // implementation type, not CS_PropertyKind!
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_USBCAMERAPROPERTY_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbUtil.cpp b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbUtil.cpp
new file mode 100644
index 0000000..ac48178
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbUtil.cpp
@@ -0,0 +1,161 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "UsbUtil.h"
+
+#include <fcntl.h>
+#include <libgen.h>
+#include <sys/ioctl.h>
+
+#include <wpi/Format.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+#include "Instance.h"
+#include "Log.h"
+
+namespace cs {
+
+static wpi::StringRef GetUsbNameFromFile(int vendor, int product,
+                                         wpi::SmallVectorImpl<char>& buf) {
+  int fd = open("/var/lib/usbutils/usb.ids", O_RDONLY);
+  if (fd < 0) return wpi::StringRef{};
+
+  wpi::raw_svector_ostream os{buf};
+  wpi::raw_fd_istream is{fd, true};
+
+  // build vendor and product 4-char hex strings
+  wpi::SmallString<16> vendorStr, productStr;
+  wpi::raw_svector_ostream vendorOs{vendorStr}, productOs{productStr};
+  vendorOs << wpi::format_hex_no_prefix(vendor, 4);
+  productOs << wpi::format_hex_no_prefix(product, 4);
+
+  // scan file
+  wpi::SmallString<128> lineBuf;
+  bool foundVendor = false;
+  for (;;) {
+    auto line = is.getline(lineBuf, 4096);
+    if (is.has_error()) break;
+
+    if (line.empty()) continue;
+
+    // look for vendor at start of line
+    if (line.startswith(vendorStr)) {
+      foundVendor = true;
+      os << line.substr(5).trim() << ' ';
+      continue;
+    }
+
+    if (foundVendor) {
+      // next vendor, but didn't match product?
+      if (line[0] != '\t') {
+        os << "Unknown";
+        return os.str();
+      }
+
+      // look for product
+      if (line.substr(1).startswith(productStr)) {
+        os << line.substr(6).trim();
+        return os.str();
+      }
+    }
+  }
+
+  return wpi::StringRef{};
+}
+
+wpi::StringRef GetUsbNameFromId(int vendor, int product,
+                                wpi::SmallVectorImpl<char>& buf) {
+  // try reading usb.ids
+  wpi::StringRef rv = GetUsbNameFromFile(vendor, product, buf);
+  if (!rv.empty()) return rv;
+
+  // Fall back to internal database
+  wpi::raw_svector_ostream os{buf};
+  switch (vendor) {
+    case 0x046d:
+      os << "Logitech, Inc. ";
+      switch (product) {
+        case 0x0802:
+          os << "Webcam C200";
+          break;
+        case 0x0804:
+          os << "Webcam C250";
+          break;
+        case 0x0805:
+          os << "Webcam C300";
+          break;
+        case 0x0807:
+          os << "Webcam B500";
+          break;
+        case 0x0808:
+          os << "Webcam C600";
+          break;
+        case 0x0809:
+          os << "Webcam Pro 9000";
+          break;
+        case 0x080a:
+          os << "Portable Webcam C905";
+          break;
+        case 0x080f:
+          os << "Webcam C120";
+          break;
+        case 0x0819:
+          os << "Webcam C210";
+          break;
+        case 0x081b:
+          os << "Webcam C310";
+          break;
+        case 0x081d:
+          os << "HD Webcam C510";
+          break;
+        case 0x0821:
+          os << "HD Webcam C910";
+          break;
+        case 0x0825:
+          os << "Webcam C270";
+          break;
+        case 0x0826:
+          os << "HD Webcam C525";
+          break;
+        case 0x0828:
+          os << "HD Webcam B990";
+          break;
+        case 0x082b:
+          os << "Webcam C170";
+          break;
+        case 0x082d:
+          os << "HD Pro Webcam C920";
+          break;
+        case 0x0836:
+          os << "B525 HD Webcam";
+          break;
+        case 0x0843:
+          os << "Webcam C930e";
+          break;
+      }
+      break;
+  }
+
+  return os.str();
+}
+
+int CheckedIoctl(int fd, unsigned long req, void* data,  // NOLINT(runtime/int)
+                 const char* name, const char* file, int line, bool quiet) {
+  int retval = ioctl(fd, req, data);
+  if (!quiet && retval < 0) {
+    wpi::SmallString<64> localfile{file};
+    localfile.push_back('\0');
+    WPI_ERROR(Instance::GetInstance().logger,
+              "ioctl " << name << " failed at " << basename(localfile.data())
+                       << ":" << line << ": " << std::strerror(errno));
+  }
+  return retval;
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbUtil.h b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbUtil.h
new file mode 100644
index 0000000..4f1d9d8
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/linux/UsbUtil.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBUTIL_H_
+#define CSCORE_USBUTIL_H_
+
+#include <stdint.h>
+
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+
+namespace cs {
+
+wpi::StringRef GetUsbNameFromId(int vendor, int product,
+                                wpi::SmallVectorImpl<char>& buf);
+
+int CheckedIoctl(int fd, unsigned long req, void* data,  // NOLINT(runtime/int)
+                 const char* name, const char* file, int line, bool quiet);
+
+#define DoIoctl(fd, req, data) \
+  CheckedIoctl(fd, req, data, #req, __FILE__, __LINE__, false)
+#define TryIoctl(fd, req, data) \
+  CheckedIoctl(fd, req, data, #req, __FILE__, __LINE__, true)
+
+}  // namespace cs
+
+#endif  // CSCORE_USBUTIL_H_
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/objcpp/objcpptemp.mm b/third_party/allwpilib_2019/cscore/src/main/native/objcpp/objcpptemp.mm
new file mode 100644
index 0000000..27aaaff
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/objcpp/objcpptemp.mm
@@ -0,0 +1,12 @@
+#import <Foundation/Foundation.h>
+
+@interface XYZPerson : NSObject
+- (void)sayHello;
+@end
+
+
+@implementation XYZPerson
+- (void)sayHello {
+    NSLog(@"Hello, World!");
+}
+@end
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/osx/NetworkListener.cpp b/third_party/allwpilib_2019/cscore/src/main/native/osx/NetworkListener.cpp
new file mode 100644
index 0000000..0716789
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/osx/NetworkListener.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "NetworkListener.h"
+
+using namespace cs;
+
+class NetworkListener::Impl {};
+
+NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier) {}
+
+NetworkListener::~NetworkListener() {}
+
+void NetworkListener::Start() {}
+
+void NetworkListener::Stop() {}
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/osx/NetworkUtil.cpp b/third_party/allwpilib_2019/cscore/src/main/native/osx/NetworkUtil.cpp
new file mode 100644
index 0000000..935c21f
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/osx/NetworkUtil.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "cscore_cpp.h"
+
+namespace cs {
+
+std::vector<std::string> GetNetworkInterfaces() {
+  return std::vector<std::string>{};  // TODO
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/osx/UsbCameraImpl.cpp b/third_party/allwpilib_2019/cscore/src/main/native/osx/UsbCameraImpl.cpp
new file mode 100644
index 0000000..a10fae4
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/osx/UsbCameraImpl.cpp
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "cscore_cpp.h"
+
+namespace cs {
+
+CS_Source CreateUsbCameraDev(const wpi::Twine& name, int dev,
+                             CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return 0;
+}
+
+CS_Source CreateUsbCameraPath(const wpi::Twine& name, const wpi::Twine& path,
+                              CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return 0;
+}
+
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return std::string{};
+}
+
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return UsbCameraInfo{};
+}
+
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status) {
+  *status = CS_INVALID_HANDLE;
+  return std::vector<UsbCameraInfo>{};
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/COMCreators.cpp b/third_party/allwpilib_2019/cscore/src/main/native/windows/COMCreators.cpp
new file mode 100644
index 0000000..265f7d3
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/COMCreators.cpp
@@ -0,0 +1,158 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <mfapi.h>
+#include <mfidl.h>
+#include <shlwapi.h>
+#include <windowsx.h>
+
+#include <Windows.h>
+
+#include "UsbCameraImpl.h"
+
+// https://github.com/opencv/opencv/blob/master/modules/videoio/src/cap_msmf.cpp
+
+#include <mfidl.h>
+#include <mfapi.h>
+#include <Dbt.h>
+#include <ks.h>
+#include <ksmedia.h>
+#include <mfreadwrite.h>
+
+#include "COMCreators.h"
+#include "ComPtr.h"
+
+#pragma comment(lib, "Mfplat.lib")
+#pragma comment(lib, "Mf.lib")
+#pragma comment(lib, "mfuuid.lib")
+#pragma comment(lib, "Ole32.lib")
+#pragma comment(lib, "User32.lib")
+#pragma comment(lib, "Mfreadwrite.lib")
+#pragma comment(lib, "Shlwapi.lib")
+
+namespace cs {
+
+SourceReaderCB::SourceReaderCB(std::weak_ptr<cs::UsbCameraImpl> source,
+                               const cs::VideoMode& mode)
+    : m_nRefCount(1), m_source(source), m_mode{mode} {}
+
+// IUnknown methods
+STDMETHODIMP SourceReaderCB::QueryInterface(REFIID iid, void** ppv) {
+  static const QITAB qit[] = {
+      QITABENT(SourceReaderCB, IMFSourceReaderCallback),
+      {0},
+  };
+  return QISearch(this, qit, iid, ppv);
+}
+STDMETHODIMP_(ULONG) SourceReaderCB::AddRef() {
+  return InterlockedIncrement(&m_nRefCount);
+}
+STDMETHODIMP_(ULONG) SourceReaderCB::Release() {
+  ULONG uCount = InterlockedDecrement(&m_nRefCount);
+  if (uCount == 0) {
+    delete this;
+  }
+  return uCount;
+}
+
+STDMETHODIMP SourceReaderCB::OnEvent(DWORD, IMFMediaEvent*) { return S_OK; }
+
+STDMETHODIMP SourceReaderCB::OnFlush(DWORD) { return S_OK; }
+
+void SourceReaderCB::NotifyError(HRESULT hr) {
+  wprintf(L"Source Reader error: 0x%X\n", hr);
+}
+
+STDMETHODIMP SourceReaderCB::OnReadSample(HRESULT hrStatus, DWORD dwStreamIndex,
+                                          DWORD dwStreamFlags,
+                                          LONGLONG llTimestamp,
+                                          IMFSample* pSample  // Can be NULL
+) {
+  auto source = m_source.lock();
+  if (!source) return S_OK;
+  if (SUCCEEDED(hrStatus)) {
+    if (pSample) {
+      // Prcoess sample
+      source->ProcessFrame(pSample, m_mode);
+      // DO NOT release the frame
+    }
+  } else {
+    // Streaming error.
+    NotifyError(hrStatus);
+  }
+  // Trigger asking for a new frame.
+  // This is piped through the message pump for concurrency reasons
+  source->PostRequestNewFrame();
+  return S_OK;
+}
+
+// Create a Source Reader COM Smart Object
+ComPtr<SourceReaderCB> CreateSourceReaderCB(
+    std::weak_ptr<cs::UsbCameraImpl> source, const cs::VideoMode& mode) {
+  SourceReaderCB* ptr = new SourceReaderCB(source, mode);
+  ComPtr<SourceReaderCB> sourceReaderCB;
+  sourceReaderCB.Attach(ptr);
+  return sourceReaderCB;
+}
+
+ComPtr<IMFMediaSource> CreateVideoCaptureDevice(LPCWSTR pszSymbolicLink) {
+  ComPtr<IMFAttributes> pAttributes;
+  ComPtr<IMFMediaSource> pSource;
+
+  HRESULT hr = MFCreateAttributes(pAttributes.GetAddressOf(), 2);
+
+  // Set the device type to video.
+  if (SUCCEEDED(hr)) {
+    hr = pAttributes->SetGUID(MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE,
+                              MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_GUID);
+  }
+
+  // Set the symbolic link.
+  if (SUCCEEDED(hr)) {
+    hr = pAttributes->SetString(
+        MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_SYMBOLIC_LINK,
+        pszSymbolicLink);
+  }
+
+  if (SUCCEEDED(hr)) {
+    hr = MFCreateDeviceSource(pAttributes.Get(), pSource.GetAddressOf());
+  }
+
+  // No need to check last HR, as the source would be null anyway.
+  return pSource;
+}
+
+ComPtr<IMFSourceReader> CreateSourceReader(IMFMediaSource* mediaSource,
+                                           IMFSourceReaderCallback* callback) {
+  HRESULT hr = S_OK;
+  ComPtr<IMFAttributes> pAttributes;
+  ComPtr<IMFSourceReader> sourceReader;
+
+  hr = MFCreateAttributes(pAttributes.GetAddressOf(), 1);
+  if (FAILED(hr)) {
+    return nullptr;
+  }
+
+  hr = pAttributes->SetUnknown(MF_SOURCE_READER_ASYNC_CALLBACK, callback);
+  if (FAILED(hr)) {
+    return nullptr;
+  }
+
+  hr = pAttributes->SetUINT32(
+      MF_SOURCE_READER_DISCONNECT_MEDIASOURCE_ON_SHUTDOWN, TRUE);
+  if (FAILED(hr)) {
+    return nullptr;
+  }
+
+  MFCreateSourceReaderFromMediaSource(mediaSource, pAttributes.Get(),
+                                      sourceReader.GetAddressOf());
+
+  // No need to check last HR, as the sourceReader would be null anyway.
+  return sourceReader;
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/COMCreators.h b/third_party/allwpilib_2019/cscore/src/main/native/windows/COMCreators.h
new file mode 100644
index 0000000..f89e6fd
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/COMCreators.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <mfidl.h>
+#include <mfreadwrite.h>
+
+#include <memory>
+
+#include "ComPtr.h"
+#include "cscore_cpp.h"
+
+namespace cs {
+
+class UsbCameraImpl;
+
+// Source callback used by the source reader.
+// COM object, so it needs a to ref count itself.
+class SourceReaderCB : public IMFSourceReaderCallback {
+ public:
+  explicit SourceReaderCB(std::weak_ptr<cs::UsbCameraImpl> source,
+                          const cs::VideoMode& mode);
+  void SetVideoMode(const VideoMode& mode) { m_mode = mode; }
+
+  STDMETHODIMP QueryInterface(REFIID iid, void** ppv);
+  STDMETHODIMP_(ULONG) AddRef();
+  STDMETHODIMP_(ULONG) Release();
+
+  STDMETHODIMP OnEvent(DWORD, IMFMediaEvent*);
+  STDMETHODIMP OnFlush(DWORD);
+  STDMETHODIMP OnReadSample(HRESULT hrStatus, DWORD dwStreamIndex,
+                            DWORD dwStreamFlags, LONGLONG llTimestamp,
+                            IMFSample* pSample  // Can be NULL
+  );
+
+  void InvalidateCapture() { m_source = std::weak_ptr<cs::UsbCameraImpl>(); }
+
+ private:
+  // Destructor is private. Caller should call Release.
+  virtual ~SourceReaderCB() {}
+  void NotifyError(HRESULT hr);
+
+  ULONG m_nRefCount;
+  std::weak_ptr<cs::UsbCameraImpl> m_source;
+  cs::VideoMode m_mode;
+};
+
+ComPtr<SourceReaderCB> CreateSourceReaderCB(
+    std::weak_ptr<cs::UsbCameraImpl> source, const cs::VideoMode& mode);
+ComPtr<IMFSourceReader> CreateSourceReader(IMFMediaSource* mediaSource,
+                                           IMFSourceReaderCallback* callback);
+ComPtr<IMFMediaSource> CreateVideoCaptureDevice(LPCWSTR pszSymbolicLink);
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/ComPtr.h b/third_party/allwpilib_2019/cscore/src/main/native/windows/ComPtr.h
new file mode 100644
index 0000000..22a330d
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/ComPtr.h
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <comdef.h>
+#include <shlwapi.h>  // QISearch
+
+#include <cassert>
+
+namespace cs {
+
+template <typename Interface>
+class RemoveAddRefRelease : public Interface {
+  ULONG __stdcall AddRef();
+  ULONG __stdcall Release();
+  virtual ~RemoveAddRefRelease();
+};
+
+template <typename Interface>
+class ComPtr {
+ public:
+  template <typename T>
+  friend class ComPtr;
+
+  ComPtr(std::nullptr_t = nullptr) noexcept {}  // NOLINT(runtime/explicit)
+  ComPtr(const ComPtr& other) noexcept : m_ptr(other.m_ptr) {
+    InternalAddRef();
+  }
+
+  template <typename T>
+  ComPtr(const ComPtr<T>& other) noexcept : m_ptr(other.m_ptr) {
+    InternalAddRef();
+  }
+
+  template <typename T>
+  ComPtr(ComPtr<T>&& other) noexcept : m_ptr(other.m_ptr) {
+    other.m_ptr = nullptr;
+  }
+
+  ~ComPtr() noexcept { InternalRelease(); }
+
+  ComPtr& operator=(const ComPtr& other) noexcept {
+    InternalCopy(other.m_ptr);
+    return *this;
+  }
+
+  template <typename T>
+  ComPtr& operator=(const ComPtr<T>& other) noexcept {
+    InternalCopy(other.m_ptr);
+    return *this;
+  }
+
+  template <typename T>
+  ComPtr& operator=(ComPtr<T>&& other) noexcept {
+    InternalMove(other);
+    return *this;
+  }
+
+  void Swap(ComPtr& other) noexcept {
+    Interface* temp = m_ptr;
+    m_ptr = other.m_ptr;
+    other.m_ptr = temp;
+  }
+
+  explicit operator bool() const noexcept { return nullptr != m_ptr; }
+
+  void Reset() noexcept { InternalRelease(); }
+
+  Interface* Get() const noexcept { return m_ptr; }
+
+  Interface* Detach() noexcept {
+    Interface* temp = m_ptr;
+    m_ptr = nullptr;
+    return temp;
+  }
+
+  void Copy(Interface* other) noexcept { InternalCopy(other); }
+
+  void Attach(Interface* other) noexcept {
+    InternalRelease();
+    m_ptr = other;
+  }
+
+  Interface** GetAddressOf() noexcept {
+    assert(m_ptr == nullptr);
+    return &m_ptr;
+  }
+
+  void CopyTo(Interface** other) const noexcept {
+    InternalAddRef();
+    *other = m_ptr;
+  }
+
+  template <typename T>
+  ComPtr<T> As() const noexcept {
+    ComPtr<T> temp;
+    m_ptr->QueryInterface(temp.GetAddressOf());
+    return temp;
+  }
+
+  RemoveAddRefRelease<Interface>* operator->() const noexcept {
+    return static_cast<RemoveAddRefRelease<Interface>*>(m_ptr);
+  }
+
+ private:
+  Interface* m_ptr = nullptr;
+
+  void InternalAddRef() const noexcept {
+    if (m_ptr) {
+      m_ptr->AddRef();
+    }
+  }
+
+  void InternalRelease() noexcept {
+    Interface* temp = m_ptr;
+    if (temp) {
+      m_ptr = nullptr;
+      temp->Release();
+    }
+  }
+
+  void InternalCopy(Interface* other) noexcept {
+    if (m_ptr != other) {
+      InternalRelease();
+      m_ptr = other;
+      InternalAddRef();
+    }
+  }
+
+  template <typename T>
+  void InternalMove(ComPtr<T>& other) noexcept {
+    if (m_ptr != other.m_ptr) {
+      InternalRelease();
+      m_ptr = other.m_ptr;
+      other.m_ptr = nullptr;
+    }
+  }
+};
+
+template <typename Interface>
+void swap(
+    ComPtr<Interface>& left,
+    ComPtr<Interface>& right) noexcept {  // NOLINT(build/include_what_you_use)
+  left.Swap(right);
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/NetworkListener.cpp b/third_party/allwpilib_2019/cscore/src/main/native/windows/NetworkListener.cpp
new file mode 100644
index 0000000..cd29e44
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/NetworkListener.cpp
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "NetworkListener.h"
+
+#include <winsock2.h>  // NOLINT(build/include_order)
+
+#include <windows.h>  // NOLINT(build/include_order)
+
+#include <ws2def.h>  // NOLINT(build/include_order)
+
+#include <ws2ipdef.h>  // NOLINT(build/include_order)
+
+#include <iphlpapi.h>  // NOLINT(build/include_order)
+
+#include <netioapi.h>  // NOLINT(build/include_order)
+
+#include "Instance.h"
+#include "Log.h"
+#include "Notifier.h"
+
+#pragma comment(lib, "Iphlpapi.lib")
+
+using namespace cs;
+
+class NetworkListener::Impl {
+ public:
+  Impl(wpi::Logger& logger, Notifier& notifier)
+      : m_logger(logger), m_notifier(notifier) {}
+  wpi::Logger& m_logger;
+  Notifier& m_notifier;
+  HANDLE eventHandle = 0;
+};
+
+// Static Callback function for NotifyIpInterfaceChange API.
+static void WINAPI OnInterfaceChange(PVOID callerContext,
+                                     PMIB_IPINTERFACE_ROW row,
+                                     MIB_NOTIFICATION_TYPE notificationType) {
+  Notifier* notifier = reinterpret_cast<Notifier*>(callerContext);
+  notifier->NotifyNetworkInterfacesChanged();
+}
+
+NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier)
+    : m_impl(std::make_unique<Impl>(logger, notifier)) {}
+
+NetworkListener::~NetworkListener() { Stop(); }
+
+void NetworkListener::Start() {
+  NotifyIpInterfaceChange(AF_INET, OnInterfaceChange, &m_impl->m_notifier, true,
+                          &m_impl->eventHandle);
+}
+
+void NetworkListener::Stop() {
+  if (m_impl->eventHandle) {
+    CancelMibChangeNotify2(m_impl->eventHandle);
+  }
+}
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
new file mode 100644
index 0000000..99e734a
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/NetworkUtil.cpp
@@ -0,0 +1,119 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <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() {
+  uv_interface_address_t* adrs;
+  int counts = 0;
+
+  std::vector<std::string> addresses{};
+
+  uv_interface_addresses(&adrs, &counts);
+
+  char ip[50];
+
+  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
new file mode 100644
index 0000000..5ec4c84
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.cpp
@@ -0,0 +1,1038 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#define _WINSOCKAPI_
+#include "UsbCameraImpl.h"
+
+#include <ks.h>
+#include <ksmedia.h>
+#include <mfapi.h>
+#include <mferror.h>
+#include <mfidl.h>
+#include <shlwapi.h>
+#include <windowsx.h>
+
+#include <cmath>
+#include <codecvt>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <Dbt.h>
+#include <Dshow.h>
+#include <Windows.h>
+#include <opencv2/core/core.hpp>
+#include <opencv2/highgui/highgui.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+#include <wpi/SmallString.h>
+#include <wpi/memory.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/timestamp.h>
+
+#include "COMCreators.h"
+#include "ComPtr.h"
+#include "Handle.h"
+#include "Instance.h"
+#include "JpegUtil.h"
+#include "Log.h"
+#include "Notifier.h"
+#include "PropertyImpl.h"
+#include "Telemetry.h"
+#include "WindowsMessagePump.h"
+#include "c_util.h"
+#include "cscore_cpp.h"
+
+#pragma comment(lib, "Mfplat.lib")
+#pragma comment(lib, "Mf.lib")
+#pragma comment(lib, "mfuuid.lib")
+#pragma comment(lib, "Ole32.lib")
+#pragma comment(lib, "User32.lib")
+#pragma comment(lib, "Mfreadwrite.lib")
+#pragma comment(lib, "Shlwapi.lib")
+
+static constexpr int NewImageMessage = 0x0400 + 4488;
+static constexpr int SetCameraMessage = 0x0400 + 254;
+static constexpr int WaitForStartupMessage = 0x0400 + 294;
+static constexpr int PumpReadyMessage = 0x0400 + 330;
+
+static constexpr char const* kPropWbValue = "WhiteBalance";
+static constexpr char const* kPropExValue = "Exposure";
+static constexpr char const* kPropBrValue = "Brightness";
+static constexpr char const* kPropConnectVerbose = "connect_verbose";
+
+static constexpr unsigned kPropConnectVerboseId = 0;
+
+using namespace cs;
+
+namespace cs {
+
+UsbCameraImpl::UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             const wpi::Twine& path)
+    : SourceImpl{name, logger, notifier, telemetry}, m_path{path.str()} {
+  std::wstring_convert<std::codecvt_utf8<wchar_t>> utf8_conv;
+  m_widePath = utf8_conv.from_bytes(m_path.c_str());
+}
+
+UsbCameraImpl::UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger,
+                             Notifier& notifier, Telemetry& telemetry,
+                             int deviceId)
+    : SourceImpl{name, logger, notifier, telemetry}, m_deviceId(deviceId) {}
+
+UsbCameraImpl::~UsbCameraImpl() { m_messagePump = nullptr; }
+
+void UsbCameraImpl::SetProperty(int property, int value, CS_Status* status) {
+  Message msg{Message::kCmdSetProperty};
+  msg.data[0] = property;
+  msg.data[1] = value;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+}
+void UsbCameraImpl::SetStringProperty(int property, const wpi::Twine& value,
+                                      CS_Status* status) {
+  Message msg{Message::kCmdSetPropertyStr};
+  msg.data[0] = property;
+  msg.dataStr = value.str();
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+}
+
+// Standard common camera properties
+void UsbCameraImpl::SetBrightness(int brightness, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropBrValue), brightness, status);
+}
+int UsbCameraImpl::GetBrightness(CS_Status* status) const {
+  return GetProperty(GetPropertyIndex(kPropBrValue), status);
+}
+void UsbCameraImpl::SetWhiteBalanceAuto(CS_Status* status) {
+  // TODO
+}
+void UsbCameraImpl::SetWhiteBalanceHoldCurrent(CS_Status* status) {
+  // TODO
+}
+void UsbCameraImpl::SetWhiteBalanceManual(int value, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropWbValue), value, status);
+}
+void UsbCameraImpl::SetExposureAuto(CS_Status* status) {
+  // TODO
+}
+void UsbCameraImpl::SetExposureHoldCurrent(CS_Status* status) {
+  // TODO
+}
+void UsbCameraImpl::SetExposureManual(int value, CS_Status* status) {
+  SetProperty(GetPropertyIndex(kPropExValue), value, status);
+}
+
+bool UsbCameraImpl::SetVideoMode(const VideoMode& mode, CS_Status* status) {
+  if (mode.pixelFormat == VideoMode::kUnknown) {
+    *status = CS_UNSUPPORTED_MODE;
+    return false;
+  }
+
+  Message msg{Message::kCmdSetMode};
+  msg.data[0] = mode.pixelFormat;
+  msg.data[1] = mode.width;
+  msg.data[2] = mode.height;
+  msg.data[3] = mode.fps;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+  return result == 0;
+}
+
+bool UsbCameraImpl::SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                                   CS_Status* status) {
+  if (pixelFormat == VideoMode::kUnknown) {
+    *status = CS_UNSUPPORTED_MODE;
+    return false;
+  }
+  Message msg{Message::kCmdSetPixelFormat};
+  msg.data[0] = pixelFormat;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+  return result == 0;
+}
+bool UsbCameraImpl::SetResolution(int width, int height, CS_Status* status) {
+  Message msg{Message::kCmdSetResolution};
+  msg.data[0] = width;
+  msg.data[1] = height;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+  return result == 0;
+}
+bool UsbCameraImpl::SetFPS(int fps, CS_Status* status) {
+  Message msg{Message::kCmdSetFPS};
+  msg.data[0] = fps;
+  auto result =
+      m_messagePump->SendWindowMessage<CS_Status, Message::Kind, Message*>(
+          SetCameraMessage, msg.kind, &msg);
+  *status = result;
+  return result == 0;
+}
+
+void UsbCameraImpl::NumSinksChanged() {
+  m_messagePump->PostWindowMessage<Message::Kind, Message*>(
+      SetCameraMessage, Message::kNumSinksChanged, nullptr);
+}
+void UsbCameraImpl::NumSinksEnabledChanged() {
+  m_messagePump->PostWindowMessage<Message::Kind, Message*>(
+      SetCameraMessage, Message::kNumSinksEnabledChanged, nullptr);
+}
+
+void UsbCameraImpl::Start() {
+  m_messagePump = std::make_unique<WindowsMessagePump>(
+      [this](HWND hwnd, UINT uiMsg, WPARAM wParam, LPARAM lParam) {
+        return this->PumpMain(hwnd, uiMsg, wParam, lParam);
+      });
+  m_messagePump->PostWindowMessage(PumpReadyMessage, nullptr, nullptr);
+}
+
+void UsbCameraImpl::PostRequestNewFrame() {
+  m_messagePump->PostWindowMessage(NewImageMessage, nullptr, nullptr);
+}
+
+bool UsbCameraImpl::CheckDeviceChange(WPARAM wParam, DEV_BROADCAST_HDR* pHdr,
+                                      bool* connected) {
+  DEV_BROADCAST_DEVICEINTERFACE* pDi = NULL;
+
+  *connected = false;
+
+  if (pHdr == NULL) {
+    return false;
+  }
+  if (pHdr->dbch_devicetype != DBT_DEVTYP_DEVICEINTERFACE) {
+    return false;
+  }
+
+  // Compare the device name with the symbolic link.
+
+  pDi = reinterpret_cast<DEV_BROADCAST_DEVICEINTERFACE*>(pHdr);
+
+  if (_stricmp(m_path.c_str(), pDi->dbcc_name) == 0) {
+    if (wParam == DBT_DEVICEARRIVAL) {
+      *connected = true;
+      return true;
+    } else if (wParam == DBT_DEVICEREMOVECOMPLETE) {
+      *connected = false;
+      return true;
+    }
+  }
+  return false;
+}
+
+void UsbCameraImpl::DeviceDisconnect() {
+  if (m_connectVerbose) SINFO("Disconnected from " << m_path);
+  m_sourceReader.Reset();
+  m_mediaSource.Reset();
+  if (m_imageCallback) {
+    m_imageCallback->InvalidateCapture();
+  }
+  m_imageCallback.Reset();
+  m_streaming = false;
+  SetConnected(false);
+}
+
+static bool IsPercentageProperty(wpi::StringRef name) {
+  if (name.startswith("raw_")) name = name.substr(4);
+  return name == "Brightness" || name == "Contrast" || name == "Saturation" ||
+         name == "Hue" || name == "Sharpness" || name == "Gain" ||
+         name == "Exposure";
+}
+
+void UsbCameraImpl::ProcessFrame(IMFSample* videoSample,
+                                 const VideoMode& mode) {
+  if (!videoSample) return;
+
+  ComPtr<IMFMediaBuffer> buf;
+
+  if (!SUCCEEDED(videoSample->ConvertToContiguousBuffer(buf.GetAddressOf()))) {
+    DWORD bcnt = 0;
+    if (!SUCCEEDED(videoSample->GetBufferCount(&bcnt))) return;
+    if (bcnt == 0) return;
+    if (!SUCCEEDED(videoSample->GetBufferByIndex(0, buf.GetAddressOf())))
+      return;
+  }
+
+  bool lock2d = false;
+  BYTE* ptr = NULL;
+  LONG pitch = 0;
+  DWORD maxsize = 0, cursize = 0;
+
+  // "For 2-D buffers, the Lock2D method is more efficient than the Lock
+  // method" see IMFMediaBuffer::Lock method documentation:
+  // https://msdn.microsoft.com/en-us/library/windows/desktop/bb970366(v=vs.85).aspx
+  ComPtr<IMF2DBuffer> buffer2d;
+  DWORD memLength2d = 0;
+  if (true) {
+    buffer2d = buf.As<IMF2DBuffer>();
+    if (buffer2d) {
+      buffer2d->GetContiguousLength(&memLength2d);
+      if (SUCCEEDED(buffer2d->Lock2D(&ptr, &pitch))) {
+        lock2d = true;
+      }
+    }
+  }
+  if (ptr == NULL) {
+    if (!SUCCEEDED(buf->Lock(&ptr, &maxsize, &cursize))) {
+      return;
+    }
+  }
+  if (!ptr) return;
+
+  cv::Mat tmpMat;
+  std::unique_ptr<Image> dest;
+  bool doFinalSet = true;
+
+  switch (mode.pixelFormat) {
+    case cs::VideoMode::PixelFormat::kMJPEG: {
+      // Special case
+      PutFrame(VideoMode::kMJPEG, mode.width, mode.height,
+               wpi::StringRef(reinterpret_cast<char*>(ptr), cursize),
+               wpi::Now());
+      doFinalSet = false;
+      break;
+    }
+    case cs::VideoMode::PixelFormat::kGray:
+      tmpMat = cv::Mat(mode.height, mode.width, CV_8UC1, ptr, pitch);
+      dest = AllocImage(VideoMode::kGray, tmpMat.cols, tmpMat.rows,
+                        tmpMat.total());
+      tmpMat.copyTo(dest->AsMat());
+      break;
+    case cs::VideoMode::PixelFormat::kBGR:
+      tmpMat = cv::Mat(mode.height, mode.width, CV_8UC3, ptr, pitch);
+      dest = AllocImage(VideoMode::kBGR, tmpMat.cols, tmpMat.rows,
+                        tmpMat.total() * 3);
+      tmpMat.copyTo(dest->AsMat());
+      break;
+    case cs::VideoMode::PixelFormat::kYUYV:
+      tmpMat = cv::Mat(mode.height, mode.width, CV_8UC2, ptr, pitch);
+      dest = AllocImage(VideoMode::kYUYV, tmpMat.cols, tmpMat.rows,
+                        tmpMat.total() * 2);
+      tmpMat.copyTo(dest->AsMat());
+      break;
+    default:
+      doFinalSet = false;
+      break;
+  }
+
+  if (doFinalSet) {
+    PutFrame(std::move(dest), wpi::Now());
+  }
+
+  if (lock2d)
+    buffer2d->Unlock2D();
+  else
+    buf->Unlock();
+}
+
+LRESULT UsbCameraImpl::PumpMain(HWND hwnd, UINT uiMsg, WPARAM wParam,
+                                LPARAM lParam) {
+  switch (uiMsg) {
+    case WM_CLOSE:
+      m_sourceReader.Reset();
+      m_mediaSource.Reset();
+      if (m_imageCallback) {
+        m_imageCallback->InvalidateCapture();
+      }
+      m_imageCallback.Reset();
+      break;
+    case PumpReadyMessage:
+      // Pump Created and ready to go
+      DeviceConnect();
+      break;
+    case WaitForStartupMessage:
+      return CS_OK;
+    case WM_DEVICECHANGE: {
+      // Device potentially changed
+      PDEV_BROADCAST_HDR parameter =
+          reinterpret_cast<PDEV_BROADCAST_HDR>(lParam);
+      // Check if we're waiting on a device path, and this is a connection
+      if (m_path.empty() && wParam == DBT_DEVICEARRIVAL &&
+          parameter->dbch_devicetype == DBT_DEVTYP_DEVICEINTERFACE) {
+        // If path is empty, we attempted to connect with a device ID. Enumerate
+        // and check
+        CS_Status status = 0;
+        auto devices = cs::EnumerateUsbCameras(&status);
+        if (devices.size() > m_deviceId) {
+          // If has device ID, use the device ID from the event
+          // because of windows bug
+          auto&& device = devices[m_deviceId];
+          DEV_BROADCAST_DEVICEINTERFACE* pDi =
+              reinterpret_cast<DEV_BROADCAST_DEVICEINTERFACE*>(parameter);
+          m_path = pDi->dbcc_name;
+          std::wstring_convert<std::codecvt_utf8<wchar_t>> utf8_conv;
+          m_widePath = utf8_conv.from_bytes(m_path.c_str());
+        } else {
+          // This device not found
+          break;
+        }
+      }
+      bool connected = false;
+      if (CheckDeviceChange(wParam, parameter, &connected)) {
+        if (connected) {
+          DeviceConnect();
+        } else {
+          // Disconnected
+          DeviceDisconnect();
+        }
+      }
+    } break;
+    case NewImageMessage: {  // New image
+      if (m_streaming && m_sourceReader) {
+        m_sourceReader->ReadSample(MF_SOURCE_READER_FIRST_VIDEO_STREAM, 0, NULL,
+                                   NULL, NULL, NULL);
+      }
+      break;
+    }
+    case SetCameraMessage: {
+      {
+        Message* msg = reinterpret_cast<Message*>(lParam);
+        Message::Kind msgKind = static_cast<Message::Kind>(wParam);
+        std::unique_lock<wpi::mutex> lock(m_mutex);
+        auto retVal = DeviceProcessCommand(lock, msgKind, msg);
+        return retVal;
+      }
+      break;
+    }
+  }
+  return 0l;
+}
+
+static cs::VideoMode::PixelFormat GetFromGUID(const GUID& guid) {
+  // Compare GUID to one of the supported ones
+  if (guid == MFVideoFormat_NV12) {
+    // GrayScale
+    return cs::VideoMode::PixelFormat::kGray;
+  } else if (guid == MFVideoFormat_YUY2) {
+    return cs::VideoMode::PixelFormat::kYUYV;
+  } else if (guid == MFVideoFormat_RGB24) {
+    return cs::VideoMode::PixelFormat::kBGR;
+  } else if (guid == MFVideoFormat_MJPG) {
+    return cs::VideoMode::PixelFormat::kMJPEG;
+  } else if (guid == MFVideoFormat_RGB565) {
+    return cs::VideoMode::PixelFormat::kRGB565;
+  } else {
+    return cs::VideoMode::PixelFormat::kUnknown;
+  }
+}
+
+bool UsbCameraImpl::DeviceConnect() {
+  if (m_mediaSource && m_sourceReader) return true;
+
+  if (m_connectVerbose) SINFO("Connecting to USB camera on " << m_path);
+
+  SDEBUG3("opening device");
+
+  const wchar_t* path = m_widePath.c_str();
+  m_mediaSource = CreateVideoCaptureDevice(path);
+
+  if (!m_mediaSource) return false;
+  m_imageCallback = CreateSourceReaderCB(shared_from_this(), m_mode);
+
+  m_sourceReader =
+      CreateSourceReader(m_mediaSource.Get(), m_imageCallback.Get());
+
+  if (!m_sourceReader) {
+    m_mediaSource.Reset();
+    return false;
+  }
+
+  if (!m_properties_cached) {
+    SDEBUG3("caching properties");
+    DeviceCacheProperties();
+    DeviceCacheVideoModes();
+    DeviceCacheMode();
+    m_properties_cached = true;
+  } else {
+    SDEBUG3("restoring video mode");
+    DeviceSetMode();
+  }
+
+  SetConnected(true);
+
+  // Turn off streaming if not enabled, and turn it on if enabled
+  if (IsEnabled()) {
+    DeviceStreamOn();
+  }
+  return true;
+}
+
+std::unique_ptr<PropertyImpl> UsbCameraImpl::CreateEmptyProperty(
+    const wpi::Twine& name) const {
+  return nullptr;
+}
+
+bool UsbCameraImpl::CacheProperties(CS_Status* status) const {
+  // Wait for Camera Thread to be started
+  auto result = m_messagePump->SendWindowMessage<CS_Status>(
+      WaitForStartupMessage, nullptr, nullptr);
+  *status = result;
+  if (*status != CS_OK) return false;
+  if (!m_properties_cached) {
+    *status = CS_SOURCE_IS_DISCONNECTED;
+    return false;
+  }
+  return true;
+}
+
+void UsbCameraImpl::DeviceAddProperty(const wpi::Twine& name_,
+                                      tagVideoProcAmpProperty tag,
+                                      IAMVideoProcAmp* 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);
+  }
+}
+
+#define CREATEPROPERTY(val) \
+  DeviceAddProperty(#val, VideoProcAmp_##val, pProcAmp);
+
+void UsbCameraImpl::DeviceCacheProperties() {
+  if (!m_sourceReader) return;
+
+  IAMVideoProcAmp* pProcAmp = NULL;
+
+  if (SUCCEEDED(m_sourceReader->GetServiceForStream(
+          (DWORD)MF_SOURCE_READER_MEDIASOURCE, GUID_NULL,
+          IID_PPV_ARGS(&pProcAmp)))) {
+    CREATEPROPERTY(Brightness)
+    CREATEPROPERTY(Contrast)
+    CREATEPROPERTY(Hue)
+    CREATEPROPERTY(Saturation)
+    CREATEPROPERTY(Sharpness)
+    CREATEPROPERTY(Gamma)
+    CREATEPROPERTY(ColorEnable)
+    CREATEPROPERTY(WhiteBalance)
+    CREATEPROPERTY(BacklightCompensation)
+    CREATEPROPERTY(Gain)
+    pProcAmp->Release();
+  }
+}
+
+int UsbCameraImpl::RawToPercentage(const UsbCameraProperty& rawProp,
+                                   int rawValue) {
+  return 100.0 * (rawValue - rawProp.minimum) /
+         (rawProp.maximum - rawProp.minimum);
+}
+
+int UsbCameraImpl::PercentageToRaw(const UsbCameraProperty& rawProp,
+                                   int percentValue) {
+  return rawProp.minimum +
+         (rawProp.maximum - rawProp.minimum) * (percentValue / 100.0);
+}
+
+void UsbCameraImpl::DeviceCacheProperty(
+    std::unique_ptr<UsbCameraProperty> rawProp, IAMVideoProcAmp* 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
+  // to rename this one as well as create/cache the percentage version.
+  //
+  // This is complicated by the fact that either the percentage version or the
+  // the raw version may have been set previously.  If both were previously set,
+  // the raw version wins.
+  std::unique_ptr<UsbCameraProperty> perProp;
+  if (IsPercentageProperty(rawProp->name)) {
+    perProp =
+        wpi::make_unique<UsbCameraProperty>(rawProp->name, 0, *rawProp, 0, 0);
+    rawProp->name = "raw_" + perProp->name;
+  }
+
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  int* rawIndex = &m_properties[rawProp->name];
+  bool newRaw = *rawIndex == 0;
+  UsbCameraProperty* oldRawProp =
+      newRaw ? nullptr
+             : static_cast<UsbCameraProperty*>(GetProperty(*rawIndex));
+
+  int* perIndex = perProp ? &m_properties[perProp->name] : nullptr;
+  bool newPer = !perIndex || *perIndex == 0;
+  UsbCameraProperty* oldPerProp =
+      newPer ? nullptr
+             : static_cast<UsbCameraProperty*>(GetProperty(*perIndex));
+
+  if (oldRawProp && oldRawProp->valueSet) {
+    // Merge existing raw setting and set percentage from it
+    rawProp->SetValue(oldRawProp->value);
+    rawProp->valueStr = std::move(oldRawProp->valueStr);
+
+    if (perProp) {
+      perProp->SetValue(RawToPercentage(*rawProp, rawProp->value));
+      perProp->valueStr = rawProp->valueStr;  // copy
+    }
+  } else if (oldPerProp && oldPerProp->valueSet) {
+    // Merge existing percentage setting and set raw from it
+    perProp->SetValue(oldPerProp->value);
+    perProp->valueStr = std::move(oldPerProp->valueStr);
+
+    rawProp->SetValue(PercentageToRaw(*rawProp, perProp->value));
+    rawProp->valueStr = perProp->valueStr;  // copy
+  } else {
+    // Read current raw value and set percentage from it
+    if (!rawProp->DeviceGet(lock, pProcAmp))
+      SWARNING("failed to get property " << rawProp->name);
+
+    if (perProp) {
+      perProp->SetValue(RawToPercentage(*rawProp, rawProp->value));
+      perProp->valueStr = rawProp->valueStr;  // copy
+    }
+  }
+
+  // Set value on device if user-configured
+  if (rawProp->valueSet) {
+    if (!rawProp->DeviceSet(lock, pProcAmp))
+      SWARNING("failed to set property " << rawProp->name);
+  }
+
+  // Update pointers since we released the lock
+  rawIndex = &m_properties[rawProp->name];
+  perIndex = perProp ? &m_properties[perProp->name] : nullptr;
+
+  // Get pointers before we move the std::unique_ptr values
+  auto rawPropPtr = rawProp.get();
+  auto perPropPtr = perProp.get();
+
+  if (newRaw) {
+    // create a new index
+    *rawIndex = m_propertyData.size() + 1;
+    m_propertyData.emplace_back(std::move(rawProp));
+  } else {
+    // update
+    m_propertyData[*rawIndex - 1] = std::move(rawProp);
+  }
+
+  // Finish setting up percentage property
+  if (perProp) {
+    perProp->propPair = *rawIndex;
+    perProp->defaultValue =
+        RawToPercentage(*rawPropPtr, rawPropPtr->defaultValue);
+
+    if (newPer) {
+      // create a new index
+      *perIndex = m_propertyData.size() + 1;
+      m_propertyData.emplace_back(std::move(perProp));
+    } else if (perIndex) {
+      // update
+      m_propertyData[*perIndex - 1] = std::move(perProp);
+    }
+
+    // Tell raw property where to find percentage property
+    rawPropPtr->propPair = *perIndex;
+  }
+
+  NotifyPropertyCreated(*rawIndex, *rawPropPtr);
+  if (perPropPtr) NotifyPropertyCreated(*perIndex, *perPropPtr);
+}
+
+CS_StatusValue UsbCameraImpl::DeviceProcessCommand(
+    std::unique_lock<wpi::mutex>& lock, Message::Kind msgKind,
+    const Message* msg) {
+  if (msgKind == Message::kCmdSetMode ||
+      msgKind == Message::kCmdSetPixelFormat ||
+      msgKind == Message::kCmdSetResolution || msgKind == Message::kCmdSetFPS) {
+    return DeviceCmdSetMode(lock, *msg);
+  } else if (msgKind == Message::kCmdSetProperty ||
+             msgKind == Message::kCmdSetPropertyStr) {
+    return DeviceCmdSetProperty(lock, *msg);
+    return CS_OK;
+  } else if (msgKind == Message::kNumSinksChanged ||
+             msgKind == Message::kNumSinksEnabledChanged) {
+    // Turn On Streams
+    if (!IsEnabled()) {
+      DeviceStreamOff();
+    } else if (!m_streaming && IsEnabled()) {
+      DeviceStreamOn();
+    }
+    return CS_OK;
+  } else {
+    return CS_OK;
+  }
+}
+
+CS_StatusValue UsbCameraImpl::DeviceCmdSetProperty(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  bool setString = (msg.kind == Message::kCmdSetPropertyStr);
+  int property = msg.data[0];
+  int value = msg.data[1];
+  wpi::StringRef valueStr = msg.dataStr;
+
+  // Look up
+  auto prop = static_cast<UsbCameraProperty*>(GetProperty(property));
+  if (!prop) return CS_INVALID_PROPERTY;
+
+  // If setting before we get, guess initial type based on set
+  if (prop->propKind == CS_PROP_NONE) {
+    if (setString)
+      prop->propKind = CS_PROP_STRING;
+    else
+      prop->propKind = CS_PROP_INTEGER;
+  }
+
+  // Check kind match
+  if ((setString && prop->propKind != CS_PROP_STRING) ||
+      (!setString && (prop->propKind &
+                      (CS_PROP_BOOLEAN | CS_PROP_INTEGER | CS_PROP_ENUM)) == 0))
+    return CS_WRONG_PROPERTY_TYPE;
+
+  // Handle percentage property
+  int percentageProperty = prop->propPair;
+  int percentageValue = value;
+  if (percentageProperty != 0) {
+    if (prop->percentage) {
+      std::swap(percentageProperty, property);
+      prop = static_cast<UsbCameraProperty*>(GetProperty(property));
+      value = PercentageToRaw(*prop, percentageValue);
+    } else {
+      percentageValue = RawToPercentage(*prop, value);
+    }
+  }
+
+  // Actually set the new value on the device (if possible)
+  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 {
+      return CS_PROPERTY_WRITE_FAILED;
+    }
+  }
+
+  // Cache the set values
+  UpdatePropertyValue(property, setString, value, valueStr);
+  if (percentageProperty != 0)
+    UpdatePropertyValue(percentageProperty, setString, percentageValue,
+                        valueStr);
+
+  return CS_OK;
+}
+
+ComPtr<IMFMediaType> UsbCameraImpl::DeviceCheckModeValid(
+    const VideoMode& toCheck) {
+  // Find the matching mode
+  auto match =
+      std::find_if(m_windowsVideoModes.begin(), m_windowsVideoModes.end(),
+                   [&](std::pair<VideoMode, ComPtr<IMFMediaType>>& input) {
+                     return input.first == toCheck;
+                   });
+
+  if (match == m_windowsVideoModes.end()) {
+    return nullptr;
+  }
+  return match->second;
+}
+
+CS_StatusValue UsbCameraImpl::DeviceCmdSetMode(
+    std::unique_lock<wpi::mutex>& lock, const Message& msg) {
+  VideoMode newMode;
+  if (msg.kind == Message::kCmdSetMode) {
+    newMode.pixelFormat = msg.data[0];
+    newMode.width = msg.data[1];
+    newMode.height = msg.data[2];
+    newMode.fps = msg.data[3];
+  } else if (msg.kind == Message::kCmdSetPixelFormat) {
+    newMode = m_mode;
+    newMode.pixelFormat = msg.data[0];
+  } else if (msg.kind == Message::kCmdSetResolution) {
+    newMode = m_mode;
+    newMode.width = msg.data[0];
+    newMode.height = msg.data[1];
+  } else if (msg.kind == Message::kCmdSetFPS) {
+    newMode = m_mode;
+    newMode.fps = msg.data[0];
+  }
+
+  // Check if the device is not connected, if not just apply and leave
+  if (!m_properties_cached) {
+    m_mode = newMode;
+    return CS_OK;
+  }
+
+  // If the pixel format or resolution changed, we need to disconnect and
+  // reconnect
+  if (newMode != m_mode) {
+    // First check if the new mode is valid
+    auto newModeType = DeviceCheckModeValid(newMode);
+    if (!newModeType) {
+      return CS_UNSUPPORTED_MODE;
+    }
+
+    m_currentMode = std::move(newModeType);
+    m_mode = newMode;
+    lock.unlock();
+    if (m_sourceReader) {
+      DeviceDisconnect();
+      DeviceConnect();
+    }
+    m_notifier.NotifySourceVideoMode(*this, newMode);
+    lock.lock();
+  }
+
+  return CS_OK;
+}
+
+bool UsbCameraImpl::DeviceStreamOn() {
+  if (m_streaming) return false;
+  if (!m_deviceValid) return false;
+  m_streaming = true;
+  m_sourceReader->ReadSample(MF_SOURCE_READER_FIRST_VIDEO_STREAM, 0, NULL, NULL,
+                             NULL, NULL);
+  return true;
+}
+
+bool UsbCameraImpl::DeviceStreamOff() {
+  m_streaming = false;
+  return true;
+}
+
+void UsbCameraImpl::DeviceCacheMode() {
+  if (!m_sourceReader) return;
+
+  if (m_windowsVideoModes.size() == 0) return;
+
+  if (!m_currentMode) {
+    // First, see if our set mode is valid
+    m_currentMode = DeviceCheckModeValid(m_mode);
+    if (!m_currentMode) {
+      if (FAILED(m_sourceReader->GetCurrentMediaType(
+              MF_SOURCE_READER_FIRST_VIDEO_STREAM,
+              m_currentMode.GetAddressOf()))) {
+        return;
+      }
+      // Find cached version
+      DWORD compare = MF_MEDIATYPE_EQUAL_MAJOR_TYPES |
+                      MF_MEDIATYPE_EQUAL_FORMAT_TYPES |
+                      MF_MEDIATYPE_EQUAL_FORMAT_DATA;
+      auto result = std::find_if(
+          m_windowsVideoModes.begin(), m_windowsVideoModes.end(),
+          [this, &compare](std::pair<VideoMode, ComPtr<IMFMediaType>>& input) {
+            return input.second->IsEqual(m_currentMode.Get(), &compare) == S_OK;
+          });
+
+      if (result == m_windowsVideoModes.end()) {
+        // Default mode is not supported. Grab first supported image
+        auto&& firstSupported = m_windowsVideoModes[0];
+        m_currentMode = firstSupported.second;
+        std::lock_guard<wpi::mutex> lock(m_mutex);
+        m_mode = firstSupported.first;
+      } else {
+        std::lock_guard<wpi::mutex> lock(m_mutex);
+        m_mode = result->first;
+      }
+    }
+  }
+
+  DeviceSetMode();
+
+  m_notifier.NotifySourceVideoMode(*this, m_mode);
+}
+
+CS_StatusValue UsbCameraImpl::DeviceSetMode() {
+  HRESULT setResult = m_sourceReader->SetCurrentMediaType(
+      MF_SOURCE_READER_FIRST_VIDEO_STREAM, NULL, m_currentMode.Get());
+
+  m_deviceValid = SUCCEEDED(setResult);
+
+  m_imageCallback->SetVideoMode(m_mode);
+
+  switch (setResult) {
+    case S_OK:
+      return CS_OK;
+      break;
+    case MF_E_INVALIDMEDIATYPE:
+      break;
+    case MF_E_INVALIDREQUEST:
+      break;
+    case MF_E_INVALIDSTREAMNUMBER:
+      break;
+    case MF_E_TOPO_CODEC_NOT_FOUND:
+      break;
+  }
+
+  return CS_UNSUPPORTED_MODE;
+}
+
+void UsbCameraImpl::DeviceCacheVideoModes() {
+  if (!m_sourceReader) return;
+
+  std::vector<VideoMode> modes;
+  m_windowsVideoModes.clear();
+
+  bool set = false;
+
+  ComPtr<IMFMediaType> nativeType;
+  int count = 0;
+  while (true) {
+    nativeType.Reset();
+    auto hr = m_sourceReader->GetNativeMediaType(
+        MF_SOURCE_READER_FIRST_VIDEO_STREAM, count, nativeType.GetAddressOf());
+    if (FAILED(hr)) {
+      break;
+    }
+    GUID guid = {0};
+    nativeType->GetGUID(MF_MT_SUBTYPE, &guid);
+
+    auto format = GetFromGUID(guid);
+    if (format == VideoMode::kUnknown) {
+      count++;
+      // Don't put in unknowns
+      continue;
+    }
+    UINT32 width, height;
+    ::MFGetAttributeSize(nativeType.Get(), MF_MT_FRAME_SIZE, &width, &height);
+
+    UINT32 num, dom;
+    ::MFGetAttributeRatio(nativeType.Get(), MF_MT_FRAME_RATE, &num, &dom);
+
+    int fps = 30;
+
+    if (dom != 0) {
+      fps = std::ceil(num / static_cast<double>(dom));
+    }
+
+    VideoMode newMode = {format, static_cast<int>(width),
+                         static_cast<int>(height), fps};
+
+    modes.emplace_back(newMode);
+    m_windowsVideoModes.emplace_back(newMode, nativeType);
+    count++;
+  }
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_videoModes.swap(modes);
+  }
+  m_notifier.NotifySource(*this, CS_SOURCE_VIDEOMODES_UPDATED);
+}
+
+std::vector<UsbCameraInfo> EnumerateUsbCameras(CS_Status* status) {
+  std::vector<UsbCameraInfo> retval;
+
+  // 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;
+
+  // Create an attribute store to specify the enumeration parameters.
+  HRESULT hr = MFCreateAttributes(pAttributes.GetAddressOf(), 1);
+  if (FAILED(hr)) {
+    goto done;
+  }
+
+  // Source type: video capture devices
+  hr = pAttributes->SetGUID(MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE,
+                            MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_GUID);
+  if (FAILED(hr)) {
+    goto done;
+  }
+
+  // Enumerate devices.
+  UINT32 count;
+  hr = MFEnumDeviceSources(pAttributes.Get(), &ppDevices, &count);
+  if (FAILED(hr)) {
+    goto done;
+  }
+
+  if (count == 0) {
+    hr = E_FAIL;
+    goto done;
+  }
+
+  for (UINT32 i = 0; i < count; i++) {
+    UsbCameraInfo info;
+    info.dev = i;
+    WCHAR buf[512];
+    ppDevices[i]->GetString(MF_DEVSOURCE_ATTRIBUTE_FRIENDLY_NAME, buf,
+                            sizeof(buf), NULL);
+    info.name = utf8_conv.to_bytes(buf);
+    ppDevices[i]->GetString(
+        MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_SYMBOLIC_LINK, buf,
+        sizeof(buf), NULL);
+    info.path = utf8_conv.to_bytes(buf);
+    retval.emplace_back(std::move(info));
+  }
+
+done:
+  pAttributes.Reset();
+
+  for (DWORD i = 0; i < count; i++) {
+    if (ppDevices[i]) {
+      ppDevices[i]->Release();
+      ppDevices[i] = nullptr;
+    }
+  }
+  CoTaskMemFree(ppDevices);
+  pSource.Reset();
+  return retval;
+}
+
+CS_Source CreateUsbCameraDev(const wpi::Twine& name, int dev,
+                             CS_Status* status) {
+  // First check if device exists
+  auto devices = cs::EnumerateUsbCameras(status);
+  if (devices.size() > dev) {
+    return CreateUsbCameraPath(name, devices[dev].path, status);
+  }
+  auto& inst = Instance::GetInstance();
+  auto source = std::make_shared<UsbCameraImpl>(
+      name, inst.logger, inst.notifier, inst.telemetry, dev);
+  return inst.CreateSource(CS_SOURCE_USB, source);
+}
+
+CS_Source CreateUsbCameraPath(const wpi::Twine& name, const wpi::Twine& path,
+                              CS_Status* status) {
+  auto& inst = Instance::GetInstance();
+  auto source = std::make_shared<UsbCameraImpl>(
+      name, inst.logger, inst.notifier, inst.telemetry, path);
+  return inst.CreateSource(CS_SOURCE_USB, source);
+}
+
+std::string GetUsbCameraPath(CS_Source source, CS_Status* status) {
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return std::string{};
+  }
+  return static_cast<UsbCameraImpl&>(*data->source).GetPath();
+}
+
+UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) {
+  UsbCameraInfo info;
+  auto data = Instance::GetInstance().GetSource(source);
+  if (!data || data->kind != CS_SOURCE_USB) {
+    *status = CS_INVALID_HANDLE;
+    return info;
+  }
+
+  info.path = static_cast<UsbCameraImpl&>(*data->source).GetPath();
+  // TODO: dev and name
+  return info;
+}
+
+}  // namespace cs
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
new file mode 100644
index 0000000..5b730fb
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraImpl.h
@@ -0,0 +1,184 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef CSCORE_USBCAMERAIMPL_H_
+#define CSCORE_USBCAMERAIMPL_H_
+
+#include <mfapi.h>
+#include <mfidl.h>
+#include <mfreadwrite.h>
+
+#include <ks.h>  // NOLINT(build/include_order)
+
+#include <ksmedia.h>  // NOLINT(build/include_order)
+
+#include <atomic>
+#include <memory>
+#include <string>
+#include <thread>
+#include <utility>
+#include <vector>
+
+#include <Dbt.h>
+#include <wpi/STLExtras.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+#include "ComCreators.h"
+#include "ComPtr.h"
+#include "SourceImpl.h"
+#include "UsbCameraProperty.h"
+#include "WindowsMessagePump.h"
+
+namespace cs {
+
+class UsbCameraImpl : public SourceImpl,
+                      public std::enable_shared_from_this<UsbCameraImpl> {
+ public:
+  UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, const wpi::Twine& path);
+  UsbCameraImpl(const wpi::Twine& name, wpi::Logger& logger, Notifier& notifier,
+                Telemetry& telemetry, int deviceId);
+  ~UsbCameraImpl() override;
+
+  void Start();
+
+  // Property functions
+  void SetProperty(int property, int value, CS_Status* status) override;
+  void SetStringProperty(int property, const wpi::Twine& value,
+                         CS_Status* status) override;
+
+  // Standard common camera properties
+  void SetBrightness(int brightness, CS_Status* status) override;
+  int GetBrightness(CS_Status* status) const override;
+  void SetWhiteBalanceAuto(CS_Status* status) override;
+  void SetWhiteBalanceHoldCurrent(CS_Status* status) override;
+  void SetWhiteBalanceManual(int value, CS_Status* status) override;
+  void SetExposureAuto(CS_Status* status) override;
+  void SetExposureHoldCurrent(CS_Status* status) override;
+  void SetExposureManual(int value, CS_Status* status) override;
+
+  bool SetVideoMode(const VideoMode& mode, CS_Status* status) override;
+  bool SetPixelFormat(VideoMode::PixelFormat pixelFormat,
+                      CS_Status* status) override;
+  bool SetResolution(int width, int height, CS_Status* status) override;
+  bool SetFPS(int fps, CS_Status* status) override;
+
+  void NumSinksChanged() override;
+  void NumSinksEnabledChanged() override;
+
+  void ProcessFrame(IMFSample* sample, const VideoMode& mode);
+  void PostRequestNewFrame();
+
+  std::string GetPath() { return m_path; }
+
+  // Messages passed to/from camera thread
+  struct Message {
+    enum Kind {
+      kNone = 0,
+      kCmdSetMode,
+      kCmdSetPixelFormat,
+      kCmdSetResolution,
+      kCmdSetFPS,
+      kCmdSetProperty,
+      kCmdSetPropertyStr,
+      kNumSinksChanged,         // no response
+      kNumSinksEnabledChanged,  // no response
+      // Responses
+      kOk,
+      kError
+    };
+
+    explicit Message(Kind kind_)
+        : kind(kind_), from(std::this_thread::get_id()) {}
+
+    Kind kind;
+    int data[4];
+    std::string dataStr;
+    std::thread::id from;
+  };
+
+ protected:
+  std::unique_ptr<PropertyImpl> CreateEmptyProperty(
+      const wpi::Twine& name) const override;
+
+  // Cache properties.  Immediately successful if properties are already cached.
+  // If they are not, tries to connect to the camera to do so; returns false and
+  // sets status to CS_SOURCE_IS_DISCONNECTED if that too fails.
+  bool CacheProperties(CS_Status* status) const override;
+
+ private:
+  // The camera processing thread
+  void CameraThreadMain();
+
+  LRESULT PumpMain(HWND hwnd, UINT uiMsg, WPARAM wParam, LPARAM lParam);
+
+  bool CheckDeviceChange(WPARAM wParam, DEV_BROADCAST_HDR* pHdr,
+                         bool* connected);
+
+  // Functions used by CameraThreadMain()
+  void DeviceDisconnect();
+  bool DeviceConnect();
+  bool DeviceStreamOn();
+  bool DeviceStreamOff();
+  CS_StatusValue DeviceSetMode();
+  void DeviceCacheMode();
+  void DeviceCacheProperty(std::unique_ptr<UsbCameraProperty> rawProp,
+                           IAMVideoProcAmp* pProcAmp);
+  void DeviceCacheProperties();
+  void DeviceCacheVideoModes();
+  void DeviceAddProperty(const wpi::Twine& name_, tagVideoProcAmpProperty tag,
+                         IAMVideoProcAmp* pProcAmp);
+
+  ComPtr<IMFMediaType> DeviceCheckModeValid(const VideoMode& toCheck);
+
+  // Command helper functions
+  CS_StatusValue DeviceProcessCommand(std::unique_lock<wpi::mutex>& lock,
+                                      Message::Kind msgKind,
+                                      const Message* msg);
+  CS_StatusValue DeviceCmdSetMode(std::unique_lock<wpi::mutex>& lock,
+                                  const Message& msg);
+  CS_StatusValue DeviceCmdSetProperty(std::unique_lock<wpi::mutex>& lock,
+                                      const Message& msg);
+
+  // Property helper functions
+  int RawToPercentage(const UsbCameraProperty& rawProp, int rawValue);
+  int PercentageToRaw(const UsbCameraProperty& rawProp, int percentValue);
+
+  //
+  // Variables only used within camera thread
+  //
+  bool m_streaming{false};
+  bool m_wasStreaming{false};
+  bool m_modeSet{false};
+  int m_connectVerbose{1};
+  bool m_deviceValid{false};
+
+  ComPtr<IMFMediaSource> m_mediaSource;
+  ComPtr<IMFSourceReader> m_sourceReader;
+  ComPtr<SourceReaderCB> m_imageCallback;
+  std::unique_ptr<cs::WindowsMessagePump> m_messagePump;
+  ComPtr<IMFMediaType> m_currentMode;
+
+  //
+  // Path never changes, so not protected by mutex.
+  //
+  std::string m_path;
+
+  std::wstring m_widePath;
+  int m_deviceId;
+
+  std::vector<std::pair<VideoMode, ComPtr<IMFMediaType>>> m_windowsVideoModes;
+};
+
+}  // namespace cs
+
+#endif  // CSCORE_USBCAMERAIMPL_H_
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
new file mode 100644
index 0000000..73bc6c0
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.cpp
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "UsbCameraProperty.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->isAutoProp = autoProp;
+  long paramVal, paramFlag;  // NOLINT(runtime/int)
+  HRESULT hr;
+  long minVal, maxVal, stepVal;  // NOLINT(runtime/int)
+  hr = pProcAmp->GetRange(tag, &minVal, &maxVal, &stepVal, &paramVal,
+                          &paramFlag);  // 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,
+                                  IAMVideoProcAmp* pProcAmp) {
+  if (!pProcAmp) return true;
+
+  lock.unlock();
+  long newValue = 0, paramFlag = 0;  // NOLINT(runtime/int)
+  if (SUCCEEDED(pProcAmp->Get(tag, &newValue, &paramFlag))) {
+    lock.lock();
+    value = newValue;
+    return true;
+  }
+
+  return false;
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  IAMVideoProcAmp* pProcAmp) const {
+  return DeviceSet(lock, pProcAmp, value);
+}
+bool UsbCameraProperty::DeviceSet(std::unique_lock<wpi::mutex>& lock,
+                                  IAMVideoProcAmp* pProcAmp,
+                                  int newValue) const {
+  if (!pProcAmp) return true;
+
+  lock.unlock();
+  if (SUCCEEDED(pProcAmp->Set(tag, newValue, VideoProcAmp_Flags_Manual))) {
+    lock.lock();
+    return true;
+  }
+
+  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
new file mode 100644
index 0000000..5d63c73
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/UsbCameraProperty.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <Dshow.h>
+#include <wpi/mutex.h>
+
+#include "PropertyImpl.h"
+
+namespace cs {
+
+// Property data
+class UsbCameraProperty : public PropertyImpl {
+ public:
+  UsbCameraProperty() = default;
+  explicit UsbCameraProperty(const wpi::Twine& name_) : PropertyImpl{name_} {}
+
+  // Software property constructor
+  UsbCameraProperty(const wpi::Twine& name_, unsigned id_,
+                    CS_PropertyKind kind_, int minimum_, int maximum_,
+                    int step_, int defaultValue_, int value_)
+      : PropertyImpl(name_, kind_, minimum_, maximum_, step_, defaultValue_,
+                     value_),
+        device{false},
+        id{id_} {}
+
+  // Normalized property constructor
+  UsbCameraProperty(const wpi::Twine& name_, int rawIndex_,
+                    const UsbCameraProperty& rawProp, int defaultValue_,
+                    int value_)
+      : PropertyImpl(name_, rawProp.propKind, 1, defaultValue_, value_),
+        percentage{true},
+        propPair{rawIndex_},
+        id{rawProp.id},
+        type{rawProp.type} {
+    hasMinimum = true;
+    minimum = 0;
+    hasMaximum = true;
+    maximum = 100;
+  }
+
+  UsbCameraProperty(const wpi::Twine& name_, tagVideoProcAmpProperty tag,
+                    bool autoProp, IAMVideoProcAmp* pProcAmp, bool* isValid);
+
+  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;
+
+  // If this is a device (rather than software) property
+  bool device{true};
+  bool isAutoProp{true};
+  tagVideoProcAmpProperty tag;
+
+  // If this is a percentage (rather than raw) property
+  bool percentage{false};
+
+  // If not 0, index of corresponding raw/percentage property
+  int propPair{0};
+
+  unsigned id{0};  // implementation-level id
+  int type{0};     // implementation type, not CS_PropertyKind!
+};
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/WindowsMessagePump.cpp b/third_party/allwpilib_2019/cscore/src/main/native/windows/WindowsMessagePump.cpp
new file mode 100644
index 0000000..0206bd0
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/WindowsMessagePump.cpp
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "WindowsMessagePump.h"
+
+#include <ks.h>
+#include <ksmedia.h>
+#include <mfapi.h>
+#include <mfidl.h>
+#include <windows.h>
+#include <windowsx.h>
+
+#include <memory>
+
+#include <Dbt.h>
+
+#pragma comment(lib, "Mfplat.lib")
+#pragma comment(lib, "Mf.lib")
+#pragma comment(lib, "mfuuid.lib")
+#pragma comment(lib, "Ole32.lib")
+#pragma comment(lib, "User32.lib")
+
+namespace cs {
+
+static LRESULT CALLBACK pWndProc(HWND hwnd, UINT uiMsg, WPARAM wParam,
+                                 LPARAM lParam) {
+  WindowsMessagePump* pumpContainer;
+  // Our "this" parameter is passed only during WM_CREATE
+  // If it is create, store in our user parameter
+  // Otherwise grab from our user parameter
+  if (uiMsg == WM_CREATE) {
+    CREATESTRUCT* pCreate = reinterpret_cast<CREATESTRUCT*>(lParam);
+    pumpContainer =
+        reinterpret_cast<WindowsMessagePump*>(pCreate->lpCreateParams);
+    SetWindowLongPtr(hwnd, GWLP_USERDATA, (LONG_PTR)pumpContainer);
+    SetWindowPos(hwnd, HWND_MESSAGE, 0, 0, 0, 0,
+                 SWP_NOMOVE | SWP_NOSIZE | SWP_NOZORDER | SWP_FRAMECHANGED);
+  } else {
+    pumpContainer = reinterpret_cast<WindowsMessagePump*>(
+        GetWindowLongPtr(hwnd, GWLP_USERDATA));
+  }
+
+  // Run the callback
+  bool hasCalledBack = false;
+  LRESULT result;
+
+  if (pumpContainer) {
+    hasCalledBack = true;
+    result = pumpContainer->m_callback(hwnd, uiMsg, wParam, lParam);
+  }
+
+  // Handle a close message
+  if (uiMsg == WM_CLOSE) {
+    return HANDLE_WM_CLOSE(hwnd, 0, 0, [](HWND) { PostQuitMessage(0); });
+  }
+
+  // Return message, otherwise return the base handler
+  if (hasCalledBack) {
+    return result;
+  }
+  return DefWindowProc(hwnd, uiMsg, wParam, lParam);
+}
+
+namespace {
+struct ClassHolder {
+  HINSTANCE current_instance;
+  WNDCLASSEX wx;
+  const char* class_name = "DUMMY_CLASS";
+  ClassHolder() {
+    current_instance = (HINSTANCE)GetModuleHandle(NULL);
+    wx = {};
+    wx.cbSize = sizeof(WNDCLASSEX);
+    wx.lpfnWndProc = pWndProc;  // function which will handle messages
+    wx.hInstance = current_instance;
+    wx.lpszClassName = class_name;
+    RegisterClassEx(&wx);
+  }
+  ~ClassHolder() { UnregisterClass(class_name, current_instance); }
+};
+}  // namespace
+
+static std::shared_ptr<ClassHolder> GetClassHolder() {
+  static std::shared_ptr<ClassHolder> clsHolder =
+      std::make_shared<ClassHolder>();
+  return clsHolder;
+}
+
+WindowsMessagePump::WindowsMessagePump(
+    std::function<LRESULT(HWND, UINT, WPARAM, LPARAM)> callback) {
+  m_callback = callback;
+  auto handle = CreateEvent(NULL, true, false, NULL);
+  m_mainThread = std::thread([=]() { ThreadMain(handle); });
+  auto waitResult = WaitForSingleObject(handle, 1000);
+  if (waitResult == WAIT_OBJECT_0) {
+    CloseHandle(handle);
+  }
+}
+
+WindowsMessagePump::~WindowsMessagePump() {
+  auto res = SendMessage(hwnd, WM_CLOSE, NULL, NULL);
+  if (m_mainThread.joinable()) m_mainThread.join();
+}
+
+void WindowsMessagePump::ThreadMain(HANDLE eventHandle) {
+  // Initialize COM
+  CoInitializeEx(0, COINIT_MULTITHREADED);
+  // Initialize MF
+  MFStartup(MF_VERSION);
+
+  auto classHolder = GetClassHolder();
+  hwnd = CreateWindowEx(0, classHolder->class_name, "dummy_name", 0, 0, 0, 0, 0,
+                        HWND_MESSAGE, NULL, NULL, this);
+
+  // Register for device notifications
+  HDEVNOTIFY g_hdevnotify = NULL;
+  HDEVNOTIFY g_hdevnotify2 = NULL;
+
+  DEV_BROADCAST_DEVICEINTERFACE di = {0};
+  di.dbcc_size = sizeof(di);
+  di.dbcc_devicetype = DBT_DEVTYP_DEVICEINTERFACE;
+  di.dbcc_classguid = KSCATEGORY_CAPTURE;
+
+  g_hdevnotify =
+      RegisterDeviceNotification(hwnd, &di, DEVICE_NOTIFY_WINDOW_HANDLE);
+
+  DEV_BROADCAST_DEVICEINTERFACE di2 = {0};
+  di2.dbcc_size = sizeof(di2);
+  di2.dbcc_devicetype = DBT_DEVTYP_DEVICEINTERFACE;
+  di2.dbcc_classguid = KSCATEGORY_VIDEO_CAMERA;
+
+  g_hdevnotify2 =
+      RegisterDeviceNotification(hwnd, &di2, DEVICE_NOTIFY_WINDOW_HANDLE);
+
+  SetEvent(eventHandle);
+
+  MSG Msg;
+  while (GetMessage(&Msg, NULL, 0, 0) > 0) {
+    TranslateMessage(&Msg);
+    DispatchMessage(&Msg);
+  }
+  UnregisterDeviceNotification(g_hdevnotify);
+  UnregisterDeviceNotification(g_hdevnotify2);
+
+  MFShutdown();
+  CoUninitialize();
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/main/native/windows/WindowsMessagePump.h b/third_party/allwpilib_2019/cscore/src/main/native/windows/WindowsMessagePump.h
new file mode 100644
index 0000000..4638e4e
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/main/native/windows/WindowsMessagePump.h
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <windows.h>
+
+#include <functional>
+#include <thread>
+
+namespace cs {
+class WindowsMessagePump {
+ public:
+  WindowsMessagePump(
+      std::function<LRESULT(HWND, UINT, WPARAM, LPARAM)> callback);
+  ~WindowsMessagePump();
+
+  friend LRESULT CALLBACK pWndProc(HWND hwnd, UINT uiMsg, WPARAM wParam,
+                                   LPARAM lParam);
+
+  template <typename RetVal = LRESULT, typename FirstParam = WPARAM,
+            typename SecondParam = LPARAM>
+  RetVal SendWindowMessage(UINT msg, FirstParam wParam, SecondParam lParam) {
+    static_assert(sizeof(FirstParam) <= sizeof(WPARAM),
+                  "First Parameter Does Not Fit");
+    static_assert(sizeof(SecondParam) <= sizeof(LPARAM),
+                  "Second Parameter Does Not Fit");
+    static_assert(sizeof(RetVal) <= sizeof(LRESULT),
+                  "Return Value Does Not Fit");
+    WPARAM firstToSend = 0;
+    LPARAM secondToSend = 0;
+    std::memcpy(&firstToSend, &wParam, sizeof(FirstParam));
+    std::memcpy(&secondToSend, &lParam, sizeof(SecondParam));
+    LRESULT result = SendMessage(hwnd, msg, firstToSend, secondToSend);
+    RetVal toReturn;
+    std::memset(&toReturn, 0, sizeof(RetVal));
+    std::memcpy(&toReturn, &result, sizeof(RetVal));
+    return toReturn;
+  }
+
+  template <typename FirstParam = WPARAM, typename SecondParam = LPARAM>
+  BOOL PostWindowMessage(UINT msg, FirstParam wParam, SecondParam lParam) {
+    static_assert(sizeof(FirstParam) <= sizeof(WPARAM),
+                  "First Parameter Does Not Fit");
+    static_assert(sizeof(SecondParam) <= sizeof(LPARAM),
+                  "Second Parameter Does Not Fit");
+    WPARAM firstToSend = 0;
+    LPARAM secondToSend = 0;
+    std::memcpy(&firstToSend, &wParam, sizeof(FirstParam));
+    std::memcpy(&secondToSend, &lParam, sizeof(SecondParam));
+    return PostMessage(hwnd, msg, firstToSend, secondToSend);
+  }
+
+ private:
+  void ThreadMain(HANDLE eventHandle);
+
+  HWND hwnd;
+  std::function<LRESULT(HWND, UINT, WPARAM, LPARAM)> m_callback;
+
+  std::thread m_mainThread;
+};
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/test/java/edu/wpi/cscore/JNITest.java b/third_party/allwpilib_2019/cscore/src/test/java/edu/wpi/cscore/JNITest.java
new file mode 100644
index 0000000..b3c1062
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/test/java/edu/wpi/cscore/JNITest.java
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import org.junit.jupiter.api.Test;
+
+class JNITest {
+  @Test
+  void jniLinkTest() {
+    // Test to verify that the JNI test link works correctly.
+    CameraServerJNI.getHostname();
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/test/java/edu/wpi/cscore/UsbCameraTest.java b/third_party/allwpilib_2019/cscore/src/test/java/edu/wpi/cscore/UsbCameraTest.java
new file mode 100644
index 0000000..b55dc4e
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/test/java/edu/wpi/cscore/UsbCameraTest.java
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.cscore;
+
+import java.time.Duration;
+import java.util.Arrays;
+import java.util.concurrent.CompletableFuture;
+import java.util.concurrent.TimeUnit;
+import java.util.concurrent.TimeoutException;
+
+import org.junit.jupiter.api.Nested;
+import org.junit.jupiter.api.Test;
+import org.junit.jupiter.api.condition.EnabledOnOs;
+import org.junit.jupiter.api.condition.OS;
+
+import static org.junit.jupiter.api.Assertions.assertThrows;
+import static org.junit.jupiter.api.Assertions.assertTimeoutPreemptively;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+class UsbCameraTest {
+  @Nested
+  @EnabledOnOs(OS.LINUX)
+  static class ConnectVerbose {
+    @Test
+    void setConnectVerboseEnabledTest() {
+      try (UsbCamera camera = new UsbCamera("Nonexistant Camera", getNonexistentCameraDev())) {
+        camera.setConnectVerbose(1);
+
+        CompletableFuture<String> result = new CompletableFuture<>();
+        CameraServerJNI.setLogger((level, file, line, message) -> {
+          result.complete(message);
+        }, 20);
+
+        assertTimeoutPreemptively(Duration.ofSeconds(5),
+            () -> assertTrue(result.get().contains("Connecting to USB camera on ")));
+      }
+    }
+
+    @Test
+    void setConnectVerboseDisabledTest() {
+      try (UsbCamera camera = new UsbCamera("Nonexistant Camera", getNonexistentCameraDev())) {
+        camera.setConnectVerbose(0);
+
+        CompletableFuture<String> result = new CompletableFuture<>();
+        CameraServerJNI.setLogger((level, file, line, message) -> {
+          result.complete(message);
+        }, 20);
+
+        assertThrows(TimeoutException.class,
+            () -> result.get(3, TimeUnit.SECONDS));
+      }
+    }
+  }
+
+  private static int getNonexistentCameraDev() {
+    return Arrays.stream(CameraServerJNI.enumerateUsbCameras())
+        .mapToInt(info -> info.dev)
+        .max().orElseGet(() -> -1) + 1;
+  }
+}
diff --git a/third_party/allwpilib_2019/cscore/src/test/native/cpp/CameraSourceTest.cpp b/third_party/allwpilib_2019/cscore/src/test/native/cpp/CameraSourceTest.cpp
new file mode 100644
index 0000000..e09f5e6
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/test/native/cpp/CameraSourceTest.cpp
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "cscore.h"
+#include "gtest/gtest.h"
+
+namespace cs {
+
+class CameraSourceTest : public ::testing::Test {
+ protected:
+  CameraSourceTest() {}
+};
+
+TEST_F(CameraSourceTest, HTTPCamera) {
+  auto source = HttpCamera("axis", "http://localhost:8000");
+}
+
+}  // namespace cs
diff --git a/third_party/allwpilib_2019/cscore/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/cscore/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..1e5ecf0
--- /dev/null
+++ b/third_party/allwpilib_2019/cscore/src/test/native/cpp/main.cpp
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/docs/build.gradle b/third_party/allwpilib_2019/docs/build.gradle
new file mode 100644
index 0000000..9f6995f
--- /dev/null
+++ b/third_party/allwpilib_2019/docs/build.gradle
@@ -0,0 +1,150 @@
+plugins {
+    id 'java'
+    id "org.ysb33r.doxygen" version "0.5"
+}
+
+evaluationDependsOn(':wpiutil')
+evaluationDependsOn(':ntcore')
+evaluationDependsOn(':cscore')
+evaluationDependsOn(':hal')
+evaluationDependsOn(':cameraserver')
+evaluationDependsOn(':wpilibc')
+evaluationDependsOn(':wpilibj')
+
+def pubVersion = ''
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseArtifactIdCpp = 'documentation'
+def artifactGroupIdCpp = 'edu.wpi.first.wpilibc'
+def zipBaseNameCpp = '_GROUP_edu_wpi_first_wpilibc_ID_documentation_CLS'
+
+def baseArtifactIdJava = 'documentation'
+def artifactGroupIdJava = 'edu.wpi.first.wpilibj'
+def zipBaseNameJava = '_GROUP_edu_wpi_first_wpilibj_ID_documentation_CLS'
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+def cppProjectZips = []
+
+cppProjectZips.add(project(':hal').cppHeadersZip)
+cppProjectZips.add(project(':wpiutil').cppHeadersZip)
+cppProjectZips.add(project(':ntcore').cppHeadersZip)
+cppProjectZips.add(project(':cscore').cppHeadersZip)
+cppProjectZips.add(project(':cameraserver').cppHeadersZip)
+cppProjectZips.add(project(':wpilibc').cppHeadersZip)
+
+doxygen {
+  executables {
+     doxygen version : '1.8.8'
+  }
+}
+
+doxygen {
+    generate_html true
+
+    cppProjectZips.each {
+        dependsOn it
+        source it.source
+    }
+
+    extension_mapping 'inc=C++'
+    project_name 'WPILibC++'
+    project_number pubVersion
+    javadoc_autobrief true
+    recursive true
+    quiet true
+    warnings false
+    warn_if_doc_error false
+    warn_no_paramdoc false
+    warn_format false
+    warn_logfile false
+    warn_if_undocumented false
+    generate_latex false
+    use_mathjax true
+    html_timestamp true
+    generate_treeview true
+}
+
+tasks.register("zipCppDocs", Zip) {
+    baseName = zipBaseNameCpp
+    destinationDir = outputsFolder
+    dependsOn doxygen
+    from ("$buildDir/docs/doxygen/html")
+    into '/'
+}
+
+
+// Java
+configurations {
+    javaSource {
+        transitive false
+    }
+}
+
+ext {
+    sharedCvConfigs = [:]
+    staticCvConfigs = [:]
+    useJava = true
+    useCpp = false
+    skipDev = true
+    useDocumentation = true
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+task generateJavaDocs(type: Javadoc) {
+    options.links("https://docs.oracle.com/javase/8/docs/api/")
+    options.addStringOption "tag", "pre:a:Pre-Condition"
+    options.addStringOption('Xdoclint:accessibility,html,missing,reference,syntax')
+    options.addBooleanOption('html5', true)
+    dependsOn project(':wpilibj').generateJavaVersion
+    dependsOn project(':hal').generateUsageReporting
+    source project(':hal').sourceSets.main.java
+    source project(':wpiutil').sourceSets.main.java
+    source project(':cscore').sourceSets.main.java
+    source project(':ntcore').sourceSets.main.java
+    source project(':wpilibj').sourceSets.main.java
+    source project(':cameraserver').sourceSets.main.java
+    source configurations.javaSource.collect { zipTree(it) }
+    include '**/*.java'
+    failOnError = true
+}
+
+tasks.register("zipJavaDocs", Zip) {
+    baseName = zipBaseNameJava
+    destinationDir = outputsFolder
+    dependsOn generateJavaDocs
+    from ("$buildDir/docs/javadoc")
+    into '/'
+}
+
+addTaskToCopyAllOutputs(zipCppDocs)
+addTaskToCopyAllOutputs(zipJavaDocs)
+
+build.dependsOn zipCppDocs
+build.dependsOn zipJavaDocs
+
+apply plugin: 'maven-publish'
+
+publishing {
+    publications {
+        java(MavenPublication) {
+            artifact zipJavaDocs
+
+            artifactId = "${baseArtifactIdJava}"
+            groupId artifactGroupIdJava
+            version pubVersion
+        }
+        cpp(MavenPublication) {
+            artifact zipCppDocs
+
+            artifactId = "${baseArtifactIdCpp}"
+            groupId artifactGroupIdCpp
+            version pubVersion
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/gradle/wrapper/gradle-wrapper.jar b/third_party/allwpilib_2019/gradle/wrapper/gradle-wrapper.jar
new file mode 100644
index 0000000..457aad0
--- /dev/null
+++ b/third_party/allwpilib_2019/gradle/wrapper/gradle-wrapper.jar
Binary files differ
diff --git a/third_party/allwpilib_2019/gradle/wrapper/gradle-wrapper.properties b/third_party/allwpilib_2019/gradle/wrapper/gradle-wrapper.properties
new file mode 100644
index 0000000..75b8c7c
--- /dev/null
+++ b/third_party/allwpilib_2019/gradle/wrapper/gradle-wrapper.properties
@@ -0,0 +1,5 @@
+distributionBase=GRADLE_USER_HOME
+distributionPath=wrapper/dists
+distributionUrl=https\://services.gradle.org/distributions/gradle-5.0-bin.zip
+zipStoreBase=GRADLE_USER_HOME
+zipStorePath=wrapper/dists
diff --git a/third_party/allwpilib_2019/gradlew b/third_party/allwpilib_2019/gradlew
new file mode 100755
index 0000000..af6708f
--- /dev/null
+++ b/third_party/allwpilib_2019/gradlew
@@ -0,0 +1,172 @@
+#!/usr/bin/env sh
+
+##############################################################################
+##
+##  Gradle start up script for UN*X
+##
+##############################################################################
+
+# Attempt to set APP_HOME
+# Resolve links: $0 may be a link
+PRG="$0"
+# Need this for relative symlinks.
+while [ -h "$PRG" ] ; do
+    ls=`ls -ld "$PRG"`
+    link=`expr "$ls" : '.*-> \(.*\)$'`
+    if expr "$link" : '/.*' > /dev/null; then
+        PRG="$link"
+    else
+        PRG=`dirname "$PRG"`"/$link"
+    fi
+done
+SAVED="`pwd`"
+cd "`dirname \"$PRG\"`/" >/dev/null
+APP_HOME="`pwd -P`"
+cd "$SAVED" >/dev/null
+
+APP_NAME="Gradle"
+APP_BASE_NAME=`basename "$0"`
+
+# Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script.
+DEFAULT_JVM_OPTS='"-Xmx64m"'
+
+# Use the maximum available, or set MAX_FD != -1 to use that value.
+MAX_FD="maximum"
+
+warn () {
+    echo "$*"
+}
+
+die () {
+    echo
+    echo "$*"
+    echo
+    exit 1
+}
+
+# OS specific support (must be 'true' or 'false').
+cygwin=false
+msys=false
+darwin=false
+nonstop=false
+case "`uname`" in
+  CYGWIN* )
+    cygwin=true
+    ;;
+  Darwin* )
+    darwin=true
+    ;;
+  MINGW* )
+    msys=true
+    ;;
+  NONSTOP* )
+    nonstop=true
+    ;;
+esac
+
+CLASSPATH=$APP_HOME/gradle/wrapper/gradle-wrapper.jar
+
+# Determine the Java command to use to start the JVM.
+if [ -n "$JAVA_HOME" ] ; then
+    if [ -x "$JAVA_HOME/jre/sh/java" ] ; then
+        # IBM's JDK on AIX uses strange locations for the executables
+        JAVACMD="$JAVA_HOME/jre/sh/java"
+    else
+        JAVACMD="$JAVA_HOME/bin/java"
+    fi
+    if [ ! -x "$JAVACMD" ] ; then
+        die "ERROR: JAVA_HOME is set to an invalid directory: $JAVA_HOME
+
+Please set the JAVA_HOME variable in your environment to match the
+location of your Java installation."
+    fi
+else
+    JAVACMD="java"
+    which java >/dev/null 2>&1 || die "ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH.
+
+Please set the JAVA_HOME variable in your environment to match the
+location of your Java installation."
+fi
+
+# Increase the maximum file descriptors if we can.
+if [ "$cygwin" = "false" -a "$darwin" = "false" -a "$nonstop" = "false" ] ; then
+    MAX_FD_LIMIT=`ulimit -H -n`
+    if [ $? -eq 0 ] ; then
+        if [ "$MAX_FD" = "maximum" -o "$MAX_FD" = "max" ] ; then
+            MAX_FD="$MAX_FD_LIMIT"
+        fi
+        ulimit -n $MAX_FD
+        if [ $? -ne 0 ] ; then
+            warn "Could not set maximum file descriptor limit: $MAX_FD"
+        fi
+    else
+        warn "Could not query maximum file descriptor limit: $MAX_FD_LIMIT"
+    fi
+fi
+
+# For Darwin, add options to specify how the application appears in the dock
+if $darwin; then
+    GRADLE_OPTS="$GRADLE_OPTS \"-Xdock:name=$APP_NAME\" \"-Xdock:icon=$APP_HOME/media/gradle.icns\""
+fi
+
+# For Cygwin, switch paths to Windows format before running java
+if $cygwin ; then
+    APP_HOME=`cygpath --path --mixed "$APP_HOME"`
+    CLASSPATH=`cygpath --path --mixed "$CLASSPATH"`
+    JAVACMD=`cygpath --unix "$JAVACMD"`
+
+    # We build the pattern for arguments to be converted via cygpath
+    ROOTDIRSRAW=`find -L / -maxdepth 1 -mindepth 1 -type d 2>/dev/null`
+    SEP=""
+    for dir in $ROOTDIRSRAW ; do
+        ROOTDIRS="$ROOTDIRS$SEP$dir"
+        SEP="|"
+    done
+    OURCYGPATTERN="(^($ROOTDIRS))"
+    # Add a user-defined pattern to the cygpath arguments
+    if [ "$GRADLE_CYGPATTERN" != "" ] ; then
+        OURCYGPATTERN="$OURCYGPATTERN|($GRADLE_CYGPATTERN)"
+    fi
+    # Now convert the arguments - kludge to limit ourselves to /bin/sh
+    i=0
+    for arg in "$@" ; do
+        CHECK=`echo "$arg"|egrep -c "$OURCYGPATTERN" -`
+        CHECK2=`echo "$arg"|egrep -c "^-"`                                 ### Determine if an option
+
+        if [ $CHECK -ne 0 ] && [ $CHECK2 -eq 0 ] ; then                    ### Added a condition
+            eval `echo args$i`=`cygpath --path --ignore --mixed "$arg"`
+        else
+            eval `echo args$i`="\"$arg\""
+        fi
+        i=$((i+1))
+    done
+    case $i in
+        (0) set -- ;;
+        (1) set -- "$args0" ;;
+        (2) set -- "$args0" "$args1" ;;
+        (3) set -- "$args0" "$args1" "$args2" ;;
+        (4) set -- "$args0" "$args1" "$args2" "$args3" ;;
+        (5) set -- "$args0" "$args1" "$args2" "$args3" "$args4" ;;
+        (6) set -- "$args0" "$args1" "$args2" "$args3" "$args4" "$args5" ;;
+        (7) set -- "$args0" "$args1" "$args2" "$args3" "$args4" "$args5" "$args6" ;;
+        (8) set -- "$args0" "$args1" "$args2" "$args3" "$args4" "$args5" "$args6" "$args7" ;;
+        (9) set -- "$args0" "$args1" "$args2" "$args3" "$args4" "$args5" "$args6" "$args7" "$args8" ;;
+    esac
+fi
+
+# Escape application args
+save () {
+    for i do printf %s\\n "$i" | sed "s/'/'\\\\''/g;1s/^/'/;\$s/\$/' \\\\/" ; done
+    echo " "
+}
+APP_ARGS=$(save "$@")
+
+# Collect all arguments for the java command, following the shell quoting and substitution rules
+eval set -- $DEFAULT_JVM_OPTS $JAVA_OPTS $GRADLE_OPTS "\"-Dorg.gradle.appname=$APP_BASE_NAME\"" -classpath "\"$CLASSPATH\"" org.gradle.wrapper.GradleWrapperMain "$APP_ARGS"
+
+# by default we should be in the correct project dir, but when run from Finder on Mac, the cwd is wrong
+if [ "$(uname)" = "Darwin" ] && [ "$HOME" = "$PWD" ]; then
+  cd "$(dirname "$0")"
+fi
+
+exec "$JAVACMD" "$@"
diff --git a/third_party/allwpilib_2019/gradlew.bat b/third_party/allwpilib_2019/gradlew.bat
new file mode 100644
index 0000000..0f8d593
--- /dev/null
+++ b/third_party/allwpilib_2019/gradlew.bat
@@ -0,0 +1,84 @@
+@if "%DEBUG%" == "" @echo off

+@rem ##########################################################################

+@rem

+@rem  Gradle startup script for Windows

+@rem

+@rem ##########################################################################

+

+@rem Set local scope for the variables with windows NT shell

+if "%OS%"=="Windows_NT" setlocal

+

+set DIRNAME=%~dp0

+if "%DIRNAME%" == "" set DIRNAME=.

+set APP_BASE_NAME=%~n0

+set APP_HOME=%DIRNAME%

+

+@rem Add default JVM options here. You can also use JAVA_OPTS and GRADLE_OPTS to pass JVM options to this script.

+set DEFAULT_JVM_OPTS="-Xmx64m"

+

+@rem Find java.exe

+if defined JAVA_HOME goto findJavaFromJavaHome

+

+set JAVA_EXE=java.exe

+%JAVA_EXE% -version >NUL 2>&1

+if "%ERRORLEVEL%" == "0" goto init

+

+echo.

+echo ERROR: JAVA_HOME is not set and no 'java' command could be found in your PATH.

+echo.

+echo Please set the JAVA_HOME variable in your environment to match the

+echo location of your Java installation.

+

+goto fail

+

+:findJavaFromJavaHome

+set JAVA_HOME=%JAVA_HOME:"=%

+set JAVA_EXE=%JAVA_HOME%/bin/java.exe

+

+if exist "%JAVA_EXE%" goto init

+

+echo.

+echo ERROR: JAVA_HOME is set to an invalid directory: %JAVA_HOME%

+echo.

+echo Please set the JAVA_HOME variable in your environment to match the

+echo location of your Java installation.

+

+goto fail

+

+:init

+@rem Get command-line arguments, handling Windows variants

+

+if not "%OS%" == "Windows_NT" goto win9xME_args

+

+:win9xME_args

+@rem Slurp the command line arguments.

+set CMD_LINE_ARGS=

+set _SKIP=2

+

+:win9xME_args_slurp

+if "x%~1" == "x" goto execute

+

+set CMD_LINE_ARGS=%*

+

+:execute

+@rem Setup the command line

+

+set CLASSPATH=%APP_HOME%\gradle\wrapper\gradle-wrapper.jar

+

+@rem Execute Gradle

+"%JAVA_EXE%" %DEFAULT_JVM_OPTS% %JAVA_OPTS% %GRADLE_OPTS% "-Dorg.gradle.appname=%APP_BASE_NAME%" -classpath "%CLASSPATH%" org.gradle.wrapper.GradleWrapperMain %CMD_LINE_ARGS%

+

+:end

+@rem End local scope for the variables with windows NT shell

+if "%ERRORLEVEL%"=="0" goto mainEnd

+

+:fail

+rem Set variable GRADLE_EXIT_CONSOLE if you need the _script_ return code instead of

+rem the _cmd.exe /c_ return code!

+if  not "" == "%GRADLE_EXIT_CONSOLE%" exit 1

+exit /b 1

+

+:mainEnd

+if "%OS%"=="Windows_NT" endlocal

+

+:omega

diff --git a/third_party/allwpilib_2019/hal/.styleguide b/third_party/allwpilib_2019/hal/.styleguide
new file mode 100644
index 0000000..49d4e29
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/.styleguide
@@ -0,0 +1,44 @@
+cppHeaderFileInclude {
+  \.h$
+  \.hpp$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+generatedFileExclude {
+  hal/src/main/native/athena/ctre/
+  hal/src/main/native/athena/frccansae/
+  hal/src/main/native/athena/visa/
+  hal/src/main/native/include/ctre/
+  UsageReporting\.h$
+}
+
+modifiableFileExclude {
+  \.patch$
+  \.png$
+  \.py$
+  \.so$
+}
+
+repoRootNameOverride {
+  hal
+}
+
+includeOtherLibs {
+  ^FRC_FPGA_ChipObject/
+  ^FRC_NetworkCommunication/
+  ^i2clib/
+  ^llvm/
+  ^opencv2/
+  ^spilib/
+  ^support/
+  ^wpi/
+}
+
+includeProject {
+  ^ctre/
+  ^mockdata/
+}
diff --git a/third_party/allwpilib_2019/hal/CMakeLists.txt b/third_party/allwpilib_2019/hal/CMakeLists.txt
new file mode 100644
index 0000000..e52d90f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/CMakeLists.txt
@@ -0,0 +1,125 @@
+project(hal)
+
+
+file(STRINGS src/generate/Instances.txt RAW_INSTANCES)
+file(STRINGS src/generate/ResourceType.txt RAW_RESOURCE_TYPES)
+
+SET(usage_reporting_types_cpp "")
+SET(usage_reporting_instances_cpp "")
+SET(usage_reporting_types "")
+SET(usage_reporting_instances "")
+
+foreach(ITEM ${RAW_INSTANCES})
+    list(APPEND usage_reporting_instances_cpp "    ${ITEM},")
+    list(APPEND usage_reporting_instances "\n    public static final int ${ITEM};")
+endforeach()
+
+foreach(ITEM ${RAW_RESOURCE_TYPES})
+    list(APPEND usage_reporting_types_cpp "    ${ITEM},")
+    list(APPEND usage_reporting_types "\n    public static final int ${ITEM};")
+endforeach()
+
+string(REPLACE ";" "\n" usage_reporting_types_cpp "${usage_reporting_types_cpp}")
+string(REPLACE ";" "\n" usage_reporting_instances_cpp "${usage_reporting_instances_cpp}")
+
+file(GLOB
+    hal_shared_native_src src/main/native/cpp/cpp/*.cpp
+    hal_shared_native_src src/main/native/cpp/handles/*.cpp
+    hal_sim_native_src src/main/native/sim/*.cpp
+    hal_sim_native_src src/main/native/sim/mockdata/*.cpp)
+add_library(hal ${hal_shared_native_src})
+set_target_properties(hal PROPERTIES DEBUG_POSTFIX "d")
+
+if(USE_EXTERNAL_HAL)
+    include(${EXTERNAL_HAL_FILE})
+else()
+    target_sources(hal PRIVATE ${hal_sim_native_src} ${hal_sim_jni_src})
+endif()
+
+configure_file(src/generate/FRCUsageReporting.h.in gen/hal/FRCUsageReporting.h)
+
+set_target_properties(hal PROPERTIES OUTPUT_NAME "wpiHal")
+
+target_include_directories(hal PUBLIC
+                $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/hal>)
+
+target_include_directories(hal PUBLIC
+                $<BUILD_INTERFACE:${CMAKE_CURRENT_BINARY_DIR}/gen>
+                            $<INSTALL_INTERFACE:${include_dest}/hal>)
+target_link_libraries(hal PUBLIC wpiutil)
+
+set_property(TARGET hal PROPERTY FOLDER "libraries")
+
+install(TARGETS hal EXPORT hal DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/hal")
+install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/gen DESTINATION "${include_dest}/hal")
+
+if (MSVC)
+    set (hal_config_dir ${wpilib_dest})
+else()
+    set (hal_config_dir share/hal)
+endif()
+
+install(FILES hal-config.cmake DESTINATION ${hal_config_dir})
+install(EXPORT hal DESTINATION ${hal_config_dir})
+
+# Java bindings
+if (NOT WITHOUT_JAVA)
+    find_package(Java REQUIRED)
+    find_package(JNI REQUIRED)
+    include(UseJava)
+    set(CMAKE_JAVA_COMPILE_FLAGS "-Xlint:unchecked")
+
+    configure_file(src/generate/FRCNetComm.java.in FRCNetComm.java)
+
+    file(GLOB
+        hal_shared_jni_src src/main/native/cpp/jni/*.cpp
+        hal_sim_jni_src src/main/native/sim/jni/*.cpp)
+
+    file(GLOB_RECURSE JAVA_SOURCES
+        ${CMAKE_CURRENT_BINARY_DIR}/FRCNetComm.java
+        src/main/java/*.java)
+    set(CMAKE_JNI_TARGET true)
+
+    if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+        set(CMAKE_JAVA_COMPILE_FLAGS "-h" "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+        add_jar(hal_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar OUTPUT_NAME wpiHal)
+    else()
+        add_jar(hal_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar OUTPUT_NAME wpiHal GENERATE_NATIVE_HEADERS hal_jni_headers)
+    endif()
+
+    get_property(HAL_JAR_FILE TARGET hal_jar PROPERTY JAR_FILE)
+    install(FILES ${HAL_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+    set_property(TARGET hal_jar PROPERTY FOLDER "java")
+
+    add_library(haljni ${hal_shared_jni_src})
+
+    if(USE_EXTERNAL_HAL)
+        include(${EXTERNAL_HAL_FILE})
+    else()
+        target_sources(haljni PRIVATE ${hal_sim_jni_src})
+    endif()
+
+    set_target_properties(haljni PROPERTIES OUTPUT_NAME "wpiHaljni")
+
+    target_link_libraries(haljni PUBLIC hal wpiutil)
+
+    set_property(TARGET haljni PROPERTY FOLDER "libraries")
+
+    if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+        target_include_directories(haljni PRIVATE ${JNI_INCLUDE_DIRS})
+        target_include_directories(haljni PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+    else()
+        target_link_libraries(haljni PRIVATE hal_jni_headers)
+    endif()
+    add_dependencies(haljni hal_jar)
+
+    if (MSVC)
+        install(TARGETS haljni RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+    endif()
+
+    install(TARGETS haljni EXPORT haljni DESTINATION "${main_lib_dest}")
+
+endif()
diff --git a/third_party/allwpilib_2019/hal/build.gradle b/third_party/allwpilib_2019/hal/build.gradle
new file mode 100644
index 0000000..2f49ee5
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/build.gradle
@@ -0,0 +1,203 @@
+def javaResourceFile = file("$buildDir/generated/java/edu/wpi/first/hal/FRCNetComm.java")
+def cppResourceFile = file("$buildDir/generated/headers/hal/FRCUsageReporting.h")
+
+def generateUsageReporting = tasks.register('generateUsageReporting') {
+    def javaBase = file('src/generate/FRCNetComm.java.in')
+    def cppBase = file('src/generate/FRCUsageReporting.h.in')
+
+    def instances = file('src/generate/Instances.txt')
+    def resourceType = file('src/generate/ResourceType.txt')
+
+    inputs.file(javaBase)
+    inputs.file(cppBase)
+    inputs.file(instances)
+    inputs.file(resourceType)
+
+    outputs.file(javaResourceFile)
+    outputs.file(cppResourceFile)
+
+    doLast {
+        def instanceTextJava = instances as String[]
+        def instanceTextCpp = instances as String[]
+        def resourceTextJava = resourceType as String[]
+        def resourceTextCpp = resourceType as String[]
+
+        instanceTextJava = instanceTextJava.collect {
+            "    public static final int ${it};"
+        }.join('\n')
+
+        instanceTextCpp = instanceTextCpp.collect {
+            "    ${it},"
+        }.join('\n')
+
+        resourceTextJava = resourceTextJava.collect {
+            "    public static final int ${it};"
+        }.join('\n')
+
+        resourceTextCpp = resourceTextCpp.collect {
+            "    ${it},"
+        }.join('\n')
+
+        javaResourceFile.text = javaBase.text.replace('${usage_reporting_types}', resourceTextJava).replace('${usage_reporting_instances}', instanceTextJava)
+        cppResourceFile.text = cppBase.text.replace('${usage_reporting_types_cpp}', resourceTextCpp).replace('${usage_reporting_instances_cpp}', instanceTextCpp)
+    }
+}
+
+ext {
+    addHalDependency = { binary, shared->
+        binary.tasks.withType(AbstractNativeSourceCompileTask) {
+            it.dependsOn generateUsageReporting
+        }
+        binary.lib project: ':hal', library: 'hal', linkage: shared
+    }
+
+    addHalJniDependency = { binary->
+        binary.tasks.withType(AbstractNativeSourceCompileTask) {
+            it.dependsOn generateUsageReporting
+        }
+        binary.lib project: ':hal', library: 'halJNIShared', linkage: 'shared'
+    }
+
+    nativeName = 'hal'
+    setBaseName = 'wpiHal'
+    devMain = 'DevMain'
+    niLibraries = true
+    generatedHeaders = "$buildDir/generated/headers"
+    jniSplitSetup = {
+        it.tasks.withType(AbstractNativeSourceCompileTask) {
+            it.dependsOn generateUsageReporting
+        }
+        if (it.targetPlatform.architecture.name == 'athena') {
+            it.sources {
+                athenaJniCpp(CppSourceSet) {
+                    source {
+                        srcDirs = ["${rootDir}/shared/singlelib", "$buildDir/generated/cpp"]
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        srcDir generatedHeaders
+                    }
+                }
+            }
+        } else {
+            it.sources {
+                simJniCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/sim'
+                        include '**/jni/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        srcDir generatedHeaders
+                    }
+                }
+            }
+        }
+    }
+    splitSetup = {
+        it.tasks.withType(AbstractNativeSourceCompileTask) {
+            it.dependsOn generateUsageReporting
+        }
+        if (it.targetPlatform.architecture.name == 'athena') {
+            it.sources {
+                athenaCpp(CppSourceSet) {
+                    source {
+                        srcDirs = ['src/main/native/athena']
+                        include '**/*.cpp'
+                        exclude '**/jni/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        srcDir generatedHeaders
+                    }
+                }
+            }
+        } else {
+            it.sources {
+                simCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/sim'
+                        include '**/*.cpp'
+                        exclude '**/jni/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        srcDir generatedHeaders
+                    }
+                }
+            }
+        }
+    }
+}
+
+apply from: "${rootDir}/shared/jni/setupBuild.gradle"
+apply from: 'simjni.gradle'
+
+sourceSets.main.java.srcDir "${buildDir}/generated/java/"
+
+compileJava {
+    dependsOn generateUsageReporting
+}
+
+cppSourcesZip {
+    from('src/main/native/athena') {
+        into '/athena'
+    }
+
+    from('src/main/native/sim') {
+        into '/sim'
+    }
+
+    from("$buildDir/generated/cpp") {
+        into '/athena/jni'
+    }
+
+    dependsOn generateAthenaSimFiles
+}
+
+cppHeadersZip {
+    dependsOn generateUsageReporting
+    from(generatedHeaders) {
+        into '/'
+    }
+}
+
+model {
+    // Exports config is a utility to enable exporting all symbols in a C++ library on windows to a DLL.
+    // This removes the need for DllExport on a library. However, the gradle C++ builder has a bug
+    // where some extra symbols are added that cannot be resolved at link time. This configuration
+    // lets you specify specific symbols to exlude from exporting.
+    exportsConfigs {
+        hal(ExportsConfig) {
+            x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVbad_cast',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure']
+            x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVbad_cast',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure']
+        }
+        halJNI(ExportsConfig) {
+            x86SymbolFilter = { symbols ->
+                def retList = []
+                symbols.each { symbol ->
+                    if (symbol.startsWith('HAL_') || symbol.startsWith('HALSIM_')) {
+                        retList << symbol
+                    }
+                }
+                return retList
+            }
+            x64SymbolFilter = { symbols ->
+                def retList = []
+                symbols.each { symbol ->
+                    if (symbol.startsWith('HAL_') || symbol.startsWith('HALSIM_')) {
+                        retList << symbol
+                    }
+                }
+                return retList
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/hal/hal-config.cmake b/third_party/allwpilib_2019/hal/hal-config.cmake
new file mode 100644
index 0000000..97a574e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/hal-config.cmake
@@ -0,0 +1,5 @@
+include(CMakeFindDependencyMacro)
+find_dependency(wpiutil)
+
+get_filename_component(SELF_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)
+include(${SELF_DIR}/hal.cmake)
diff --git a/third_party/allwpilib_2019/hal/simjni.gradle b/third_party/allwpilib_2019/hal/simjni.gradle
new file mode 100644
index 0000000..599f094
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/simjni.gradle
@@ -0,0 +1,111 @@
+def athenaSimJniOutputDir = file("$buildDir/generated/cpp")
+def athenaSimJniOutputFile = file("$athenaSimJniOutputDir/simjni.cpp")
+
+task generateAthenaSimFiles() {
+    Set dirs = [];
+
+    def createdTask = it
+    outputs.file athenaSimJniOutputFile
+
+    model {
+        components {
+            it.all { component ->
+                if (component in getJniSpecClass()) {
+                    component.binaries.all { binary ->
+                        if (binary.targetPlatform.architecture.name == 'athena') {
+                            binary.tasks.withType(CppCompile) {
+                                it.dependsOn createdTask
+                            }
+                            component.jniHeaderLocations.each {
+                                dependsOn it.key
+                                createdTask.inputs.dir it.value
+                                dirs << it.value
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+
+    doLast {
+        def symbolList = []
+        dirs.each {
+            def tree = fileTree(dir: it)
+            tree.each { file ->
+                if (!file.name.contains('edu_wpi_first_hal_sim_mockdata_')) {
+                    return
+                }
+                boolean reading = false
+                String currentLine = ''
+                file.eachLine { line ->
+                    if (line.trim()) {
+                        if (line.contains(';') && reading) {
+                            currentLine += line.trim()
+                            reading = false
+                            symbolList << currentLine
+                            currentLine = ''
+                        }
+                        if (line.startsWith("JNIEXPORT ") && line.contains('JNICALL')) {
+                            if (line.contains(';')) {
+                                symbolList << line
+                                currentLine = ''
+                                reading = false
+                            } else {
+                                reading = true
+                                currentLine += line.trim()
+                            }
+
+                        }
+                    }
+                }
+            }
+        }
+        athenaSimJniOutputDir.mkdirs()
+        athenaSimJniOutputFile.withWriter { out ->
+            out.println '#include <jni.h>'
+            out.println '''
+static JavaVM* jvm = nullptr;
+
+namespace sim {
+jint SimOnLoad(JavaVM* vm, void* reserved) {
+  jvm = vm;
+
+  JNIEnv *env;
+  if (vm->GetEnv(reinterpret_cast<void **>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return JNI_ERR;
+
+  return JNI_VERSION_1_6;
+}
+
+void SimOnUnload(JavaVM * vm, void* reserved) {
+  JNIEnv *env;
+  if (vm->GetEnv(reinterpret_cast<void **>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return;
+  jvm = nullptr;
+}
+}
+
+static void ThrowSimException(JNIEnv* env) {
+
+}
+'''
+            out.println 'extern "C" {'
+            symbolList.each {
+                def symbol = it.replace('JNIEnv *', 'JNIEnv * env')
+                if (symbol.contains('JNIEXPORT void')) {
+                    symbol = symbol.replace(';', ''' {
+  ThrowSimException(env);
+}''')
+                } else {
+                    symbol = symbol.replace(';', ''' {
+  ThrowSimException(env);
+  return 0;
+}''')
+                }
+                out.println symbol
+            }
+            out.println '}'
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/hal/src/dev/java/DevMain.java b/third_party/allwpilib_2019/hal/src/dev/java/DevMain.java
new file mode 100644
index 0000000..8cdb8ba
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/dev/java/DevMain.java
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+public final class DevMain {
+  public static void main(String[] args) {
+
+  }
+
+  private DevMain() {
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/hal/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..6bfa3df
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/dev/native/cpp/main.cpp
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include "hal/HAL.h"
+
+int main() {
+  std::cout << "Hello World" << std::endl;
+  std::cout << HAL_GetRuntimeType() << std::endl;
+}
diff --git a/third_party/allwpilib_2019/hal/src/generate/FRCNetComm.java.in b/third_party/allwpilib_2019/hal/src/generate/FRCNetComm.java.in
new file mode 100644
index 0000000..af49407
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/generate/FRCNetComm.java.in
@@ -0,0 +1,33 @@
+/*

+ * Autogenerated file! Do not manually edit this file.

+ */

+

+package edu.wpi.first.hal;

+

+/**

+ * JNI wrapper for library <b>FRC_NetworkCommunication</b><br>.

+ */

+@SuppressWarnings({"MethodName", "LineLength"})

+public class FRCNetComm {

+  /**

+   * Resource type from UsageReporting.

+   */

+  @SuppressWarnings({"TypeName", "PMD.ConstantsInInterface"})

+  public static final class tResourceType {

+    private tResourceType() {

+    }

+

+${usage_reporting_types}

+  }

+

+  /**

+   * Instances from UsageReporting.

+   */

+  @SuppressWarnings({"TypeName", "PMD.ConstantsInInterface"})

+  public static final class tInstances {

+    private tInstances() {

+    }

+

+${usage_reporting_instances}

+  }

+}

diff --git a/third_party/allwpilib_2019/hal/src/generate/FRCUsageReporting.h.in b/third_party/allwpilib_2019/hal/src/generate/FRCUsageReporting.h.in
new file mode 100644
index 0000000..7cf8128
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/generate/FRCUsageReporting.h.in
@@ -0,0 +1,14 @@
+#pragma once

+

+/*

+ * Autogenerated file! Do not manually edit this file.

+ */

+

+namespace HALUsageReporting {

+  typedef enum {

+${usage_reporting_types_cpp}

+  } tResourceType;

+  typedef enum {

+${usage_reporting_instances_cpp}

+  } tInstances;

+}

diff --git a/third_party/allwpilib_2019/hal/src/generate/Instances.txt b/third_party/allwpilib_2019/hal/src/generate/Instances.txt
new file mode 100644
index 0000000..25fc463
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/generate/Instances.txt
@@ -0,0 +1,44 @@
+kLanguage_LabVIEW = 1

+kLanguage_CPlusPlus = 2

+kLanguage_Java = 3

+kLanguage_Python = 4

+kLanguage_DotNet = 5

+kCANPlugin_BlackJagBridge = 1

+kCANPlugin_2CAN = 2

+kFramework_Iterative = 1

+kFramework_Simple = 2

+kFramework_CommandControl = 3

+kFramework_Timed = 4

+kFramework_ROS = 5

+kFramework_RobotBuilder = 6

+kRobotDrive_ArcadeStandard = 1

+kRobotDrive_ArcadeButtonSpin = 2

+kRobotDrive_ArcadeRatioCurve = 3

+kRobotDrive_Tank = 4

+kRobotDrive_MecanumPolar = 5

+kRobotDrive_MecanumCartesian = 6

+kRobotDrive2_DifferentialArcade = 7

+kRobotDrive2_DifferentialTank = 8

+kRobotDrive2_DifferentialCurvature = 9

+kRobotDrive2_MecanumCartesian = 10

+kRobotDrive2_MecanumPolar = 11

+kRobotDrive2_KilloughCartesian = 12

+kRobotDrive2_KilloughPolar = 13

+kDriverStationCIO_Analog = 1

+kDriverStationCIO_DigitalIn = 2

+kDriverStationCIO_DigitalOut = 3

+kDriverStationEIO_Acceleration = 1

+kDriverStationEIO_AnalogIn = 2

+kDriverStationEIO_AnalogOut = 3

+kDriverStationEIO_Button = 4

+kDriverStationEIO_LED = 5

+kDriverStationEIO_DigitalIn = 6

+kDriverStationEIO_DigitalOut = 7

+kDriverStationEIO_FixedDigitalOut = 8

+kDriverStationEIO_PWM = 9

+kDriverStationEIO_Encoder = 10

+kDriverStationEIO_TouchSlider = 11

+kADXL345_SPI = 1

+kADXL345_I2C = 2

+kCommand_Scheduler = 1

+kSmartDashboard_Instance = 1

diff --git a/third_party/allwpilib_2019/hal/src/generate/ResourceType.txt b/third_party/allwpilib_2019/hal/src/generate/ResourceType.txt
new file mode 100644
index 0000000..b8699b0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/generate/ResourceType.txt
@@ -0,0 +1,85 @@
+kResourceType_Controller = 0

+kResourceType_Module = 1

+kResourceType_Language = 2

+kResourceType_CANPlugin = 3

+kResourceType_Accelerometer = 4

+kResourceType_ADXL345 = 5

+kResourceType_AnalogChannel = 6

+kResourceType_AnalogTrigger = 7

+kResourceType_AnalogTriggerOutput = 8

+kResourceType_CANJaguar = 9

+kResourceType_Compressor = 10

+kResourceType_Counter = 11

+kResourceType_Dashboard = 12

+kResourceType_DigitalInput = 13

+kResourceType_DigitalOutput = 14

+kResourceType_DriverStationCIO = 15

+kResourceType_DriverStationEIO = 16

+kResourceType_DriverStationLCD = 17

+kResourceType_Encoder = 18

+kResourceType_GearTooth = 19

+kResourceType_Gyro = 20

+kResourceType_I2C = 21

+kResourceType_Framework = 22

+kResourceType_Jaguar = 23

+kResourceType_Joystick = 24

+kResourceType_Kinect = 25

+kResourceType_KinectStick = 26

+kResourceType_PIDController = 27

+kResourceType_Preferences = 28

+kResourceType_PWM = 29

+kResourceType_Relay = 30

+kResourceType_RobotDrive = 31

+kResourceType_SerialPort = 32

+kResourceType_Servo = 33

+kResourceType_Solenoid = 34

+kResourceType_SPI = 35

+kResourceType_Task = 36

+kResourceType_Ultrasonic = 37

+kResourceType_Victor = 38

+kResourceType_Button = 39

+kResourceType_Command = 40

+kResourceType_AxisCamera = 41

+kResourceType_PCVideoServer = 42

+kResourceType_SmartDashboard = 43

+kResourceType_Talon = 44

+kResourceType_HiTechnicColorSensor = 45

+kResourceType_HiTechnicAccel = 46

+kResourceType_HiTechnicCompass = 47

+kResourceType_SRF08 = 48

+kResourceType_AnalogOutput = 49

+kResourceType_VictorSP = 50

+kResourceType_PWMTalonSRX = 51

+kResourceType_CANTalonSRX = 52

+kResourceType_ADXL362 = 53

+kResourceType_ADXRS450 = 54

+kResourceType_RevSPARK = 55

+kResourceType_MindsensorsSD540 = 56

+kResourceType_DigitalGlitchFilter = 57

+kResourceType_ADIS16448 = 58

+kResourceType_PDP = 59

+kResourceType_PCM = 60

+kResourceType_PigeonIMU = 61

+kResourceType_NidecBrushless = 62

+kResourceType_CANifier = 63

+kResourceType_CTRE_future0 = 64

+kResourceType_CTRE_future1 = 65

+kResourceType_CTRE_future2 = 66

+kResourceType_CTRE_future3 = 67

+kResourceType_CTRE_future4 = 68

+kResourceType_CTRE_future5 = 69

+kResourceType_CTRE_future6 = 70

+kResourceType_LinearFilter = 71

+kResourceType_XboxController = 72

+kResourceType_UsbCamera = 73

+kResourceType_NavX = 74

+kResourceType_Pixy = 75

+kResourceType_Pixy2 = 76

+kResourceType_ScanseSweep = 77

+kResourceType_Shuffleboard = 78

+kResourceType_CAN = 79

+kResourceType_DigilentDMC60 = 80

+kResourceType_PWMVictorSPX = 81

+kResourceType_RevSparkMaxPWM = 82

+kResourceType_RevSparkMaxCAN = 83

+kResourceType_ADIS16470 = 84

diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AccelerometerJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AccelerometerJNI.java
new file mode 100644
index 0000000..e1e3750
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AccelerometerJNI.java
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class AccelerometerJNI extends JNIWrapper {
+  public static native void setAccelerometerActive(boolean active);
+
+  public static native void setAccelerometerRange(int range);
+
+  public static native double getAccelerometerX();
+
+  public static native double getAccelerometerY();
+
+  public static native double getAccelerometerZ();
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java
new file mode 100644
index 0000000..d3aa8c8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AccumulatorResult.java
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+/**
+ * Structure for holding the values stored in an accumulator.
+ */
+public class AccumulatorResult {
+  /**
+   * The total value accumulated.
+   */
+  @SuppressWarnings("MemberName")
+  public long value;
+  /**
+   * The number of sample value was accumulated over.
+   */
+  @SuppressWarnings("MemberName")
+  public long count;
+
+  /**
+   * Set the value and count.
+   */
+  public void set(long value, long count) {
+    this.value = value;
+    this.count = count;
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AllianceStationID.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AllianceStationID.java
new file mode 100644
index 0000000..148dd76
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AllianceStationID.java
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public enum AllianceStationID {
+  Red1, Red2, Red3, Blue1, Blue2, Blue3
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AnalogGyroJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AnalogGyroJNI.java
new file mode 100644
index 0000000..332be79
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AnalogGyroJNI.java
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class AnalogGyroJNI extends JNIWrapper {
+  public static native int initializeAnalogGyro(int halAnalogInputHandle);
+
+  public static native void setupAnalogGyro(int handle);
+
+  public static native void freeAnalogGyro(int handle);
+
+  public static native void setAnalogGyroParameters(int handle,
+                                                    double voltsPerDegreePerSecond,
+                                                    double offset, int center);
+
+  public static native void setAnalogGyroVoltsPerDegreePerSecond(int handle,
+                                                                 double voltsPerDegreePerSecond);
+
+  public static native void resetAnalogGyro(int handle);
+
+  public static native void calibrateAnalogGyro(int handle);
+
+  public static native void setAnalogGyroDeadband(int handle, double volts);
+
+  public static native double getAnalogGyroAngle(int handle);
+
+  public static native double getAnalogGyroRate(int handle);
+
+  public static native double getAnalogGyroOffset(int handle);
+
+  public static native int getAnalogGyroCenter(int handle);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
new file mode 100644
index 0000000..3e78039
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/AnalogJNI.java
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+import java.nio.IntBuffer;
+
+public class AnalogJNI extends JNIWrapper {
+  /**
+   * <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:58</i><br> enum values
+   */
+  public interface AnalogTriggerType {
+    /**
+     * <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:54</i>
+     */
+    int kInWindow = 0;
+    /**
+     * <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:55</i>
+     */
+    int kState = 1;
+    /**
+     * <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:56</i>
+     */
+    int kRisingPulse = 2;
+    /**
+     * <i>native declaration : AthenaJava\target\native\include\HAL\Analog.h:57</i>
+     */
+    int kFallingPulse = 3;
+  }
+
+  public static native int initializeAnalogInputPort(int halPortHandle);
+
+  public static native void freeAnalogInputPort(int portHandle);
+
+  public static native int initializeAnalogOutputPort(int halPortHandle);
+
+  public static native void freeAnalogOutputPort(int portHandle);
+
+  public static native boolean checkAnalogModule(byte module);
+
+  public static native boolean checkAnalogInputChannel(int channel);
+
+  public static native boolean checkAnalogOutputChannel(int channel);
+
+  public static native void setAnalogOutput(int portHandle, double voltage);
+
+  public static native double getAnalogOutput(int portHandle);
+
+  public static native void setAnalogSampleRate(double samplesPerSecond);
+
+  public static native double getAnalogSampleRate();
+
+  public static native void setAnalogAverageBits(int analogPortHandle, int bits);
+
+  public static native int getAnalogAverageBits(int analogPortHandle);
+
+  public static native void setAnalogOversampleBits(int analogPortHandle, int bits);
+
+  public static native int getAnalogOversampleBits(int analogPortHandle);
+
+  public static native short getAnalogValue(int analogPortHandle);
+
+  public static native int getAnalogAverageValue(int analogPortHandle);
+
+  public static native int getAnalogVoltsToValue(int analogPortHandle, double voltage);
+
+  public static native double getAnalogVoltage(int analogPortHandle);
+
+  public static native double getAnalogAverageVoltage(int analogPortHandle);
+
+  public static native int getAnalogLSBWeight(int analogPortHandle);
+
+  public static native int getAnalogOffset(int analogPortHandle);
+
+  public static native boolean isAccumulatorChannel(int analogPortHandle);
+
+  public static native void initAccumulator(int analogPortHandle);
+
+  public static native void resetAccumulator(int analogPortHandle);
+
+  public static native void setAccumulatorCenter(int analogPortHandle, int center);
+
+  public static native void setAccumulatorDeadband(int analogPortHandle, int deadband);
+
+  public static native long getAccumulatorValue(int analogPortHandle);
+
+  public static native int getAccumulatorCount(int analogPortHandle);
+
+  public static native void getAccumulatorOutput(int analogPortHandle, AccumulatorResult result);
+
+  public static native int initializeAnalogTrigger(int analogInputHandle, IntBuffer index);
+
+  public static native void cleanAnalogTrigger(int analogTriggerHandle);
+
+  public static native void setAnalogTriggerLimitsRaw(int analogTriggerHandle, int lower,
+                                                      int upper);
+
+  public static native void setAnalogTriggerLimitsVoltage(int analogTriggerHandle,
+                                                          double lower, double upper);
+
+  public static native void setAnalogTriggerAveraged(int analogTriggerHandle,
+                                                     boolean useAveragedValue);
+
+  public static native void setAnalogTriggerFiltered(int analogTriggerHandle,
+                                                     boolean useFilteredValue);
+
+  public static native boolean getAnalogTriggerInWindow(int analogTriggerHandle);
+
+  public static native boolean getAnalogTriggerTriggerState(int analogTriggerHandle);
+
+  public static native boolean getAnalogTriggerOutput(int analogTriggerHandle, int type);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java
new file mode 100644
index 0000000..1ac3ca7
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CANAPIJNI.java
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public class CANAPIJNI extends JNIWrapper {
+  public static native int initializeCAN(int manufacturer, int deviceId, int deviceType);
+
+  public static native void cleanCAN(int handle);
+
+  public static native void writeCANPacket(int handle, byte[] data, int apiId);
+
+  public static native void writeCANPacketRepeating(int handle, byte[] data, int apiId,
+                                                    int repeatMs);
+
+  public static native void stopCANPacketRepeating(int handle, int apiId);
+
+  public static native boolean readCANPacketNew(int handle, int apiId, CANData data);
+
+  public static native boolean readCANPacketLatest(int handle, int apiId, CANData data);
+
+  public static native boolean readCANPacketTimeout(int handle, int apiId, int timeoutMs,
+                                                 CANData data);
+
+  public static native boolean readCANPeriodicPacket(int handle, int apiId, int timeoutMs,
+                                                  int periodMs, CANData data);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CANData.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CANData.java
new file mode 100644
index 0000000..23d37c9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CANData.java
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class CANData {
+  @SuppressWarnings("MemberName")
+  public final byte[] data = new byte[8];
+  @SuppressWarnings("MemberName")
+  public int length;
+  @SuppressWarnings("MemberName")
+  public long timestamp;
+
+  /**
+   * API used from JNI to set the data.
+   */
+  @SuppressWarnings("PMD.MethodReturnsInternalArray")
+  public byte[] setData(int length, long timestamp) {
+    this.length = length;
+    this.timestamp = timestamp;
+    return data;
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CompressorJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CompressorJNI.java
new file mode 100644
index 0000000..64e9e1d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CompressorJNI.java
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class CompressorJNI extends JNIWrapper {
+  public static native int initializeCompressor(byte module);
+
+  public static native boolean checkCompressorModule(byte module);
+
+  public static native boolean getCompressor(int compressorHandle);
+
+  public static native void setCompressorClosedLoopControl(int compressorHandle, boolean value);
+
+  public static native boolean getCompressorClosedLoopControl(int compressorHandle);
+
+  public static native boolean getCompressorPressureSwitch(int compressorHandle);
+
+  public static native double getCompressorCurrent(int compressorHandle);
+
+  public static native boolean getCompressorCurrentTooHighFault(int compressorHandle);
+
+  public static native boolean getCompressorCurrentTooHighStickyFault(int compressorHandle);
+
+  public static native boolean getCompressorShortedStickyFault(int compressorHandle);
+
+  public static native boolean getCompressorShortedFault(int compressorHandle);
+
+  public static native boolean getCompressorNotConnectedStickyFault(int compressorHandle);
+
+  public static native boolean getCompressorNotConnectedFault(int compressorHandle);
+
+  public static native void clearAllPCMStickyFaults(byte compressorModule);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ConstantsJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ConstantsJNI.java
new file mode 100644
index 0000000..3db75f5
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ConstantsJNI.java
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class ConstantsJNI extends JNIWrapper {
+  public static native int getSystemClockTicksPerMicrosecond();
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ControlWord.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ControlWord.java
new file mode 100644
index 0000000..8353606
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ControlWord.java
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+/**
+ * A wrapper for the HALControlWord bitfield.
+ */
+public class ControlWord {
+  private boolean m_enabled;
+  private boolean m_autonomous;
+  private boolean m_test;
+  private boolean m_emergencyStop;
+  private boolean m_fmsAttached;
+  private boolean m_dsAttached;
+
+  void update(boolean enabled, boolean autonomous, boolean test, boolean emergencyStop,
+              boolean fmsAttached, boolean dsAttached) {
+    m_enabled = enabled;
+    m_autonomous = autonomous;
+    m_test = test;
+    m_emergencyStop = emergencyStop;
+    m_fmsAttached = fmsAttached;
+    m_dsAttached = dsAttached;
+  }
+
+  public boolean getEnabled() {
+    return m_enabled;
+  }
+
+  public boolean getAutonomous() {
+    return m_autonomous;
+  }
+
+  public boolean getTest() {
+    return m_test;
+  }
+
+  public boolean getEStop() {
+    return m_emergencyStop;
+  }
+
+  public boolean getFMSAttached() {
+    return m_fmsAttached;
+  }
+
+  public boolean getDSAttached() {
+    return m_dsAttached;
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CounterJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CounterJNI.java
new file mode 100644
index 0000000..b7935d6
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/CounterJNI.java
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+import java.nio.IntBuffer;
+
+public class CounterJNI extends JNIWrapper {
+  public static native int initializeCounter(int mode, IntBuffer index);
+
+  public static native void freeCounter(int counterHandle);
+
+  public static native void setCounterAverageSize(int counterHandle, int size);
+
+  public static native void setCounterUpSource(int counterHandle, int digitalSourceHandle,
+                                               int analogTriggerType);
+
+  public static native void setCounterUpSourceEdge(int counterHandle, boolean risingEdge,
+                                                   boolean fallingEdge);
+
+  public static native void clearCounterUpSource(int counterHandle);
+
+  public static native void setCounterDownSource(int counterHandle, int digitalSourceHandle,
+                                                 int analogTriggerType);
+
+  public static native void setCounterDownSourceEdge(int counterHandle, boolean risingEdge,
+                                                     boolean fallingEdge);
+
+  public static native void clearCounterDownSource(int counterHandle);
+
+  public static native void setCounterUpDownMode(int counterHandle);
+
+  public static native void setCounterExternalDirectionMode(int counterHandle);
+
+  public static native void setCounterSemiPeriodMode(int counterHandle,
+                                                     boolean highSemiPeriod);
+
+  public static native void setCounterPulseLengthMode(int counterHandle, double threshold);
+
+  public static native int getCounterSamplesToAverage(int counterHandle);
+
+  public static native void setCounterSamplesToAverage(int counterHandle,
+                                                       int samplesToAverage);
+
+  public static native void resetCounter(int counterHandle);
+
+  public static native int getCounter(int counterHandle);
+
+  public static native double getCounterPeriod(int counterHandle);
+
+  public static native void setCounterMaxPeriod(int counterHandle, double maxPeriod);
+
+  public static native void setCounterUpdateWhenEmpty(int counterHandle, boolean enabled);
+
+  public static native boolean getCounterStopped(int counterHandle);
+
+  public static native boolean getCounterDirection(int counterHandle);
+
+  public static native void setCounterReverseDirection(int counterHandle,
+                                                       boolean reverseDirection);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java
new file mode 100644
index 0000000..b9c11a5
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/DIOJNI.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public class DIOJNI extends JNIWrapper {
+  public static native int initializeDIOPort(int halPortHandle, boolean input);
+
+  public static native boolean checkDIOChannel(int channel);
+
+  public static native void freeDIOPort(int dioPortHandle);
+
+  // TODO(Thad): Switch this to use boolean
+  public static native void setDIO(int dioPortHandle, short value);
+
+  public static native void setDIODirection(int dioPortHandle, boolean input);
+
+  public static native boolean getDIO(int dioPortHandle);
+
+  public static native boolean getDIODirection(int dioPortHandle);
+
+  public static native void pulse(int dioPortHandle, double pulseLength);
+
+  public static native boolean isPulsing(int dioPortHandle);
+
+  public static native boolean isAnyPulsing();
+
+  public static native short getLoopTiming();
+
+  public static native int allocateDigitalPWM();
+
+  public static native void freeDigitalPWM(int pwmGenerator);
+
+  public static native void setDigitalPWMRate(double rate);
+
+  public static native void setDigitalPWMDutyCycle(int pwmGenerator, double dutyCycle);
+
+  public static native void setDigitalPWMOutputChannel(int pwmGenerator, int channel);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/DigitalGlitchFilterJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/DigitalGlitchFilterJNI.java
new file mode 100644
index 0000000..aa818cf
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/DigitalGlitchFilterJNI.java
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class DigitalGlitchFilterJNI extends JNIWrapper {
+  public static native void setFilterSelect(int digitalPortHandle, int filterIndex);
+
+  public static native int getFilterSelect(int digitalPortHandle);
+
+  public static native void setFilterPeriod(int filterIndex, int fpgaCycles);
+
+  public static native int getFilterPeriod(int filterIndex);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java
new file mode 100644
index 0000000..082b6d9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/EncoderJNI.java
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class EncoderJNI extends JNIWrapper {
+  public static native int initializeEncoder(int digitalSourceHandleA, int analogTriggerTypeA,
+                                             int digitalSourceHandleB, int analogTriggerTypeB,
+                                             boolean reverseDirection, int encodingType);
+
+  public static native void freeEncoder(int encoderHandle);
+
+  public static native int getEncoder(int encoderHandle);
+
+  public static native int getEncoderRaw(int encoderHandle);
+
+  public static native int getEncodingScaleFactor(int encoderHandle);
+
+  public static native void resetEncoder(int encoderHandle);
+
+  public static native double getEncoderPeriod(int encoderHandle);
+
+  public static native void setEncoderMaxPeriod(int encoderHandle, double maxPeriod);
+
+  public static native boolean getEncoderStopped(int encoderHandle);
+
+  public static native boolean getEncoderDirection(int encoderHandle);
+
+  public static native double getEncoderDistance(int encoderHandle);
+
+  public static native double getEncoderRate(int encoderHandle);
+
+  public static native void setEncoderMinRate(int encoderHandle, double minRate);
+
+  public static native void setEncoderDistancePerPulse(int encoderHandle, double distancePerPulse);
+
+  public static native void setEncoderReverseDirection(int encoderHandle,
+                                                       boolean reverseDirection);
+
+  public static native void setEncoderSamplesToAverage(int encoderHandle,
+                                                       int samplesToAverage);
+
+  public static native int getEncoderSamplesToAverage(int encoderHandle);
+
+  public static native void setEncoderIndexSource(int encoderHandle, int digitalSourceHandle,
+                                                  int analogTriggerType, int indexingType);
+
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public static native int getEncoderFPGAIndex(int encoderHandle);
+
+  public static native int getEncoderEncodingScale(int encoderHandle);
+
+  public static native double getEncoderDecodingScaleFactor(int encoderHandle);
+
+  public static native double getEncoderDistancePerPulse(int encoderHandle);
+
+  public static native int getEncoderEncodingType(int encoderHandle);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/HAL.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/HAL.java
new file mode 100644
index 0000000..a298ff6
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/HAL.java
@@ -0,0 +1,134 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+import java.nio.ByteBuffer;
+
+/**
+ * JNI Wrapper for HAL<br>.
+ */
+@SuppressWarnings({"AbbreviationAsWordInName", "MethodName", "PMD.TooManyMethods"})
+public final class HAL extends JNIWrapper {
+  public static native void waitForDSData();
+
+  public static native boolean initialize(int timeout, int mode);
+
+  public static native void observeUserProgramStarting();
+
+  public static native void observeUserProgramDisabled();
+
+  public static native void observeUserProgramAutonomous();
+
+  public static native void observeUserProgramTeleop();
+
+  public static native void observeUserProgramTest();
+
+  public static void report(int resource, int instanceNumber) {
+    report(resource, instanceNumber, 0, "");
+  }
+
+  public static void report(int resource, int instanceNumber, int context) {
+    report(resource, instanceNumber, context, "");
+  }
+
+  /**
+   * Report the usage of a resource of interest. <br>
+   *
+   * <p>Original signature: <code>uint32_t report(tResourceType, uint8_t, uint8_t, const
+   * char*)</code>
+   *
+   * @param resource       one of the values in the tResourceType above (max value 51). <br>
+   * @param instanceNumber an index that identifies the resource instance. <br>
+   * @param context        an optional additional context number for some cases (such as module
+   *                       number). Set to 0 to omit. <br>
+   * @param feature        a string to be included describing features in use on a specific
+   *                       resource. Setting the same resource more than once allows you to change
+   *                       the feature string.
+   */
+  public static native int report(int resource, int instanceNumber, int context, String feature);
+
+  public static native int nativeGetControlWord();
+
+  @SuppressWarnings("JavadocMethod")
+  public static void getControlWord(ControlWord controlWord) {
+    int word = nativeGetControlWord();
+    controlWord.update((word & 1) != 0, ((word >> 1) & 1) != 0, ((word >> 2) & 1) != 0,
+        ((word >> 3) & 1) != 0, ((word >> 4) & 1) != 0, ((word >> 5) & 1) != 0);
+  }
+
+  private static native int nativeGetAllianceStation();
+
+  @SuppressWarnings("JavadocMethod")
+  public static AllianceStationID getAllianceStation() {
+    switch (nativeGetAllianceStation()) {
+      case 0:
+        return AllianceStationID.Red1;
+      case 1:
+        return AllianceStationID.Red2;
+      case 2:
+        return AllianceStationID.Red3;
+      case 3:
+        return AllianceStationID.Blue1;
+      case 4:
+        return AllianceStationID.Blue2;
+      case 5:
+        return AllianceStationID.Blue3;
+      default:
+        return null;
+    }
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  public static native boolean isNewControlData();
+
+  @SuppressWarnings("JavadocMethod")
+  public static native void releaseDSMutex();
+
+  @SuppressWarnings("JavadocMethod")
+  public static native boolean waitForDSDataTimeout(double timeout);
+
+  public static int kMaxJoystickAxes = 12;
+  public static int kMaxJoystickPOVs = 12;
+
+  public static native short getJoystickAxes(byte joystickNum, float[] axesArray);
+
+  public static native short getJoystickPOVs(byte joystickNum, short[] povsArray);
+
+  public static native int getJoystickButtons(byte joystickNum, ByteBuffer count);
+
+  public static native int setJoystickOutputs(byte joystickNum, int outputs, short leftRumble,
+                                              short rightRumble);
+
+  public static native int getJoystickIsXbox(byte joystickNum);
+
+  public static native int getJoystickType(byte joystickNum);
+
+  public static native String getJoystickName(byte joystickNum);
+
+  public static native int getJoystickAxisType(byte joystickNum, byte axis);
+
+  public static native double getMatchTime();
+
+  public static native boolean getSystemActive();
+
+  public static native boolean getBrownedOut();
+
+  public static native int getMatchInfo(MatchInfoData info);
+
+  public static native int sendError(boolean isError, int errorCode, boolean isLVCode,
+                                     String details, String location, String callStack,
+                                     boolean printMsg);
+
+  public static native int getPortWithModule(byte module, byte channel);
+
+  public static native int getPort(byte channel);
+
+  private HAL() {
+
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/HALUtil.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/HALUtil.java
new file mode 100644
index 0000000..0e5fe21
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/HALUtil.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public final class HALUtil extends JNIWrapper {
+  public static final int NULL_PARAMETER = -1005;
+  public static final int SAMPLE_RATE_TOO_HIGH = 1001;
+  public static final int VOLTAGE_OUT_OF_RANGE = 1002;
+  public static final int LOOP_TIMING_ERROR = 1004;
+  public static final int INCOMPATIBLE_STATE = 1015;
+  public static final int ANALOG_TRIGGER_PULSE_OUTPUT_ERROR = -1011;
+  public static final int NO_AVAILABLE_RESOURCES = -104;
+  public static final int PARAMETER_OUT_OF_RANGE = -1028;
+
+  public static native short getFPGAVersion();
+
+  public static native int getFPGARevision();
+
+  public static native long getFPGATime();
+
+  public static native int getHALRuntimeType();
+
+  public static native boolean getFPGAButton();
+
+  public static native String getHALErrorMessage(int code);
+
+  public static native int getHALErrno();
+
+  public static native String getHALstrerror(int errno);
+
+  public static String getHALstrerror() {
+    return getHALstrerror(getHALErrno());
+  }
+
+  private HALUtil() {
+
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java
new file mode 100644
index 0000000..12a9af0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/I2CJNI.java
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+import java.nio.ByteBuffer;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public class I2CJNI extends JNIWrapper {
+  public static native void i2CInitialize(int port);
+
+  public static native int i2CTransaction(int port, byte address, ByteBuffer dataToSend,
+                                          byte sendSize, ByteBuffer dataReceived, byte receiveSize);
+
+  public static native int i2CTransactionB(int port, byte address, byte[] dataToSend,
+                                           byte sendSize, byte[] dataReceived, byte receiveSize);
+
+  public static native int i2CWrite(int port, byte address, ByteBuffer dataToSend, byte sendSize);
+
+  public static native int i2CWriteB(int port, byte address, byte[] dataToSend, byte sendSize);
+
+  public static native int i2CRead(int port, byte address, ByteBuffer dataReceived,
+                                   byte receiveSize);
+
+  public static native int i2CReadB(int port, byte address, byte[] dataReceived,
+                                    byte receiveSize);
+
+  public static native void i2CClose(int port);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/InterruptJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/InterruptJNI.java
new file mode 100644
index 0000000..8574a25
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/InterruptJNI.java
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class InterruptJNI extends JNIWrapper {
+  public static final int HalInvalidHandle = 0;
+
+  public interface InterruptJNIHandlerFunction {
+    void apply(int interruptAssertedMask, Object param);
+  }
+
+  public static native int initializeInterrupts(boolean watcher);
+
+  public static native void cleanInterrupts(int interruptHandle);
+
+  public static native int waitForInterrupt(int interruptHandle, double timeout,
+                                            boolean ignorePrevious);
+
+  public static native void enableInterrupts(int interruptHandle);
+
+  public static native void disableInterrupts(int interruptHandle);
+
+  public static native long readInterruptRisingTimestamp(int interruptHandle);
+
+  public static native long readInterruptFallingTimestamp(int interruptHandle);
+
+  public static native void requestInterrupts(int interruptHandle, int digitalSourceHandle,
+                                              int analogTriggerType);
+
+  public static native void attachInterruptHandler(int interruptHandle,
+                                                   InterruptJNIHandlerFunction handler,
+                                                   Object param);
+
+  public static native void setInterruptUpSourceEdge(int interruptHandle, boolean risingEdge,
+                                                     boolean fallingEdge);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/JNIWrapper.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/JNIWrapper.java
new file mode 100644
index 0000000..21342bc
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/JNIWrapper.java
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+import java.io.IOException;
+
+import edu.wpi.first.wpiutil.RuntimeLoader;
+
+/**
+ * Base class for all JNI wrappers.
+ */
+public class JNIWrapper {
+  static boolean libraryLoaded = false;
+  static RuntimeLoader<JNIWrapper> loader = null;
+
+  static {
+    if (!libraryLoaded) {
+      try {
+        loader = new RuntimeLoader<>("wpiHaljni", RuntimeLoader.getDefaultExtractionRoot(), JNIWrapper.class);
+        loader.loadLibrary();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      libraryLoaded = true;
+      libraryLoaded = true;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java
new file mode 100644
index 0000000..2f11515
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/MatchInfoData.java
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+/**
+ * Structure for holding the match info data request.
+ */
+public class MatchInfoData {
+  /**
+   * Stores the event name.
+   */
+  @SuppressWarnings("MemberName")
+  public String eventName = "";
+
+  /**
+   * Stores the game specific message.
+   */
+  @SuppressWarnings("MemberName")
+  public String gameSpecificMessage = "";
+
+  /**
+   * Stores the match number.
+   */
+  @SuppressWarnings("MemberName")
+  public int matchNumber;
+
+  /**
+   * Stores the replay number.
+   */
+  @SuppressWarnings("MemberName")
+  public int replayNumber;
+
+  /**
+   * Stores the match type.
+   */
+  @SuppressWarnings("MemberName")
+  public int matchType;
+
+  /**
+   * Called from JNI to set the structure data.
+   */
+  @SuppressWarnings("JavadocMethod")
+  public void setData(String eventName, String gameSpecificMessage,
+                      int matchNumber, int replayNumber, int matchType) {
+    this.eventName = eventName;
+    this.gameSpecificMessage = gameSpecificMessage;
+    this.matchNumber = matchNumber;
+    this.replayNumber = replayNumber;
+    this.matchType = matchType;
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java
new file mode 100644
index 0000000..bf92c37
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/NotifierJNI.java
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+/**
+ * The NotifierJNI class directly wraps the C++ HAL Notifier.
+ *
+ * <p>This class is not meant for direct use by teams. Instead, the edu.wpi.first.wpilibj.Notifier
+ * class, which corresponds to the C++ Notifier class, should be used.
+ */
+public class NotifierJNI extends JNIWrapper {
+  /**
+   * Initializes the notifier.
+   */
+  public static native int initializeNotifier();
+
+  /**
+   * Wakes up the waiter with time=0.  Note: after this function is called, all
+   * calls to waitForNotifierAlarm() will immediately start returning 0.
+   */
+  public static native void stopNotifier(int notifierHandle);
+
+  /**
+   * Deletes the notifier object when we are done with it.
+   */
+  public static native void cleanNotifier(int notifierHandle);
+
+  /**
+   * Sets the notifier to wakeup the waiter in another triggerTime microseconds.
+   */
+  public static native void updateNotifierAlarm(int notifierHandle, long triggerTime);
+
+  /**
+   * Cancels any pending wakeups set by updateNotifierAlarm().  Does NOT wake
+   * up any waiters.
+   */
+  public static native void cancelNotifierAlarm(int notifierHandle);
+
+  /**
+   * Block until woken up by an alarm (or stop).
+   * @return Time when woken up.
+   */
+  public static native long waitForNotifierAlarm(int notifierHandle);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PDPJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PDPJNI.java
new file mode 100644
index 0000000..c45a053
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PDPJNI.java
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public class PDPJNI extends JNIWrapper {
+  public static native int initializePDP(int module);
+
+  public static native boolean checkPDPModule(int module);
+
+  public static native boolean checkPDPChannel(int channel);
+
+  public static native double getPDPTemperature(int handle);
+
+  public static native double getPDPVoltage(int handle);
+
+  public static native double getPDPChannelCurrent(byte channel, int handle);
+
+  public static native double getPDPTotalCurrent(int handle);
+
+  public static native double getPDPTotalPower(int handle);
+
+  public static native double getPDPTotalEnergy(int handle);
+
+  public static native void resetPDPTotalEnergy(int handle);
+
+  public static native void clearPDPStickyFaults(int handle);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java
new file mode 100644
index 0000000..d29b0df
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PWMConfigDataResult.java
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+/**
+ * Structure for holding the config data result for PWM.
+ */
+public class PWMConfigDataResult {
+  PWMConfigDataResult(int max, int deadbandMax, int center, int deadbandMin, int min) {
+    this.max = max;
+    this.deadbandMax = deadbandMax;
+    this.center = center;
+    this.deadbandMin = deadbandMin;
+    this.min = min;
+  }
+
+  /**
+   * The maximum PWM value.
+   */
+  @SuppressWarnings("MemberName")
+  public int max;
+
+  /**
+   * The deadband maximum PWM value.
+   */
+  @SuppressWarnings("MemberName")
+  public int deadbandMax;
+
+  /**
+   * The center PWM value.
+   */
+  @SuppressWarnings("MemberName")
+  public int center;
+
+  /**
+   * The deadband minimum PWM value.
+   */
+  @SuppressWarnings("MemberName")
+  public int deadbandMin;
+
+  /**
+   * The minimum PWM value.
+   */
+  @SuppressWarnings("MemberName")
+  public int min;
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java
new file mode 100644
index 0000000..3af6f96
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PWMJNI.java
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public class PWMJNI extends DIOJNI {
+  public static native int initializePWMPort(int halPortHandle);
+
+  public static native boolean checkPWMChannel(int channel);
+
+  public static native void freePWMPort(int pwmPortHandle);
+
+  public static native void setPWMConfigRaw(int pwmPortHandle, int maxPwm,
+                                            int deadbandMaxPwm, int centerPwm,
+                                            int deadbandMinPwm, int minPwm);
+
+  public static native void setPWMConfig(int pwmPortHandle, double maxPwm,
+                                         double deadbandMaxPwm, double centerPwm,
+                                         double deadbandMinPwm, double minPwm);
+
+  public static native PWMConfigDataResult getPWMConfigRaw(int pwmPortHandle);
+
+  public static native void setPWMEliminateDeadband(int pwmPortHandle, boolean eliminateDeadband);
+
+  public static native boolean getPWMEliminateDeadband(int pwmPortHandle);
+
+  public static native void setPWMRaw(int pwmPortHandle, short value);
+
+  public static native void setPWMSpeed(int pwmPortHandle, double speed);
+
+  public static native void setPWMPosition(int pwmPortHandle, double position);
+
+  public static native short getPWMRaw(int pwmPortHandle);
+
+  public static native double getPWMSpeed(int pwmPortHandle);
+
+  public static native double getPWMPosition(int pwmPortHandle);
+
+  public static native  void setPWMDisabled(int pwmPortHandle);
+
+  public static native void latchPWMZero(int pwmPortHandle);
+
+  public static native void setPWMPeriodScale(int pwmPortHandle, int squelchMask);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java
new file mode 100644
index 0000000..a2ac60b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PortsJNI.java
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class PortsJNI extends JNIWrapper {
+  public static native int getNumAccumulators();
+
+  public static native int getNumAnalogTriggers();
+
+  public static native int getNumAnalogInputs();
+
+  public static native int getNumAnalogOutputs();
+
+  public static native int getNumCounters();
+
+  public static native int getNumDigitalHeaders();
+
+  public static native int getNumPWMHeaders();
+
+  public static native int getNumDigitalChannels();
+
+  public static native int getNumPWMChannels();
+
+  public static native int getNumDigitalPWMOutputs();
+
+  public static native int getNumEncoders();
+
+  public static native int getNumInterrupts();
+
+  public static native int getNumRelayChannels();
+
+  public static native int getNumRelayHeaders();
+
+  public static native int getNumPCMModules();
+
+  public static native int getNumSolenoidChannels();
+
+  public static native int getNumPDPModules();
+
+  public static native int getNumPDPChannels();
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PowerJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PowerJNI.java
new file mode 100644
index 0000000..7a0a376
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/PowerJNI.java
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class PowerJNI extends JNIWrapper {
+  public static native double getVinVoltage();
+
+  public static native double getVinCurrent();
+
+  public static native double getUserVoltage6V();
+
+  public static native double getUserCurrent6V();
+
+  public static native boolean getUserActive6V();
+
+  public static native int getUserCurrentFaults6V();
+
+  public static native double getUserVoltage5V();
+
+  public static native double getUserCurrent5V();
+
+  public static native boolean getUserActive5V();
+
+  public static native int getUserCurrentFaults5V();
+
+  public static native double getUserVoltage3V3();
+
+  public static native double getUserCurrent3V3();
+
+  public static native boolean getUserActive3V3();
+
+  public static native int getUserCurrentFaults3V3();
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/RelayJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/RelayJNI.java
new file mode 100644
index 0000000..1b507dc
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/RelayJNI.java
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class RelayJNI extends DIOJNI {
+  public static native int initializeRelayPort(int halPortHandle, boolean forward);
+
+  public static native void freeRelayPort(int relayPortHandle);
+
+  public static native boolean checkRelayChannel(int channel);
+
+  public static native void setRelay(int relayPortHandle, boolean on);
+
+  public static native boolean getRelay(int relayPortHandle);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java
new file mode 100644
index 0000000..c473181
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SPIJNI.java
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+import java.nio.ByteBuffer;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public class SPIJNI extends JNIWrapper {
+  public static native void spiInitialize(int port);
+
+  public static native int spiTransaction(int port, ByteBuffer dataToSend,
+                                          ByteBuffer dataReceived, byte size);
+
+  public static native int spiTransactionB(int port, byte[] dataToSend,
+                                           byte[] dataReceived, byte size);
+
+  public static native int spiWrite(int port, ByteBuffer dataToSend, byte sendSize);
+
+  public static native int spiWriteB(int port, byte[] dataToSend, byte sendSize);
+
+  public static native int spiRead(int port, boolean initiate, ByteBuffer dataReceived, byte size);
+
+  public static native int spiReadB(int port, boolean initiate, byte[] dataReceived, byte size);
+
+  public static native void spiClose(int port);
+
+  public static native void spiSetSpeed(int port, int speed);
+
+  public static native void spiSetOpts(int port, int msbFirst, int sampleOnTrailing,
+                                       int clkIdleHigh);
+
+  public static native void spiSetChipSelectActiveHigh(int port);
+
+  public static native void spiSetChipSelectActiveLow(int port);
+
+  public static native void spiInitAuto(int port, int bufferSize);
+
+  public static native void spiFreeAuto(int port);
+
+  public static native void spiStartAutoRate(int port, double period);
+
+  public static native void spiStartAutoTrigger(int port, int digitalSourceHandle,
+                                                int analogTriggerType, boolean triggerRising,
+                                                boolean triggerFalling);
+
+  public static native void spiStopAuto(int port);
+
+  public static native void spiSetAutoTransmitData(int port, byte[] dataToSend, int zeroSize);
+
+  public static native void spiForceAutoRead(int port);
+
+  public static native int spiReadAutoReceivedData(int port, ByteBuffer buffer, int numToRead,
+                                                   double timeout);
+
+  public static native int spiReadAutoReceivedData(int port, int[] buffer, int numToRead,
+                                                   double timeout);
+
+  public static native int spiGetAutoDroppedCount(int port);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SerialPortJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SerialPortJNI.java
new file mode 100644
index 0000000..db98b9c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SerialPortJNI.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class SerialPortJNI extends JNIWrapper {
+  public static native void serialInitializePort(byte port);
+
+  public static native void serialInitializePortDirect(byte port, String portName);
+
+  public static native void serialSetBaudRate(byte port, int baud);
+
+  public static native void serialSetDataBits(byte port, byte bits);
+
+  public static native void serialSetParity(byte port, byte parity);
+
+  public static native void serialSetStopBits(byte port, byte stopBits);
+
+  public static native void serialSetWriteMode(byte port, byte mode);
+
+  public static native void serialSetFlowControl(byte port, byte flow);
+
+  public static native void serialSetTimeout(byte port, double timeout);
+
+  public static native void serialEnableTermination(byte port, char terminator);
+
+  public static native void serialDisableTermination(byte port);
+
+  public static native void serialSetReadBufferSize(byte port, int size);
+
+  public static native void serialSetWriteBufferSize(byte port, int size);
+
+  public static native int serialGetBytesReceived(byte port);
+
+  public static native int serialRead(byte port, byte[] buffer, int count);
+
+  public static native int serialWrite(byte port, byte[] buffer, int count);
+
+  public static native void serialFlush(byte port);
+
+  public static native void serialClear(byte port);
+
+  public static native void serialClose(byte port);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SolenoidJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SolenoidJNI.java
new file mode 100644
index 0000000..66acbea
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/SolenoidJNI.java
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class SolenoidJNI extends JNIWrapper {
+  public static native int initializeSolenoidPort(int halPortHandle);
+
+  public static native boolean checkSolenoidModule(int module);
+
+  public static native boolean checkSolenoidChannel(int channel);
+
+  public static native void freeSolenoidPort(int portHandle);
+
+  public static native void setSolenoid(int portHandle, boolean on);
+
+  public static native boolean getSolenoid(int portHandle);
+
+  public static native int getAllSolenoids(int module);
+
+  public static native int getPCMSolenoidBlackList(int module);
+
+  public static native boolean getPCMSolenoidVoltageStickyFault(int module);
+
+  public static native boolean getPCMSolenoidVoltageFault(int module);
+
+  public static native void clearAllPCMStickyFaults(int module);
+
+  public static native void setOneShotDuration(int portHandle, long durationMS);
+
+  public static native void fireOneShot(int portHandle);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ThreadsJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ThreadsJNI.java
new file mode 100644
index 0000000..e320eb5
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/ThreadsJNI.java
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal;
+
+public class ThreadsJNI extends JNIWrapper {
+  public static native int getCurrentThreadPriority();
+
+  public static native boolean getCurrentThreadIsRealTime();
+
+  public static native boolean setCurrentThreadPriority(boolean realTime, int priority);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANExceptionFactory.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANExceptionFactory.java
new file mode 100644
index 0000000..132dae1
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANExceptionFactory.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.can;
+
+import edu.wpi.first.hal.communication.NIRioStatus;
+import edu.wpi.first.hal.util.UncleanStatusException;
+
+public final class CANExceptionFactory {
+  // FRC Error codes
+  static final int ERR_CANSessionMux_InvalidBuffer = -44086;
+  static final int ERR_CANSessionMux_MessageNotFound = -44087;
+  static final int ERR_CANSessionMux_NotAllowed = -44088;
+  static final int ERR_CANSessionMux_NotInitialized = -44089;
+
+  @SuppressWarnings({"JavadocMethod", "PMD.CyclomaticComplexity"})
+  public static void checkStatus(int status, int messageID) throws CANInvalidBufferException,
+      CANMessageNotAllowedException, CANNotInitializedException, UncleanStatusException {
+    switch (status) {
+      case NIRioStatus.kRioStatusSuccess:
+        // Everything is ok... don't throw.
+        return;
+      case ERR_CANSessionMux_InvalidBuffer:
+      case NIRioStatus.kRIOStatusBufferInvalidSize:
+        throw new CANInvalidBufferException();
+      case ERR_CANSessionMux_MessageNotFound:
+      case NIRioStatus.kRIOStatusOperationTimedOut:
+        throw new CANMessageNotFoundException();
+      case ERR_CANSessionMux_NotAllowed:
+      case NIRioStatus.kRIOStatusFeatureNotSupported:
+        throw new CANMessageNotAllowedException("MessageID = " + Integer.toString(messageID));
+      case ERR_CANSessionMux_NotInitialized:
+      case NIRioStatus.kRIOStatusResourceNotInitialized:
+        throw new CANNotInitializedException();
+      default:
+        throw new UncleanStatusException("Fatal status code detected:  " + Integer.toString(
+            status));
+    }
+  }
+
+  private CANExceptionFactory() {
+
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANInvalidBufferException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANInvalidBufferException.java
new file mode 100644
index 0000000..8ea718b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANInvalidBufferException.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.can;
+
+/**
+ * Exception indicating that a CAN driver library entry-point was passed an invalid buffer.
+ * Typically, this is due to a buffer being too small to include the needed safety token.
+ */
+public class CANInvalidBufferException extends RuntimeException {
+  private static final long serialVersionUID = -7993785672956997939L;
+
+  public CANInvalidBufferException() {
+    super();
+  }
+
+  public CANInvalidBufferException(String msg) {
+    super(msg);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java
new file mode 100644
index 0000000..754157b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANJNI.java
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.can;
+
+import java.nio.ByteBuffer;
+import java.nio.IntBuffer;
+
+import edu.wpi.first.hal.JNIWrapper;
+
+@SuppressWarnings("AbbreviationAsWordInName")
+public class CANJNI extends JNIWrapper {
+  public static final int CAN_SEND_PERIOD_NO_REPEAT = 0;
+  public static final int CAN_SEND_PERIOD_STOP_REPEATING = -1;
+
+  /* Flags in the upper bits of the messageID */
+  public static final int CAN_IS_FRAME_REMOTE = 0x80000000;
+  public static final int CAN_IS_FRAME_11BIT = 0x40000000;
+
+  @SuppressWarnings("MethodName")
+  public static native void FRCNetCommCANSessionMuxSendMessage(int messageID,
+                                                               byte[] data,
+                                                               int periodMs);
+
+  @SuppressWarnings("MethodName")
+  public static native byte[] FRCNetCommCANSessionMuxReceiveMessage(
+      IntBuffer messageID, int messageIDMask, ByteBuffer timeStamp);
+
+
+  @SuppressWarnings("MethodName")
+  public static native void GetCANStatus(CANStatus status);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANMessageNotAllowedException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANMessageNotAllowedException.java
new file mode 100644
index 0000000..f4ba6a8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANMessageNotAllowedException.java
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.can;
+
+/**
+ * Exception indicating that the Jaguar CAN Driver layer refused to send a restricted message ID to
+ * the CAN bus.
+ */
+public class CANMessageNotAllowedException extends RuntimeException {
+  private static final long serialVersionUID = -638450112427013494L;
+
+  public CANMessageNotAllowedException(String msg) {
+    super(msg);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANMessageNotFoundException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANMessageNotFoundException.java
new file mode 100644
index 0000000..0838691
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANMessageNotFoundException.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.can;
+
+/**
+ * Exception indicating that a can message is not available from Network Communications. This
+ * usually just means we already have the most recent value cached locally.
+ */
+public class CANMessageNotFoundException extends RuntimeException {
+  private static final long serialVersionUID = 8249780881928189975L;
+
+  public CANMessageNotFoundException() {
+    super();
+  }
+
+  public CANMessageNotFoundException(String msg) {
+    super(msg);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANNotInitializedException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANNotInitializedException.java
new file mode 100644
index 0000000..119b59d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANNotInitializedException.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.can;
+
+/**
+ * Exception indicating that the CAN driver layer has not been initialized. This happens when an
+ * entry-point is called before a CAN driver plugin has been installed.
+ */
+public class CANNotInitializedException extends RuntimeException {
+  private static final long serialVersionUID = -5982895147092686594L;
+
+  public CANNotInitializedException() {
+    super();
+  }
+
+  public CANNotInitializedException(String msg) {
+    super(msg);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java
new file mode 100644
index 0000000..492d999
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/can/CANStatus.java
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.can;
+
+/**
+ * Structure for holding the result of a CAN Status request.
+ */
+public class CANStatus {
+  /**
+   * The utilization of the CAN Bus.
+   */
+  @SuppressWarnings("MemberName")
+  public double percentBusUtilization;
+
+  /**
+   * The CAN Bus off count.
+   */
+  @SuppressWarnings("MemberName")
+  public int busOffCount;
+
+  /**
+   * The CAN Bus TX full count.
+   */
+  @SuppressWarnings("MemberName")
+  public int txFullCount;
+
+  /**
+   * The CAN Bus receive error count.
+   */
+  @SuppressWarnings("MemberName")
+  public int receiveErrorCount;
+
+  /**
+   * The CAN Bus transmit error count.
+   */
+  @SuppressWarnings("MemberName")
+  public int transmitErrorCount;
+
+  @SuppressWarnings("JavadocMethod")
+  public void setStatus(double percentBusUtilization, int busOffCount, int txFullCount,
+                        int receiveErrorCount, int transmitErrorCount) {
+    this.percentBusUtilization = percentBusUtilization;
+    this.busOffCount = busOffCount;
+    this.txFullCount = txFullCount;
+    this.receiveErrorCount = receiveErrorCount;
+    this.transmitErrorCount = transmitErrorCount;
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/communication/NIRioStatus.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/communication/NIRioStatus.java
new file mode 100644
index 0000000..f49f34e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/communication/NIRioStatus.java
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.communication;
+
+public class NIRioStatus {
+  public static final int kRioStatusOffset = -63000;
+
+  public static final int kRioStatusSuccess = 0;
+  public static final int kRIOStatusBufferInvalidSize = kRioStatusOffset - 80;
+  public static final int kRIOStatusOperationTimedOut = -52007;
+  public static final int kRIOStatusFeatureNotSupported = kRioStatusOffset - 193;
+  public static final int kRIOStatusResourceNotInitialized = -52010;
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AccelerometerSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AccelerometerSim.java
new file mode 100644
index 0000000..d9c95af
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AccelerometerSim.java
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.AccelerometerDataJNI;
+
+public class AccelerometerSim {
+  private final int m_index;
+
+  public AccelerometerSim() {
+    m_index = 0;
+  }
+
+  public CallbackStore registerActiveCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AccelerometerDataJNI.registerActiveCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelActiveCallback);
+  }
+  public boolean getActive() {
+    return AccelerometerDataJNI.getActive(m_index);
+  }
+  public void setActive(boolean active) {
+    AccelerometerDataJNI.setActive(m_index, active);
+  }
+
+  public CallbackStore registerRangeCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AccelerometerDataJNI.registerRangeCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelRangeCallback);
+  }
+  public int getRange() {
+    return AccelerometerDataJNI.getRange(m_index);
+  }
+  public void setRange(int range) {
+    AccelerometerDataJNI.setRange(m_index, range);
+  }
+
+  public CallbackStore registerXCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AccelerometerDataJNI.registerXCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelXCallback);
+  }
+  public double getX() {
+    return AccelerometerDataJNI.getX(m_index);
+  }
+  public void setX(double x) {
+    AccelerometerDataJNI.setX(m_index, x);
+  }
+
+  public CallbackStore registerYCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AccelerometerDataJNI.registerYCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelYCallback);
+  }
+  public double getY() {
+    return AccelerometerDataJNI.getY(m_index);
+  }
+  public void setY(double y) {
+    AccelerometerDataJNI.setY(m_index, y);
+  }
+
+  public CallbackStore registerZCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AccelerometerDataJNI.registerZCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AccelerometerDataJNI::cancelZCallback);
+  }
+  public double getZ() {
+    return AccelerometerDataJNI.getZ(m_index);
+  }
+  public void setZ(double z) {
+    AccelerometerDataJNI.setZ(m_index, z);
+  }
+
+  public void resetData() {
+    AccelerometerDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogGyroSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogGyroSim.java
new file mode 100644
index 0000000..ddaa0ce
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogGyroSim.java
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.AnalogGyroDataJNI;
+
+public class AnalogGyroSim {
+  private final int m_index;
+
+  public AnalogGyroSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerAngleCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogGyroDataJNI.registerAngleCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogGyroDataJNI::cancelAngleCallback);
+  }
+  public double getAngle() {
+    return AnalogGyroDataJNI.getAngle(m_index);
+  }
+  public void setAngle(double angle) {
+    AnalogGyroDataJNI.setAngle(m_index, angle);
+  }
+
+  public CallbackStore registerRateCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogGyroDataJNI.registerRateCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogGyroDataJNI::cancelRateCallback);
+  }
+  public double getRate() {
+    return AnalogGyroDataJNI.getRate(m_index);
+  }
+  public void setRate(double rate) {
+    AnalogGyroDataJNI.setRate(m_index, rate);
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogGyroDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogGyroDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return AnalogGyroDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    AnalogGyroDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public void resetData() {
+    AnalogGyroDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogInSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogInSim.java
new file mode 100644
index 0000000..f7f86bb
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogInSim.java
@@ -0,0 +1,121 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.AnalogInDataJNI;
+
+public class AnalogInSim {
+  private final int m_index;
+
+  public AnalogInSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return AnalogInDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    AnalogInDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerAverageBitsCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerAverageBitsCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelAverageBitsCallback);
+  }
+  public int getAverageBits() {
+    return AnalogInDataJNI.getAverageBits(m_index);
+  }
+  public void setAverageBits(int averageBits) {
+    AnalogInDataJNI.setAverageBits(m_index, averageBits);
+  }
+
+  public CallbackStore registerOversampleBitsCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerOversampleBitsCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelOversampleBitsCallback);
+  }
+  public int getOversampleBits() {
+    return AnalogInDataJNI.getOversampleBits(m_index);
+  }
+  public void setOversampleBits(int oversampleBits) {
+    AnalogInDataJNI.setOversampleBits(m_index, oversampleBits);
+  }
+
+  public CallbackStore registerVoltageCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerVoltageCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelVoltageCallback);
+  }
+  public double getVoltage() {
+    return AnalogInDataJNI.getVoltage(m_index);
+  }
+  public void setVoltage(double voltage) {
+    AnalogInDataJNI.setVoltage(m_index, voltage);
+  }
+
+  public CallbackStore registerAccumulatorInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerAccumulatorInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelAccumulatorInitializedCallback);
+  }
+  public boolean getAccumulatorInitialized() {
+    return AnalogInDataJNI.getAccumulatorInitialized(m_index);
+  }
+  public void setAccumulatorInitialized(boolean accumulatorInitialized) {
+    AnalogInDataJNI.setAccumulatorInitialized(m_index, accumulatorInitialized);
+  }
+
+  public CallbackStore registerAccumulatorValueCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerAccumulatorValueCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelAccumulatorValueCallback);
+  }
+  public long getAccumulatorValue() {
+    return AnalogInDataJNI.getAccumulatorValue(m_index);
+  }
+  public void setAccumulatorValue(long accumulatorValue) {
+    AnalogInDataJNI.setAccumulatorValue(m_index, accumulatorValue);
+  }
+
+  public CallbackStore registerAccumulatorCountCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerAccumulatorCountCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelAccumulatorCountCallback);
+  }
+  public long getAccumulatorCount() {
+    return AnalogInDataJNI.getAccumulatorCount(m_index);
+  }
+  public void setAccumulatorCount(long accumulatorCount) {
+    AnalogInDataJNI.setAccumulatorCount(m_index, accumulatorCount);
+  }
+
+  public CallbackStore registerAccumulatorCenterCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerAccumulatorCenterCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelAccumulatorCenterCallback);
+  }
+  public int getAccumulatorCenter() {
+    return AnalogInDataJNI.getAccumulatorCenter(m_index);
+  }
+  public void setAccumulatorCenter(int accumulatorCenter) {
+    AnalogInDataJNI.setAccumulatorCenter(m_index, accumulatorCenter);
+  }
+
+  public CallbackStore registerAccumulatorDeadbandCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogInDataJNI.registerAccumulatorDeadbandCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogInDataJNI::cancelAccumulatorDeadbandCallback);
+  }
+  public int getAccumulatorDeadband() {
+    return AnalogInDataJNI.getAccumulatorDeadband(m_index);
+  }
+  public void setAccumulatorDeadband(int accumulatorDeadband) {
+    AnalogInDataJNI.setAccumulatorDeadband(m_index, accumulatorDeadband);
+  }
+
+  public void resetData() {
+    AnalogInDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogOutSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogOutSim.java
new file mode 100644
index 0000000..4731b11
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogOutSim.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.AnalogOutDataJNI;
+
+public class AnalogOutSim {
+  private final int m_index;
+
+  public AnalogOutSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerVoltageCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogOutDataJNI.registerVoltageCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogOutDataJNI::cancelVoltageCallback);
+  }
+  public double getVoltage() {
+    return AnalogOutDataJNI.getVoltage(m_index);
+  }
+  public void setVoltage(double voltage) {
+    AnalogOutDataJNI.setVoltage(m_index, voltage);
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogOutDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogOutDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return AnalogOutDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    AnalogOutDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public void resetData() {
+    AnalogOutDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogTriggerSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogTriggerSim.java
new file mode 100644
index 0000000..fd88d5f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/AnalogTriggerSim.java
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.AnalogTriggerDataJNI;
+
+public class AnalogTriggerSim {
+  private final int m_index;
+
+  public AnalogTriggerSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogTriggerDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogTriggerDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return AnalogTriggerDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    AnalogTriggerDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerTriggerLowerBoundCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogTriggerDataJNI.registerTriggerLowerBoundCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogTriggerDataJNI::cancelTriggerLowerBoundCallback);
+  }
+  public double getTriggerLowerBound() {
+    return AnalogTriggerDataJNI.getTriggerLowerBound(m_index);
+  }
+  public void setTriggerLowerBound(double triggerLowerBound) {
+    AnalogTriggerDataJNI.setTriggerLowerBound(m_index, triggerLowerBound);
+  }
+
+  public CallbackStore registerTriggerUpperBoundCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = AnalogTriggerDataJNI.registerTriggerUpperBoundCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, AnalogTriggerDataJNI::cancelTriggerUpperBoundCallback);
+  }
+  public double getTriggerUpperBound() {
+    return AnalogTriggerDataJNI.getTriggerUpperBound(m_index);
+  }
+  public void setTriggerUpperBound(double triggerUpperBound) {
+    AnalogTriggerDataJNI.setTriggerUpperBound(m_index, triggerUpperBound);
+  }
+
+  public void resetData() {
+    AnalogTriggerDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/BufferCallback.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/BufferCallback.java
new file mode 100644
index 0000000..0f7b2d9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/BufferCallback.java
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+public interface BufferCallback {
+  void callback(String name, byte[] buffer, int count);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/CallbackStore.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/CallbackStore.java
new file mode 100644
index 0000000..7564104
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/CallbackStore.java
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+public class CallbackStore implements AutoCloseable {
+  interface CancelCallbackFunc {
+    void cancel(int index, int uid);
+  }
+
+  interface CancelCallbackChannelFunc {
+    void cancel(int index, int channel, int uid);
+  }
+
+  interface CancelCallbackNoIndexFunc {
+    void cancel(int uid);
+  }
+
+  public CallbackStore(int index, int uid, CancelCallbackFunc ccf) {
+    this.m_cancelType = kNormalCancel;
+    this.m_index = index;
+    this.m_uid = uid;
+    this.m_cancelCallback = ccf;
+  }
+
+  public CallbackStore(int index, int channel, int uid, CancelCallbackChannelFunc ccf) {
+    this.m_cancelType = kChannelCancel;
+    this.m_index = index;
+    this.m_uid = uid;
+    this.m_channel = channel;
+    this.m_cancelCallbackChannel = ccf;
+  }
+
+  public CallbackStore(int uid, CancelCallbackNoIndexFunc ccf) {
+    this.m_cancelType = kNoIndexCancel;
+    this.m_uid = uid;
+    this.m_cancelCallbackNoIndex = ccf;
+  }
+
+  private int m_index;
+  private int m_channel;
+  private final int m_uid;
+  private CancelCallbackFunc m_cancelCallback;
+  private CancelCallbackChannelFunc m_cancelCallbackChannel;
+  private CancelCallbackNoIndexFunc m_cancelCallbackNoIndex;
+  private static final int kNormalCancel = 0;
+  private static final int kChannelCancel = 1;
+  private static final int kNoIndexCancel = 2;
+  private int m_cancelType;
+
+  @Override
+  public void close() {
+    switch (m_cancelType) {
+      case kNormalCancel:
+        m_cancelCallback.cancel(m_index, m_uid);
+        break;
+      case kChannelCancel:
+        m_cancelCallbackChannel.cancel(m_index, m_channel, m_uid);
+        break;
+      case kNoIndexCancel:
+        m_cancelCallbackNoIndex.cancel(m_uid);
+        break;
+      default:
+        assert false;
+        break;
+    }
+    m_cancelType = -1;
+  }
+
+  @Override
+  protected void finalize() throws Throwable {
+    try {
+      if (m_cancelType >= 0) {
+        close();        // close open files
+      }
+    } finally {
+      super.finalize();
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/ConstBufferCallback.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/ConstBufferCallback.java
new file mode 100644
index 0000000..a4251c2
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/ConstBufferCallback.java
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+public interface ConstBufferCallback {
+  void callback(String name, byte[] buffer, int count);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DIOSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DIOSim.java
new file mode 100644
index 0000000..cd75822
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DIOSim.java
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.DIODataJNI;
+
+public class DIOSim {
+  private final int m_index;
+
+  public DIOSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DIODataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DIODataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return DIODataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    DIODataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerValueCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DIODataJNI.registerValueCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DIODataJNI::cancelValueCallback);
+  }
+  public boolean getValue() {
+    return DIODataJNI.getValue(m_index);
+  }
+  public void setValue(boolean value) {
+    DIODataJNI.setValue(m_index, value);
+  }
+
+  public CallbackStore registerPulseLengthCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DIODataJNI.registerPulseLengthCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DIODataJNI::cancelPulseLengthCallback);
+  }
+  public double getPulseLength() {
+    return DIODataJNI.getPulseLength(m_index);
+  }
+  public void setPulseLength(double pulseLength) {
+    DIODataJNI.setPulseLength(m_index, pulseLength);
+  }
+
+  public CallbackStore registerIsInputCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DIODataJNI.registerIsInputCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DIODataJNI::cancelIsInputCallback);
+  }
+  public boolean getIsInput() {
+    return DIODataJNI.getIsInput(m_index);
+  }
+  public void setIsInput(boolean isInput) {
+    DIODataJNI.setIsInput(m_index, isInput);
+  }
+
+  public CallbackStore registerFilterIndexCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DIODataJNI.registerFilterIndexCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DIODataJNI::cancelFilterIndexCallback);
+  }
+  public int getFilterIndex() {
+    return DIODataJNI.getFilterIndex(m_index);
+  }
+  public void setFilterIndex(int filterIndex) {
+    DIODataJNI.setFilterIndex(m_index, filterIndex);
+  }
+
+  public void resetData() {
+    DIODataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DigitalPWMSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DigitalPWMSim.java
new file mode 100644
index 0000000..314d994
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DigitalPWMSim.java
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.DigitalPWMDataJNI;
+
+public class DigitalPWMSim {
+  private final int m_index;
+
+  public DigitalPWMSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DigitalPWMDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DigitalPWMDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return DigitalPWMDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    DigitalPWMDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerDutyCycleCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DigitalPWMDataJNI.registerDutyCycleCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DigitalPWMDataJNI::cancelDutyCycleCallback);
+  }
+  public double getDutyCycle() {
+    return DigitalPWMDataJNI.getDutyCycle(m_index);
+  }
+  public void setDutyCycle(double dutyCycle) {
+    DigitalPWMDataJNI.setDutyCycle(m_index, dutyCycle);
+  }
+
+  public CallbackStore registerPinCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DigitalPWMDataJNI.registerPinCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, DigitalPWMDataJNI::cancelPinCallback);
+  }
+  public int getPin() {
+    return DigitalPWMDataJNI.getPin(m_index);
+  }
+  public void setPin(int pin) {
+    DigitalPWMDataJNI.setPin(m_index, pin);
+  }
+
+  public void resetData() {
+    DigitalPWMDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DriverStationSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DriverStationSim.java
new file mode 100644
index 0000000..20fed0d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/DriverStationSim.java
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.DriverStationDataJNI;
+
+public class DriverStationSim {
+  public CallbackStore registerEnabledCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DriverStationDataJNI.registerEnabledCallback(callback, initialNotify);
+    return new CallbackStore(uid, DriverStationDataJNI::cancelEnabledCallback);
+  }
+  public boolean getEnabled() {
+    return DriverStationDataJNI.getEnabled();
+  }
+  public void setEnabled(boolean enabled) {
+    DriverStationDataJNI.setEnabled(enabled);
+  }
+
+  public CallbackStore registerAutonomousCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DriverStationDataJNI.registerAutonomousCallback(callback, initialNotify);
+    return new CallbackStore(uid, DriverStationDataJNI::cancelAutonomousCallback);
+  }
+  public boolean getAutonomous() {
+    return DriverStationDataJNI.getAutonomous();
+  }
+  public void setAutonomous(boolean autonomous) {
+    DriverStationDataJNI.setAutonomous(autonomous);
+  }
+
+  public CallbackStore registerTestCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DriverStationDataJNI.registerTestCallback(callback, initialNotify);
+    return new CallbackStore(uid, DriverStationDataJNI::cancelTestCallback);
+  }
+  public boolean getTest() {
+    return DriverStationDataJNI.getTest();
+  }
+  public void setTest(boolean test) {
+    DriverStationDataJNI.setTest(test);
+  }
+
+  public CallbackStore registerEStopCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DriverStationDataJNI.registerEStopCallback(callback, initialNotify);
+    return new CallbackStore(uid, DriverStationDataJNI::cancelEStopCallback);
+  }
+  public boolean getEStop() {
+    return DriverStationDataJNI.getEStop();
+  }
+  public void setEStop(boolean eStop) {
+    DriverStationDataJNI.setEStop(eStop);
+  }
+
+  public CallbackStore registerFmsAttachedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DriverStationDataJNI.registerFmsAttachedCallback(callback, initialNotify);
+    return new CallbackStore(uid, DriverStationDataJNI::cancelFmsAttachedCallback);
+  }
+  public boolean getFmsAttached() {
+    return DriverStationDataJNI.getFmsAttached();
+  }
+  public void setFmsAttached(boolean fmsAttached) {
+    DriverStationDataJNI.setFmsAttached(fmsAttached);
+  }
+
+  public CallbackStore registerDsAttachedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = DriverStationDataJNI.registerDsAttachedCallback(callback, initialNotify);
+    return new CallbackStore(uid, DriverStationDataJNI::cancelDsAttachedCallback);
+  }
+  public boolean getDsAttached() {
+    return DriverStationDataJNI.getDsAttached();
+  }
+  public void setDsAttached(boolean dsAttached) {
+    DriverStationDataJNI.setDsAttached(dsAttached);
+  }
+  public void notifyNewData() {
+    DriverStationDataJNI.notifyNewData();
+  }
+
+  public void resetData() {
+    DriverStationDataJNI.resetData();
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/EncoderSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/EncoderSim.java
new file mode 100644
index 0000000..408ca84
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/EncoderSim.java
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.EncoderDataJNI;
+
+public class EncoderSim {
+  private final int m_index;
+
+  public EncoderSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = EncoderDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, EncoderDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return EncoderDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    EncoderDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerCountCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = EncoderDataJNI.registerCountCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, EncoderDataJNI::cancelCountCallback);
+  }
+  public int getCount() {
+    return EncoderDataJNI.getCount(m_index);
+  }
+  public void setCount(int count) {
+    EncoderDataJNI.setCount(m_index, count);
+  }
+
+  public CallbackStore registerPeriodCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = EncoderDataJNI.registerPeriodCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, EncoderDataJNI::cancelPeriodCallback);
+  }
+  public double getPeriod() {
+    return EncoderDataJNI.getPeriod(m_index);
+  }
+  public void setPeriod(double period) {
+    EncoderDataJNI.setPeriod(m_index, period);
+  }
+
+  public CallbackStore registerResetCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = EncoderDataJNI.registerResetCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, EncoderDataJNI::cancelResetCallback);
+  }
+  public boolean getReset() {
+    return EncoderDataJNI.getReset(m_index);
+  }
+  public void setReset(boolean reset) {
+    EncoderDataJNI.setReset(m_index, reset);
+  }
+
+  public CallbackStore registerMaxPeriodCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = EncoderDataJNI.registerMaxPeriodCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, EncoderDataJNI::cancelMaxPeriodCallback);
+  }
+  public double getMaxPeriod() {
+    return EncoderDataJNI.getMaxPeriod(m_index);
+  }
+  public void setMaxPeriod(double maxPeriod) {
+    EncoderDataJNI.setMaxPeriod(m_index, maxPeriod);
+  }
+
+  public CallbackStore registerDirectionCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = EncoderDataJNI.registerDirectionCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, EncoderDataJNI::cancelDirectionCallback);
+  }
+  public boolean getDirection() {
+    return EncoderDataJNI.getDirection(m_index);
+  }
+  public void setDirection(boolean direction) {
+    EncoderDataJNI.setDirection(m_index, direction);
+  }
+
+  public CallbackStore registerReverseDirectionCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = EncoderDataJNI.registerReverseDirectionCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, EncoderDataJNI::cancelReverseDirectionCallback);
+  }
+  public boolean getReverseDirection() {
+    return EncoderDataJNI.getReverseDirection(m_index);
+  }
+  public void setReverseDirection(boolean reverseDirection) {
+    EncoderDataJNI.setReverseDirection(m_index, reverseDirection);
+  }
+
+  public CallbackStore registerSamplesToAverageCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = EncoderDataJNI.registerSamplesToAverageCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, EncoderDataJNI::cancelSamplesToAverageCallback);
+  }
+  public int getSamplesToAverage() {
+    return EncoderDataJNI.getSamplesToAverage(m_index);
+  }
+  public void setSamplesToAverage(int samplesToAverage) {
+    EncoderDataJNI.setSamplesToAverage(m_index, samplesToAverage);
+  }
+
+  public void resetData() {
+    EncoderDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/I2CSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/I2CSim.java
new file mode 100644
index 0000000..3a9aa02
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/I2CSim.java
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.I2CDataJNI;
+
+public class I2CSim {
+  private final int m_index;
+
+  public I2CSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = I2CDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, I2CDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return I2CDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    I2CDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerReadCallback(BufferCallback callback) {
+    int uid = I2CDataJNI.registerReadCallback(m_index, callback);
+    return new CallbackStore(m_index, uid, I2CDataJNI::cancelReadCallback);
+  }
+
+  public CallbackStore registerWriteCallback(ConstBufferCallback callback) {
+    int uid = I2CDataJNI.registerWriteCallback(m_index, callback);
+    return new CallbackStore(m_index, uid, I2CDataJNI::cancelWriteCallback);
+  }
+
+  public void resetData() {
+    I2CDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/NotifyCallback.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/NotifyCallback.java
new file mode 100644
index 0000000..8781f75
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/NotifyCallback.java
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+public interface NotifyCallback {
+  void callback(String name, SimValue value);
+
+  default void callbackNative(String name, int type, long value1, double value2) {
+    switch (type) {
+      case 0x01:
+        callback(name, SimValue.makeBoolean(value1 != 0));
+        break;
+      case 0x02:
+        callback(name, SimValue.makeDouble(value2));
+        break;
+      case 0x16:
+        callback(name, SimValue.makeEnum((int) value1));
+        break;
+      case 0x32:
+        callback(name, SimValue.makeInt((int) value1));
+        break;
+      case 0x64:
+        callback(name, SimValue.makeLong(value1));
+        break;
+      default:
+        callback(name, SimValue.makeUnassigned());
+        break;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PCMSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PCMSim.java
new file mode 100644
index 0000000..f8cc327
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PCMSim.java
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.PCMDataJNI;
+
+public class PCMSim {
+  private final int m_index;
+
+  public PCMSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerSolenoidInitializedCallback(int channel, NotifyCallback callback, boolean initialNotify) {
+    int uid = PCMDataJNI.registerSolenoidInitializedCallback(m_index, channel, callback, initialNotify);
+    return new CallbackStore(m_index, channel, uid, PCMDataJNI::cancelSolenoidInitializedCallback);
+  }
+  public boolean getSolenoidInitialized(int channel) {
+    return PCMDataJNI.getSolenoidInitialized(m_index, channel);
+  }
+  public void setSolenoidInitialized(int channel, boolean solenoidInitialized) {
+    PCMDataJNI.setSolenoidInitialized(m_index, channel, solenoidInitialized);
+  }
+
+  public CallbackStore registerSolenoidOutputCallback(int channel, NotifyCallback callback, boolean initialNotify) {
+    int uid = PCMDataJNI.registerSolenoidOutputCallback(m_index, channel, callback, initialNotify);
+    return new CallbackStore(m_index, channel, uid, PCMDataJNI::cancelSolenoidOutputCallback);
+  }
+  public boolean getSolenoidOutput(int channel) {
+    return PCMDataJNI.getSolenoidOutput(m_index, channel);
+  }
+  public void setSolenoidOutput(int channel, boolean solenoidOutput) {
+    PCMDataJNI.setSolenoidOutput(m_index, channel, solenoidOutput);
+  }
+
+  public CallbackStore registerCompressorInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PCMDataJNI.registerCompressorInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PCMDataJNI::cancelCompressorInitializedCallback);
+  }
+  public boolean getCompressorInitialized() {
+    return PCMDataJNI.getCompressorInitialized(m_index);
+  }
+  public void setCompressorInitialized(boolean compressorInitialized) {
+    PCMDataJNI.setCompressorInitialized(m_index, compressorInitialized);
+  }
+
+  public CallbackStore registerCompressorOnCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PCMDataJNI.registerCompressorOnCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PCMDataJNI::cancelCompressorOnCallback);
+  }
+  public boolean getCompressorOn() {
+    return PCMDataJNI.getCompressorOn(m_index);
+  }
+  public void setCompressorOn(boolean compressorOn) {
+    PCMDataJNI.setCompressorOn(m_index, compressorOn);
+  }
+
+  public CallbackStore registerClosedLoopEnabledCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PCMDataJNI.registerClosedLoopEnabledCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PCMDataJNI::cancelClosedLoopEnabledCallback);
+  }
+  public boolean getClosedLoopEnabled() {
+    return PCMDataJNI.getClosedLoopEnabled(m_index);
+  }
+  public void setClosedLoopEnabled(boolean closedLoopEnabled) {
+    PCMDataJNI.setClosedLoopEnabled(m_index, closedLoopEnabled);
+  }
+
+  public CallbackStore registerPressureSwitchCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PCMDataJNI.registerPressureSwitchCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PCMDataJNI::cancelPressureSwitchCallback);
+  }
+  public boolean getPressureSwitch() {
+    return PCMDataJNI.getPressureSwitch(m_index);
+  }
+  public void setPressureSwitch(boolean pressureSwitch) {
+    PCMDataJNI.setPressureSwitch(m_index, pressureSwitch);
+  }
+
+  public CallbackStore registerCompressorCurrentCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PCMDataJNI.registerCompressorCurrentCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PCMDataJNI::cancelCompressorCurrentCallback);
+  }
+  public double getCompressorCurrent() {
+    return PCMDataJNI.getCompressorCurrent(m_index);
+  }
+  public void setCompressorCurrent(double compressorCurrent) {
+    PCMDataJNI.setCompressorCurrent(m_index, compressorCurrent);
+  }
+
+  public void resetData() {
+    PCMDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PDPSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PDPSim.java
new file mode 100644
index 0000000..d44cf3a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PDPSim.java
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.PDPDataJNI;
+
+public class PDPSim {
+  private final int m_index;
+
+  public PDPSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PDPDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PDPDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return PDPDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    PDPDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerTemperatureCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PDPDataJNI.registerTemperatureCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PDPDataJNI::cancelTemperatureCallback);
+  }
+  public double getTemperature() {
+    return PDPDataJNI.getTemperature(m_index);
+  }
+  public void setTemperature(double temperature) {
+    PDPDataJNI.setTemperature(m_index, temperature);
+  }
+
+  public CallbackStore registerVoltageCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PDPDataJNI.registerVoltageCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PDPDataJNI::cancelVoltageCallback);
+  }
+  public double getVoltage() {
+    return PDPDataJNI.getVoltage(m_index);
+  }
+  public void setVoltage(double voltage) {
+    PDPDataJNI.setVoltage(m_index, voltage);
+  }
+
+  public CallbackStore registerCurrentCallback(int channel, NotifyCallback callback, boolean initialNotify) {
+    int uid = PDPDataJNI.registerCurrentCallback(m_index, channel, callback, initialNotify);
+    return new CallbackStore(m_index, channel, uid, PDPDataJNI::cancelCurrentCallback);
+  }
+  public double getCurrent(int channel) {
+    return PDPDataJNI.getCurrent(m_index, channel);
+  }
+  public void setCurrent(int channel, double current) {
+    PDPDataJNI.setCurrent(m_index, channel, current);
+  }
+
+  public void resetData() {
+    PDPDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PWMSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PWMSim.java
new file mode 100644
index 0000000..dde38a4
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/PWMSim.java
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.PWMDataJNI;
+
+public class PWMSim {
+  private final int m_index;
+
+  public PWMSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PWMDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PWMDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return PWMDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    PWMDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerRawValueCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PWMDataJNI.registerRawValueCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PWMDataJNI::cancelRawValueCallback);
+  }
+  public int getRawValue() {
+    return PWMDataJNI.getRawValue(m_index);
+  }
+  public void setRawValue(int rawValue) {
+    PWMDataJNI.setRawValue(m_index, rawValue);
+  }
+
+  public CallbackStore registerSpeedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PWMDataJNI.registerSpeedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PWMDataJNI::cancelSpeedCallback);
+  }
+  public double getSpeed() {
+    return PWMDataJNI.getSpeed(m_index);
+  }
+  public void setSpeed(double speed) {
+    PWMDataJNI.setSpeed(m_index, speed);
+  }
+
+  public CallbackStore registerPositionCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PWMDataJNI.registerPositionCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PWMDataJNI::cancelPositionCallback);
+  }
+  public double getPosition() {
+    return PWMDataJNI.getPosition(m_index);
+  }
+  public void setPosition(double position) {
+    PWMDataJNI.setPosition(m_index, position);
+  }
+
+  public CallbackStore registerPeriodScaleCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PWMDataJNI.registerPeriodScaleCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PWMDataJNI::cancelPeriodScaleCallback);
+  }
+  public int getPeriodScale() {
+    return PWMDataJNI.getPeriodScale(m_index);
+  }
+  public void setPeriodScale(int periodScale) {
+    PWMDataJNI.setPeriodScale(m_index, periodScale);
+  }
+
+  public CallbackStore registerZeroLatchCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = PWMDataJNI.registerZeroLatchCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, PWMDataJNI::cancelZeroLatchCallback);
+  }
+  public boolean getZeroLatch() {
+    return PWMDataJNI.getZeroLatch(m_index);
+  }
+  public void setZeroLatch(boolean zeroLatch) {
+    PWMDataJNI.setZeroLatch(m_index, zeroLatch);
+  }
+
+  public void resetData() {
+    PWMDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/RelaySim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/RelaySim.java
new file mode 100644
index 0000000..84059e8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/RelaySim.java
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.RelayDataJNI;
+
+public class RelaySim {
+  private final int m_index;
+
+  public RelaySim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedForwardCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RelayDataJNI.registerInitializedForwardCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RelayDataJNI::cancelInitializedForwardCallback);
+  }
+  public boolean getInitializedForward() {
+    return RelayDataJNI.getInitializedForward(m_index);
+  }
+  public void setInitializedForward(boolean initializedForward) {
+    RelayDataJNI.setInitializedForward(m_index, initializedForward);
+  }
+
+  public CallbackStore registerInitializedReverseCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RelayDataJNI.registerInitializedReverseCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RelayDataJNI::cancelInitializedReverseCallback);
+  }
+  public boolean getInitializedReverse() {
+    return RelayDataJNI.getInitializedReverse(m_index);
+  }
+  public void setInitializedReverse(boolean initializedReverse) {
+    RelayDataJNI.setInitializedReverse(m_index, initializedReverse);
+  }
+
+  public CallbackStore registerForwardCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RelayDataJNI.registerForwardCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RelayDataJNI::cancelForwardCallback);
+  }
+  public boolean getForward() {
+    return RelayDataJNI.getForward(m_index);
+  }
+  public void setForward(boolean forward) {
+    RelayDataJNI.setForward(m_index, forward);
+  }
+
+  public CallbackStore registerReverseCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RelayDataJNI.registerReverseCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RelayDataJNI::cancelReverseCallback);
+  }
+  public boolean getReverse() {
+    return RelayDataJNI.getReverse(m_index);
+  }
+  public void setReverse(boolean reverse) {
+    RelayDataJNI.setReverse(m_index, reverse);
+  }
+
+  public void resetData() {
+    RelayDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/RoboRioSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/RoboRioSim.java
new file mode 100644
index 0000000..082f712
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/RoboRioSim.java
@@ -0,0 +1,188 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.RoboRioDataJNI;
+
+@SuppressWarnings({"PMD.ExcessivePublicCount", "PMD.TooManyMethods"})
+public class RoboRioSim {
+  private final int m_index;
+
+  public RoboRioSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerFPGAButtonCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerFPGAButtonCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelFPGAButtonCallback);
+  }
+  public boolean getFPGAButton() {
+    return RoboRioDataJNI.getFPGAButton(m_index);
+  }
+  public void setFPGAButton(boolean fPGAButton) {
+    RoboRioDataJNI.setFPGAButton(m_index, fPGAButton);
+  }
+
+  public CallbackStore registerVInVoltageCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerVInVoltageCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelVInVoltageCallback);
+  }
+  public double getVInVoltage() {
+    return RoboRioDataJNI.getVInVoltage(m_index);
+  }
+  public void setVInVoltage(double vInVoltage) {
+    RoboRioDataJNI.setVInVoltage(m_index, vInVoltage);
+  }
+
+  public CallbackStore registerVInCurrentCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerVInCurrentCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelVInCurrentCallback);
+  }
+  public double getVInCurrent() {
+    return RoboRioDataJNI.getVInCurrent(m_index);
+  }
+  public void setVInCurrent(double vInCurrent) {
+    RoboRioDataJNI.setVInCurrent(m_index, vInCurrent);
+  }
+
+  public CallbackStore registerUserVoltage6VCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserVoltage6VCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserVoltage6VCallback);
+  }
+  public double getUserVoltage6V() {
+    return RoboRioDataJNI.getUserVoltage6V(m_index);
+  }
+  public void setUserVoltage6V(double userVoltage6V) {
+    RoboRioDataJNI.setUserVoltage6V(m_index, userVoltage6V);
+  }
+
+  public CallbackStore registerUserCurrent6VCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserCurrent6VCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserCurrent6VCallback);
+  }
+  public double getUserCurrent6V() {
+    return RoboRioDataJNI.getUserCurrent6V(m_index);
+  }
+  public void setUserCurrent6V(double userCurrent6V) {
+    RoboRioDataJNI.setUserCurrent6V(m_index, userCurrent6V);
+  }
+
+  public CallbackStore registerUserActive6VCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserActive6VCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserActive6VCallback);
+  }
+  public boolean getUserActive6V() {
+    return RoboRioDataJNI.getUserActive6V(m_index);
+  }
+  public void setUserActive6V(boolean userActive6V) {
+    RoboRioDataJNI.setUserActive6V(m_index, userActive6V);
+  }
+
+  public CallbackStore registerUserVoltage5VCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserVoltage5VCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserVoltage5VCallback);
+  }
+  public double getUserVoltage5V() {
+    return RoboRioDataJNI.getUserVoltage5V(m_index);
+  }
+  public void setUserVoltage5V(double userVoltage5V) {
+    RoboRioDataJNI.setUserVoltage5V(m_index, userVoltage5V);
+  }
+
+  public CallbackStore registerUserCurrent5VCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserCurrent5VCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserCurrent5VCallback);
+  }
+  public double getUserCurrent5V() {
+    return RoboRioDataJNI.getUserCurrent5V(m_index);
+  }
+  public void setUserCurrent5V(double userCurrent5V) {
+    RoboRioDataJNI.setUserCurrent5V(m_index, userCurrent5V);
+  }
+
+  public CallbackStore registerUserActive5VCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserActive5VCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserActive5VCallback);
+  }
+  public boolean getUserActive5V() {
+    return RoboRioDataJNI.getUserActive5V(m_index);
+  }
+  public void setUserActive5V(boolean userActive5V) {
+    RoboRioDataJNI.setUserActive5V(m_index, userActive5V);
+  }
+
+  public CallbackStore registerUserVoltage3V3Callback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserVoltage3V3Callback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserVoltage3V3Callback);
+  }
+  public double getUserVoltage3V3() {
+    return RoboRioDataJNI.getUserVoltage3V3(m_index);
+  }
+  public void setUserVoltage3V3(double userVoltage3V3) {
+    RoboRioDataJNI.setUserVoltage3V3(m_index, userVoltage3V3);
+  }
+
+  public CallbackStore registerUserCurrent3V3Callback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserCurrent3V3Callback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserCurrent3V3Callback);
+  }
+  public double getUserCurrent3V3() {
+    return RoboRioDataJNI.getUserCurrent3V3(m_index);
+  }
+  public void setUserCurrent3V3(double userCurrent3V3) {
+    RoboRioDataJNI.setUserCurrent3V3(m_index, userCurrent3V3);
+  }
+
+  public CallbackStore registerUserActive3V3Callback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserActive3V3Callback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserActive3V3Callback);
+  }
+  public boolean getUserActive3V3() {
+    return RoboRioDataJNI.getUserActive3V3(m_index);
+  }
+  public void setUserActive3V3(boolean userActive3V3) {
+    RoboRioDataJNI.setUserActive3V3(m_index, userActive3V3);
+  }
+
+  public CallbackStore registerUserFaults6VCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserFaults6VCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserFaults6VCallback);
+  }
+  public int getUserFaults6V() {
+    return RoboRioDataJNI.getUserFaults6V(m_index);
+  }
+  public void setUserFaults6V(int userFaults6V) {
+    RoboRioDataJNI.setUserFaults6V(m_index, userFaults6V);
+  }
+
+  public CallbackStore registerUserFaults5VCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserFaults5VCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserFaults5VCallback);
+  }
+  public int getUserFaults5V() {
+    return RoboRioDataJNI.getUserFaults5V(m_index);
+  }
+  public void setUserFaults5V(int userFaults5V) {
+    RoboRioDataJNI.setUserFaults5V(m_index, userFaults5V);
+  }
+
+  public CallbackStore registerUserFaults3V3Callback(NotifyCallback callback, boolean initialNotify) {
+    int uid = RoboRioDataJNI.registerUserFaults3V3Callback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, RoboRioDataJNI::cancelUserFaults3V3Callback);
+  }
+  public int getUserFaults3V3() {
+    return RoboRioDataJNI.getUserFaults3V3(m_index);
+  }
+  public void setUserFaults3V3(int userFaults3V3) {
+    RoboRioDataJNI.setUserFaults3V3(m_index, userFaults3V3);
+  }
+
+  public void resetData() {
+    RoboRioDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SPIAccelerometerSim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SPIAccelerometerSim.java
new file mode 100644
index 0000000..94577bd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SPIAccelerometerSim.java
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.SPIAccelerometerDataJNI;
+
+public class SPIAccelerometerSim {
+  private final int m_index;
+
+  public SPIAccelerometerSim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerActiveCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = SPIAccelerometerDataJNI.registerActiveCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, SPIAccelerometerDataJNI::cancelActiveCallback);
+  }
+  public boolean getActive() {
+    return SPIAccelerometerDataJNI.getActive(m_index);
+  }
+  public void setActive(boolean active) {
+    SPIAccelerometerDataJNI.setActive(m_index, active);
+  }
+
+  public CallbackStore registerRangeCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = SPIAccelerometerDataJNI.registerRangeCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, SPIAccelerometerDataJNI::cancelRangeCallback);
+  }
+  public int getRange() {
+    return SPIAccelerometerDataJNI.getRange(m_index);
+  }
+  public void setRange(int range) {
+    SPIAccelerometerDataJNI.setRange(m_index, range);
+  }
+
+  public CallbackStore registerXCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = SPIAccelerometerDataJNI.registerXCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, SPIAccelerometerDataJNI::cancelXCallback);
+  }
+  public double getX() {
+    return SPIAccelerometerDataJNI.getX(m_index);
+  }
+  public void setX(double x) {
+    SPIAccelerometerDataJNI.setX(m_index, x);
+  }
+
+  public CallbackStore registerYCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = SPIAccelerometerDataJNI.registerYCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, SPIAccelerometerDataJNI::cancelYCallback);
+  }
+  public double getY() {
+    return SPIAccelerometerDataJNI.getY(m_index);
+  }
+  public void setY(double y) {
+    SPIAccelerometerDataJNI.setY(m_index, y);
+  }
+
+  public CallbackStore registerZCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = SPIAccelerometerDataJNI.registerZCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, SPIAccelerometerDataJNI::cancelZCallback);
+  }
+  public double getZ() {
+    return SPIAccelerometerDataJNI.getZ(m_index);
+  }
+  public void setZ(double z) {
+    SPIAccelerometerDataJNI.setZ(m_index, z);
+  }
+
+  public void resetData() {
+    SPIAccelerometerDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SPISim.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SPISim.java
new file mode 100644
index 0000000..5f43bca
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SPISim.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.SPIDataJNI;
+
+public class SPISim {
+  private final int m_index;
+
+  public SPISim(int index) {
+    m_index = index;
+  }
+
+  public CallbackStore registerInitializedCallback(NotifyCallback callback, boolean initialNotify) {
+    int uid = SPIDataJNI.registerInitializedCallback(m_index, callback, initialNotify);
+    return new CallbackStore(m_index, uid, SPIDataJNI::cancelInitializedCallback);
+  }
+  public boolean getInitialized() {
+    return SPIDataJNI.getInitialized(m_index);
+  }
+  public void setInitialized(boolean initialized) {
+    SPIDataJNI.setInitialized(m_index, initialized);
+  }
+
+  public CallbackStore registerReadCallback(BufferCallback callback) {
+    int uid = SPIDataJNI.registerReadCallback(m_index, callback);
+    return new CallbackStore(m_index, uid, SPIDataJNI::cancelReadCallback);
+  }
+
+  public CallbackStore registerWriteCallback(ConstBufferCallback callback) {
+    int uid = SPIDataJNI.registerWriteCallback(m_index, callback);
+    return new CallbackStore(m_index, uid, SPIDataJNI::cancelWriteCallback);
+  }
+
+  public CallbackStore registerReadAutoReceiveBufferCallback(SpiReadAutoReceiveBufferCallback callback) {
+    int uid = SPIDataJNI.registerReadAutoReceiveBufferCallback(m_index, callback);
+    return new CallbackStore(m_index, uid, SPIDataJNI::cancelReadAutoReceiveBufferCallback);
+  }
+
+  public void resetData() {
+    SPIDataJNI.resetData(m_index);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SimHooks.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SimHooks.java
new file mode 100644
index 0000000..6c46111
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SimHooks.java
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import edu.wpi.first.hal.sim.mockdata.SimulatorJNI;
+
+public final class SimHooks {
+  private SimHooks() {
+  }
+
+  public static void waitForProgramStart() {
+    SimulatorJNI.waitForProgramStart();
+  }
+
+  public static void setProgramStarted() {
+    SimulatorJNI.setProgramStarted();
+  }
+
+  public static void restartTiming() {
+    SimulatorJNI.restartTiming();
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SimValue.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SimValue.java
new file mode 100644
index 0000000..3dbb7c9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SimValue.java
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+public final class SimValue {
+  private boolean m_boolean;
+  private long m_long;
+  private double m_double;
+
+  private SimValue(boolean b) {
+    m_boolean = b;
+  }
+
+  private SimValue(double v) {
+    m_double = v;
+  }
+
+  private SimValue(long v) {
+    m_long = v;
+  }
+
+  private SimValue() {
+
+  }
+
+  public boolean getBoolean() {
+    return m_boolean;
+  }
+
+  public long getLong() {
+    return m_long;
+  }
+
+  public double getDouble() {
+    return m_double;
+  }
+
+  public static SimValue makeBoolean(boolean value) {
+    return new SimValue(value);
+  }
+
+  public static SimValue makeEnum(int value) {
+    return new SimValue(value);
+  }
+
+  public static SimValue makeInt(int value) {
+    return new SimValue(value);
+  }
+
+  public static SimValue makeLong(long value) {
+    return new SimValue(value);
+  }
+
+  public static SimValue makeDouble(double value) {
+    return new SimValue(value);
+  }
+
+  public static SimValue makeUnassigned() {
+    return new SimValue();
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SpiReadAutoReceiveBufferCallback.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SpiReadAutoReceiveBufferCallback.java
new file mode 100644
index 0000000..5083fab
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/SpiReadAutoReceiveBufferCallback.java
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+public interface SpiReadAutoReceiveBufferCallback {
+  int callback(String name, int[] buffer, int numToRead);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AccelerometerDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AccelerometerDataJNI.java
new file mode 100644
index 0000000..22276d4
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AccelerometerDataJNI.java
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class AccelerometerDataJNI extends JNIWrapper {
+  public static native int registerActiveCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelActiveCallback(int index, int uid);
+  public static native boolean getActive(int index);
+  public static native void setActive(int index, boolean active);
+
+  public static native int registerRangeCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelRangeCallback(int index, int uid);
+  public static native int getRange(int index);
+  public static native void setRange(int index, int range);
+
+  public static native int registerXCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelXCallback(int index, int uid);
+  public static native double getX(int index);
+  public static native void setX(int index, double x);
+
+  public static native int registerYCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelYCallback(int index, int uid);
+  public static native double getY(int index);
+  public static native void setY(int index, double y);
+
+  public static native int registerZCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelZCallback(int index, int uid);
+  public static native double getZ(int index);
+  public static native void setZ(int index, double z);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogGyroDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogGyroDataJNI.java
new file mode 100644
index 0000000..4995df2
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogGyroDataJNI.java
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class AnalogGyroDataJNI extends JNIWrapper {
+  public static native int registerAngleCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelAngleCallback(int index, int uid);
+  public static native double getAngle(int index);
+  public static native void setAngle(int index, double angle);
+
+  public static native int registerRateCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelRateCallback(int index, int uid);
+  public static native double getRate(int index);
+  public static native void setRate(int index, double rate);
+
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogInDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogInDataJNI.java
new file mode 100644
index 0000000..ed4fbac
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogInDataJNI.java
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class AnalogInDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerAverageBitsCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelAverageBitsCallback(int index, int uid);
+  public static native int getAverageBits(int index);
+  public static native void setAverageBits(int index, int averageBits);
+
+  public static native int registerOversampleBitsCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelOversampleBitsCallback(int index, int uid);
+  public static native int getOversampleBits(int index);
+  public static native void setOversampleBits(int index, int oversampleBits);
+
+  public static native int registerVoltageCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelVoltageCallback(int index, int uid);
+  public static native double getVoltage(int index);
+  public static native void setVoltage(int index, double voltage);
+
+  public static native int registerAccumulatorInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelAccumulatorInitializedCallback(int index, int uid);
+  public static native boolean getAccumulatorInitialized(int index);
+  public static native void setAccumulatorInitialized(int index, boolean accumulatorInitialized);
+
+  public static native int registerAccumulatorValueCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelAccumulatorValueCallback(int index, int uid);
+  public static native long getAccumulatorValue(int index);
+  public static native void setAccumulatorValue(int index, long accumulatorValue);
+
+  public static native int registerAccumulatorCountCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelAccumulatorCountCallback(int index, int uid);
+  public static native long getAccumulatorCount(int index);
+  public static native void setAccumulatorCount(int index, long accumulatorCount);
+
+  public static native int registerAccumulatorCenterCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelAccumulatorCenterCallback(int index, int uid);
+  public static native int getAccumulatorCenter(int index);
+  public static native void setAccumulatorCenter(int index, int AccumulatorCenter);
+
+  public static native int registerAccumulatorDeadbandCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelAccumulatorDeadbandCallback(int index, int uid);
+  public static native int getAccumulatorDeadband(int index);
+  public static native void setAccumulatorDeadband(int index, int AccumulatorDeadband);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogOutDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogOutDataJNI.java
new file mode 100644
index 0000000..2f7596c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogOutDataJNI.java
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class AnalogOutDataJNI extends JNIWrapper {
+  public static native int registerVoltageCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelVoltageCallback(int index, int uid);
+  public static native double getVoltage(int index);
+  public static native void setVoltage(int index, double voltage);
+
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogTriggerDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogTriggerDataJNI.java
new file mode 100644
index 0000000..cf4187f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/AnalogTriggerDataJNI.java
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class AnalogTriggerDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerTriggerLowerBoundCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelTriggerLowerBoundCallback(int index, int uid);
+  public static native double getTriggerLowerBound(int index);
+  public static native void setTriggerLowerBound(int index, double triggerLowerBound);
+
+  public static native int registerTriggerUpperBoundCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelTriggerUpperBoundCallback(int index, int uid);
+  public static native double getTriggerUpperBound(int index);
+  public static native void setTriggerUpperBound(int index, double triggerUpperBound);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DIODataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DIODataJNI.java
new file mode 100644
index 0000000..55de7de
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DIODataJNI.java
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class DIODataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerValueCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelValueCallback(int index, int uid);
+  public static native boolean getValue(int index);
+  public static native void setValue(int index, boolean value);
+
+  public static native int registerPulseLengthCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelPulseLengthCallback(int index, int uid);
+  public static native double getPulseLength(int index);
+  public static native void setPulseLength(int index, double pulseLength);
+
+  public static native int registerIsInputCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelIsInputCallback(int index, int uid);
+  public static native boolean getIsInput(int index);
+  public static native void setIsInput(int index, boolean isInput);
+
+  public static native int registerFilterIndexCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelFilterIndexCallback(int index, int uid);
+  public static native int getFilterIndex(int index);
+  public static native void setFilterIndex(int index, int filterIndex);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DigitalPWMDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DigitalPWMDataJNI.java
new file mode 100644
index 0000000..69bee07
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DigitalPWMDataJNI.java
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class DigitalPWMDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerDutyCycleCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelDutyCycleCallback(int index, int uid);
+  public static native double getDutyCycle(int index);
+  public static native void setDutyCycle(int index, double dutyCycle);
+
+  public static native int registerPinCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelPinCallback(int index, int uid);
+  public static native int getPin(int index);
+  public static native void setPin(int index, int pin);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DriverStationDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DriverStationDataJNI.java
new file mode 100644
index 0000000..2d41ca7
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/DriverStationDataJNI.java
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.JNIWrapper;
+import edu.wpi.first.hal.sim.NotifyCallback;
+
+public class DriverStationDataJNI extends JNIWrapper {
+  public static native int registerEnabledCallback(NotifyCallback callback, boolean initialNotify);
+  public static native void cancelEnabledCallback(int uid);
+  public static native boolean getEnabled();
+  public static native void setEnabled(boolean enabled);
+
+  public static native int registerAutonomousCallback(NotifyCallback callback, boolean initialNotify);
+  public static native void cancelAutonomousCallback(int uid);
+  public static native boolean getAutonomous();
+  public static native void setAutonomous(boolean autonomous);
+
+  public static native int registerTestCallback(NotifyCallback callback, boolean initialNotify);
+  public static native void cancelTestCallback(int uid);
+  public static native boolean getTest();
+  public static native void setTest(boolean test);
+
+  public static native int registerEStopCallback(NotifyCallback callback, boolean initialNotify);
+  public static native void cancelEStopCallback(int uid);
+  public static native boolean getEStop();
+  public static native void setEStop(boolean eStop);
+
+  public static native int registerFmsAttachedCallback(NotifyCallback callback, boolean initialNotify);
+  public static native void cancelFmsAttachedCallback(int uid);
+  public static native boolean getFmsAttached();
+  public static native void setFmsAttached(boolean fmsAttached);
+
+  public static native int registerDsAttachedCallback(NotifyCallback callback, boolean initialNotify);
+  public static native void cancelDsAttachedCallback(int uid);
+  public static native boolean getDsAttached();
+  public static native void setDsAttached(boolean dsAttached);
+
+  public static native void setJoystickAxes(byte joystickNum, float[] axesArray);
+  public static native void setJoystickPOVs(byte joystickNum, short[] povsArray);
+  public static native void setJoystickButtons(byte joystickNum, int buttons, int count);
+
+  public static native void setMatchInfo(String eventName, String gameSpecificMessage, int matchNumber, int replayNumber, int matchType);
+  public static native void registerAllCallbacks(NotifyCallback callback, boolean initialNotify);
+  public static native void notifyNewData();
+
+  public static native void resetData();
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/EncoderDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/EncoderDataJNI.java
new file mode 100644
index 0000000..17e242e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/EncoderDataJNI.java
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class EncoderDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerCountCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelCountCallback(int index, int uid);
+  public static native int getCount(int index);
+  public static native void setCount(int index, int count);
+
+  public static native int registerPeriodCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelPeriodCallback(int index, int uid);
+  public static native double getPeriod(int index);
+  public static native void setPeriod(int index, double period);
+
+  public static native int registerResetCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelResetCallback(int index, int uid);
+  public static native boolean getReset(int index);
+  public static native void setReset(int index, boolean reset);
+
+  public static native int registerMaxPeriodCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelMaxPeriodCallback(int index, int uid);
+  public static native double getMaxPeriod(int index);
+  public static native void setMaxPeriod(int index, double maxPeriod);
+
+  public static native int registerDirectionCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelDirectionCallback(int index, int uid);
+  public static native boolean getDirection(int index);
+  public static native void setDirection(int index, boolean direction);
+
+  public static native int registerReverseDirectionCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelReverseDirectionCallback(int index, int uid);
+  public static native boolean getReverseDirection(int index);
+  public static native void setReverseDirection(int index, boolean reverseDirection);
+
+  public static native int registerSamplesToAverageCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelSamplesToAverageCallback(int index, int uid);
+  public static native int getSamplesToAverage(int index);
+  public static native void setSamplesToAverage(int index, int samplesToAverage);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/I2CDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/I2CDataJNI.java
new file mode 100644
index 0000000..33d78f8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/I2CDataJNI.java
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.BufferCallback;
+import edu.wpi.first.hal.sim.ConstBufferCallback;
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class I2CDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerReadCallback(int index, BufferCallback callback);
+  public static native void cancelReadCallback(int index, int uid);
+
+  public static native int registerWriteCallback(int index, ConstBufferCallback callback);
+  public static native void cancelWriteCallback(int index, int uid);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PCMDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PCMDataJNI.java
new file mode 100644
index 0000000..c5de287
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PCMDataJNI.java
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class PCMDataJNI extends JNIWrapper {
+  public static native int registerSolenoidInitializedCallback(int index, int channel, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelSolenoidInitializedCallback(int index, int channel, int uid);
+  public static native boolean getSolenoidInitialized(int index, int channel);
+  public static native void setSolenoidInitialized(int index, int channel, boolean solenoidInitialized);
+
+  public static native int registerSolenoidOutputCallback(int index, int channel, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelSolenoidOutputCallback(int index, int channel, int uid);
+  public static native boolean getSolenoidOutput(int index, int channel);
+  public static native void setSolenoidOutput(int index, int channel, boolean solenoidOutput);
+
+  public static native int registerCompressorInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelCompressorInitializedCallback(int index, int uid);
+  public static native boolean getCompressorInitialized(int index);
+  public static native void setCompressorInitialized(int index, boolean compressorInitialized);
+
+  public static native int registerCompressorOnCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelCompressorOnCallback(int index, int uid);
+  public static native boolean getCompressorOn(int index);
+  public static native void setCompressorOn(int index, boolean compressorOn);
+
+  public static native int registerClosedLoopEnabledCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelClosedLoopEnabledCallback(int index, int uid);
+  public static native boolean getClosedLoopEnabled(int index);
+  public static native void setClosedLoopEnabled(int index, boolean closeLoopEnabled);
+
+  public static native int registerPressureSwitchCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelPressureSwitchCallback(int index, int uid);
+  public static native boolean getPressureSwitch(int index);
+  public static native void setPressureSwitch(int index, boolean pressureSwitch);
+
+  public static native int registerCompressorCurrentCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelCompressorCurrentCallback(int index, int uid);
+  public static native double getCompressorCurrent(int index);
+  public static native void setCompressorCurrent(int index, double compressorCurrent);
+
+  public static native void registerAllNonSolenoidCallbacks(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void registerAllSolenoidCallbacks(int index, int channel, NotifyCallback callback, boolean initialNotify);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PDPDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PDPDataJNI.java
new file mode 100644
index 0000000..581a727
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PDPDataJNI.java
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class PDPDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerTemperatureCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelTemperatureCallback(int index, int uid);
+  public static native double getTemperature(int index);
+  public static native void setTemperature(int index, double temperature);
+
+  public static native int registerVoltageCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelVoltageCallback(int index, int uid);
+  public static native double getVoltage(int index);
+  public static native void setVoltage(int index, double voltage);
+
+
+  public static native int registerCurrentCallback(int index, int channel, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelCurrentCallback(int index, int channel, int uid);
+  public static native double getCurrent(int index, int channel);
+  public static native void setCurrent(int index, int channel, double current);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PWMDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PWMDataJNI.java
new file mode 100644
index 0000000..e36990e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/PWMDataJNI.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class PWMDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerRawValueCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelRawValueCallback(int index, int uid);
+  public static native int getRawValue(int index);
+  public static native void setRawValue(int index, int rawValue);
+
+  public static native int registerSpeedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelSpeedCallback(int index, int uid);
+  public static native double getSpeed(int index);
+  public static native void setSpeed(int index, double speed);
+
+  public static native int registerPositionCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelPositionCallback(int index, int uid);
+  public static native double getPosition(int index);
+  public static native void setPosition(int index, double position);
+
+  public static native int registerPeriodScaleCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelPeriodScaleCallback(int index, int uid);
+  public static native int getPeriodScale(int index);
+  public static native void setPeriodScale(int index, int periodScale);
+
+  public static native int registerZeroLatchCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelZeroLatchCallback(int index, int uid);
+  public static native boolean getZeroLatch(int index);
+  public static native void setZeroLatch(int index, boolean zeroLatch);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/RelayDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/RelayDataJNI.java
new file mode 100644
index 0000000..320a86d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/RelayDataJNI.java
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class RelayDataJNI extends JNIWrapper {
+  public static native int registerInitializedForwardCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedForwardCallback(int index, int uid);
+  public static native boolean getInitializedForward(int index);
+  public static native void setInitializedForward(int index, boolean initializedForward);
+
+  public static native int registerInitializedReverseCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedReverseCallback(int index, int uid);
+  public static native boolean getInitializedReverse(int index);
+  public static native void setInitializedReverse(int index, boolean initializedReverse);
+
+  public static native int registerForwardCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelForwardCallback(int index, int uid);
+  public static native boolean getForward(int index);
+  public static native void setForward(int index, boolean forward);
+
+  public static native int registerReverseCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelReverseCallback(int index, int uid);
+  public static native boolean getReverse(int index);
+  public static native void setReverse(int index, boolean reverse);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/RoboRioDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/RoboRioDataJNI.java
new file mode 100644
index 0000000..a13845c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/RoboRioDataJNI.java
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class RoboRioDataJNI extends JNIWrapper {
+  public static native int registerFPGAButtonCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelFPGAButtonCallback(int index, int uid);
+  public static native boolean getFPGAButton(int index);
+  public static native void setFPGAButton(int index, boolean fPGAButton);
+
+  public static native int registerVInVoltageCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelVInVoltageCallback(int index, int uid);
+  public static native double getVInVoltage(int index);
+  public static native void setVInVoltage(int index, double vInVoltage);
+
+  public static native int registerVInCurrentCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelVInCurrentCallback(int index, int uid);
+  public static native double getVInCurrent(int index);
+  public static native void setVInCurrent(int index, double vInCurrent);
+
+  public static native int registerUserVoltage6VCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserVoltage6VCallback(int index, int uid);
+  public static native double getUserVoltage6V(int index);
+  public static native void setUserVoltage6V(int index, double userVoltage6V);
+
+  public static native int registerUserCurrent6VCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserCurrent6VCallback(int index, int uid);
+  public static native double getUserCurrent6V(int index);
+  public static native void setUserCurrent6V(int index, double userCurrent6V);
+
+  public static native int registerUserActive6VCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserActive6VCallback(int index, int uid);
+  public static native boolean getUserActive6V(int index);
+  public static native void setUserActive6V(int index, boolean userActive6V);
+
+  public static native int registerUserVoltage5VCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserVoltage5VCallback(int index, int uid);
+  public static native double getUserVoltage5V(int index);
+  public static native void setUserVoltage5V(int index, double userVoltage5V);
+
+  public static native int registerUserCurrent5VCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserCurrent5VCallback(int index, int uid);
+  public static native double getUserCurrent5V(int index);
+  public static native void setUserCurrent5V(int index, double userCurrent5V);
+
+  public static native int registerUserActive5VCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserActive5VCallback(int index, int uid);
+  public static native boolean getUserActive5V(int index);
+  public static native void setUserActive5V(int index, boolean userActive5V);
+
+  public static native int registerUserVoltage3V3Callback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserVoltage3V3Callback(int index, int uid);
+  public static native double getUserVoltage3V3(int index);
+  public static native void setUserVoltage3V3(int index, double userVoltage3V3);
+
+  public static native int registerUserCurrent3V3Callback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserCurrent3V3Callback(int index, int uid);
+  public static native double getUserCurrent3V3(int index);
+  public static native void setUserCurrent3V3(int index, double userCurrent3V3);
+
+  public static native int registerUserActive3V3Callback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserActive3V3Callback(int index, int uid);
+  public static native boolean getUserActive3V3(int index);
+  public static native void setUserActive3V3(int index, boolean userActive3V3);
+
+  public static native int registerUserFaults6VCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserFaults6VCallback(int index, int uid);
+  public static native int getUserFaults6V(int index);
+  public static native void setUserFaults6V(int index, int userFaults6V);
+
+  public static native int registerUserFaults5VCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserFaults5VCallback(int index, int uid);
+  public static native int getUserFaults5V(int index);
+  public static native void setUserFaults5V(int index, int userFaults5V);
+
+  public static native int registerUserFaults3V3Callback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelUserFaults3V3Callback(int index, int uid);
+  public static native int getUserFaults3V3(int index);
+  public static native void setUserFaults3V3(int index, int userFaults3V3);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SPIAccelerometerDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SPIAccelerometerDataJNI.java
new file mode 100644
index 0000000..d8e7353
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SPIAccelerometerDataJNI.java
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class SPIAccelerometerDataJNI extends JNIWrapper {
+  public static native int registerActiveCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelActiveCallback(int index, int uid);
+  public static native boolean getActive(int index);
+  public static native void setActive(int index, boolean active);
+
+  public static native int registerRangeCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelRangeCallback(int index, int uid);
+  public static native int getRange(int index);
+  public static native void setRange(int index, int range);
+
+  public static native int registerXCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelXCallback(int index, int uid);
+  public static native double getX(int index);
+  public static native void setX(int index, double x);
+
+  public static native int registerYCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelYCallback(int index, int uid);
+  public static native double getY(int index);
+  public static native void setY(int index, double y);
+
+  public static native int registerZCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelZCallback(int index, int uid);
+  public static native double getZ(int index);
+  public static native void setZ(int index, double z);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SPIDataJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SPIDataJNI.java
new file mode 100644
index 0000000..a12ec66
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SPIDataJNI.java
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.sim.BufferCallback;
+import edu.wpi.first.hal.sim.ConstBufferCallback;
+import edu.wpi.first.hal.sim.NotifyCallback;
+import edu.wpi.first.hal.sim.SpiReadAutoReceiveBufferCallback;
+import edu.wpi.first.hal.JNIWrapper;
+
+public class SPIDataJNI extends JNIWrapper {
+  public static native int registerInitializedCallback(int index, NotifyCallback callback, boolean initialNotify);
+  public static native void cancelInitializedCallback(int index, int uid);
+  public static native boolean getInitialized(int index);
+  public static native void setInitialized(int index, boolean initialized);
+
+  public static native int registerReadCallback(int index, BufferCallback callback);
+  public static native void cancelReadCallback(int index, int uid);
+
+  public static native int registerWriteCallback(int index, ConstBufferCallback callback);
+  public static native void cancelWriteCallback(int index, int uid);
+
+  public static native int registerReadAutoReceiveBufferCallback(int index, SpiReadAutoReceiveBufferCallback callback);
+  public static native void cancelReadAutoReceiveBufferCallback(int index, int uid);
+
+  public static native void resetData(int index);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SimulatorJNI.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SimulatorJNI.java
new file mode 100644
index 0000000..bb86005
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/sim/mockdata/SimulatorJNI.java
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim.mockdata;
+
+import edu.wpi.first.hal.JNIWrapper;
+
+public class SimulatorJNI extends JNIWrapper {
+  public static native void waitForProgramStart();
+  public static native void setProgramStarted();
+  public static native void restartTiming();
+  public static native void resetHandles();
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/AllocationException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/AllocationException.java
new file mode 100644
index 0000000..6f789d8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/AllocationException.java
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.util;
+
+/**
+ * Exception indicating that the resource is already allocated.
+ */
+public class AllocationException extends RuntimeException {
+  /**
+   * Create a new AllocationException.
+   *
+   * @param msg the message to attach to the exception
+   */
+  public AllocationException(String msg) {
+    super(msg);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/BoundaryException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/BoundaryException.java
new file mode 100644
index 0000000..8f21e60
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/BoundaryException.java
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.util;
+
+/**
+ * This exception represents an error in which a lower limit was set as higher than an upper limit.
+ */
+public class BoundaryException extends RuntimeException {
+  /**
+   * Create a new exception with the given message.
+   *
+   * @param message the message to attach to the exception
+   */
+  public BoundaryException(String message) {
+    super(message);
+  }
+
+  /**
+   * Make sure that the given value is between the upper and lower bounds, and throw an exception if
+   * they are not.
+   *
+   * @param value The value to check.
+   * @param lower The minimum acceptable value.
+   * @param upper The maximum acceptable value.
+   */
+  public static void assertWithinBounds(double value, double lower, double upper) {
+    if (value < lower || value > upper) {
+      throw new BoundaryException("Value must be between " + lower + " and " + upper + ", " + value
+          + " given");
+    }
+  }
+
+  /**
+   * Returns the message for a boundary exception. Used to keep the message consistent across all
+   * boundary exceptions.
+   *
+   * @param value The given value
+   * @param lower The lower limit
+   * @param upper The upper limit
+   * @return the message for a boundary exception
+   */
+  public static String getMessage(double value, double lower, double upper) {
+    return "Value must be between " + lower + " and " + upper + ", " + value + " given";
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/CheckedAllocationException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/CheckedAllocationException.java
new file mode 100644
index 0000000..f17e381
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/CheckedAllocationException.java
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.util;
+
+/**
+ * Exception indicating that the resource is already allocated This is meant to be thrown by the
+ * resource class.
+ */
+public class CheckedAllocationException extends Exception {
+  /**
+   * Create a new CheckedAllocationException.
+   *
+   * @param msg the message to attach to the exception
+   */
+  public CheckedAllocationException(String msg) {
+    super(msg);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/HalHandleException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/HalHandleException.java
new file mode 100644
index 0000000..874b07a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/HalHandleException.java
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.util;
+
+/**
+ * Exception indicating that an error has occured with a HAL Handle.
+ */
+public class HalHandleException extends RuntimeException {
+  /**
+   * Create a new HalHandleException.
+   *
+   * @param msg the message to attach to the exception
+   */
+  public HalHandleException(String msg) {
+    super(msg);
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/UncleanStatusException.java b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/UncleanStatusException.java
new file mode 100644
index 0000000..3a3e217
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/java/edu/wpi/first/hal/util/UncleanStatusException.java
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.util;
+
+/**
+ * Exception for bad status codes from the chip object.
+ */
+public final class UncleanStatusException extends IllegalStateException {
+  private final int m_statusCode;
+
+  /**
+   * Create a new UncleanStatusException.
+   *
+   * @param status  the status code that caused the exception
+   * @param message A message describing the exception
+   */
+  public UncleanStatusException(int status, String message) {
+    super(message);
+    m_statusCode = status;
+  }
+
+  /**
+   * Create a new UncleanStatusException.
+   *
+   * @param status the status code that caused the exception
+   */
+  public UncleanStatusException(int status) {
+    this(status, "Status code was non-zero");
+  }
+
+  /**
+   * Create a new UncleanStatusException.
+   *
+   * @param message a message describing the exception
+   */
+  public UncleanStatusException(String message) {
+    this(-1, message);
+  }
+
+  /**
+   * Create a new UncleanStatusException.
+   */
+  public UncleanStatusException() {
+    this(-1, "Status code was non-zero");
+  }
+
+  /**
+   * Create a new UncleanStatusException.
+   *
+   * @return the status code that caused the exception
+   */
+  public int getStatus() {
+    return m_statusCode;
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Accelerometer.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Accelerometer.cpp
new file mode 100644
index 0000000..f83c06e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Accelerometer.cpp
@@ -0,0 +1,243 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Accelerometer.h"
+
+#include <stdint.h>
+
+#include <cassert>
+#include <cstdio>
+#include <memory>
+
+#include "HALInitializer.h"
+#include "hal/ChipObject.h"
+#include "hal/HAL.h"
+
+using namespace hal;
+
+// The 7-bit I2C address with a 0 "send" bit
+static constexpr uint8_t kSendAddress = (0x1c << 1) | 0;
+
+// The 7-bit I2C address with a 1 "receive" bit
+static constexpr uint8_t kReceiveAddress = (0x1c << 1) | 1;
+
+static constexpr uint8_t kControlTxRx = 1;
+static constexpr uint8_t kControlStart = 2;
+static constexpr uint8_t kControlStop = 4;
+
+static std::unique_ptr<tAccel> accel;
+static HAL_AccelerometerRange accelerometerRange;
+
+// Register addresses
+enum Register {
+  kReg_Status = 0x00,
+  kReg_OutXMSB = 0x01,
+  kReg_OutXLSB = 0x02,
+  kReg_OutYMSB = 0x03,
+  kReg_OutYLSB = 0x04,
+  kReg_OutZMSB = 0x05,
+  kReg_OutZLSB = 0x06,
+  kReg_Sysmod = 0x0B,
+  kReg_IntSource = 0x0C,
+  kReg_WhoAmI = 0x0D,
+  kReg_XYZDataCfg = 0x0E,
+  kReg_HPFilterCutoff = 0x0F,
+  kReg_PLStatus = 0x10,
+  kReg_PLCfg = 0x11,
+  kReg_PLCount = 0x12,
+  kReg_PLBfZcomp = 0x13,
+  kReg_PLThsReg = 0x14,
+  kReg_FFMtCfg = 0x15,
+  kReg_FFMtSrc = 0x16,
+  kReg_FFMtThs = 0x17,
+  kReg_FFMtCount = 0x18,
+  kReg_TransientCfg = 0x1D,
+  kReg_TransientSrc = 0x1E,
+  kReg_TransientThs = 0x1F,
+  kReg_TransientCount = 0x20,
+  kReg_PulseCfg = 0x21,
+  kReg_PulseSrc = 0x22,
+  kReg_PulseThsx = 0x23,
+  kReg_PulseThsy = 0x24,
+  kReg_PulseThsz = 0x25,
+  kReg_PulseTmlt = 0x26,
+  kReg_PulseLtcy = 0x27,
+  kReg_PulseWind = 0x28,
+  kReg_ASlpCount = 0x29,
+  kReg_CtrlReg1 = 0x2A,
+  kReg_CtrlReg2 = 0x2B,
+  kReg_CtrlReg3 = 0x2C,
+  kReg_CtrlReg4 = 0x2D,
+  kReg_CtrlReg5 = 0x2E,
+  kReg_OffX = 0x2F,
+  kReg_OffY = 0x30,
+  kReg_OffZ = 0x31
+};
+
+namespace hal {
+namespace init {
+void InitializeAccelerometer() {}
+}  // namespace init
+}  // namespace hal
+
+namespace hal {
+
+static void writeRegister(Register reg, uint8_t data);
+static uint8_t readRegister(Register reg);
+
+/**
+ * Initialize the accelerometer.
+ */
+static void initializeAccelerometer() {
+  hal::init::CheckInit();
+  int32_t status;
+
+  if (!accel) {
+    accel.reset(tAccel::create(&status));
+
+    accelerometerRange = HAL_AccelerometerRange::HAL_AccelerometerRange_k2G;
+
+    // Enable I2C
+    accel->writeCNFG(1, &status);
+
+    // Set the counter to 100 kbps
+    accel->writeCNTR(213, &status);
+
+    // The device identification number should be 0x2a
+    assert(readRegister(kReg_WhoAmI) == 0x2a);
+  }
+}
+
+static void writeRegister(Register reg, uint8_t data) {
+  int32_t status = 0;
+  uint64_t initialTime;
+
+  accel->writeADDR(kSendAddress, &status);
+
+  // Send a start transmit/receive message with the register address
+  accel->writeCNTL(kControlStart | kControlTxRx, &status);
+  accel->writeDATO(reg, &status);
+  accel->strobeGO(&status);
+
+  // Execute and wait until it's done (up to a millisecond)
+  initialTime = HAL_GetFPGATime(&status);
+  while (accel->readSTAT(&status) & 1) {
+    if (HAL_GetFPGATime(&status) > initialTime + 1000) break;
+  }
+
+  // Send a stop transmit/receive message with the data
+  accel->writeCNTL(kControlStop | kControlTxRx, &status);
+  accel->writeDATO(data, &status);
+  accel->strobeGO(&status);
+
+  // Execute and wait until it's done (up to a millisecond)
+  initialTime = HAL_GetFPGATime(&status);
+  while (accel->readSTAT(&status) & 1) {
+    if (HAL_GetFPGATime(&status) > initialTime + 1000) break;
+  }
+}
+
+static uint8_t readRegister(Register reg) {
+  int32_t status = 0;
+  uint64_t initialTime;
+
+  // Send a start transmit/receive message with the register address
+  accel->writeADDR(kSendAddress, &status);
+  accel->writeCNTL(kControlStart | kControlTxRx, &status);
+  accel->writeDATO(reg, &status);
+  accel->strobeGO(&status);
+
+  // Execute and wait until it's done (up to a millisecond)
+  initialTime = HAL_GetFPGATime(&status);
+  while (accel->readSTAT(&status) & 1) {
+    if (HAL_GetFPGATime(&status) > initialTime + 1000) break;
+  }
+
+  // Receive a message with the data and stop
+  accel->writeADDR(kReceiveAddress, &status);
+  accel->writeCNTL(kControlStart | kControlStop | kControlTxRx, &status);
+  accel->strobeGO(&status);
+
+  // Execute and wait until it's done (up to a millisecond)
+  initialTime = HAL_GetFPGATime(&status);
+  while (accel->readSTAT(&status) & 1) {
+    if (HAL_GetFPGATime(&status) > initialTime + 1000) break;
+  }
+
+  return accel->readDATI(&status);
+}
+
+/**
+ * Convert a 12-bit raw acceleration value into a scaled double in units of
+ * 1 g-force, taking into account the accelerometer range.
+ */
+static double unpackAxis(int16_t raw) {
+  // The raw value is actually 12 bits, not 16, so we need to propogate the
+  // 2's complement sign bit to the unused 4 bits for this to work with
+  // negative numbers.
+  raw <<= 4;
+  raw >>= 4;
+
+  switch (accelerometerRange) {
+    case HAL_AccelerometerRange_k2G:
+      return raw / 1024.0;
+    case HAL_AccelerometerRange_k4G:
+      return raw / 512.0;
+    case HAL_AccelerometerRange_k8G:
+      return raw / 256.0;
+    default:
+      return 0.0;
+  }
+}
+
+}  // namespace hal
+
+extern "C" {
+
+void HAL_SetAccelerometerActive(HAL_Bool active) {
+  initializeAccelerometer();
+
+  uint8_t ctrlReg1 = readRegister(kReg_CtrlReg1);
+  ctrlReg1 &= ~1;  // Clear the existing active bit
+  writeRegister(kReg_CtrlReg1, ctrlReg1 | (active ? 1 : 0));
+}
+
+void HAL_SetAccelerometerRange(HAL_AccelerometerRange range) {
+  initializeAccelerometer();
+
+  accelerometerRange = range;
+
+  uint8_t xyzDataCfg = readRegister(kReg_XYZDataCfg);
+  xyzDataCfg &= ~3;  // Clear the existing two range bits
+  writeRegister(kReg_XYZDataCfg, xyzDataCfg | range);
+}
+
+double HAL_GetAccelerometerX(void) {
+  initializeAccelerometer();
+
+  int32_t raw =
+      (readRegister(kReg_OutXMSB) << 4) | (readRegister(kReg_OutXLSB) >> 4);
+  return unpackAxis(raw);
+}
+
+double HAL_GetAccelerometerY(void) {
+  initializeAccelerometer();
+
+  int32_t raw =
+      (readRegister(kReg_OutYMSB) << 4) | (readRegister(kReg_OutYLSB) >> 4);
+  return unpackAxis(raw);
+}
+
+double HAL_GetAccelerometerZ(void) {
+  initializeAccelerometer();
+
+  int32_t raw =
+      (readRegister(kReg_OutZMSB) << 4) | (readRegister(kReg_OutZLSB) >> 4);
+  return unpackAxis(raw);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogAccumulator.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogAccumulator.cpp
new file mode 100644
index 0000000..6664c52
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogAccumulator.cpp
@@ -0,0 +1,139 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/AnalogAccumulator.h"
+
+#include "AnalogInternal.h"
+#include "hal/HAL.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAnalogAccumulator() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_Bool HAL_IsAccumulatorChannel(HAL_AnalogInputHandle analogPortHandle,
+                                  int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  for (int32_t i = 0; i < kNumAccumulators; i++) {
+    if (port->channel == kAccumulatorChannels[i]) return true;
+  }
+  return false;
+}
+
+void HAL_InitAccumulator(HAL_AnalogInputHandle analogPortHandle,
+                         int32_t* status) {
+  if (!HAL_IsAccumulatorChannel(analogPortHandle, status)) {
+    *status = HAL_INVALID_ACCUMULATOR_CHANNEL;
+    return;
+  }
+  HAL_SetAccumulatorCenter(analogPortHandle, 0, status);
+  HAL_ResetAccumulator(analogPortHandle, status);
+}
+
+void HAL_ResetAccumulator(HAL_AnalogInputHandle analogPortHandle,
+                          int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (port->accumulator == nullptr) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+  port->accumulator->strobeReset(status);
+}
+
+void HAL_SetAccumulatorCenter(HAL_AnalogInputHandle analogPortHandle,
+                              int32_t center, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (port->accumulator == nullptr) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+  port->accumulator->writeCenter(center, status);
+}
+
+void HAL_SetAccumulatorDeadband(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t deadband, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (port->accumulator == nullptr) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+  port->accumulator->writeDeadband(deadband, status);
+}
+
+int64_t HAL_GetAccumulatorValue(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  if (port->accumulator == nullptr) {
+    *status = NULL_PARAMETER;
+    return 0;
+  }
+  int64_t value = port->accumulator->readOutput_Value(status);
+  return value;
+}
+
+int64_t HAL_GetAccumulatorCount(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  if (port->accumulator == nullptr) {
+    *status = NULL_PARAMETER;
+    return 0;
+  }
+  return port->accumulator->readOutput_Count(status);
+}
+
+void HAL_GetAccumulatorOutput(HAL_AnalogInputHandle analogPortHandle,
+                              int64_t* value, int64_t* count, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (port->accumulator == nullptr) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+  if (value == nullptr || count == nullptr) {
+    *status = NULL_PARAMETER;
+    return;
+  }
+
+  tAccumulator::tOutput output = port->accumulator->readOutput(status);
+
+  *value = output.Value;
+  *count = output.Count;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogGyro.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogGyro.cpp
new file mode 100644
index 0000000..56b6f28
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogGyro.cpp
@@ -0,0 +1,261 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/AnalogGyro.h"
+
+#include <thread>
+
+#include <wpi/raw_ostream.h>
+
+#include "AnalogInternal.h"
+#include "HALInitializer.h"
+#include "hal/AnalogAccumulator.h"
+#include "hal/AnalogInput.h"
+#include "hal/handles/IndexedHandleResource.h"
+
+namespace {
+
+struct AnalogGyro {
+  HAL_AnalogInputHandle handle;
+  double voltsPerDegreePerSecond;
+  double offset;
+  int32_t center;
+};
+
+}  // namespace
+
+static constexpr uint32_t kOversampleBits = 10;
+static constexpr uint32_t kAverageBits = 0;
+static constexpr double kSamplesPerSecond = 50.0;
+static constexpr double kCalibrationSampleTime = 5.0;
+static constexpr double kDefaultVoltsPerDegreePerSecond = 0.007;
+
+using namespace hal;
+
+static IndexedHandleResource<HAL_GyroHandle, AnalogGyro, kNumAccumulators,
+                             HAL_HandleEnum::AnalogGyro>* analogGyroHandles;
+
+namespace hal {
+namespace init {
+void InitializeAnalogGyro() {
+  static IndexedHandleResource<HAL_GyroHandle, AnalogGyro, kNumAccumulators,
+                               HAL_HandleEnum::AnalogGyro>
+      agHandles;
+  analogGyroHandles = &agHandles;
+}
+}  // namespace init
+}  // namespace hal
+
+static void Wait(double seconds) {
+  if (seconds < 0.0) return;
+  std::this_thread::sleep_for(std::chrono::duration<double>(seconds));
+}
+
+extern "C" {
+
+HAL_GyroHandle HAL_InitializeAnalogGyro(HAL_AnalogInputHandle analogHandle,
+                                        int32_t* status) {
+  hal::init::CheckInit();
+  if (!HAL_IsAccumulatorChannel(analogHandle, status)) {
+    if (*status == 0) {
+      *status = HAL_INVALID_ACCUMULATOR_CHANNEL;
+    }
+    return HAL_kInvalidHandle;
+  }
+
+  // handle known to be correct, so no need to type check
+  int16_t channel = getHandleIndex(analogHandle);
+
+  auto handle = analogGyroHandles->Allocate(channel, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  // Initialize port structure
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {  // would only error on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  gyro->handle = analogHandle;
+  gyro->voltsPerDegreePerSecond = 0;
+  gyro->offset = 0;
+  gyro->center = 0;
+
+  return handle;
+}
+
+void HAL_SetupAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  gyro->voltsPerDegreePerSecond = kDefaultVoltsPerDegreePerSecond;
+
+  HAL_SetAnalogAverageBits(gyro->handle, kAverageBits, status);
+  if (*status != 0) return;
+  HAL_SetAnalogOversampleBits(gyro->handle, kOversampleBits, status);
+  if (*status != 0) return;
+  double sampleRate =
+      kSamplesPerSecond * (1 << (kAverageBits + kOversampleBits));
+  HAL_SetAnalogSampleRate(sampleRate, status);
+  if (*status != 0) return;
+  Wait(0.1);
+
+  HAL_SetAnalogGyroDeadband(handle, 0.0, status);
+  if (*status != 0) return;
+}
+
+void HAL_FreeAnalogGyro(HAL_GyroHandle handle) {
+  analogGyroHandles->Free(handle);
+}
+
+void HAL_SetAnalogGyroParameters(HAL_GyroHandle handle,
+                                 double voltsPerDegreePerSecond, double offset,
+                                 int32_t center, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  gyro->voltsPerDegreePerSecond = voltsPerDegreePerSecond;
+  gyro->offset = offset;
+  gyro->center = center;
+  HAL_SetAccumulatorCenter(gyro->handle, center, status);
+}
+
+void HAL_SetAnalogGyroVoltsPerDegreePerSecond(HAL_GyroHandle handle,
+                                              double voltsPerDegreePerSecond,
+                                              int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  gyro->voltsPerDegreePerSecond = voltsPerDegreePerSecond;
+}
+
+void HAL_ResetAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  HAL_ResetAccumulator(gyro->handle, status);
+  if (*status != 0) return;
+
+  const double sampleTime = 1.0 / HAL_GetAnalogSampleRate(status);
+  const double overSamples =
+      1 << HAL_GetAnalogOversampleBits(gyro->handle, status);
+  const double averageSamples =
+      1 << HAL_GetAnalogAverageBits(gyro->handle, status);
+  if (*status != 0) return;
+  Wait(sampleTime * overSamples * averageSamples);
+}
+
+void HAL_CalibrateAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  HAL_InitAccumulator(gyro->handle, status);
+  if (*status != 0) return;
+  wpi::outs() << "Calibrating analog gyro for " << kCalibrationSampleTime
+              << " seconds." << '\n';
+  Wait(kCalibrationSampleTime);
+
+  int64_t value;
+  int64_t count;
+  HAL_GetAccumulatorOutput(gyro->handle, &value, &count, status);
+  if (*status != 0) return;
+
+  gyro->center = static_cast<int32_t>(
+      static_cast<double>(value) / static_cast<double>(count) + .5);
+
+  gyro->offset = static_cast<double>(value) / static_cast<double>(count) -
+                 static_cast<double>(gyro->center);
+  HAL_SetAccumulatorCenter(gyro->handle, gyro->center, status);
+  if (*status != 0) return;
+  HAL_ResetAnalogGyro(handle, status);
+}
+
+void HAL_SetAnalogGyroDeadband(HAL_GyroHandle handle, double volts,
+                               int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  int32_t deadband = static_cast<int32_t>(
+      volts * 1e9 / HAL_GetAnalogLSBWeight(gyro->handle, status) *
+      (1 << HAL_GetAnalogOversampleBits(gyro->handle, status)));
+  if (*status != 0) return;
+  HAL_SetAccumulatorDeadband(gyro->handle, deadband, status);
+}
+
+double HAL_GetAnalogGyroAngle(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  int64_t rawValue = 0;
+  int64_t count = 0;
+  HAL_GetAccumulatorOutput(gyro->handle, &rawValue, &count, status);
+
+  int64_t value = rawValue - static_cast<int64_t>(static_cast<double>(count) *
+                                                  gyro->offset);
+
+  double scaledValue =
+      value * 1e-9 *
+      static_cast<double>(HAL_GetAnalogLSBWeight(gyro->handle, status)) *
+      static_cast<double>(1 << HAL_GetAnalogAverageBits(gyro->handle, status)) /
+      (HAL_GetAnalogSampleRate(status) * gyro->voltsPerDegreePerSecond);
+
+  return scaledValue;
+}
+
+double HAL_GetAnalogGyroRate(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return (HAL_GetAnalogAverageValue(gyro->handle, status) -
+          (static_cast<double>(gyro->center) + gyro->offset)) *
+         1e-9 * HAL_GetAnalogLSBWeight(gyro->handle, status) /
+         ((1 << HAL_GetAnalogOversampleBits(gyro->handle, status)) *
+          gyro->voltsPerDegreePerSecond);
+}
+
+double HAL_GetAnalogGyroOffset(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return gyro->offset;
+}
+
+int32_t HAL_GetAnalogGyroCenter(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return gyro->center;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInput.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInput.cpp
new file mode 100644
index 0000000..b11280d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInput.cpp
@@ -0,0 +1,238 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/AnalogInput.h"
+
+#include <FRC_NetworkCommunication/AICalibration.h>
+#include <wpi/mutex.h>
+
+#include "AnalogInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/AnalogAccumulator.h"
+#include "hal/handles/HandlesInternal.h"
+
+namespace hal {
+namespace init {
+void InitializeAnalogInput() {}
+}  // namespace init
+}  // namespace hal
+
+using namespace hal;
+
+extern "C" {
+
+HAL_AnalogInputHandle HAL_InitializeAnalogInputPort(HAL_PortHandle portHandle,
+                                                    int32_t* status) {
+  hal::init::CheckInit();
+  initializeAnalog(status);
+
+  if (*status != 0) return HAL_kInvalidHandle;
+
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  HAL_AnalogInputHandle handle = analogInputHandles->Allocate(channel, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  // Initialize port structure
+  auto analog_port = analogInputHandles->Get(handle);
+  if (analog_port == nullptr) {  // would only error on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  analog_port->channel = static_cast<uint8_t>(channel);
+  if (HAL_IsAccumulatorChannel(handle, status)) {
+    analog_port->accumulator.reset(tAccumulator::create(channel, status));
+  } else {
+    analog_port->accumulator = nullptr;
+  }
+
+  // Set default configuration
+  analogInputSystem->writeScanList(channel, channel, status);
+  HAL_SetAnalogAverageBits(handle, kDefaultAverageBits, status);
+  HAL_SetAnalogOversampleBits(handle, kDefaultOversampleBits, status);
+  return handle;
+}
+
+void HAL_FreeAnalogInputPort(HAL_AnalogInputHandle analogPortHandle) {
+  // no status, so no need to check for a proper free.
+  analogInputHandles->Free(analogPortHandle);
+}
+
+HAL_Bool HAL_CheckAnalogModule(int32_t module) { return module == 1; }
+
+HAL_Bool HAL_CheckAnalogInputChannel(int32_t channel) {
+  return channel < kNumAnalogInputs && channel >= 0;
+}
+
+void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status) {
+  // TODO: This will change when variable size scan lists are implemented.
+  // TODO: Need double comparison with epsilon.
+  // wpi_assert(!sampleRateSet || GetSampleRate() == samplesPerSecond);
+  initializeAnalog(status);
+  if (*status != 0) return;
+  setAnalogSampleRate(samplesPerSecond, status);
+}
+
+double HAL_GetAnalogSampleRate(int32_t* status) {
+  initializeAnalog(status);
+  if (*status != 0) return 0;
+  uint32_t ticksPerConversion = analogInputSystem->readLoopTiming(status);
+  uint32_t ticksPerSample =
+      ticksPerConversion * getAnalogNumActiveChannels(status);
+  return static_cast<double>(kTimebase) / static_cast<double>(ticksPerSample);
+}
+
+void HAL_SetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
+                              int32_t bits, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  analogInputSystem->writeAverageBits(port->channel, static_cast<uint8_t>(bits),
+                                      status);
+}
+
+int32_t HAL_GetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return kDefaultAverageBits;
+  }
+  uint8_t result = analogInputSystem->readAverageBits(port->channel, status);
+  return result;
+}
+
+void HAL_SetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t bits, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  analogInputSystem->writeOversampleBits(port->channel,
+                                         static_cast<uint8_t>(bits), status);
+}
+
+int32_t HAL_GetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
+                                    int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return kDefaultOversampleBits;
+  }
+  uint8_t result = analogInputSystem->readOversampleBits(port->channel, status);
+  return result;
+}
+
+int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle,
+                           int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  tAI::tReadSelect readSelect;
+  readSelect.Channel = port->channel;
+  readSelect.Averaged = false;
+
+  std::lock_guard<wpi::mutex> lock(analogRegisterWindowMutex);
+  analogInputSystem->writeReadSelect(readSelect, status);
+  analogInputSystem->strobeLatchOutput(status);
+  return static_cast<int16_t>(analogInputSystem->readOutput(status));
+}
+
+int32_t HAL_GetAnalogAverageValue(HAL_AnalogInputHandle analogPortHandle,
+                                  int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  tAI::tReadSelect readSelect;
+  readSelect.Channel = port->channel;
+  readSelect.Averaged = true;
+
+  std::lock_guard<wpi::mutex> lock(analogRegisterWindowMutex);
+  analogInputSystem->writeReadSelect(readSelect, status);
+  analogInputSystem->strobeLatchOutput(status);
+  return static_cast<int32_t>(analogInputSystem->readOutput(status));
+}
+
+int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle,
+                                  double voltage, int32_t* status) {
+  if (voltage > 5.0) {
+    voltage = 5.0;
+    *status = VOLTAGE_OUT_OF_RANGE;
+  }
+  if (voltage < 0.0) {
+    voltage = 0.0;
+    *status = VOLTAGE_OUT_OF_RANGE;
+  }
+  int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogPortHandle, status);
+  int32_t offset = HAL_GetAnalogOffset(analogPortHandle, status);
+  int32_t value =
+      static_cast<int32_t>((voltage + offset * 1.0e-9) / (LSBWeight * 1.0e-9));
+  return value;
+}
+
+double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle,
+                            int32_t* status) {
+  int32_t value = HAL_GetAnalogValue(analogPortHandle, status);
+  int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogPortHandle, status);
+  int32_t offset = HAL_GetAnalogOffset(analogPortHandle, status);
+  double voltage = LSBWeight * 1.0e-9 * value - offset * 1.0e-9;
+  return voltage;
+}
+
+double HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analogPortHandle,
+                                   int32_t* status) {
+  int32_t value = HAL_GetAnalogAverageValue(analogPortHandle, status);
+  int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogPortHandle, status);
+  int32_t offset = HAL_GetAnalogOffset(analogPortHandle, status);
+  int32_t oversampleBits =
+      HAL_GetAnalogOversampleBits(analogPortHandle, status);
+  double voltage =
+      LSBWeight * 1.0e-9 * value / static_cast<double>(1 << oversampleBits) -
+      offset * 1.0e-9;
+  return voltage;
+}
+
+int32_t HAL_GetAnalogLSBWeight(HAL_AnalogInputHandle analogPortHandle,
+                               int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  int32_t lsbWeight = FRC_NetworkCommunication_nAICalibration_getLSBWeight(
+      0, port->channel, status);  // XXX: aiSystemIndex == 0?
+  return lsbWeight;
+}
+
+int32_t HAL_GetAnalogOffset(HAL_AnalogInputHandle analogPortHandle,
+                            int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  int32_t offset = FRC_NetworkCommunication_nAICalibration_getOffset(
+      0, port->channel, status);  // XXX: aiSystemIndex == 0?
+  return offset;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInternal.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInternal.cpp
new file mode 100644
index 0000000..6e02def
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInternal.cpp
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "AnalogInternal.h"
+
+#include <atomic>
+
+#include <wpi/mutex.h>
+
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/AnalogInput.h"
+#include "hal/ChipObject.h"
+
+namespace hal {
+
+wpi::mutex analogRegisterWindowMutex;
+std::unique_ptr<tAI> analogInputSystem;
+std::unique_ptr<tAO> analogOutputSystem;
+
+IndexedHandleResource<HAL_AnalogInputHandle, ::hal::AnalogPort,
+                      kNumAnalogInputs, HAL_HandleEnum::AnalogInput>*
+    analogInputHandles;
+
+static int32_t analogNumChannelsToActivate = 0;
+
+static std::atomic<bool> analogSystemInitialized{false};
+
+bool analogSampleRateSet = false;
+
+namespace init {
+void InitializeAnalogInternal() {
+  static IndexedHandleResource<HAL_AnalogInputHandle, ::hal::AnalogPort,
+                               kNumAnalogInputs, HAL_HandleEnum::AnalogInput>
+      alH;
+  analogInputHandles = &alH;
+}
+}  // namespace init
+
+void initializeAnalog(int32_t* status) {
+  hal::init::CheckInit();
+  if (analogSystemInitialized) return;
+  std::lock_guard<wpi::mutex> lock(analogRegisterWindowMutex);
+  if (analogSystemInitialized) return;
+  analogInputSystem.reset(tAI::create(status));
+  analogOutputSystem.reset(tAO::create(status));
+  setAnalogNumChannelsToActivate(kNumAnalogInputs);
+  setAnalogSampleRate(kDefaultSampleRate, status);
+  analogSystemInitialized = true;
+}
+
+int32_t getAnalogNumActiveChannels(int32_t* status) {
+  int32_t scanSize = analogInputSystem->readConfig_ScanSize(status);
+  if (scanSize == 0) return 8;
+  return scanSize;
+}
+
+void setAnalogNumChannelsToActivate(int32_t channels) {
+  analogNumChannelsToActivate = channels;
+}
+
+int32_t getAnalogNumChannelsToActivate(int32_t* status) {
+  if (analogNumChannelsToActivate == 0)
+    return getAnalogNumActiveChannels(status);
+  return analogNumChannelsToActivate;
+}
+
+void setAnalogSampleRate(double samplesPerSecond, int32_t* status) {
+  // TODO: This will change when variable size scan lists are implemented.
+  // TODO: Need double comparison with epsilon.
+  // wpi_assert(!sampleRateSet || GetSampleRate() == samplesPerSecond);
+  analogSampleRateSet = true;
+
+  // Compute the convert rate
+  uint32_t ticksPerSample =
+      static_cast<uint32_t>(static_cast<double>(kTimebase) / samplesPerSecond);
+  uint32_t ticksPerConversion =
+      ticksPerSample / getAnalogNumChannelsToActivate(status);
+  // ticksPerConversion must be at least 80
+  if (ticksPerConversion < 80) {
+    if ((*status) >= 0) *status = SAMPLE_RATE_TOO_HIGH;
+    ticksPerConversion = 80;
+  }
+
+  // Atomically set the scan size and the convert rate so that the sample rate
+  // is constant
+  tAI::tConfig config;
+  config.ScanSize = getAnalogNumChannelsToActivate(status);
+  config.ConvertRate = ticksPerConversion;
+  analogInputSystem->writeConfig(config, status);
+
+  // Indicate that the scan size has been commited to hardware.
+  setAnalogNumChannelsToActivate(0);
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInternal.h b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInternal.h
new file mode 100644
index 0000000..a74562f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogInternal.h
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+
+#include <wpi/mutex.h>
+
+#include "PortsInternal.h"
+#include "hal/ChipObject.h"
+#include "hal/Ports.h"
+#include "hal/handles/IndexedHandleResource.h"
+
+namespace hal {
+
+constexpr int32_t kTimebase = 40000000;  ///< 40 MHz clock
+constexpr int32_t kDefaultOversampleBits = 0;
+constexpr int32_t kDefaultAverageBits = 7;
+constexpr double kDefaultSampleRate = 50000.0;
+static constexpr uint32_t kAccumulatorChannels[] = {0, 1};
+
+extern std::unique_ptr<tAI> analogInputSystem;
+extern std::unique_ptr<tAO> analogOutputSystem;
+extern wpi::mutex analogRegisterWindowMutex;
+extern bool analogSampleRateSet;
+
+struct AnalogPort {
+  uint8_t channel;
+  std::unique_ptr<tAccumulator> accumulator;
+};
+
+extern IndexedHandleResource<HAL_AnalogInputHandle, hal::AnalogPort,
+                             kNumAnalogInputs, HAL_HandleEnum::AnalogInput>*
+    analogInputHandles;
+
+/**
+ * Initialize the analog System.
+ */
+void initializeAnalog(int32_t* status);
+
+/**
+ * Return the number of channels on the module in use.
+ *
+ * @return Active channels.
+ */
+int32_t getAnalogNumActiveChannels(int32_t* status);
+
+/**
+ * Set the number of active channels.
+ *
+ * Store the number of active channels to set.  Don't actually commit to
+ * hardware
+ * until SetSampleRate().
+ *
+ * @param channels Number of active channels.
+ */
+void setAnalogNumChannelsToActivate(int32_t channels);
+
+/**
+ * Get the number of active channels.
+ *
+ * This is an internal function to allow the atomic update of both the
+ * number of active channels and the sample rate.
+ *
+ * When the number of channels changes, use the new value.  Otherwise,
+ * return the curent value.
+ *
+ * @return Value to write to the active channels field.
+ */
+int32_t getAnalogNumChannelsToActivate(int32_t* status);
+
+/**
+ * Set the sample rate.
+ *
+ * This is a global setting for the Athena and effects all channels.
+ *
+ * @param samplesPerSecond The number of samples per channel per second.
+ */
+void setAnalogSampleRate(double samplesPerSecond, int32_t* status);
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogOutput.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogOutput.cpp
new file mode 100644
index 0000000..77f841b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogOutput.cpp
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/AnalogOutput.h"
+
+#include "AnalogInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/IndexedHandleResource.h"
+
+using namespace hal;
+
+namespace {
+
+struct AnalogOutput {
+  uint8_t channel;
+};
+
+}  // namespace
+
+static IndexedHandleResource<HAL_AnalogOutputHandle, AnalogOutput,
+                             kNumAnalogOutputs, HAL_HandleEnum::AnalogOutput>*
+    analogOutputHandles;
+
+namespace hal {
+namespace init {
+void InitializeAnalogOutput() {
+  static IndexedHandleResource<HAL_AnalogOutputHandle, AnalogOutput,
+                               kNumAnalogOutputs, HAL_HandleEnum::AnalogOutput>
+      aoH;
+  analogOutputHandles = &aoH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_AnalogOutputHandle HAL_InitializeAnalogOutputPort(HAL_PortHandle portHandle,
+                                                      int32_t* status) {
+  hal::init::CheckInit();
+  initializeAnalog(status);
+
+  if (*status != 0) return HAL_kInvalidHandle;
+
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  HAL_AnalogOutputHandle handle =
+      analogOutputHandles->Allocate(channel, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  auto port = analogOutputHandles->Get(handle);
+  if (port == nullptr) {  // would only error on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  port->channel = static_cast<uint8_t>(channel);
+  return handle;
+}
+
+void HAL_FreeAnalogOutputPort(HAL_AnalogOutputHandle analogOutputHandle) {
+  // no status, so no need to check for a proper free.
+  analogOutputHandles->Free(analogOutputHandle);
+}
+
+void HAL_SetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle,
+                         double voltage, int32_t* status) {
+  auto port = analogOutputHandles->Get(analogOutputHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint16_t rawValue = static_cast<uint16_t>(voltage / 5.0 * 0x1000);
+
+  if (voltage < 0.0)
+    rawValue = 0;
+  else if (voltage > 5.0)
+    rawValue = 0x1000;
+
+  analogOutputSystem->writeMXP(port->channel, rawValue, status);
+}
+
+double HAL_GetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle,
+                           int32_t* status) {
+  auto port = analogOutputHandles->Get(analogOutputHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+
+  uint16_t rawValue = analogOutputSystem->readMXP(port->channel, status);
+
+  return rawValue * 5.0 / 0x1000;
+}
+
+HAL_Bool HAL_CheckAnalogOutputChannel(int32_t channel) {
+  return channel < kNumAnalogOutputs && channel >= 0;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogTrigger.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogTrigger.cpp
new file mode 100644
index 0000000..1841c51
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/AnalogTrigger.cpp
@@ -0,0 +1,192 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/AnalogTrigger.h"
+
+#include "AnalogInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/AnalogInput.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+using namespace hal;
+
+namespace {
+
+struct AnalogTrigger {
+  std::unique_ptr<tAnalogTrigger> trigger;
+  HAL_AnalogInputHandle analogHandle;
+  uint8_t index;
+};
+
+}  // namespace
+
+static LimitedHandleResource<HAL_AnalogTriggerHandle, AnalogTrigger,
+                             kNumAnalogTriggers, HAL_HandleEnum::AnalogTrigger>*
+    analogTriggerHandles;
+
+namespace hal {
+namespace init {
+void InitializeAnalogTrigger() {
+  static LimitedHandleResource<HAL_AnalogTriggerHandle, AnalogTrigger,
+                               kNumAnalogTriggers,
+                               HAL_HandleEnum::AnalogTrigger>
+      atH;
+  analogTriggerHandles = &atH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger(
+    HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status) {
+  hal::init::CheckInit();
+  // ensure we are given a valid and active AnalogInput handle
+  auto analog_port = analogInputHandles->Get(portHandle);
+  if (analog_port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  HAL_AnalogTriggerHandle handle = analogTriggerHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto trigger = analogTriggerHandles->Get(handle);
+  if (trigger == nullptr) {  // would only occur on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  trigger->analogHandle = portHandle;
+  trigger->index = static_cast<uint8_t>(getHandleIndex(handle));
+  *index = trigger->index;
+
+  trigger->trigger.reset(tAnalogTrigger::create(trigger->index, status));
+  trigger->trigger->writeSourceSelect_Channel(analog_port->channel, status);
+  return handle;
+}
+
+void HAL_CleanAnalogTrigger(HAL_AnalogTriggerHandle analogTriggerHandle,
+                            int32_t* status) {
+  analogTriggerHandles->Free(analogTriggerHandle);
+  // caller owns the analog input handle.
+}
+
+void HAL_SetAnalogTriggerLimitsRaw(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                   int32_t lower, int32_t upper,
+                                   int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (lower > upper) {
+    *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+  }
+  trigger->trigger->writeLowerLimit(lower, status);
+  trigger->trigger->writeUpperLimit(upper, status);
+}
+
+void HAL_SetAnalogTriggerLimitsVoltage(
+    HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
+    int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (lower > upper) {
+    *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+  }
+
+  // TODO: This depends on the averaged setting.  Only raw values will work as
+  // is.
+  trigger->trigger->writeLowerLimit(
+      HAL_GetAnalogVoltsToValue(trigger->analogHandle, lower, status), status);
+  trigger->trigger->writeUpperLimit(
+      HAL_GetAnalogVoltsToValue(trigger->analogHandle, upper, status), status);
+}
+
+void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                  HAL_Bool useAveragedValue, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (trigger->trigger->readSourceSelect_Filter(status) != 0) {
+    *status = INCOMPATIBLE_STATE;
+    // TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not
+    // support average and filtering at the same time.");
+  }
+  trigger->trigger->writeSourceSelect_Averaged(useAveragedValue, status);
+}
+
+void HAL_SetAnalogTriggerFiltered(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                  HAL_Bool useFilteredValue, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (trigger->trigger->readSourceSelect_Averaged(status) != 0) {
+    *status = INCOMPATIBLE_STATE;
+    // TODO: wpi_setWPIErrorWithContext(IncompatibleMode, "Hardware does not "
+    // "support average and filtering at the same time.");
+  }
+  trigger->trigger->writeSourceSelect_Filter(useFilteredValue, status);
+}
+
+HAL_Bool HAL_GetAnalogTriggerInWindow(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  return trigger->trigger->readOutput_InHysteresis(trigger->index, status) != 0;
+}
+
+HAL_Bool HAL_GetAnalogTriggerTriggerState(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  return trigger->trigger->readOutput_OverLimit(trigger->index, status) != 0;
+}
+
+HAL_Bool HAL_GetAnalogTriggerOutput(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                    HAL_AnalogTriggerType type,
+                                    int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool result = false;
+  switch (type) {
+    case HAL_Trigger_kInWindow:
+      result =
+          trigger->trigger->readOutput_InHysteresis(trigger->index, status);
+      break;  // XXX: Backport
+    case HAL_Trigger_kState:
+      result = trigger->trigger->readOutput_OverLimit(trigger->index, status);
+      break;  // XXX: Backport
+    case HAL_Trigger_kRisingPulse:
+    case HAL_Trigger_kFallingPulse:
+      *status = ANALOG_TRIGGER_PULSE_OUTPUT_ERROR;
+      return false;
+  }
+  return result;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/CAN.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/CAN.cpp
new file mode 100644
index 0000000..8105358
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/CAN.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/CAN.h"
+
+#include <FRC_NetworkCommunication/CANSessionMux.h>
+
+namespace hal {
+namespace init {
+void InitializeCAN() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+void HAL_CAN_SendMessage(uint32_t messageID, const uint8_t* data,
+                         uint8_t dataSize, int32_t periodMs, int32_t* status) {
+  FRC_NetworkCommunication_CANSessionMux_sendMessage(messageID, data, dataSize,
+                                                     periodMs, status);
+}
+void HAL_CAN_ReceiveMessage(uint32_t* messageID, uint32_t messageIDMask,
+                            uint8_t* data, uint8_t* dataSize,
+                            uint32_t* timeStamp, int32_t* status) {
+  FRC_NetworkCommunication_CANSessionMux_receiveMessage(
+      messageID, messageIDMask, data, dataSize, timeStamp, status);
+}
+void HAL_CAN_OpenStreamSession(uint32_t* sessionHandle, uint32_t messageID,
+                               uint32_t messageIDMask, uint32_t maxMessages,
+                               int32_t* status) {
+  FRC_NetworkCommunication_CANSessionMux_openStreamSession(
+      sessionHandle, messageID, messageIDMask, maxMessages, status);
+}
+void HAL_CAN_CloseStreamSession(uint32_t sessionHandle) {
+  FRC_NetworkCommunication_CANSessionMux_closeStreamSession(sessionHandle);
+}
+void HAL_CAN_ReadStreamSession(uint32_t sessionHandle,
+                               struct HAL_CANStreamMessage* messages,
+                               uint32_t messagesToRead, uint32_t* messagesRead,
+                               int32_t* status) {
+  FRC_NetworkCommunication_CANSessionMux_readStreamSession(
+      sessionHandle, reinterpret_cast<tCANStreamMessage*>(messages),
+      messagesToRead, messagesRead, status);
+}
+void HAL_CAN_GetCANStatus(float* percentBusUtilization, uint32_t* busOffCount,
+                          uint32_t* txFullCount, uint32_t* receiveErrorCount,
+                          uint32_t* transmitErrorCount, int32_t* status) {
+  FRC_NetworkCommunication_CANSessionMux_getCANStatus(
+      percentBusUtilization, busOffCount, txFullCount, receiveErrorCount,
+      transmitErrorCount, status);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/CANAPI.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/CANAPI.cpp
new file mode 100644
index 0000000..01c06bd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/CANAPI.cpp
@@ -0,0 +1,326 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "hal/CANAPI.h"
+
+#include <atomic>
+#include <ctime>
+
+#include <wpi/DenseMap.h>
+
+#include "HALInitializer.h"
+#include "hal/CAN.h"
+#include "hal/Errors.h"
+#include "hal/HAL.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+
+using namespace hal;
+
+namespace {
+struct Receives {
+  uint32_t lastTimeStamp;
+  uint8_t data[8];
+  uint8_t length;
+};
+
+struct CANStorage {
+  HAL_CANManufacturer manufacturer;
+  HAL_CANDeviceType deviceType;
+  uint8_t deviceId;
+  wpi::mutex mapMutex;
+  wpi::SmallDenseMap<int32_t, int32_t> periodicSends;
+  wpi::SmallDenseMap<int32_t, Receives> receives;
+};
+}  // namespace
+
+static UnlimitedHandleResource<HAL_CANHandle, CANStorage, HAL_HandleEnum::CAN>*
+    canHandles;
+
+static uint32_t GetPacketBaseTime() {
+  timespec t;
+  clock_gettime(CLOCK_MONOTONIC, &t);
+
+  // Convert t to milliseconds
+  uint64_t ms = t.tv_sec * 1000ull + t.tv_nsec / 1000000ull;
+  return ms & 0xFFFFFFFF;
+}
+
+namespace hal {
+namespace init {
+void InitializeCANAPI() {
+  static UnlimitedHandleResource<HAL_CANHandle, CANStorage, HAL_HandleEnum::CAN>
+      cH;
+  canHandles = &cH;
+}
+}  // namespace init
+}  // namespace hal
+
+static int32_t CreateCANId(CANStorage* storage, int32_t apiId) {
+  int32_t createdId = 0;
+  createdId |= (static_cast<int32_t>(storage->deviceType) & 0x1F) << 24;
+  createdId |= (static_cast<int32_t>(storage->manufacturer) & 0xFF) << 16;
+  createdId |= (apiId & 0x3FF) << 6;
+  createdId |= (storage->deviceId & 0x3F);
+  return createdId;
+}
+
+HAL_CANHandle HAL_InitializeCAN(HAL_CANManufacturer manufacturer,
+                                int32_t deviceId, HAL_CANDeviceType deviceType,
+                                int32_t* status) {
+  hal::init::CheckInit();
+  auto can = std::make_shared<CANStorage>();
+
+  auto handle = canHandles->Allocate(can);
+
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  can->deviceId = deviceId;
+  can->deviceType = deviceType;
+  can->manufacturer = manufacturer;
+
+  return handle;
+}
+
+void HAL_CleanCAN(HAL_CANHandle handle) {
+  auto data = canHandles->Free(handle);
+
+  std::lock_guard<wpi::mutex> lock(data->mapMutex);
+
+  for (auto&& i : data->periodicSends) {
+    int32_t s = 0;
+    HAL_CAN_SendMessage(i.first, nullptr, 0, HAL_CAN_SEND_PERIOD_STOP_REPEATING,
+                        &s);
+    i.second = -1;
+  }
+}
+
+void HAL_WriteCANPacket(HAL_CANHandle handle, const uint8_t* data,
+                        int32_t length, int32_t apiId, int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  auto id = CreateCANId(can.get(), apiId);
+
+  HAL_CAN_SendMessage(id, data, length, HAL_CAN_SEND_PERIOD_NO_REPEAT, status);
+
+  if (*status != 0) {
+    return;
+  }
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  can->periodicSends[apiId] = -1;
+}
+
+void HAL_WriteCANPacketRepeating(HAL_CANHandle handle, const uint8_t* data,
+                                 int32_t length, int32_t apiId,
+                                 int32_t repeatMs, int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  auto id = CreateCANId(can.get(), apiId);
+
+  HAL_CAN_SendMessage(id, data, length, repeatMs, status);
+
+  if (*status != 0) {
+    return;
+  }
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  can->periodicSends[apiId] = repeatMs;
+}
+
+void HAL_StopCANPacketRepeating(HAL_CANHandle handle, int32_t apiId,
+                                int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  auto id = CreateCANId(can.get(), apiId);
+
+  HAL_CAN_SendMessage(id, nullptr, 0, HAL_CAN_SEND_PERIOD_STOP_REPEATING,
+                      status);
+
+  if (*status != 0) {
+    return;
+  }
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  can->periodicSends[apiId] = -1;
+}
+
+void HAL_ReadCANPacketNew(HAL_CANHandle handle, int32_t apiId, uint8_t* data,
+                          int32_t* length, uint64_t* receivedTimestamp,
+                          int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+  uint8_t dataSize = 0;
+  uint32_t ts = 0;
+  HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
+
+  if (*status == 0) {
+    std::lock_guard<wpi::mutex> lock(can->mapMutex);
+    auto& msg = can->receives[messageId];
+    msg.length = dataSize;
+    msg.lastTimeStamp = ts;
+    // The NetComm call placed in data, copy into the msg
+    std::memcpy(msg.data, data, dataSize);
+  }
+  *length = dataSize;
+  *receivedTimestamp = ts;
+}
+
+void HAL_ReadCANPacketLatest(HAL_CANHandle handle, int32_t apiId, uint8_t* data,
+                             int32_t* length, uint64_t* receivedTimestamp,
+                             int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+  uint8_t dataSize = 0;
+  uint32_t ts = 0;
+  HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
+
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  if (*status == 0) {
+    // fresh update
+    auto& msg = can->receives[messageId];
+    msg.length = dataSize;
+    *length = dataSize;
+    msg.lastTimeStamp = ts;
+    *receivedTimestamp = ts;
+    // The NetComm call placed in data, copy into the msg
+    std::memcpy(msg.data, data, dataSize);
+  } else {
+    auto i = can->receives.find(messageId);
+    if (i != can->receives.end()) {
+      // Read the data from the stored message into the output
+      std::memcpy(data, i->second.data, i->second.length);
+      *length = i->second.length;
+      *receivedTimestamp = i->second.lastTimeStamp;
+      *status = 0;
+    }
+  }
+}
+
+void HAL_ReadCANPacketTimeout(HAL_CANHandle handle, int32_t apiId,
+                              uint8_t* data, int32_t* length,
+                              uint64_t* receivedTimestamp, int32_t timeoutMs,
+                              int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+  uint8_t dataSize = 0;
+  uint32_t ts = 0;
+  HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
+
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  if (*status == 0) {
+    // fresh update
+    auto& msg = can->receives[messageId];
+    msg.length = dataSize;
+    *length = dataSize;
+    msg.lastTimeStamp = ts;
+    *receivedTimestamp = ts;
+    // The NetComm call placed in data, copy into the msg
+    std::memcpy(msg.data, data, dataSize);
+  } else {
+    auto i = can->receives.find(messageId);
+    if (i != can->receives.end()) {
+      // Found, check if new enough
+      uint32_t now = GetPacketBaseTime();
+      if (now - i->second.lastTimeStamp > static_cast<uint32_t>(timeoutMs)) {
+        // Timeout, return bad status
+        *status = HAL_CAN_TIMEOUT;
+        return;
+      }
+      // Read the data from the stored message into the output
+      std::memcpy(data, i->second.data, i->second.length);
+      *length = i->second.length;
+      *receivedTimestamp = i->second.lastTimeStamp;
+      *status = 0;
+    }
+  }
+}
+
+void HAL_ReadCANPeriodicPacket(HAL_CANHandle handle, int32_t apiId,
+                               uint8_t* data, int32_t* length,
+                               uint64_t* receivedTimestamp, int32_t timeoutMs,
+                               int32_t periodMs, int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+
+  {
+    std::lock_guard<wpi::mutex> lock(can->mapMutex);
+    auto i = can->receives.find(messageId);
+    if (i != can->receives.end()) {
+      // Found, check if new enough
+      uint32_t now = GetPacketBaseTime();
+      if (now - i->second.lastTimeStamp < static_cast<uint32_t>(periodMs)) {
+        // Read the data from the stored message into the output
+        std::memcpy(data, i->second.data, i->second.length);
+        *length = i->second.length;
+        *receivedTimestamp = i->second.lastTimeStamp;
+        *status = 0;
+        return;
+      }
+    }
+  }
+
+  uint8_t dataSize = 0;
+  uint32_t ts = 0;
+  HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
+
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  if (*status == 0) {
+    // fresh update
+    auto& msg = can->receives[messageId];
+    msg.length = dataSize;
+    *length = dataSize;
+    msg.lastTimeStamp = ts;
+    *receivedTimestamp = ts;
+    // The NetComm call placed in data, copy into the msg
+    std::memcpy(msg.data, data, dataSize);
+  } else {
+    auto i = can->receives.find(messageId);
+    if (i != can->receives.end()) {
+      // Found, check if new enough
+      uint32_t now = GetPacketBaseTime();
+      if (now - i->second.lastTimeStamp > static_cast<uint32_t>(timeoutMs)) {
+        // Timeout, return bad status
+        *status = HAL_CAN_TIMEOUT;
+        return;
+      }
+      // Read the data from the stored message into the output
+      std::memcpy(data, i->second.data, i->second.length);
+      *length = i->second.length;
+      *receivedTimestamp = i->second.lastTimeStamp;
+      *status = 0;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Compressor.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Compressor.cpp
new file mode 100644
index 0000000..f381305
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Compressor.cpp
@@ -0,0 +1,202 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Compressor.h"
+
+#include "HALInitializer.h"
+#include "PCMInternal.h"
+#include "PortsInternal.h"
+#include "ctre/PCM.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeCompressor() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_CompressorHandle HAL_InitializeCompressor(int32_t module, int32_t* status) {
+  hal::init::CheckInit();
+  // Use status to check for invalid index
+  initializePCM(module, status);
+  if (*status != 0) {
+    return HAL_kInvalidHandle;
+  }
+
+  // As compressors can have unlimited objects, just create a
+  // handle with the module number as the index.
+
+  return (HAL_CompressorHandle)createHandle(static_cast<int16_t>(module),
+                                            HAL_HandleEnum::Compressor, 0);
+}
+
+HAL_Bool HAL_CheckCompressorModule(int32_t module) {
+  return module < kNumPCMModules && module >= 0;
+}
+
+HAL_Bool HAL_GetCompressor(HAL_CompressorHandle compressorHandle,
+                           int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetCompressor(value);
+
+  return value;
+}
+
+void HAL_SetCompressorClosedLoopControl(HAL_CompressorHandle compressorHandle,
+                                        HAL_Bool value, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  *status = PCM_modules[index]->SetClosedLoopControl(value);
+}
+
+HAL_Bool HAL_GetCompressorClosedLoopControl(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetClosedLoopControl(value);
+
+  return value;
+}
+
+HAL_Bool HAL_GetCompressorPressureSwitch(HAL_CompressorHandle compressorHandle,
+                                         int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetPressure(value);
+
+  return value;
+}
+
+double HAL_GetCompressorCurrent(HAL_CompressorHandle compressorHandle,
+                                int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  float value;
+
+  *status = PCM_modules[index]->GetCompressorCurrent(value);
+
+  return value;
+}
+HAL_Bool HAL_GetCompressorCurrentTooHighFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetCompressorCurrentTooHighFault(value);
+
+  return value;
+}
+HAL_Bool HAL_GetCompressorCurrentTooHighStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetCompressorCurrentTooHighStickyFault(value);
+
+  return value;
+}
+HAL_Bool HAL_GetCompressorShortedStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetCompressorShortedStickyFault(value);
+
+  return value;
+}
+HAL_Bool HAL_GetCompressorShortedFault(HAL_CompressorHandle compressorHandle,
+                                       int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetCompressorShortedFault(value);
+
+  return value;
+}
+HAL_Bool HAL_GetCompressorNotConnectedStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetCompressorNotConnectedStickyFault(value);
+
+  return value;
+}
+HAL_Bool HAL_GetCompressorNotConnectedFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[index]->GetCompressorNotConnectedFault(value);
+
+  return value;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Constants.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Constants.cpp
new file mode 100644
index 0000000..6af443d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Constants.cpp
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Constants.h"
+
+#include "ConstantsInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeConstants() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+int32_t HAL_GetSystemClockTicksPerMicrosecond(void) {
+  return kSystemClockTicksPerMicrosecond;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/ConstantsInternal.h b/third_party/allwpilib_2019/hal/src/main/native/athena/ConstantsInternal.h
new file mode 100644
index 0000000..55bbdee
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/ConstantsInternal.h
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+namespace hal {
+
+constexpr int32_t kSystemClockTicksPerMicrosecond = 40;
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Counter.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Counter.cpp
new file mode 100644
index 0000000..6d7e254
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Counter.cpp
@@ -0,0 +1,372 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Counter.h"
+
+#include "ConstantsInternal.h"
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/HAL.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+using namespace hal;
+
+namespace {
+
+struct Counter {
+  std::unique_ptr<tCounter> counter;
+  uint8_t index;
+};
+
+}  // namespace
+
+static LimitedHandleResource<HAL_CounterHandle, Counter, kNumCounters,
+                             HAL_HandleEnum::Counter>* counterHandles;
+
+namespace hal {
+namespace init {
+void InitializeCounter() {
+  static LimitedHandleResource<HAL_CounterHandle, Counter, kNumCounters,
+                               HAL_HandleEnum::Counter>
+      ch;
+  counterHandles = &ch;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_CounterHandle HAL_InitializeCounter(HAL_Counter_Mode mode, int32_t* index,
+                                        int32_t* status) {
+  hal::init::CheckInit();
+  auto handle = counterHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {  // out of resources
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto counter = counterHandles->Get(handle);
+  if (counter == nullptr) {  // would only occur on thread issues
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  counter->index = static_cast<uint8_t>(getHandleIndex(handle));
+  *index = counter->index;
+
+  counter->counter.reset(tCounter::create(counter->index, status));
+  counter->counter->writeConfig_Mode(mode, status);
+  counter->counter->writeTimerConfig_AverageSize(1, status);
+  return handle;
+}
+
+void HAL_FreeCounter(HAL_CounterHandle counterHandle, int32_t* status) {
+  counterHandles->Free(counterHandle);
+}
+
+void HAL_SetCounterAverageSize(HAL_CounterHandle counterHandle, int32_t size,
+                               int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeTimerConfig_AverageSize(size, status);
+}
+
+void HAL_SetCounterUpSource(HAL_CounterHandle counterHandle,
+                            HAL_Handle digitalSourceHandle,
+                            HAL_AnalogTriggerType analogTriggerType,
+                            int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  bool routingAnalogTrigger = false;
+  uint8_t routingChannel = 0;
+  uint8_t routingModule = 0;
+  bool success =
+      remapDigitalSource(digitalSourceHandle, analogTriggerType, routingChannel,
+                         routingModule, routingAnalogTrigger);
+  if (!success) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  counter->counter->writeConfig_UpSource_Module(routingModule, status);
+  counter->counter->writeConfig_UpSource_Channel(routingChannel, status);
+  counter->counter->writeConfig_UpSource_AnalogTrigger(routingAnalogTrigger,
+                                                       status);
+
+  if (counter->counter->readConfig_Mode(status) == HAL_Counter_kTwoPulse ||
+      counter->counter->readConfig_Mode(status) ==
+          HAL_Counter_kExternalDirection) {
+    HAL_SetCounterUpSourceEdge(counterHandle, true, false, status);
+  }
+  counter->counter->strobeReset(status);
+}
+
+void HAL_SetCounterUpSourceEdge(HAL_CounterHandle counterHandle,
+                                HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeConfig_UpRisingEdge(risingEdge, status);
+  counter->counter->writeConfig_UpFallingEdge(fallingEdge, status);
+}
+
+void HAL_ClearCounterUpSource(HAL_CounterHandle counterHandle,
+                              int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeConfig_UpFallingEdge(false, status);
+  counter->counter->writeConfig_UpRisingEdge(false, status);
+  // Index 0 of digital is always 0.
+  counter->counter->writeConfig_UpSource_Channel(0, status);
+  counter->counter->writeConfig_UpSource_AnalogTrigger(false, status);
+}
+
+void HAL_SetCounterDownSource(HAL_CounterHandle counterHandle,
+                              HAL_Handle digitalSourceHandle,
+                              HAL_AnalogTriggerType analogTriggerType,
+                              int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  uint8_t mode = counter->counter->readConfig_Mode(status);
+  if (mode != HAL_Counter_kTwoPulse && mode != HAL_Counter_kExternalDirection) {
+    // TODO: wpi_setWPIErrorWithContext(ParameterOutOfRange, "Counter only
+    // supports DownSource in TwoPulse and ExternalDirection modes.");
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  bool routingAnalogTrigger = false;
+  uint8_t routingChannel = 0;
+  uint8_t routingModule = 0;
+  bool success =
+      remapDigitalSource(digitalSourceHandle, analogTriggerType, routingChannel,
+                         routingModule, routingAnalogTrigger);
+  if (!success) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  counter->counter->writeConfig_DownSource_Module(routingModule, status);
+  counter->counter->writeConfig_DownSource_Channel(routingChannel, status);
+  counter->counter->writeConfig_DownSource_AnalogTrigger(routingAnalogTrigger,
+                                                         status);
+
+  HAL_SetCounterDownSourceEdge(counterHandle, true, false, status);
+  counter->counter->strobeReset(status);
+}
+
+void HAL_SetCounterDownSourceEdge(HAL_CounterHandle counterHandle,
+                                  HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                  int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeConfig_DownRisingEdge(risingEdge, status);
+  counter->counter->writeConfig_DownFallingEdge(fallingEdge, status);
+}
+
+void HAL_ClearCounterDownSource(HAL_CounterHandle counterHandle,
+                                int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeConfig_DownFallingEdge(false, status);
+  counter->counter->writeConfig_DownRisingEdge(false, status);
+  // Index 0 of digital is always 0.
+  counter->counter->writeConfig_DownSource_Channel(0, status);
+  counter->counter->writeConfig_DownSource_AnalogTrigger(false, status);
+}
+
+void HAL_SetCounterUpDownMode(HAL_CounterHandle counterHandle,
+                              int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeConfig_Mode(HAL_Counter_kTwoPulse, status);
+}
+
+void HAL_SetCounterExternalDirectionMode(HAL_CounterHandle counterHandle,
+                                         int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeConfig_Mode(HAL_Counter_kExternalDirection, status);
+}
+
+void HAL_SetCounterSemiPeriodMode(HAL_CounterHandle counterHandle,
+                                  HAL_Bool highSemiPeriod, int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeConfig_Mode(HAL_Counter_kSemiperiod, status);
+  counter->counter->writeConfig_UpRisingEdge(highSemiPeriod, status);
+  HAL_SetCounterUpdateWhenEmpty(counterHandle, false, status);
+}
+
+void HAL_SetCounterPulseLengthMode(HAL_CounterHandle counterHandle,
+                                   double threshold, int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeConfig_Mode(HAL_Counter_kPulseLength, status);
+  counter->counter->writeConfig_PulseLengthThreshold(
+      static_cast<uint32_t>(threshold * 1.0e6) *
+          kSystemClockTicksPerMicrosecond,
+      status);
+}
+
+int32_t HAL_GetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
+                                       int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return counter->counter->readTimerConfig_AverageSize(status);
+}
+
+void HAL_SetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
+                                    int32_t samplesToAverage, int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    *status = PARAMETER_OUT_OF_RANGE;
+  }
+  counter->counter->writeTimerConfig_AverageSize(samplesToAverage, status);
+}
+
+void HAL_ResetCounter(HAL_CounterHandle counterHandle, int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->strobeReset(status);
+}
+
+int32_t HAL_GetCounter(HAL_CounterHandle counterHandle, int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  int32_t value = counter->counter->readOutput_Value(status);
+  return value;
+}
+
+double HAL_GetCounterPeriod(HAL_CounterHandle counterHandle, int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+  tCounter::tTimerOutput output = counter->counter->readTimerOutput(status);
+  double period;
+  if (output.Stalled) {
+    // Return infinity
+    double zero = 0.0;
+    period = 1.0 / zero;
+  } else {
+    // output.Period is a fixed point number that counts by 2 (24 bits, 25
+    // integer bits)
+    period = static_cast<double>(output.Period << 1) /
+             static_cast<double>(output.Count);
+  }
+  return static_cast<double>(period *
+                             2.5e-8);  // result * timebase (currently 25ns)
+}
+
+void HAL_SetCounterMaxPeriod(HAL_CounterHandle counterHandle, double maxPeriod,
+                             int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeTimerConfig_StallPeriod(
+      static_cast<uint32_t>(maxPeriod * 4.0e8), status);
+}
+
+void HAL_SetCounterUpdateWhenEmpty(HAL_CounterHandle counterHandle,
+                                   HAL_Bool enabled, int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  counter->counter->writeTimerConfig_UpdateWhenEmpty(enabled, status);
+}
+
+HAL_Bool HAL_GetCounterStopped(HAL_CounterHandle counterHandle,
+                               int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  return counter->counter->readTimerOutput_Stalled(status);
+}
+
+HAL_Bool HAL_GetCounterDirection(HAL_CounterHandle counterHandle,
+                                 int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value = counter->counter->readOutput_Direction(status);
+  return value;
+}
+
+void HAL_SetCounterReverseDirection(HAL_CounterHandle counterHandle,
+                                    HAL_Bool reverseDirection,
+                                    int32_t* status) {
+  auto counter = counterHandles->Get(counterHandle);
+  if (counter == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (counter->counter->readConfig_Mode(status) ==
+      HAL_Counter_kExternalDirection) {
+    if (reverseDirection)
+      HAL_SetCounterDownSourceEdge(counterHandle, true, true, status);
+    else
+      HAL_SetCounterDownSourceEdge(counterHandle, false, true, status);
+  }
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/DIO.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/DIO.cpp
new file mode 100644
index 0000000..96eab2b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/DIO.cpp
@@ -0,0 +1,486 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/DIO.h"
+
+#include <cmath>
+#include <thread>
+
+#include <wpi/raw_ostream.h>
+
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/cpp/fpga_clock.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+using namespace hal;
+
+// Create a mutex to protect changes to the DO PWM config
+static wpi::mutex digitalPwmMutex;
+
+static LimitedHandleResource<HAL_DigitalPWMHandle, uint8_t,
+                             kNumDigitalPWMOutputs, HAL_HandleEnum::DigitalPWM>*
+    digitalPWMHandles;
+
+namespace hal {
+namespace init {
+void InitializeDIO() {
+  static LimitedHandleResource<HAL_DigitalPWMHandle, uint8_t,
+                               kNumDigitalPWMOutputs,
+                               HAL_HandleEnum::DigitalPWM>
+      dpH;
+  digitalPWMHandles = &dpH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_DigitalHandle HAL_InitializeDIOPort(HAL_PortHandle portHandle,
+                                        HAL_Bool input, int32_t* status) {
+  hal::init::CheckInit();
+  initializeDigital(status);
+
+  if (*status != 0) return HAL_kInvalidHandle;
+
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex || channel >= kNumDigitalChannels) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  auto handle =
+      digitalChannelHandles->Allocate(channel, HAL_HandleEnum::DIO, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  auto port = digitalChannelHandles->Get(handle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  port->channel = static_cast<uint8_t>(channel);
+
+  std::lock_guard<wpi::mutex> lock(digitalDIOMutex);
+
+  tDIO::tOutputEnable outputEnable = digitalSystem->readOutputEnable(status);
+
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    if (!getPortHandleSPIEnable(portHandle)) {
+      // if this flag is not set, we actually want DIO.
+      uint32_t bitToSet = 1u << remapSPIChannel(port->channel);
+
+      uint16_t specialFunctions = spiSystem->readEnableDIO(status);
+      // Set the field to enable SPI DIO
+      spiSystem->writeEnableDIO(specialFunctions | bitToSet, status);
+
+      if (input) {
+        outputEnable.SPIPort =
+            outputEnable.SPIPort & (~bitToSet);  // clear the field for read
+      } else {
+        outputEnable.SPIPort =
+            outputEnable.SPIPort | bitToSet;  // set the bits for write
+      }
+    }
+  } else if (port->channel < kNumDigitalHeaders) {
+    uint32_t bitToSet = 1u << port->channel;
+    if (input) {
+      outputEnable.Headers =
+          outputEnable.Headers & (~bitToSet);  // clear the bit for read
+    } else {
+      outputEnable.Headers =
+          outputEnable.Headers | bitToSet;  // set the bit for write
+    }
+  } else {
+    uint32_t bitToSet = 1u << remapMXPChannel(port->channel);
+
+    uint16_t specialFunctions =
+        digitalSystem->readEnableMXPSpecialFunction(status);
+    digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToSet,
+                                                 status);
+
+    if (input) {
+      outputEnable.MXP =
+          outputEnable.MXP & (~bitToSet);  // clear the bit for read
+    } else {
+      outputEnable.MXP = outputEnable.MXP | bitToSet;  // set the bit for write
+    }
+  }
+
+  digitalSystem->writeOutputEnable(outputEnable, status);
+
+  return handle;
+}
+
+HAL_Bool HAL_CheckDIOChannel(int32_t channel) {
+  return channel < kNumDigitalChannels && channel >= 0;
+}
+
+void HAL_FreeDIOPort(HAL_DigitalHandle dioPortHandle) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  // no status, so no need to check for a proper free.
+  if (port == nullptr) return;
+  digitalChannelHandles->Free(dioPortHandle, HAL_HandleEnum::DIO);
+
+  // Wait for no other object to hold this handle.
+  auto start = hal::fpga_clock::now();
+  while (port.use_count() != 1) {
+    auto current = hal::fpga_clock::now();
+    if (start + std::chrono::seconds(1) < current) {
+      wpi::outs() << "DIO handle free timeout\n";
+      wpi::outs().flush();
+      break;
+    }
+    std::this_thread::yield();
+  }
+
+  int32_t status = 0;
+  std::lock_guard<wpi::mutex> lock(digitalDIOMutex);
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    // Unset the SPI flag
+    int32_t bitToUnset = 1 << remapSPIChannel(port->channel);
+    uint16_t specialFunctions = spiSystem->readEnableDIO(&status);
+    spiSystem->writeEnableDIO(specialFunctions & ~bitToUnset, &status);
+  } else if (port->channel >= kNumDigitalHeaders) {
+    // Unset the MXP flag
+    uint32_t bitToUnset = 1u << remapMXPChannel(port->channel);
+
+    uint16_t specialFunctions =
+        digitalSystem->readEnableMXPSpecialFunction(&status);
+    digitalSystem->writeEnableMXPSpecialFunction(specialFunctions | bitToUnset,
+                                                 &status);
+  }
+}
+
+HAL_DigitalPWMHandle HAL_AllocateDigitalPWM(int32_t* status) {
+  auto handle = digitalPWMHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  auto id = digitalPWMHandles->Get(handle);
+  if (id == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  *id = static_cast<uint8_t>(getHandleIndex(handle));
+
+  return handle;
+}
+
+void HAL_FreeDigitalPWM(HAL_DigitalPWMHandle pwmGenerator, int32_t* status) {
+  digitalPWMHandles->Free(pwmGenerator);
+}
+
+void HAL_SetDigitalPWMRate(double rate, int32_t* status) {
+  // Currently rounding in the log rate domain... heavy weight toward picking a
+  // higher freq.
+  // TODO: Round in the linear rate domain.
+  initializeDigital(status);
+  if (*status != 0) return;
+  uint16_t pwmPeriodPower = static_cast<uint16_t>(
+      std::log(1.0 / (16 * 1.0E-6 * rate)) / std::log(2.0) + 0.5);
+  digitalSystem->writePWMPeriodPower(pwmPeriodPower, status);
+}
+
+void HAL_SetDigitalPWMDutyCycle(HAL_DigitalPWMHandle pwmGenerator,
+                                double dutyCycle, int32_t* status) {
+  auto port = digitalPWMHandles->Get(pwmGenerator);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  int32_t id = *port;
+  if (dutyCycle > 1.0) dutyCycle = 1.0;
+  if (dutyCycle < 0.0) dutyCycle = 0.0;
+  double rawDutyCycle = 256.0 * dutyCycle;
+  if (rawDutyCycle > 255.5) rawDutyCycle = 255.5;
+  {
+    std::lock_guard<wpi::mutex> lock(digitalPwmMutex);
+    uint16_t pwmPeriodPower = digitalSystem->readPWMPeriodPower(status);
+    if (pwmPeriodPower < 4) {
+      // The resolution of the duty cycle drops close to the highest
+      // frequencies.
+      rawDutyCycle = rawDutyCycle / std::pow(2.0, 4 - pwmPeriodPower);
+    }
+    if (id < 4)
+      digitalSystem->writePWMDutyCycleA(id, static_cast<uint8_t>(rawDutyCycle),
+                                        status);
+    else
+      digitalSystem->writePWMDutyCycleB(
+          id - 4, static_cast<uint8_t>(rawDutyCycle), status);
+  }
+}
+
+void HAL_SetDigitalPWMOutputChannel(HAL_DigitalPWMHandle pwmGenerator,
+                                    int32_t channel, int32_t* status) {
+  auto port = digitalPWMHandles->Get(pwmGenerator);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  int32_t id = *port;
+  if (channel >= kNumDigitalHeaders &&
+      channel <
+          kNumDigitalHeaders + kNumDigitalMXPChannels) {  // If it is on the MXP
+    /* Then to write as a digital PWM channel an offset is needed to write on
+     * the correct channel
+     */
+    channel += kMXPDigitalPWMOffset;
+  }
+  digitalSystem->writePWMOutputSelect(id, channel, status);
+}
+
+void HAL_SetDIO(HAL_DigitalHandle dioPortHandle, HAL_Bool value,
+                int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (value != 0 && value != 1) {
+    if (value != 0) value = 1;
+  }
+  {
+    std::lock_guard<wpi::mutex> lock(digitalDIOMutex);
+    tDIO::tDO currentDIO = digitalSystem->readDO(status);
+
+    if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+      if (value == 0) {
+        currentDIO.SPIPort =
+            currentDIO.SPIPort & ~(1u << remapSPIChannel(port->channel));
+      } else if (value == 1) {
+        currentDIO.SPIPort =
+            currentDIO.SPIPort | (1u << remapSPIChannel(port->channel));
+      }
+    } else if (port->channel < kNumDigitalHeaders) {
+      if (value == 0) {
+        currentDIO.Headers = currentDIO.Headers & ~(1u << port->channel);
+      } else if (value == 1) {
+        currentDIO.Headers = currentDIO.Headers | (1u << port->channel);
+      }
+    } else {
+      if (value == 0) {
+        currentDIO.MXP =
+            currentDIO.MXP & ~(1u << remapMXPChannel(port->channel));
+      } else if (value == 1) {
+        currentDIO.MXP =
+            currentDIO.MXP | (1u << remapMXPChannel(port->channel));
+      }
+    }
+    digitalSystem->writeDO(currentDIO, status);
+  }
+}
+
+void HAL_SetDIODirection(HAL_DigitalHandle dioPortHandle, HAL_Bool input,
+                         int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  {
+    std::lock_guard<wpi::mutex> lock(digitalDIOMutex);
+    tDIO::tOutputEnable currentDIO = digitalSystem->readOutputEnable(status);
+
+    if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+      if (input) {
+        currentDIO.SPIPort =
+            currentDIO.SPIPort & ~(1u << remapSPIChannel(port->channel));
+      } else {
+        currentDIO.SPIPort =
+            currentDIO.SPIPort | (1u << remapSPIChannel(port->channel));
+      }
+    } else if (port->channel < kNumDigitalHeaders) {
+      if (input) {
+        currentDIO.Headers = currentDIO.Headers & ~(1u << port->channel);
+      } else {
+        currentDIO.Headers = currentDIO.Headers | (1u << port->channel);
+      }
+    } else {
+      if (input) {
+        currentDIO.MXP =
+            currentDIO.MXP & ~(1u << remapMXPChannel(port->channel));
+      } else {
+        currentDIO.MXP =
+            currentDIO.MXP | (1u << remapMXPChannel(port->channel));
+      }
+    }
+    digitalSystem->writeOutputEnable(currentDIO, status);
+  }
+}
+
+HAL_Bool HAL_GetDIO(HAL_DigitalHandle dioPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  tDIO::tDI currentDIO = digitalSystem->readDI(status);
+  // Shift 00000001 over channel-1 places.
+  // AND it against the currentDIO
+  // if it == 0, then return false
+  // else return true
+
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    return ((currentDIO.SPIPort >> remapSPIChannel(port->channel)) & 1) != 0;
+  } else if (port->channel < kNumDigitalHeaders) {
+    return ((currentDIO.Headers >> port->channel) & 1) != 0;
+  } else {
+    return ((currentDIO.MXP >> remapMXPChannel(port->channel)) & 1) != 0;
+  }
+}
+
+HAL_Bool HAL_GetDIODirection(HAL_DigitalHandle dioPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  tDIO::tOutputEnable currentOutputEnable =
+      digitalSystem->readOutputEnable(status);
+  // Shift 00000001 over port->channel-1 places.
+  // AND it against the currentOutputEnable
+  // if it == 0, then return false
+  // else return true
+
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    return ((currentOutputEnable.SPIPort >> remapSPIChannel(port->channel)) &
+            1) != 0;
+  } else if (port->channel < kNumDigitalHeaders) {
+    return ((currentOutputEnable.Headers >> port->channel) & 1) != 0;
+  } else {
+    return ((currentOutputEnable.MXP >> remapMXPChannel(port->channel)) & 1) !=
+           0;
+  }
+}
+
+void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLength,
+               int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  tDIO::tPulse pulse;
+
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    pulse.SPIPort = 1u << remapSPIChannel(port->channel);
+  } else if (port->channel < kNumDigitalHeaders) {
+    pulse.Headers = 1u << port->channel;
+  } else {
+    pulse.MXP = 1u << remapMXPChannel(port->channel);
+  }
+
+  digitalSystem->writePulseLength(
+      static_cast<uint8_t>(1.0e9 * pulseLength /
+                           (pwmSystem->readLoopTiming(status) * 25)),
+      status);
+  digitalSystem->writePulse(pulse, status);
+}
+
+HAL_Bool HAL_IsPulsing(HAL_DigitalHandle dioPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  tDIO::tPulse pulseRegister = digitalSystem->readPulse(status);
+
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    return (pulseRegister.SPIPort & (1 << remapSPIChannel(port->channel))) != 0;
+  } else if (port->channel < kNumDigitalHeaders) {
+    return (pulseRegister.Headers & (1 << port->channel)) != 0;
+  } else {
+    return (pulseRegister.MXP & (1 << remapMXPChannel(port->channel))) != 0;
+  }
+}
+
+HAL_Bool HAL_IsAnyPulsing(int32_t* status) {
+  initializeDigital(status);
+  if (*status != 0) return false;
+  tDIO::tPulse pulseRegister = digitalSystem->readPulse(status);
+  return pulseRegister.Headers != 0 && pulseRegister.MXP != 0 &&
+         pulseRegister.SPIPort != 0;
+}
+
+void HAL_SetFilterSelect(HAL_DigitalHandle dioPortHandle, int32_t filterIndex,
+                         int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  std::lock_guard<wpi::mutex> lock(digitalDIOMutex);
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    // Channels 10-15 are SPI channels, so subtract our MXP channels
+    digitalSystem->writeFilterSelectHdr(port->channel - kNumDigitalMXPChannels,
+                                        filterIndex, status);
+  } else if (port->channel < kNumDigitalHeaders) {
+    digitalSystem->writeFilterSelectHdr(port->channel, filterIndex, status);
+  } else {
+    digitalSystem->writeFilterSelectMXP(remapMXPChannel(port->channel),
+                                        filterIndex, status);
+  }
+}
+
+int32_t HAL_GetFilterSelect(HAL_DigitalHandle dioPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  std::lock_guard<wpi::mutex> lock(digitalDIOMutex);
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    // Channels 10-15 are SPI channels, so subtract our MXP channels
+    return digitalSystem->readFilterSelectHdr(
+        port->channel - kNumDigitalMXPChannels, status);
+  } else if (port->channel < kNumDigitalHeaders) {
+    return digitalSystem->readFilterSelectHdr(port->channel, status);
+  } else {
+    return digitalSystem->readFilterSelectMXP(remapMXPChannel(port->channel),
+                                              status);
+  }
+}
+
+void HAL_SetFilterPeriod(int32_t filterIndex, int64_t value, int32_t* status) {
+  initializeDigital(status);
+  if (*status != 0) return;
+  std::lock_guard<wpi::mutex> lock(digitalDIOMutex);
+  digitalSystem->writeFilterPeriodHdr(filterIndex, value, status);
+  if (*status == 0) {
+    digitalSystem->writeFilterPeriodMXP(filterIndex, value, status);
+  }
+}
+
+int64_t HAL_GetFilterPeriod(int32_t filterIndex, int32_t* status) {
+  initializeDigital(status);
+  if (*status != 0) return 0;
+  uint32_t hdrPeriod = 0;
+  uint32_t mxpPeriod = 0;
+  {
+    std::lock_guard<wpi::mutex> lock(digitalDIOMutex);
+    hdrPeriod = digitalSystem->readFilterPeriodHdr(filterIndex, status);
+    if (*status == 0) {
+      mxpPeriod = digitalSystem->readFilterPeriodMXP(filterIndex, status);
+    }
+  }
+  if (hdrPeriod != mxpPeriod) {
+    *status = NiFpga_Status_SoftwareFault;
+    return -1;
+  }
+  return hdrPeriod;
+}
+
+}  // extern "C"
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
new file mode 100644
index 0000000..1db6c7e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/DigitalInternal.cpp
@@ -0,0 +1,183 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "DigitalInternal.h"
+
+#include <atomic>
+#include <thread>
+
+#include <FRC_NetworkCommunication/LoadOut.h>
+#include <wpi/mutex.h>
+
+#include "ConstantsInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/AnalogTrigger.h"
+#include "hal/ChipObject.h"
+#include "hal/HAL.h"
+#include "hal/Ports.h"
+#include "hal/cpp/UnsafeDIO.h"
+
+namespace hal {
+
+std::unique_ptr<tDIO> digitalSystem;
+std::unique_ptr<tRelay> relaySystem;
+std::unique_ptr<tPWM> pwmSystem;
+std::unique_ptr<tSPI> spiSystem;
+
+// Create a mutex to protect changes to the digital output values
+wpi::mutex digitalDIOMutex;
+
+DigitalHandleResource<HAL_DigitalHandle, DigitalPort,
+                      kNumDigitalChannels + kNumPWMHeaders>*
+    digitalChannelHandles;
+
+namespace init {
+void InitializeDigitalInternal() {
+  static DigitalHandleResource<HAL_DigitalHandle, DigitalPort,
+                               kNumDigitalChannels + kNumPWMHeaders>
+      dcH;
+  digitalChannelHandles = &dcH;
+}
+}  // namespace init
+
+namespace detail {
+wpi::mutex& UnsafeGetDIOMutex() { return digitalDIOMutex; }
+tDIO* UnsafeGetDigialSystem() { return digitalSystem.get(); }
+int32_t ComputeDigitalMask(HAL_DigitalHandle handle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(handle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  tDIO::tDO output;
+  output.value = 0;
+  if (port->channel >= kNumDigitalHeaders + kNumDigitalMXPChannels) {
+    output.SPIPort = (1u << remapSPIChannel(port->channel));
+  } else if (port->channel < kNumDigitalHeaders) {
+    output.Headers = (1u << port->channel);
+  } else {
+    output.MXP = (1u << remapMXPChannel(port->channel));
+  }
+  return output.value;
+}
+}  // namespace detail
+
+void initializeDigital(int32_t* status) {
+  hal::init::CheckInit();
+  static std::atomic_bool initialized{false};
+  static wpi::mutex initializeMutex;
+  // Initial check, as if it's true initialization has finished
+  if (initialized) return;
+
+  std::lock_guard<wpi::mutex> lock(initializeMutex);
+  // Second check in case another thread was waiting
+  if (initialized) return;
+
+  digitalSystem.reset(tDIO::create(status));
+
+  // Relay Setup
+  relaySystem.reset(tRelay::create(status));
+
+  // Turn off all relay outputs.
+  relaySystem->writeValue_Forward(0, status);
+  relaySystem->writeValue_Reverse(0, status);
+
+  // PWM Setup
+  pwmSystem.reset(tPWM::create(status));
+
+  // Make sure that the 9403 IONode has had a chance to initialize before
+  // continuing.
+  while (pwmSystem->readLoopTiming(status) == 0) std::this_thread::yield();
+
+  if (pwmSystem->readLoopTiming(status) != kExpectedLoopTiming) {
+    *status = LOOP_TIMING_ERROR;  // NOTE: Doesn't display the error
+  }
+
+  // Calculate the length, in ms, of one DIO loop
+  double loopTime = pwmSystem->readLoopTiming(status) /
+                    (kSystemClockTicksPerMicrosecond * 1e3);
+
+  pwmSystem->writeConfig_Period(
+      static_cast<uint16_t>(kDefaultPwmPeriod / loopTime + .5), status);
+  uint16_t minHigh = static_cast<uint16_t>(
+      (kDefaultPwmCenter - kDefaultPwmStepsDown * loopTime) / loopTime + .5);
+  pwmSystem->writeConfig_MinHigh(minHigh, status);
+  // Ensure that PWM output values are set to OFF
+  for (uint8_t pwmIndex = 0; pwmIndex < kNumPWMChannels; pwmIndex++) {
+    // Copy of SetPWM
+    if (pwmIndex < tPWM::kNumHdrRegisters) {
+      pwmSystem->writeHdr(pwmIndex, kPwmDisabled, status);
+    } else {
+      pwmSystem->writeMXP(pwmIndex - tPWM::kNumHdrRegisters, kPwmDisabled,
+                          status);
+    }
+
+    // Copy of SetPWMPeriodScale, set to 4x by default.
+    if (pwmIndex < tPWM::kNumPeriodScaleHdrElements) {
+      pwmSystem->writePeriodScaleHdr(pwmIndex, 3, status);
+    } else {
+      pwmSystem->writePeriodScaleMXP(
+          pwmIndex - tPWM::kNumPeriodScaleHdrElements, 3, status);
+    }
+  }
+
+  // SPI setup
+  spiSystem.reset(tSPI::create(status));
+
+  initialized = true;
+}
+
+bool remapDigitalSource(HAL_Handle digitalSourceHandle,
+                        HAL_AnalogTriggerType analogTriggerType,
+                        uint8_t& channel, uint8_t& module,
+                        bool& analogTrigger) {
+  if (isHandleType(digitalSourceHandle, HAL_HandleEnum::AnalogTrigger)) {
+    // If handle passed, index is not negative
+    int32_t index = getHandleIndex(digitalSourceHandle);
+    channel = (index << 2) + analogTriggerType;
+    module = channel >> 4;
+    analogTrigger = true;
+    return true;
+  } else if (isHandleType(digitalSourceHandle, HAL_HandleEnum::DIO)) {
+    int32_t index = getHandleIndex(digitalSourceHandle);
+    if (index > kNumDigitalHeaders + kNumDigitalMXPChannels) {
+      // channels 10-15, so need to add headers to remap index
+      channel = remapSPIChannel(index) + kNumDigitalHeaders;
+      module = 0;
+    } else if (index >= kNumDigitalHeaders) {
+      channel = remapMXPChannel(index);
+      module = 1;
+    } else {
+      channel = index;
+      module = 0;
+    }
+    analogTrigger = false;
+    return true;
+  } else {
+    return false;
+  }
+}
+
+int32_t remapMXPChannel(int32_t channel) { return channel - 10; }
+
+int32_t remapMXPPWMChannel(int32_t channel) {
+  if (channel < 14) {
+    return channel - 10;  // first block of 4 pwms (MXP 0-3)
+  } else {
+    return channel - 6;  // block of PWMs after SPI
+  }
+}
+
+int32_t remapSPIChannel(int32_t channel) { return channel - 26; }
+
+}  // namespace hal
+
+// Unused function here to test template compile.
+__attribute__((unused)) static void CompileFunctorTest() {
+  hal::UnsafeManipulateDIO(0, nullptr, [](hal::DIOSetProxy& proxy) {});
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/DigitalInternal.h b/third_party/allwpilib_2019/hal/src/main/native/athena/DigitalInternal.h
new file mode 100644
index 0000000..b486f48
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/DigitalInternal.h
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+
+#include <wpi/mutex.h>
+
+#include "PortsInternal.h"
+#include "hal/AnalogTrigger.h"
+#include "hal/ChipObject.h"
+#include "hal/Ports.h"
+#include "hal/Types.h"
+#include "hal/handles/DigitalHandleResource.h"
+#include "hal/handles/HandlesInternal.h"
+
+namespace hal {
+
+/**
+ * MXP channels when used as digital output PWM are offset from actual value
+ */
+constexpr int32_t kMXPDigitalPWMOffset = 6;
+
+constexpr int32_t kExpectedLoopTiming = 40;
+
+/**
+ * kDefaultPwmPeriod is in ms
+ *
+ * - 20ms periods (50 Hz) are the "safest" setting in that this works for all
+ *   devices
+ * - 20ms periods seem to be desirable for Vex Motors
+ * - 20ms periods are the specified period for HS-322HD servos, but work
+ *   reliably down to 10.0 ms; starting at about 8.5ms, the servo sometimes hums
+ *   and get hot; by 5.0ms the hum is nearly continuous
+ * - 10ms periods work well for Victor 884
+ * - 5ms periods allows higher update rates for Luminary Micro Jaguar speed
+ *   controllers. Due to the shipping firmware on the Jaguar, we can't run the
+ *   update period less than 5.05 ms.
+ *
+ * kDefaultPwmPeriod is the 1x period (5.05 ms).  In hardware, the period
+ * scaling is implemented as an output squelch to get longer periods for old
+ * devices.
+ */
+constexpr double kDefaultPwmPeriod = 5.05;
+/**
+ * kDefaultPwmCenter is the PWM range center in ms
+ */
+constexpr double kDefaultPwmCenter = 1.5;
+/**
+ * kDefaultPWMStepsDown is the number of PWM steps below the centerpoint
+ */
+constexpr int32_t kDefaultPwmStepsDown = 1000;
+constexpr int32_t kPwmDisabled = 0;
+
+extern std::unique_ptr<tDIO> digitalSystem;
+extern std::unique_ptr<tRelay> relaySystem;
+extern std::unique_ptr<tPWM> pwmSystem;
+extern std::unique_ptr<tSPI> spiSystem;
+
+struct DigitalPort {
+  uint8_t channel;
+  bool configSet = false;
+  bool eliminateDeadband = false;
+  int32_t maxPwm = 0;
+  int32_t deadbandMaxPwm = 0;
+  int32_t centerPwm = 0;
+  int32_t deadbandMinPwm = 0;
+  int32_t minPwm = 0;
+};
+
+extern DigitalHandleResource<HAL_DigitalHandle, DigitalPort,
+                             kNumDigitalChannels + kNumPWMHeaders>*
+    digitalChannelHandles;
+
+extern wpi::mutex digitalDIOMutex;
+
+/**
+ * Initialize the digital system.
+ */
+void initializeDigital(int32_t* status);
+
+/**
+ * remap the digital source channel and set the module.
+ * If it's an analog trigger, determine the module from the high order routing
+ * channel else do normal digital input remapping based on channel number
+ * (MXP)
+ */
+bool remapDigitalSource(HAL_Handle digitalSourceHandle,
+                        HAL_AnalogTriggerType analogTriggerType,
+                        uint8_t& channel, uint8_t& module, bool& analogTrigger);
+
+/**
+ * Map DIO channel numbers from their physical number (10 to 26) to their
+ * position in the bit field.
+ */
+int32_t remapMXPChannel(int32_t channel);
+
+int32_t remapMXPPWMChannel(int32_t channel);
+
+/**
+ * Map SPI channel numbers from their physical number (27 to 31) to their
+ * position in the bit field.
+ */
+int32_t remapSPIChannel(int32_t channel);
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Encoder.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Encoder.cpp
new file mode 100644
index 0000000..adf70ed
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Encoder.cpp
@@ -0,0 +1,462 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Encoder.h"
+
+#include "EncoderInternal.h"
+#include "FPGAEncoder.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/ChipObject.h"
+#include "hal/Counter.h"
+#include "hal/Errors.h"
+#include "hal/handles/LimitedClassedHandleResource.h"
+
+using namespace hal;
+
+Encoder::Encoder(HAL_Handle digitalSourceHandleA,
+                 HAL_AnalogTriggerType analogTriggerTypeA,
+                 HAL_Handle digitalSourceHandleB,
+                 HAL_AnalogTriggerType analogTriggerTypeB,
+                 bool reverseDirection, HAL_EncoderEncodingType encodingType,
+                 int32_t* status) {
+  m_encodingType = encodingType;
+  switch (encodingType) {
+    case HAL_Encoder_k4X: {
+      m_encodingScale = 4;
+      m_encoder = HAL_InitializeFPGAEncoder(
+          digitalSourceHandleA, analogTriggerTypeA, digitalSourceHandleB,
+          analogTriggerTypeB, reverseDirection, &m_index, status);
+      if (*status != 0) {
+        return;
+      }
+      m_counter = HAL_kInvalidHandle;
+      SetMaxPeriod(.5, status);
+      break;
+    }
+    case HAL_Encoder_k1X:
+    case HAL_Encoder_k2X: {
+      SetupCounter(digitalSourceHandleA, analogTriggerTypeA,
+                   digitalSourceHandleB, analogTriggerTypeB, reverseDirection,
+                   encodingType, status);
+
+      m_encodingScale = encodingType == HAL_Encoder_k1X ? 1 : 2;
+      break;
+    }
+    default:
+      *status = PARAMETER_OUT_OF_RANGE;
+      return;
+  }
+}
+
+void Encoder::SetupCounter(HAL_Handle digitalSourceHandleA,
+                           HAL_AnalogTriggerType analogTriggerTypeA,
+                           HAL_Handle digitalSourceHandleB,
+                           HAL_AnalogTriggerType analogTriggerTypeB,
+                           bool reverseDirection,
+                           HAL_EncoderEncodingType encodingType,
+                           int32_t* status) {
+  m_encodingScale = encodingType == HAL_Encoder_k1X ? 1 : 2;
+  m_counter =
+      HAL_InitializeCounter(HAL_Counter_kExternalDirection, &m_index, status);
+  if (*status != 0) return;
+  HAL_SetCounterMaxPeriod(m_counter, 0.5, status);
+  if (*status != 0) return;
+  HAL_SetCounterUpSource(m_counter, digitalSourceHandleA, analogTriggerTypeA,
+                         status);
+  if (*status != 0) return;
+  HAL_SetCounterDownSource(m_counter, digitalSourceHandleB, analogTriggerTypeB,
+                           status);
+  if (*status != 0) return;
+  if (encodingType == HAL_Encoder_k1X) {
+    HAL_SetCounterUpSourceEdge(m_counter, true, false, status);
+    HAL_SetCounterAverageSize(m_counter, 1, status);
+  } else {
+    HAL_SetCounterUpSourceEdge(m_counter, true, true, status);
+    HAL_SetCounterAverageSize(m_counter, 2, status);
+  }
+  HAL_SetCounterDownSourceEdge(m_counter, reverseDirection, true, status);
+}
+
+Encoder::~Encoder() {
+  if (m_counter != HAL_kInvalidHandle) {
+    int32_t status = 0;
+    HAL_FreeCounter(m_counter, &status);
+  } else {
+    int32_t status = 0;
+    HAL_FreeFPGAEncoder(m_encoder, &status);
+  }
+}
+
+// CounterBase interface
+int32_t Encoder::Get(int32_t* status) const {
+  return static_cast<int32_t>(GetRaw(status) * DecodingScaleFactor());
+}
+
+int32_t Encoder::GetRaw(int32_t* status) const {
+  if (m_counter) {
+    return HAL_GetCounter(m_counter, status);
+  } else {
+    return HAL_GetFPGAEncoder(m_encoder, status);
+  }
+}
+
+int32_t Encoder::GetEncodingScale(int32_t* status) const {
+  return m_encodingScale;
+}
+
+void Encoder::Reset(int32_t* status) {
+  if (m_counter) {
+    HAL_ResetCounter(m_counter, status);
+  } else {
+    HAL_ResetFPGAEncoder(m_encoder, status);
+  }
+}
+
+double Encoder::GetPeriod(int32_t* status) const {
+  if (m_counter) {
+    return HAL_GetCounterPeriod(m_counter, status) / DecodingScaleFactor();
+  } else {
+    return HAL_GetFPGAEncoderPeriod(m_encoder, status);
+  }
+}
+
+void Encoder::SetMaxPeriod(double maxPeriod, int32_t* status) {
+  if (m_counter) {
+    HAL_SetCounterMaxPeriod(m_counter, maxPeriod, status);
+  } else {
+    HAL_SetFPGAEncoderMaxPeriod(m_encoder, maxPeriod, status);
+  }
+}
+
+bool Encoder::GetStopped(int32_t* status) const {
+  if (m_counter) {
+    return HAL_GetCounterStopped(m_counter, status);
+  } else {
+    return HAL_GetFPGAEncoderStopped(m_encoder, status);
+  }
+}
+
+bool Encoder::GetDirection(int32_t* status) const {
+  if (m_counter) {
+    return HAL_GetCounterDirection(m_counter, status);
+  } else {
+    return HAL_GetFPGAEncoderDirection(m_encoder, status);
+  }
+}
+
+double Encoder::GetDistance(int32_t* status) const {
+  return GetRaw(status) * DecodingScaleFactor() * m_distancePerPulse;
+}
+
+double Encoder::GetRate(int32_t* status) const {
+  return m_distancePerPulse / GetPeriod(status);
+}
+
+void Encoder::SetMinRate(double minRate, int32_t* status) {
+  SetMaxPeriod(m_distancePerPulse / minRate, status);
+}
+
+void Encoder::SetDistancePerPulse(double distancePerPulse, int32_t* status) {
+  m_distancePerPulse = distancePerPulse;
+}
+
+void Encoder::SetReverseDirection(bool reverseDirection, int32_t* status) {
+  if (m_counter) {
+    HAL_SetCounterReverseDirection(m_counter, reverseDirection, status);
+  } else {
+    HAL_SetFPGAEncoderReverseDirection(m_encoder, reverseDirection, status);
+  }
+}
+
+void Encoder::SetSamplesToAverage(int32_t samplesToAverage, int32_t* status) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+  if (m_counter) {
+    HAL_SetCounterSamplesToAverage(m_counter, samplesToAverage, status);
+  } else {
+    HAL_SetFPGAEncoderSamplesToAverage(m_encoder, samplesToAverage, status);
+  }
+}
+
+int32_t Encoder::GetSamplesToAverage(int32_t* status) const {
+  if (m_counter) {
+    return HAL_GetCounterSamplesToAverage(m_counter, status);
+  } else {
+    return HAL_GetFPGAEncoderSamplesToAverage(m_encoder, status);
+  }
+}
+
+void Encoder::SetIndexSource(HAL_Handle digitalSourceHandle,
+                             HAL_AnalogTriggerType analogTriggerType,
+                             HAL_EncoderIndexingType type, int32_t* status) {
+  if (m_counter) {
+    *status = HAL_COUNTER_NOT_SUPPORTED;
+    return;
+  }
+  bool activeHigh =
+      (type == HAL_kResetWhileHigh) || (type == HAL_kResetOnRisingEdge);
+  bool edgeSensitive =
+      (type == HAL_kResetOnFallingEdge) || (type == HAL_kResetOnRisingEdge);
+  HAL_SetFPGAEncoderIndexSource(m_encoder, digitalSourceHandle,
+                                analogTriggerType, activeHigh, edgeSensitive,
+                                status);
+}
+
+double Encoder::DecodingScaleFactor() const {
+  switch (m_encodingType) {
+    case HAL_Encoder_k1X:
+      return 1.0;
+    case HAL_Encoder_k2X:
+      return 0.5;
+    case HAL_Encoder_k4X:
+      return 0.25;
+    default:
+      return 0.0;
+  }
+}
+
+static LimitedClassedHandleResource<HAL_EncoderHandle, Encoder,
+                                    kNumEncoders + kNumCounters,
+                                    HAL_HandleEnum::Encoder>* encoderHandles;
+
+namespace hal {
+namespace init {
+void InitializeEncoder() {
+  static LimitedClassedHandleResource<HAL_EncoderHandle, Encoder,
+                                      kNumEncoders + kNumCounters,
+                                      HAL_HandleEnum::Encoder>
+      eH;
+  encoderHandles = &eH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_EncoderHandle HAL_InitializeEncoder(
+    HAL_Handle digitalSourceHandleA, HAL_AnalogTriggerType analogTriggerTypeA,
+    HAL_Handle digitalSourceHandleB, HAL_AnalogTriggerType analogTriggerTypeB,
+    HAL_Bool reverseDirection, HAL_EncoderEncodingType encodingType,
+    int32_t* status) {
+  hal::init::CheckInit();
+  auto encoder = std::make_shared<Encoder>(
+      digitalSourceHandleA, analogTriggerTypeA, digitalSourceHandleB,
+      analogTriggerTypeB, reverseDirection, encodingType, status);
+  if (*status != 0) return HAL_kInvalidHandle;  // return in creation error
+  auto handle = encoderHandles->Allocate(encoder);
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  return handle;
+}
+
+void HAL_FreeEncoder(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  encoderHandles->Free(encoderHandle);
+}
+
+int32_t HAL_GetEncoder(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->Get(status);
+}
+
+int32_t HAL_GetEncoderRaw(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetRaw(status);
+}
+
+int32_t HAL_GetEncoderEncodingScale(HAL_EncoderHandle encoderHandle,
+                                    int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetEncodingScale(status);
+}
+
+void HAL_ResetEncoder(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->Reset(status);
+}
+
+double HAL_GetEncoderPeriod(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetPeriod(status);
+}
+
+void HAL_SetEncoderMaxPeriod(HAL_EncoderHandle encoderHandle, double maxPeriod,
+                             int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->SetMaxPeriod(maxPeriod, status);
+}
+
+HAL_Bool HAL_GetEncoderStopped(HAL_EncoderHandle encoderHandle,
+                               int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetStopped(status);
+}
+
+HAL_Bool HAL_GetEncoderDirection(HAL_EncoderHandle encoderHandle,
+                                 int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetDirection(status);
+}
+
+double HAL_GetEncoderDistance(HAL_EncoderHandle encoderHandle,
+                              int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetDistance(status);
+}
+
+double HAL_GetEncoderRate(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetRate(status);
+}
+
+void HAL_SetEncoderMinRate(HAL_EncoderHandle encoderHandle, double minRate,
+                           int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->SetMinRate(minRate, status);
+}
+
+void HAL_SetEncoderDistancePerPulse(HAL_EncoderHandle encoderHandle,
+                                    double distancePerPulse, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->SetDistancePerPulse(distancePerPulse, status);
+}
+
+void HAL_SetEncoderReverseDirection(HAL_EncoderHandle encoderHandle,
+                                    HAL_Bool reverseDirection,
+                                    int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->SetReverseDirection(reverseDirection, status);
+}
+
+void HAL_SetEncoderSamplesToAverage(HAL_EncoderHandle encoderHandle,
+                                    int32_t samplesToAverage, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->SetSamplesToAverage(samplesToAverage, status);
+}
+
+int32_t HAL_GetEncoderSamplesToAverage(HAL_EncoderHandle encoderHandle,
+                                       int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetSamplesToAverage(status);
+}
+
+double HAL_GetEncoderDecodingScaleFactor(HAL_EncoderHandle encoderHandle,
+                                         int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->DecodingScaleFactor();
+}
+
+double HAL_GetEncoderDistancePerPulse(HAL_EncoderHandle encoderHandle,
+                                      int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetDistancePerPulse();
+}
+
+HAL_EncoderEncodingType HAL_GetEncoderEncodingType(
+    HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_Encoder_k4X;  // default to k4X
+  }
+  return encoder->GetEncodingType();
+}
+
+void HAL_SetEncoderIndexSource(HAL_EncoderHandle encoderHandle,
+                               HAL_Handle digitalSourceHandle,
+                               HAL_AnalogTriggerType analogTriggerType,
+                               HAL_EncoderIndexingType type, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->SetIndexSource(digitalSourceHandle, analogTriggerType, type, status);
+}
+
+int32_t HAL_GetEncoderFPGAIndex(HAL_EncoderHandle encoderHandle,
+                                int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->GetFPGAIndex();
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/EncoderInternal.h b/third_party/allwpilib_2019/hal/src/main/native/athena/EncoderInternal.h
new file mode 100644
index 0000000..1e7ed4d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/EncoderInternal.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Encoder.h"
+
+namespace hal {
+
+class Encoder {
+ public:
+  Encoder(HAL_Handle digitalSourceHandleA,
+          HAL_AnalogTriggerType analogTriggerTypeA,
+          HAL_Handle digitalSourceHandleB,
+          HAL_AnalogTriggerType analogTriggerTypeB, bool reverseDirection,
+          HAL_EncoderEncodingType encodingType, int32_t* status);
+  ~Encoder();
+
+  // CounterBase interface
+  int32_t Get(int32_t* status) const;
+  int32_t GetRaw(int32_t* status) const;
+  int32_t GetEncodingScale(int32_t* status) const;
+  void Reset(int32_t* status);
+  double GetPeriod(int32_t* status) const;
+  void SetMaxPeriod(double maxPeriod, int32_t* status);
+  bool GetStopped(int32_t* status) const;
+  bool GetDirection(int32_t* status) const;
+
+  double GetDistance(int32_t* status) const;
+  double GetRate(int32_t* status) const;
+  void SetMinRate(double minRate, int32_t* status);
+  void SetDistancePerPulse(double distancePerPulse, int32_t* status);
+  void SetReverseDirection(bool reverseDirection, int32_t* status);
+  void SetSamplesToAverage(int32_t samplesToAverage, int32_t* status);
+  int32_t GetSamplesToAverage(int32_t* status) const;
+
+  void SetIndexSource(HAL_Handle digitalSourceHandle,
+                      HAL_AnalogTriggerType analogTriggerType,
+                      HAL_EncoderIndexingType type, int32_t* status);
+
+  int32_t GetFPGAIndex() const { return m_index; }
+
+  int32_t GetEncodingScale() const { return m_encodingScale; }
+
+  double DecodingScaleFactor() const;
+
+  double GetDistancePerPulse() const { return m_distancePerPulse; }
+
+  HAL_EncoderEncodingType GetEncodingType() const { return m_encodingType; }
+
+ private:
+  void SetupCounter(HAL_Handle digitalSourceHandleA,
+                    HAL_AnalogTriggerType analogTriggerTypeA,
+                    HAL_Handle digitalSourceHandleB,
+                    HAL_AnalogTriggerType analogTriggerTypeB,
+                    bool reverseDirection, HAL_EncoderEncodingType encodingType,
+                    int32_t* status);
+
+  HAL_FPGAEncoderHandle m_encoder = HAL_kInvalidHandle;
+
+  HAL_CounterHandle m_counter = HAL_kInvalidHandle;
+
+  int32_t m_index = 0;
+
+  double m_distancePerPulse = 1.0;
+
+  HAL_EncoderEncodingType m_encodingType;
+
+  int32_t m_encodingScale;
+};
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/FPGAEncoder.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/FPGAEncoder.cpp
new file mode 100644
index 0000000..7f2e107
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/FPGAEncoder.cpp
@@ -0,0 +1,245 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "FPGAEncoder.h"
+
+#include <memory>
+
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+using namespace hal;
+
+namespace {
+
+struct Encoder {
+  std::unique_ptr<tEncoder> encoder;
+  uint8_t index;
+};
+
+}  // namespace
+
+static constexpr double DECODING_SCALING_FACTOR = 0.25;
+
+static LimitedHandleResource<HAL_FPGAEncoderHandle, Encoder, kNumEncoders,
+                             HAL_HandleEnum::FPGAEncoder>* fpgaEncoderHandles;
+
+namespace hal {
+namespace init {
+void InitializeFPGAEncoder() {
+  static LimitedHandleResource<HAL_FPGAEncoderHandle, Encoder, kNumEncoders,
+                               HAL_HandleEnum::FPGAEncoder>
+      feH;
+  fpgaEncoderHandles = &feH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_FPGAEncoderHandle HAL_InitializeFPGAEncoder(
+    HAL_Handle digitalSourceHandleA, HAL_AnalogTriggerType analogTriggerTypeA,
+    HAL_Handle digitalSourceHandleB, HAL_AnalogTriggerType analogTriggerTypeB,
+    HAL_Bool reverseDirection, int32_t* index, int32_t* status) {
+  hal::init::CheckInit();
+  bool routingAnalogTriggerA = false;
+  uint8_t routingChannelA = 0;
+  uint8_t routingModuleA = 0;
+  bool successA = remapDigitalSource(digitalSourceHandleA, analogTriggerTypeA,
+                                     routingChannelA, routingModuleA,
+                                     routingAnalogTriggerA);
+  bool routingAnalogTriggerB = false;
+  uint8_t routingChannelB = 0;
+  uint8_t routingModuleB = 0;
+  bool successB = remapDigitalSource(digitalSourceHandleB, analogTriggerTypeB,
+                                     routingChannelB, routingModuleB,
+                                     routingAnalogTriggerB);
+
+  if (!successA || !successB) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  auto handle = fpgaEncoderHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {  // out of resources
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  auto encoder = fpgaEncoderHandles->Get(handle);
+  if (encoder == nullptr) {  // will only error on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  encoder->index = static_cast<uint8_t>(getHandleIndex(handle));
+  *index = encoder->index;
+  // TODO: if (index == ~0ul) { CloneError(quadEncoders); return; }
+  encoder->encoder.reset(tEncoder::create(encoder->index, status));
+  encoder->encoder->writeConfig_ASource_Module(routingModuleA, status);
+  encoder->encoder->writeConfig_ASource_Channel(routingChannelA, status);
+  encoder->encoder->writeConfig_ASource_AnalogTrigger(routingAnalogTriggerA,
+                                                      status);
+  encoder->encoder->writeConfig_BSource_Module(routingModuleB, status);
+  encoder->encoder->writeConfig_BSource_Channel(routingChannelB, status);
+  encoder->encoder->writeConfig_BSource_AnalogTrigger(routingAnalogTriggerB,
+                                                      status);
+  encoder->encoder->strobeReset(status);
+  encoder->encoder->writeConfig_Reverse(reverseDirection, status);
+  encoder->encoder->writeTimerConfig_AverageSize(4, status);
+
+  return handle;
+}
+
+void HAL_FreeFPGAEncoder(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                         int32_t* status) {
+  fpgaEncoderHandles->Free(fpgaEncoderHandle);
+}
+
+void HAL_ResetFPGAEncoder(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                          int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->encoder->strobeReset(status);
+}
+
+int32_t HAL_GetFPGAEncoder(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                           int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->encoder->readOutput_Value(status);
+}
+
+double HAL_GetFPGAEncoderPeriod(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+  tEncoder::tTimerOutput output = encoder->encoder->readTimerOutput(status);
+  double value;
+  if (output.Stalled) {
+    // Return infinity
+    double zero = 0.0;
+    value = 1.0 / zero;
+  } else {
+    // output.Period is a fixed point number that counts by 2 (24 bits, 25
+    // integer bits)
+    value = static_cast<double>(output.Period << 1) /
+            static_cast<double>(output.Count);
+  }
+  double measuredPeriod = value * 2.5e-8;
+  return measuredPeriod / DECODING_SCALING_FACTOR;
+}
+
+void HAL_SetFPGAEncoderMaxPeriod(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                 double maxPeriod, int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->encoder->writeTimerConfig_StallPeriod(
+      static_cast<uint32_t>(maxPeriod * 4.0e8 * DECODING_SCALING_FACTOR),
+      status);
+}
+
+HAL_Bool HAL_GetFPGAEncoderStopped(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                   int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  return encoder->encoder->readTimerOutput_Stalled(status) != 0;
+}
+
+HAL_Bool HAL_GetFPGAEncoderDirection(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                     int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  return encoder->encoder->readOutput_Direction(status);
+}
+
+void HAL_SetFPGAEncoderReverseDirection(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                        HAL_Bool reverseDirection,
+                                        int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  encoder->encoder->writeConfig_Reverse(reverseDirection, status);
+}
+
+void HAL_SetFPGAEncoderSamplesToAverage(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                        int32_t samplesToAverage,
+                                        int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    *status = PARAMETER_OUT_OF_RANGE;
+  }
+  encoder->encoder->writeTimerConfig_AverageSize(samplesToAverage, status);
+}
+
+int32_t HAL_GetFPGAEncoderSamplesToAverage(
+    HAL_FPGAEncoderHandle fpgaEncoderHandle, int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return encoder->encoder->readTimerConfig_AverageSize(status);
+}
+
+void HAL_SetFPGAEncoderIndexSource(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                   HAL_Handle digitalSourceHandle,
+                                   HAL_AnalogTriggerType analogTriggerType,
+                                   HAL_Bool activeHigh, HAL_Bool edgeSensitive,
+                                   int32_t* status) {
+  auto encoder = fpgaEncoderHandles->Get(fpgaEncoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  bool routingAnalogTrigger = false;
+  uint8_t routingChannel = 0;
+  uint8_t routingModule = 0;
+  bool success =
+      remapDigitalSource(digitalSourceHandle, analogTriggerType, routingChannel,
+                         routingModule, routingAnalogTrigger);
+  if (!success) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  encoder->encoder->writeConfig_IndexSource_Channel(routingChannel, status);
+  encoder->encoder->writeConfig_IndexSource_Module(routingModule, status);
+  encoder->encoder->writeConfig_IndexSource_AnalogTrigger(routingAnalogTrigger,
+                                                          status);
+  encoder->encoder->writeConfig_IndexActiveHigh(activeHigh, status);
+  encoder->encoder->writeConfig_IndexEdgeSensitive(edgeSensitive, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/FPGAEncoder.h b/third_party/allwpilib_2019/hal/src/main/native/athena/FPGAEncoder.h
new file mode 100644
index 0000000..f29aeae
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/FPGAEncoder.h
@@ -0,0 +1,126 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/AnalogTrigger.h"
+#include "hal/Types.h"
+
+extern "C" {
+
+HAL_FPGAEncoderHandle HAL_InitializeFPGAEncoder(
+    HAL_Handle digitalSourceHandleA, HAL_AnalogTriggerType analogTriggerTypeA,
+    HAL_Handle digitalSourceHandleB, HAL_AnalogTriggerType analogTriggerTypeB,
+    HAL_Bool reverseDirection, int32_t* index, int32_t* status);
+void HAL_FreeFPGAEncoder(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                         int32_t* status);
+
+/**
+ * Reset the Encoder distance to zero.
+ * Resets the current count to zero on the encoder.
+ */
+void HAL_ResetFPGAEncoder(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                          int32_t* status);
+
+/**
+ * Gets the fpga value from the encoder.
+ * The fpga value is the actual count unscaled by the 1x, 2x, or 4x scale
+ * factor.
+ * @return Current fpga count from the encoder
+ */
+int32_t HAL_GetFPGAEncoder(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                           int32_t* status);  // Raw value
+
+/**
+ * Returns the period of the most recent pulse.
+ * Returns the period of the most recent Encoder pulse in seconds.
+ * This method compenstates for the decoding type.
+ *
+ * @deprecated Use GetRate() in favor of this method.  This returns unscaled
+ * periods and GetRate() scales using value from SetDistancePerPulse().
+ *
+ * @return Period in seconds of the most recent pulse.
+ */
+double HAL_GetFPGAEncoderPeriod(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                int32_t* status);
+
+/**
+ * Sets the maximum period for stopped detection.
+ * Sets the value that represents the maximum period of the Encoder before it
+ * will assume that the attached device is stopped. This timeout allows users
+ * to determine if the wheels or other shaft has stopped rotating.
+ * This method compensates for the decoding type.
+ *
+ * @deprecated Use SetMinRate() in favor of this method.  This takes unscaled
+ * periods and SetMinRate() scales using value from SetDistancePerPulse().
+ *
+ * @param maxPeriod The maximum time between rising and falling edges before the
+ * FPGA will
+ * report the device stopped. This is expressed in seconds.
+ */
+void HAL_SetFPGAEncoderMaxPeriod(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                 double maxPeriod, int32_t* status);
+
+/**
+ * Determine if the encoder is stopped.
+ * Using the MaxPeriod value, a boolean is returned that is true if the encoder
+ * is considered stopped and false if it is still moving. A stopped encoder is
+ * one where the most recent pulse width exceeds the MaxPeriod.
+ * @return True if the encoder is considered stopped.
+ */
+HAL_Bool HAL_GetFPGAEncoderStopped(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                   int32_t* status);
+
+/**
+ * The last direction the encoder value changed.
+ * @return The last direction the encoder value changed.
+ */
+HAL_Bool HAL_GetFPGAEncoderDirection(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                     int32_t* status);
+
+/**
+ * Set the direction sensing for this encoder.
+ * This sets the direction sensing on the encoder so that it could count in the
+ * correct software direction regardless of the mounting.
+ * @param reverseDirection true if the encoder direction should be reversed
+ */
+void HAL_SetFPGAEncoderReverseDirection(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                        HAL_Bool reverseDirection,
+                                        int32_t* status);
+
+/**
+ * Set the Samples to Average which specifies the number of samples of the timer
+ * to average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @param samplesToAverage The number of samples to average from 1 to 127.
+ */
+void HAL_SetFPGAEncoderSamplesToAverage(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                        int32_t samplesToAverage,
+                                        int32_t* status);
+
+/**
+ * Get the Samples to Average which specifies the number of samples of the timer
+ * to average when calculating the period. Perform averaging to account for
+ * mechanical imperfections or as oversampling to increase resolution.
+ * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
+ */
+int32_t HAL_GetFPGAEncoderSamplesToAverage(
+    HAL_FPGAEncoderHandle fpgaEncoderHandle, int32_t* status);
+
+/**
+ * Set an index source for an encoder, which is an input that resets the
+ * encoder's count.
+ */
+void HAL_SetFPGAEncoderIndexSource(HAL_FPGAEncoderHandle fpgaEncoderHandle,
+                                   HAL_Handle digitalSourceHandle,
+                                   HAL_AnalogTriggerType analogTriggerType,
+                                   HAL_Bool activeHigh, HAL_Bool edgeSensitive,
+                                   int32_t* status);
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/FRCDriverStation.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/FRCDriverStation.cpp
new file mode 100644
index 0000000..5409ad0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/FRCDriverStation.cpp
@@ -0,0 +1,536 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <atomic>
+#include <chrono>
+#include <cstdlib>
+#include <cstring>
+#include <limits>
+
+#include <FRC_NetworkCommunication/FRCComm.h>
+#include <FRC_NetworkCommunication/NetCommRPCProxy_Occur.h>
+#include <wpi/SafeThread.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "hal/DriverStation.h"
+
+static_assert(sizeof(int32_t) >= sizeof(int),
+              "FRC_NetworkComm status variable is larger than 32 bits");
+
+struct HAL_JoystickAxesInt {
+  int16_t count;
+  int16_t axes[HAL_kMaxJoystickAxes];
+};
+
+static constexpr int kJoystickPorts = 6;
+
+// Joystick User Data
+static std::unique_ptr<HAL_JoystickAxes[]> m_joystickAxes;
+static std::unique_ptr<HAL_JoystickPOVs[]> m_joystickPOVs;
+static std::unique_ptr<HAL_JoystickButtons[]> m_joystickButtons;
+static std::unique_ptr<HAL_JoystickDescriptor[]> m_joystickDescriptor;
+static std::unique_ptr<HAL_MatchInfo> m_matchInfo;
+
+// Joystick Cached Data
+static std::unique_ptr<HAL_JoystickAxes[]> m_joystickAxesCache;
+static std::unique_ptr<HAL_JoystickPOVs[]> m_joystickPOVsCache;
+static std::unique_ptr<HAL_JoystickButtons[]> m_joystickButtonsCache;
+static std::unique_ptr<HAL_JoystickDescriptor[]> m_joystickDescriptorCache;
+static std::unique_ptr<HAL_MatchInfo> m_matchInfoCache;
+
+static wpi::mutex m_cacheDataMutex;
+
+// Control word variables
+static HAL_ControlWord m_controlWordCache;
+static std::chrono::steady_clock::time_point m_lastControlWordUpdate;
+static wpi::mutex m_controlWordMutex;
+
+// Message and Data variables
+static wpi::mutex msgMutex;
+
+static void InitializeDriverStationCaches() {
+  m_joystickAxes = std::make_unique<HAL_JoystickAxes[]>(kJoystickPorts);
+  m_joystickPOVs = std::make_unique<HAL_JoystickPOVs[]>(kJoystickPorts);
+  m_joystickButtons = std::make_unique<HAL_JoystickButtons[]>(kJoystickPorts);
+  m_joystickDescriptor =
+      std::make_unique<HAL_JoystickDescriptor[]>(kJoystickPorts);
+  m_matchInfo = std::make_unique<HAL_MatchInfo>();
+  m_joystickAxesCache = std::make_unique<HAL_JoystickAxes[]>(kJoystickPorts);
+  m_joystickPOVsCache = std::make_unique<HAL_JoystickPOVs[]>(kJoystickPorts);
+  m_joystickButtonsCache =
+      std::make_unique<HAL_JoystickButtons[]>(kJoystickPorts);
+  m_joystickDescriptorCache =
+      std::make_unique<HAL_JoystickDescriptor[]>(kJoystickPorts);
+  m_matchInfoCache = std::make_unique<HAL_MatchInfo>();
+
+  // 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_joystickAxes[i].count = 0;
+    m_joystickPOVs[i].count = 0;
+    m_joystickButtons[i].count = 0;
+    m_joystickDescriptor[i].isXbox = 0;
+    m_joystickDescriptor[i].type = -1;
+    m_joystickDescriptor[i].name[0] = '\0';
+
+    m_joystickAxesCache[i].count = 0;
+    m_joystickPOVsCache[i].count = 0;
+    m_joystickButtonsCache[i].count = 0;
+    m_joystickDescriptorCache[i].isXbox = 0;
+    m_joystickDescriptorCache[i].type = -1;
+    m_joystickDescriptorCache[i].name[0] = '\0';
+  }
+}
+
+static int32_t HAL_GetJoystickAxesInternal(int32_t joystickNum,
+                                           HAL_JoystickAxes* axes) {
+  HAL_JoystickAxesInt axesInt;
+
+  int retVal = FRC_NetworkCommunication_getJoystickAxes(
+      joystickNum, reinterpret_cast<JoystickAxes_t*>(&axesInt),
+      HAL_kMaxJoystickAxes);
+
+  // copy integer values to double values
+  axes->count = axesInt.count;
+  // current scaling is -128 to 127, can easily be patched in the future by
+  // changing this function.
+  for (int32_t i = 0; i < axesInt.count; i++) {
+    int8_t value = axesInt.axes[i];
+    if (value < 0) {
+      axes->axes[i] = value / 128.0;
+    } else {
+      axes->axes[i] = value / 127.0;
+    }
+  }
+
+  return retVal;
+}
+
+static int32_t HAL_GetJoystickPOVsInternal(int32_t joystickNum,
+                                           HAL_JoystickPOVs* povs) {
+  return FRC_NetworkCommunication_getJoystickPOVs(
+      joystickNum, reinterpret_cast<JoystickPOV_t*>(povs),
+      HAL_kMaxJoystickPOVs);
+}
+
+static int32_t HAL_GetJoystickButtonsInternal(int32_t joystickNum,
+                                              HAL_JoystickButtons* buttons) {
+  return FRC_NetworkCommunication_getJoystickButtons(
+      joystickNum, &buttons->buttons, &buttons->count);
+}
+/**
+ * Retrieve the Joystick Descriptor for particular slot
+ * @param desc [out] descriptor (data transfer object) to fill in.  desc is
+ * filled in regardless of success. In other words, if descriptor is not
+ * available, desc is filled in with default values matching the init-values in
+ * Java and C++ Driverstation for when caller requests a too-large joystick
+ * index.
+ *
+ * @return error code reported from Network Comm back-end.  Zero is good,
+ * nonzero is bad.
+ */
+static int32_t HAL_GetJoystickDescriptorInternal(int32_t joystickNum,
+                                                 HAL_JoystickDescriptor* desc) {
+  desc->isXbox = 0;
+  desc->type = std::numeric_limits<uint8_t>::max();
+  desc->name[0] = '\0';
+  desc->axisCount =
+      HAL_kMaxJoystickAxes; /* set to the desc->axisTypes's capacity */
+  desc->buttonCount = 0;
+  desc->povCount = 0;
+  int retval = FRC_NetworkCommunication_getJoystickDesc(
+      joystickNum, &desc->isXbox, &desc->type,
+      reinterpret_cast<char*>(&desc->name), &desc->axisCount,
+      reinterpret_cast<uint8_t*>(&desc->axisTypes), &desc->buttonCount,
+      &desc->povCount);
+  /* check the return, if there is an error and the RIOimage predates FRC2017,
+   * then axisCount needs to be cleared */
+  if (retval != 0) {
+    /* set count to zero so downstream code doesn't decode invalid axisTypes. */
+    desc->axisCount = 0;
+  }
+  return retval;
+}
+
+static int32_t HAL_GetControlWordInternal(HAL_ControlWord* controlWord) {
+  std::memset(controlWord, 0, sizeof(HAL_ControlWord));
+  return FRC_NetworkCommunication_getControlWord(
+      reinterpret_cast<ControlWord_t*>(controlWord));
+}
+
+static int32_t HAL_GetMatchInfoInternal(HAL_MatchInfo* info) {
+  MatchType_t matchType = MatchType_t::kMatchType_none;
+  int status = FRC_NetworkCommunication_getMatchInfo(
+      info->eventName, &matchType, &info->matchNumber, &info->replayNumber,
+      info->gameSpecificMessage, &info->gameSpecificMessageSize);
+
+  info->matchType = static_cast<HAL_MatchType>(matchType);
+
+  *(std::end(info->eventName) - 1) = '\0';
+
+  return status;
+}
+
+static void UpdateDriverStationControlWord(bool force,
+                                           HAL_ControlWord& controlWord) {
+  auto now = std::chrono::steady_clock::now();
+  std::lock_guard<wpi::mutex> lock(m_controlWordMutex);
+  // Update every 50 ms or on force.
+  if ((now - m_lastControlWordUpdate > std::chrono::milliseconds(50)) ||
+      force) {
+    HAL_GetControlWordInternal(&m_controlWordCache);
+    m_lastControlWordUpdate = now;
+  }
+  controlWord = m_controlWordCache;
+}
+
+static void UpdateDriverStationDataCaches() {
+  // Get the status of all of the joysticks, and save to the cache
+  for (uint8_t stick = 0; stick < kJoystickPorts; stick++) {
+    HAL_GetJoystickAxesInternal(stick, &m_joystickAxesCache[stick]);
+    HAL_GetJoystickPOVsInternal(stick, &m_joystickPOVsCache[stick]);
+    HAL_GetJoystickButtonsInternal(stick, &m_joystickButtonsCache[stick]);
+    HAL_GetJoystickDescriptorInternal(stick, &m_joystickDescriptorCache[stick]);
+  }
+  // Grab match specific data
+  HAL_GetMatchInfoInternal(m_matchInfoCache.get());
+
+  // Force a control word update, to make sure the data is the newest.
+  HAL_ControlWord controlWord;
+  UpdateDriverStationControlWord(true, controlWord);
+
+  {
+    // Obtain a lock on the data, swap the cached data into the main data arrays
+    std::lock_guard<wpi::mutex> lock(m_cacheDataMutex);
+
+    m_joystickAxes.swap(m_joystickAxesCache);
+    m_joystickPOVs.swap(m_joystickPOVsCache);
+    m_joystickButtons.swap(m_joystickButtonsCache);
+    m_joystickDescriptor.swap(m_joystickDescriptorCache);
+    m_matchInfo.swap(m_matchInfoCache);
+  }
+}
+
+class DriverStationThread : public wpi::SafeThread {
+ public:
+  void Main() {
+    std::unique_lock<wpi::mutex> lock(m_mutex);
+    while (m_active) {
+      m_cond.wait(lock, [&] { return !m_active || m_notify; });
+      if (!m_active) break;
+      m_notify = false;
+
+      lock.unlock();
+      UpdateDriverStationDataCaches();
+      lock.lock();
+
+      // Notify all threads
+      newDSDataAvailableCounter++;
+      newDSDataAvailableCond.notify_all();
+    }
+
+    // Notify waiters on thread exit
+    newDSDataAvailableCounter++;
+    newDSDataAvailableCond.notify_all();
+  }
+
+  bool m_notify = false;
+  wpi::condition_variable newDSDataAvailableCond;
+  int newDSDataAvailableCounter{0};
+};
+
+class DriverStationThreadOwner
+    : public wpi::SafeThreadOwner<DriverStationThread> {
+ public:
+  void Notify() {
+    auto thr = GetThread();
+    if (!thr) return;
+    thr->m_notify = true;
+    thr->m_cond.notify_one();
+  }
+};
+
+static std::unique_ptr<DriverStationThreadOwner> dsThread = nullptr;
+
+namespace hal {
+namespace init {
+void InitializeFRCDriverStation() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+int32_t HAL_SendError(HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode,
+                      const char* details, const char* location,
+                      const char* callStack, HAL_Bool printMsg) {
+  // Avoid flooding console by keeping track of previous 5 error
+  // messages and only printing again if they're longer than 1 second old.
+  static constexpr int KEEP_MSGS = 5;
+  std::lock_guard<wpi::mutex> lock(msgMutex);
+  static std::string prevMsg[KEEP_MSGS];
+  static std::chrono::time_point<std::chrono::steady_clock>
+      prevMsgTime[KEEP_MSGS];
+  static bool initialized = false;
+  if (!initialized) {
+    for (int i = 0; i < KEEP_MSGS; i++) {
+      prevMsgTime[i] =
+          std::chrono::steady_clock::now() - std::chrono::seconds(2);
+    }
+    initialized = true;
+  }
+
+  auto curTime = std::chrono::steady_clock::now();
+  int i;
+  for (i = 0; i < KEEP_MSGS; ++i) {
+    if (prevMsg[i] == details) break;
+  }
+  int retval = 0;
+  if (i == KEEP_MSGS || (curTime - prevMsgTime[i]) >= std::chrono::seconds(1)) {
+    retval = FRC_NetworkCommunication_sendError(isError, errorCode, isLVCode,
+                                                details, location, callStack);
+    if (printMsg) {
+      if (location && location[0] != '\0') {
+        wpi::errs() << (isError ? "Error" : "Warning") << " at " << location
+                    << ": ";
+      }
+      wpi::errs() << details << "\n";
+      if (callStack && callStack[0] != '\0') {
+        wpi::errs() << callStack << "\n";
+      }
+    }
+    if (i == KEEP_MSGS) {
+      // replace the oldest one
+      i = 0;
+      auto first = prevMsgTime[0];
+      for (int j = 1; j < KEEP_MSGS; ++j) {
+        if (prevMsgTime[j] < first) {
+          first = prevMsgTime[j];
+          i = j;
+        }
+      }
+      prevMsg[i] = details;
+    }
+    prevMsgTime[i] = curTime;
+  }
+  return retval;
+}
+
+int32_t HAL_GetControlWord(HAL_ControlWord* controlWord) {
+  std::memset(controlWord, 0, sizeof(HAL_ControlWord));
+  UpdateDriverStationControlWord(false, *controlWord);
+  return 0;
+}
+
+int32_t HAL_GetJoystickAxes(int32_t joystickNum, HAL_JoystickAxes* axes) {
+  std::unique_lock<wpi::mutex> lock(m_cacheDataMutex);
+  *axes = m_joystickAxes[joystickNum];
+  return 0;
+}
+
+int32_t HAL_GetJoystickPOVs(int32_t joystickNum, HAL_JoystickPOVs* povs) {
+  std::unique_lock<wpi::mutex> lock(m_cacheDataMutex);
+  *povs = m_joystickPOVs[joystickNum];
+  return 0;
+}
+
+int32_t HAL_GetJoystickButtons(int32_t joystickNum,
+                               HAL_JoystickButtons* buttons) {
+  std::unique_lock<wpi::mutex> lock(m_cacheDataMutex);
+  *buttons = m_joystickButtons[joystickNum];
+  return 0;
+}
+
+int32_t HAL_GetJoystickDescriptor(int32_t joystickNum,
+                                  HAL_JoystickDescriptor* desc) {
+  std::unique_lock<wpi::mutex> lock(m_cacheDataMutex);
+  *desc = m_joystickDescriptor[joystickNum];
+  return 0;
+}
+
+int32_t HAL_GetMatchInfo(HAL_MatchInfo* info) {
+  std::unique_lock<wpi::mutex> lock(m_cacheDataMutex);
+  *info = *m_matchInfo;
+  return 0;
+}
+
+HAL_AllianceStationID HAL_GetAllianceStation(int32_t* status) {
+  HAL_AllianceStationID allianceStation;
+  *status = FRC_NetworkCommunication_getAllianceStation(
+      reinterpret_cast<AllianceStationID_t*>(&allianceStation));
+  return allianceStation;
+}
+
+HAL_Bool HAL_GetJoystickIsXbox(int32_t joystickNum) {
+  HAL_JoystickDescriptor joystickDesc;
+  if (HAL_GetJoystickDescriptor(joystickNum, &joystickDesc) < 0) {
+    return 0;
+  } else {
+    return joystickDesc.isXbox;
+  }
+}
+
+int32_t HAL_GetJoystickType(int32_t joystickNum) {
+  HAL_JoystickDescriptor joystickDesc;
+  if (HAL_GetJoystickDescriptor(joystickNum, &joystickDesc) < 0) {
+    return -1;
+  } else {
+    return joystickDesc.type;
+  }
+}
+
+char* HAL_GetJoystickName(int32_t joystickNum) {
+  HAL_JoystickDescriptor joystickDesc;
+  if (HAL_GetJoystickDescriptor(joystickNum, &joystickDesc) < 0) {
+    char* name = static_cast<char*>(std::malloc(1));
+    name[0] = '\0';
+    return name;
+  } else {
+    size_t len = std::strlen(joystickDesc.name);
+    char* name = static_cast<char*>(std::malloc(len + 1));
+    std::strncpy(name, joystickDesc.name, len);
+    name[len] = '\0';
+    return name;
+  }
+}
+
+void HAL_FreeJoystickName(char* name) { std::free(name); }
+
+int32_t HAL_GetJoystickAxisType(int32_t joystickNum, int32_t axis) {
+  HAL_JoystickDescriptor joystickDesc;
+  if (HAL_GetJoystickDescriptor(joystickNum, &joystickDesc) < 0) {
+    return -1;
+  } else {
+    return joystickDesc.axisTypes[axis];
+  }
+}
+
+int32_t HAL_SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
+                               int32_t leftRumble, int32_t rightRumble) {
+  return FRC_NetworkCommunication_setJoystickOutputs(joystickNum, outputs,
+                                                     leftRumble, rightRumble);
+}
+
+double HAL_GetMatchTime(int32_t* status) {
+  float matchTime;
+  *status = FRC_NetworkCommunication_getMatchTime(&matchTime);
+  return matchTime;
+}
+
+void HAL_ObserveUserProgramStarting(void) {
+  FRC_NetworkCommunication_observeUserProgramStarting();
+}
+
+void HAL_ObserveUserProgramDisabled(void) {
+  FRC_NetworkCommunication_observeUserProgramDisabled();
+}
+
+void HAL_ObserveUserProgramAutonomous(void) {
+  FRC_NetworkCommunication_observeUserProgramAutonomous();
+}
+
+void HAL_ObserveUserProgramTeleop(void) {
+  FRC_NetworkCommunication_observeUserProgramTeleop();
+}
+
+void HAL_ObserveUserProgramTest(void) {
+  FRC_NetworkCommunication_observeUserProgramTest();
+}
+
+HAL_Bool HAL_IsNewControlData(void) {
+  // 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
+  // 20ms rate occurs once every 2.7 years of DS connected runtime, so not
+  // worth the cycles to check.
+  thread_local int lastCount{-1};
+  if (!dsThread) return false;
+  auto thr = dsThread->GetThread();
+  if (!thr) return false;
+  int currentCount = thr->newDSDataAvailableCounter;
+  if (lastCount == currentCount) return false;
+  lastCount = currentCount;
+  return true;
+}
+
+/**
+ * Waits for the newest DS packet to arrive. Note that this is a blocking call.
+ */
+void HAL_WaitForDSData(void) { HAL_WaitForDSDataTimeout(0); }
+
+/**
+ * Waits for the newest DS packet to arrive. If timeout is <= 0, this will wait
+ * forever. Otherwise, it will wait until either a new packet, or the timeout
+ * time has passed. Returns true on new data, false on timeout.
+ */
+HAL_Bool HAL_WaitForDSDataTimeout(double timeout) {
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+
+  if (!dsThread) return false;
+  auto thr = dsThread->GetThread();
+  if (!thr) return false;
+  int currentCount = thr->newDSDataAvailableCounter;
+  while (thr->newDSDataAvailableCounter == currentCount) {
+    if (timeout > 0) {
+      auto timedOut =
+          thr->newDSDataAvailableCond.wait_until(thr.GetLock(), timeoutTime);
+      if (timedOut == std::cv_status::timeout) {
+        return false;
+      }
+    } else {
+      thr->newDSDataAvailableCond.wait(thr.GetLock());
+    }
+  }
+  return true;
+}
+
+// Constant number to be used for our occur handle
+constexpr int32_t refNumber = 42;
+
+static void newDataOccur(uint32_t refNum) {
+  // Since we could get other values, require our specific handle
+  // to signal our threads
+  if (refNum != refNumber) return;
+  dsThread->Notify();
+}
+
+/*
+ * Call this to initialize the driver station communication. This will properly
+ * handle multiple calls. However note that this CANNOT be called from a library
+ * that interfaces with LabVIEW.
+ */
+void HAL_InitializeDriverStation(void) {
+  static std::atomic_bool initialized{false};
+  static wpi::mutex initializeMutex;
+  // Initial check, as if it's true initialization has finished
+  if (initialized) return;
+
+  std::lock_guard<wpi::mutex> lock(initializeMutex);
+  // Second check in case another thread was waiting
+  if (initialized) return;
+
+  InitializeDriverStationCaches();
+
+  dsThread = std::make_unique<DriverStationThreadOwner>();
+  dsThread->Start();
+
+  // Set up the occur function internally with NetComm
+  NetCommRPCProxy_SetOccurFuncPointer(newDataOccur);
+  // Set up our occur reference number
+  setNewDataOccurRef(refNumber);
+
+  initialized = true;
+}
+
+/*
+ * Releases the DS Mutex to allow proper shutdown of any threads that are
+ * waiting on it.
+ */
+void HAL_ReleaseDSMutex(void) { newDataOccur(refNumber); }
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/HAL.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/HAL.cpp
new file mode 100644
index 0000000..dbdb826
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/HAL.cpp
@@ -0,0 +1,410 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/HAL.h"
+
+#include <signal.h>  // linux for kill
+#include <sys/prctl.h>
+#include <unistd.h>
+
+#include <atomic>
+#include <cstdlib>
+#include <fstream>
+#include <thread>
+
+#include <FRC_NetworkCommunication/FRCComm.h>
+#include <FRC_NetworkCommunication/LoadOut.h>
+#include <FRC_NetworkCommunication/UsageReporting.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/timestamp.h>
+
+#include "HALInitializer.h"
+#include "ctre/ctre.h"
+#include "hal/ChipObject.h"
+#include "hal/DriverStation.h"
+#include "hal/Errors.h"
+#include "hal/Notifier.h"
+#include "hal/handles/HandlesInternal.h"
+#include "visa/visa.h"
+
+using namespace hal;
+
+static std::unique_ptr<tGlobal> global;
+static std::unique_ptr<tSysWatchdog> watchdog;
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeHAL() {
+  InitializeAccelerometer();
+  InitializeAnalogAccumulator();
+  InitializeAnalogGyro();
+  InitializeAnalogInput();
+  InitializeAnalogInternal();
+  InitializeAnalogOutput();
+  InitializeAnalogTrigger();
+  InitializeCAN();
+  InitializeCANAPI();
+  InitializeCompressor();
+  InitializeConstants();
+  InitializeCounter();
+  InitializeDigitalInternal();
+  InitializeDIO();
+  InitializeEncoder();
+  InitializeFPGAEncoder();
+  InitializeFRCDriverStation();
+  InitializeI2C();
+  InitialzeInterrupts();
+  InitializeNotifier();
+  InitializePCMInternal();
+  InitializePDP();
+  InitializePorts();
+  InitializePower();
+  InitializePWM();
+  InitializeRelay();
+  InitializeSerialPort();
+  InitializeSolenoid();
+  InitializeSPI();
+  InitializeThreads();
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_PortHandle HAL_GetPort(int32_t channel) {
+  // Dont allow a number that wouldn't fit in a uint8_t
+  if (channel < 0 || channel >= 255) return HAL_kInvalidHandle;
+  return createPortHandle(channel, 1);
+}
+
+HAL_PortHandle HAL_GetPortWithModule(int32_t module, int32_t channel) {
+  // Dont allow a number that wouldn't fit in a uint8_t
+  if (channel < 0 || channel >= 255) return HAL_kInvalidHandle;
+  if (module < 0 || module >= 255) return HAL_kInvalidHandle;
+  return createPortHandle(channel, module);
+}
+
+const char* HAL_GetErrorMessage(int32_t code) {
+  switch (code) {
+    case 0:
+      return "";
+    case CTR_RxTimeout:
+      return CTR_RxTimeout_MESSAGE;
+    case CTR_TxTimeout:
+      return CTR_TxTimeout_MESSAGE;
+    case CTR_InvalidParamValue:
+      return CTR_InvalidParamValue_MESSAGE;
+    case CTR_UnexpectedArbId:
+      return CTR_UnexpectedArbId_MESSAGE;
+    case CTR_TxFailed:
+      return CTR_TxFailed_MESSAGE;
+    case CTR_SigNotUpdated:
+      return CTR_SigNotUpdated_MESSAGE;
+    case NiFpga_Status_FifoTimeout:
+      return NiFpga_Status_FifoTimeout_MESSAGE;
+    case NiFpga_Status_TransferAborted:
+      return NiFpga_Status_TransferAborted_MESSAGE;
+    case NiFpga_Status_MemoryFull:
+      return NiFpga_Status_MemoryFull_MESSAGE;
+    case NiFpga_Status_SoftwareFault:
+      return NiFpga_Status_SoftwareFault_MESSAGE;
+    case NiFpga_Status_InvalidParameter:
+      return NiFpga_Status_InvalidParameter_MESSAGE;
+    case NiFpga_Status_ResourceNotFound:
+      return NiFpga_Status_ResourceNotFound_MESSAGE;
+    case NiFpga_Status_ResourceNotInitialized:
+      return NiFpga_Status_ResourceNotInitialized_MESSAGE;
+    case NiFpga_Status_HardwareFault:
+      return NiFpga_Status_HardwareFault_MESSAGE;
+    case NiFpga_Status_IrqTimeout:
+      return NiFpga_Status_IrqTimeout_MESSAGE;
+    case SAMPLE_RATE_TOO_HIGH:
+      return SAMPLE_RATE_TOO_HIGH_MESSAGE;
+    case VOLTAGE_OUT_OF_RANGE:
+      return VOLTAGE_OUT_OF_RANGE_MESSAGE;
+    case LOOP_TIMING_ERROR:
+      return LOOP_TIMING_ERROR_MESSAGE;
+    case SPI_WRITE_NO_MOSI:
+      return SPI_WRITE_NO_MOSI_MESSAGE;
+    case SPI_READ_NO_MISO:
+      return SPI_READ_NO_MISO_MESSAGE;
+    case SPI_READ_NO_DATA:
+      return SPI_READ_NO_DATA_MESSAGE;
+    case INCOMPATIBLE_STATE:
+      return INCOMPATIBLE_STATE_MESSAGE;
+    case NO_AVAILABLE_RESOURCES:
+      return NO_AVAILABLE_RESOURCES_MESSAGE;
+    case RESOURCE_IS_ALLOCATED:
+      return RESOURCE_IS_ALLOCATED_MESSAGE;
+    case RESOURCE_OUT_OF_RANGE:
+      return RESOURCE_OUT_OF_RANGE_MESSAGE;
+    case HAL_INVALID_ACCUMULATOR_CHANNEL:
+      return HAL_INVALID_ACCUMULATOR_CHANNEL_MESSAGE;
+    case HAL_HANDLE_ERROR:
+      return HAL_HANDLE_ERROR_MESSAGE;
+    case NULL_PARAMETER:
+      return NULL_PARAMETER_MESSAGE;
+    case ANALOG_TRIGGER_LIMIT_ORDER_ERROR:
+      return ANALOG_TRIGGER_LIMIT_ORDER_ERROR_MESSAGE;
+    case ANALOG_TRIGGER_PULSE_OUTPUT_ERROR:
+      return ANALOG_TRIGGER_PULSE_OUTPUT_ERROR_MESSAGE;
+    case PARAMETER_OUT_OF_RANGE:
+      return PARAMETER_OUT_OF_RANGE_MESSAGE;
+    case HAL_COUNTER_NOT_SUPPORTED:
+      return HAL_COUNTER_NOT_SUPPORTED_MESSAGE;
+    case HAL_ERR_CANSessionMux_InvalidBuffer:
+      return ERR_CANSessionMux_InvalidBuffer_MESSAGE;
+    case HAL_ERR_CANSessionMux_MessageNotFound:
+      return ERR_CANSessionMux_MessageNotFound_MESSAGE;
+    case HAL_WARN_CANSessionMux_NoToken:
+      return WARN_CANSessionMux_NoToken_MESSAGE;
+    case HAL_ERR_CANSessionMux_NotAllowed:
+      return ERR_CANSessionMux_NotAllowed_MESSAGE;
+    case HAL_ERR_CANSessionMux_NotInitialized:
+      return ERR_CANSessionMux_NotInitialized_MESSAGE;
+    case VI_ERROR_SYSTEM_ERROR:
+      return VI_ERROR_SYSTEM_ERROR_MESSAGE;
+    case VI_ERROR_INV_OBJECT:
+      return VI_ERROR_INV_OBJECT_MESSAGE;
+    case VI_ERROR_RSRC_LOCKED:
+      return VI_ERROR_RSRC_LOCKED_MESSAGE;
+    case VI_ERROR_RSRC_NFOUND:
+      return VI_ERROR_RSRC_NFOUND_MESSAGE;
+    case VI_ERROR_INV_RSRC_NAME:
+      return VI_ERROR_INV_RSRC_NAME_MESSAGE;
+    case VI_ERROR_QUEUE_OVERFLOW:
+      return VI_ERROR_QUEUE_OVERFLOW_MESSAGE;
+    case VI_ERROR_IO:
+      return VI_ERROR_IO_MESSAGE;
+    case VI_ERROR_ASRL_PARITY:
+      return VI_ERROR_ASRL_PARITY_MESSAGE;
+    case VI_ERROR_ASRL_FRAMING:
+      return VI_ERROR_ASRL_FRAMING_MESSAGE;
+    case VI_ERROR_ASRL_OVERRUN:
+      return VI_ERROR_ASRL_OVERRUN_MESSAGE;
+    case VI_ERROR_RSRC_BUSY:
+      return VI_ERROR_RSRC_BUSY_MESSAGE;
+    case VI_ERROR_INV_PARAMETER:
+      return VI_ERROR_INV_PARAMETER_MESSAGE;
+    case HAL_PWM_SCALE_ERROR:
+      return HAL_PWM_SCALE_ERROR_MESSAGE;
+    case HAL_SERIAL_PORT_NOT_FOUND:
+      return HAL_SERIAL_PORT_NOT_FOUND_MESSAGE;
+    case HAL_THREAD_PRIORITY_ERROR:
+      return HAL_THREAD_PRIORITY_ERROR_MESSAGE;
+    case HAL_THREAD_PRIORITY_RANGE_ERROR:
+      return HAL_THREAD_PRIORITY_RANGE_ERROR_MESSAGE;
+    case HAL_SERIAL_PORT_OPEN_ERROR:
+      return HAL_SERIAL_PORT_OPEN_ERROR_MESSAGE;
+    case HAL_SERIAL_PORT_ERROR:
+      return HAL_SERIAL_PORT_ERROR_MESSAGE;
+    case HAL_CAN_TIMEOUT:
+      return HAL_CAN_TIMEOUT_MESSAGE;
+    case ERR_FRCSystem_NetCommNotResponding:
+      return ERR_FRCSystem_NetCommNotResponding_MESSAGE;
+    case ERR_FRCSystem_NoDSConnection:
+      return ERR_FRCSystem_NoDSConnection_MESSAGE;
+    default:
+      return "Unknown error status";
+  }
+}
+
+HAL_RuntimeType HAL_GetRuntimeType(void) { return HAL_Athena; }
+
+int32_t HAL_GetFPGAVersion(int32_t* status) {
+  if (!global) {
+    *status = NiFpga_Status_ResourceNotInitialized;
+    return 0;
+  }
+  return global->readVersion(status);
+}
+
+int64_t HAL_GetFPGARevision(int32_t* status) {
+  if (!global) {
+    *status = NiFpga_Status_ResourceNotInitialized;
+    return 0;
+  }
+  return global->readRevision(status);
+}
+
+uint64_t HAL_GetFPGATime(int32_t* status) {
+  if (!global) {
+    *status = NiFpga_Status_ResourceNotInitialized;
+    return 0;
+  }
+  *status = 0;
+  uint64_t upper1 = global->readLocalTimeUpper(status);
+  uint32_t lower = global->readLocalTime(status);
+  uint64_t upper2 = global->readLocalTimeUpper(status);
+  if (*status != 0) return 0;
+  if (upper1 != upper2) {
+    // Rolled over between the lower call, reread lower
+    lower = global->readLocalTime(status);
+    if (*status != 0) return 0;
+  }
+  return (upper2 << 32) + lower;
+}
+
+HAL_Bool HAL_GetFPGAButton(int32_t* status) {
+  if (!global) {
+    *status = NiFpga_Status_ResourceNotInitialized;
+    return false;
+  }
+  return global->readUserButton(status);
+}
+
+HAL_Bool HAL_GetSystemActive(int32_t* status) {
+  if (!watchdog) {
+    *status = NiFpga_Status_ResourceNotInitialized;
+    return false;
+  }
+  return watchdog->readStatus_SystemActive(status);
+}
+
+HAL_Bool HAL_GetBrownedOut(int32_t* status) {
+  if (!watchdog) {
+    *status = NiFpga_Status_ResourceNotInitialized;
+    return false;
+  }
+  return !(watchdog->readStatus_PowerAlive(status));
+}
+
+void HAL_BaseInitialize(int32_t* status) {
+  static std::atomic_bool initialized{false};
+  static wpi::mutex initializeMutex;
+  // Initial check, as if it's true initialization has finished
+  if (initialized) return;
+
+  std::lock_guard<wpi::mutex> lock(initializeMutex);
+  // Second check in case another thread was waiting
+  if (initialized) return;
+  // image 4; Fixes errors caused by multiple processes. Talk to NI about this
+  nFPGA::nRoboRIO_FPGANamespace::g_currentTargetClass =
+      nLoadOut::kTargetClass_RoboRIO;
+
+  global.reset(tGlobal::create(status));
+  watchdog.reset(tSysWatchdog::create(status));
+  initialized = true;
+}
+
+static bool killExistingProgram(int timeout, int mode) {
+  // Kill any previous robot programs
+  std::fstream fs;
+  // By making this both in/out, it won't give us an error if it doesnt exist
+  fs.open("/var/lock/frc.pid", std::fstream::in | std::fstream::out);
+  if (fs.bad()) return false;
+
+  pid_t pid = 0;
+  if (!fs.eof() && !fs.fail()) {
+    fs >> pid;
+    // see if the pid is around, but we don't want to mess with init id=1, or
+    // ourselves
+    if (pid >= 2 && kill(pid, 0) == 0 && pid != getpid()) {
+      wpi::outs() << "Killing previously running FRC program...\n";
+      kill(pid, SIGTERM);  // try to kill it
+      std::this_thread::sleep_for(std::chrono::milliseconds(timeout));
+      if (kill(pid, 0) == 0) {
+        // still not successfull
+        wpi::outs() << "FRC pid " << pid << " did not die within " << timeout
+                    << "ms. Force killing with kill -9\n";
+        // Force kill -9
+        auto forceKill = kill(pid, SIGKILL);
+        if (forceKill != 0) {
+          auto errorMsg = std::strerror(forceKill);
+          wpi::outs() << "Kill -9 error: " << errorMsg << "\n";
+        }
+        // Give a bit of time for the kill to take place
+        std::this_thread::sleep_for(std::chrono::milliseconds(250));
+      }
+    }
+  }
+  fs.close();
+  // we will re-open it write only to truncate the file
+  fs.open("/var/lock/frc.pid", std::fstream::out | std::fstream::trunc);
+  fs.seekp(0);
+  pid = getpid();
+  fs << pid << std::endl;
+  fs.close();
+  return true;
+}
+
+HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) {
+  static std::atomic_bool initialized{false};
+  static wpi::mutex initializeMutex;
+  // Initial check, as if it's true initialization has finished
+  if (initialized) return true;
+
+  std::lock_guard<wpi::mutex> lock(initializeMutex);
+  // Second check in case another thread was waiting
+  if (initialized) return true;
+
+  hal::init::InitializeHAL();
+
+  hal::init::HAL_IsInitialized.store(true);
+
+  setlinebuf(stdin);
+  setlinebuf(stdout);
+  wpi::outs().SetUnbuffered();
+
+  prctl(PR_SET_PDEATHSIG, SIGTERM);
+
+  // Return false if program failed to kill an existing program
+  if (!killExistingProgram(timeout, mode)) {
+    return false;
+  }
+
+  FRC_NetworkCommunication_Reserve(nullptr);
+
+  std::atexit([]() {
+    // Unregister our new data condition variable.
+    setNewDataSem(nullptr);
+  });
+
+  int32_t status = 0;
+  HAL_BaseInitialize(&status);
+  if (status != 0) return false;
+
+  HAL_InitializeDriverStation();
+
+  // Set WPI_Now to use FPGA timestamp
+  wpi::SetNowImpl([]() -> uint64_t {
+    int32_t status = 0;
+    uint64_t rv = HAL_GetFPGATime(&status);
+    if (status != 0) {
+      wpi::errs()
+          << "Call to HAL_GetFPGATime failed."
+          << "Initialization might have failed. Time will not be correct\n";
+      wpi::errs().flush();
+      return 0u;
+    }
+    return rv;
+  });
+
+  initialized = true;
+  return true;
+}
+
+int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context,
+                   const char* feature) {
+  if (feature == nullptr) {
+    feature = "";
+  }
+
+  return FRC_NetworkCommunication_nUsageReporting_report(
+      resource, instanceNumber, context, feature);
+}
+
+// TODO: HACKS
+// No need for header definitions, as we should not run from user code.
+void NumericArrayResize(void) {}
+void RTSetCleanupProc(void) {}
+void EDVR_CreateReference(void) {}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/HALInitializer.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/HALInitializer.cpp
new file mode 100644
index 0000000..a0456d4
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/HALInitializer.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HALInitializer.h"
+
+#include "hal/HAL.h"
+
+namespace hal {
+namespace init {
+std::atomic_bool HAL_IsInitialized{false};
+void RunInitialize() { HAL_Initialize(500, 0); }
+}  // namespace init
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/HALInitializer.h b/third_party/allwpilib_2019/hal/src/main/native/athena/HALInitializer.h
new file mode 100644
index 0000000..384fe58
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/HALInitializer.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+
+namespace hal {
+namespace init {
+extern std::atomic_bool HAL_IsInitialized;
+extern void RunInitialize();
+static inline void CheckInit() {
+  if (HAL_IsInitialized.load(std::memory_order_relaxed)) return;
+  RunInitialize();
+}
+
+extern void InitializeAccelerometer();
+extern void InitializeAnalogAccumulator();
+extern void InitializeAnalogGyro();
+extern void InitializeAnalogInput();
+extern void InitializeAnalogInternal();
+extern void InitializeAnalogOutput();
+extern void InitializeAnalogTrigger();
+extern void InitializeCAN();
+extern void InitializeCANAPI();
+extern void InitializeCompressor();
+extern void InitializeConstants();
+extern void InitializeCounter();
+extern void InitializeDigitalInternal();
+extern void InitializeDIO();
+extern void InitializeEncoder();
+extern void InitializeFPGAEncoder();
+extern void InitializeFRCDriverStation();
+extern void InitializeHAL();
+extern void InitializeI2C();
+extern void InitialzeInterrupts();
+extern void InitializeNotifier();
+extern void InitializePCMInternal();
+extern void InitializePDP();
+extern void InitializePorts();
+extern void InitializePower();
+extern void InitializePWM();
+extern void InitializeRelay();
+extern void InitializeSerialPort();
+extern void InitializeSolenoid();
+extern void InitializeSPI();
+extern void InitializeThreads();
+}  // namespace init
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/I2C.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/I2C.cpp
new file mode 100644
index 0000000..907906e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/I2C.cpp
@@ -0,0 +1,192 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/I2C.h"
+
+#include <fcntl.h>
+#include <linux/i2c-dev.h>
+#include <linux/i2c.h>
+#include <sys/ioctl.h>
+#include <unistd.h>
+
+#include <cstring>
+
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "hal/DIO.h"
+#include "hal/HAL.h"
+
+using namespace hal;
+
+static wpi::mutex digitalI2COnBoardMutex;
+static wpi::mutex digitalI2CMXPMutex;
+
+static uint8_t i2COnboardObjCount{0};
+static uint8_t i2CMXPObjCount{0};
+static int i2COnBoardHandle{-1};
+static int i2CMXPHandle{-1};
+
+static HAL_DigitalHandle i2CMXPDigitalHandle1{HAL_kInvalidHandle};
+static HAL_DigitalHandle i2CMXPDigitalHandle2{HAL_kInvalidHandle};
+
+namespace hal {
+namespace init {
+void InitializeI2C() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+void HAL_InitializeI2C(HAL_I2CPort port, int32_t* status) {
+  hal::init::CheckInit();
+  initializeDigital(status);
+  if (*status != 0) return;
+
+  if (port < 0 || port > 1) {
+    // Set port out of range error here
+    return;
+  }
+
+  if (port == HAL_I2C_kOnboard) {
+    std::lock_guard<wpi::mutex> lock(digitalI2COnBoardMutex);
+    i2COnboardObjCount++;
+    if (i2COnboardObjCount > 1) return;
+    int handle = open("/dev/i2c-2", O_RDWR);
+    if (handle < 0) {
+      std::printf("Failed to open onboard i2c bus: %s\n", std::strerror(errno));
+      return;
+    }
+    i2COnBoardHandle = handle;
+  } else {
+    std::lock_guard<wpi::mutex> lock(digitalI2CMXPMutex);
+    i2CMXPObjCount++;
+    if (i2CMXPObjCount > 1) return;
+    if ((i2CMXPDigitalHandle1 = HAL_InitializeDIOPort(
+             HAL_GetPort(24), false, status)) == HAL_kInvalidHandle) {
+      return;
+    }
+    if ((i2CMXPDigitalHandle2 = HAL_InitializeDIOPort(
+             HAL_GetPort(25), false, status)) == HAL_kInvalidHandle) {
+      HAL_FreeDIOPort(i2CMXPDigitalHandle1);  // free the first port allocated
+      return;
+    }
+    digitalSystem->writeEnableMXPSpecialFunction(
+        digitalSystem->readEnableMXPSpecialFunction(status) | 0xC000, status);
+    int handle = open("/dev/i2c-1", O_RDWR);
+    if (handle < 0) {
+      std::printf("Failed to open MXP i2c bus: %s\n", std::strerror(errno));
+      return;
+    }
+    i2CMXPHandle = handle;
+  }
+}
+
+int32_t HAL_TransactionI2C(HAL_I2CPort port, int32_t deviceAddress,
+                           const uint8_t* dataToSend, int32_t sendSize,
+                           uint8_t* dataReceived, int32_t receiveSize) {
+  if (port < 0 || port > 1) {
+    // Set port out of range error here
+    return -1;
+  }
+
+  struct i2c_msg msgs[2];
+  msgs[0].addr = deviceAddress;
+  msgs[0].flags = 0;
+  msgs[0].len = sendSize;
+  msgs[0].buf = const_cast<uint8_t*>(dataToSend);
+  msgs[1].addr = deviceAddress;
+  msgs[1].flags = I2C_M_RD;
+  msgs[1].len = receiveSize;
+  msgs[1].buf = dataReceived;
+
+  struct i2c_rdwr_ioctl_data rdwr;
+  rdwr.msgs = msgs;
+  rdwr.nmsgs = 2;
+
+  if (port == HAL_I2C_kOnboard) {
+    std::lock_guard<wpi::mutex> lock(digitalI2COnBoardMutex);
+    return ioctl(i2COnBoardHandle, I2C_RDWR, &rdwr);
+  } else {
+    std::lock_guard<wpi::mutex> lock(digitalI2CMXPMutex);
+    return ioctl(i2CMXPHandle, I2C_RDWR, &rdwr);
+  }
+}
+
+int32_t HAL_WriteI2C(HAL_I2CPort port, int32_t deviceAddress,
+                     const uint8_t* dataToSend, int32_t sendSize) {
+  if (port < 0 || port > 1) {
+    // Set port out of range error here
+    return -1;
+  }
+
+  struct i2c_msg msg;
+  msg.addr = deviceAddress;
+  msg.flags = 0;
+  msg.len = sendSize;
+  msg.buf = const_cast<uint8_t*>(dataToSend);
+
+  struct i2c_rdwr_ioctl_data rdwr;
+  rdwr.msgs = &msg;
+  rdwr.nmsgs = 1;
+
+  if (port == HAL_I2C_kOnboard) {
+    std::lock_guard<wpi::mutex> lock(digitalI2COnBoardMutex);
+    return ioctl(i2COnBoardHandle, I2C_RDWR, &rdwr);
+  } else {
+    std::lock_guard<wpi::mutex> lock(digitalI2CMXPMutex);
+    return ioctl(i2CMXPHandle, I2C_RDWR, &rdwr);
+  }
+}
+
+int32_t HAL_ReadI2C(HAL_I2CPort port, int32_t deviceAddress, uint8_t* buffer,
+                    int32_t count) {
+  if (port < 0 || port > 1) {
+    // Set port out of range error here
+    return -1;
+  }
+
+  struct i2c_msg msg;
+  msg.addr = deviceAddress;
+  msg.flags = I2C_M_RD;
+  msg.len = count;
+  msg.buf = buffer;
+
+  struct i2c_rdwr_ioctl_data rdwr;
+  rdwr.msgs = &msg;
+  rdwr.nmsgs = 1;
+
+  if (port == HAL_I2C_kOnboard) {
+    std::lock_guard<wpi::mutex> lock(digitalI2COnBoardMutex);
+    return ioctl(i2COnBoardHandle, I2C_RDWR, &rdwr);
+  } else {
+    std::lock_guard<wpi::mutex> lock(digitalI2CMXPMutex);
+    return ioctl(i2CMXPHandle, I2C_RDWR, &rdwr);
+  }
+}
+
+void HAL_CloseI2C(HAL_I2CPort port) {
+  if (port < 0 || port > 1) {
+    // Set port out of range error here
+    return;
+  }
+
+  if (port == HAL_I2C_kOnboard) {
+    std::lock_guard<wpi::mutex> lock(digitalI2COnBoardMutex);
+    if (i2COnboardObjCount-- == 0) {
+      close(i2COnBoardHandle);
+    }
+  } else {
+    std::lock_guard<wpi::mutex> lock(digitalI2CMXPMutex);
+    if (i2CMXPObjCount-- == 0) {
+      close(i2CMXPHandle);
+    }
+    HAL_FreeDIOPort(i2CMXPDigitalHandle1);
+    HAL_FreeDIOPort(i2CMXPDigitalHandle2);
+  }
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Interrupts.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Interrupts.cpp
new file mode 100644
index 0000000..c661da4
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Interrupts.cpp
@@ -0,0 +1,262 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Interrupts.h"
+
+#include <memory>
+
+#include <wpi/SafeThread.h>
+
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/ChipObject.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+using namespace hal;
+
+namespace {
+// Safe thread to allow callbacks to run on their own thread
+class InterruptThread : public wpi::SafeThread {
+ public:
+  void Main() {
+    std::unique_lock<wpi::mutex> lock(m_mutex);
+    while (m_active) {
+      m_cond.wait(lock, [&] { return !m_active || m_notify; });
+      if (!m_active) break;
+      m_notify = false;
+      HAL_InterruptHandlerFunction handler = m_handler;
+      uint32_t mask = m_mask;
+      void* param = m_param;
+      lock.unlock();  // don't hold mutex during callback execution
+      handler(mask, param);
+      lock.lock();
+    }
+  }
+
+  bool m_notify = false;
+  HAL_InterruptHandlerFunction m_handler;
+  void* m_param;
+  uint32_t m_mask;
+};
+
+class InterruptThreadOwner : public wpi::SafeThreadOwner<InterruptThread> {
+ public:
+  void SetFunc(HAL_InterruptHandlerFunction handler, void* param) {
+    auto thr = GetThread();
+    if (!thr) return;
+    thr->m_handler = handler;
+    thr->m_param = param;
+  }
+
+  void Notify(uint32_t mask) {
+    auto thr = GetThread();
+    if (!thr) return;
+    thr->m_mask = mask;
+    thr->m_notify = true;
+    thr->m_cond.notify_one();
+  }
+};
+
+}  // namespace
+
+static void threadedInterruptHandler(uint32_t mask, void* param) {
+  static_cast<InterruptThreadOwner*>(param)->Notify(mask);
+}
+
+struct Interrupt {
+  std::unique_ptr<tInterrupt> anInterrupt;
+  std::unique_ptr<tInterruptManager> manager;
+  std::unique_ptr<InterruptThreadOwner> threadOwner = nullptr;
+  void* param = nullptr;
+};
+
+static LimitedHandleResource<HAL_InterruptHandle, Interrupt, kNumInterrupts,
+                             HAL_HandleEnum::Interrupt>* interruptHandles;
+
+namespace hal {
+namespace init {
+void InitialzeInterrupts() {
+  static LimitedHandleResource<HAL_InterruptHandle, Interrupt, kNumInterrupts,
+                               HAL_HandleEnum::Interrupt>
+      iH;
+  interruptHandles = &iH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_InterruptHandle HAL_InitializeInterrupts(HAL_Bool watcher,
+                                             int32_t* status) {
+  hal::init::CheckInit();
+  HAL_InterruptHandle handle = interruptHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto anInterrupt = interruptHandles->Get(handle);
+  uint32_t interruptIndex = static_cast<uint32_t>(getHandleIndex(handle));
+  // Expects the calling leaf class to allocate an interrupt index.
+  anInterrupt->anInterrupt.reset(tInterrupt::create(interruptIndex, status));
+  anInterrupt->anInterrupt->writeConfig_WaitForAck(false, status);
+  anInterrupt->manager = std::make_unique<tInterruptManager>(
+      (1u << interruptIndex) | (1u << (interruptIndex + 8u)), watcher, status);
+  return handle;
+}
+
+void* HAL_CleanInterrupts(HAL_InterruptHandle interruptHandle,
+                          int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  interruptHandles->Free(interruptHandle);
+  if (anInterrupt == nullptr) {
+    return nullptr;
+  }
+  anInterrupt->manager->enable(status);
+  void* param = anInterrupt->param;
+  return param;
+}
+
+int64_t HAL_WaitForInterrupt(HAL_InterruptHandle interruptHandle,
+                             double timeout, HAL_Bool ignorePrevious,
+                             int32_t* status) {
+  uint32_t result;
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  result = anInterrupt->manager->watch(static_cast<int32_t>(timeout * 1e3),
+                                       ignorePrevious, status);
+
+  // Don't report a timeout as an error - the return code is enough to tell
+  // that a timeout happened.
+  if (*status == -NiFpga_Status_IrqTimeout) {
+    *status = NiFpga_Status_Success;
+  }
+
+  return result;
+}
+
+void HAL_EnableInterrupts(HAL_InterruptHandle interruptHandle,
+                          int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  anInterrupt->manager->enable(status);
+}
+
+void HAL_DisableInterrupts(HAL_InterruptHandle interruptHandle,
+                           int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  anInterrupt->manager->disable(status);
+}
+
+int64_t HAL_ReadInterruptRisingTimestamp(HAL_InterruptHandle interruptHandle,
+                                         int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  uint32_t timestamp = anInterrupt->anInterrupt->readRisingTimeStamp(status);
+  return timestamp;
+}
+
+int64_t HAL_ReadInterruptFallingTimestamp(HAL_InterruptHandle interruptHandle,
+                                          int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  uint32_t timestamp = anInterrupt->anInterrupt->readFallingTimeStamp(status);
+  return timestamp;
+}
+
+void HAL_RequestInterrupts(HAL_InterruptHandle interruptHandle,
+                           HAL_Handle digitalSourceHandle,
+                           HAL_AnalogTriggerType analogTriggerType,
+                           int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  anInterrupt->anInterrupt->writeConfig_WaitForAck(false, status);
+  bool routingAnalogTrigger = false;
+  uint8_t routingChannel = 0;
+  uint8_t routingModule = 0;
+  bool success =
+      remapDigitalSource(digitalSourceHandle, analogTriggerType, routingChannel,
+                         routingModule, routingAnalogTrigger);
+  if (!success) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  anInterrupt->anInterrupt->writeConfig_Source_AnalogTrigger(
+      routingAnalogTrigger, status);
+  anInterrupt->anInterrupt->writeConfig_Source_Channel(routingChannel, status);
+  anInterrupt->anInterrupt->writeConfig_Source_Module(routingModule, status);
+}
+
+void HAL_AttachInterruptHandler(HAL_InterruptHandle interruptHandle,
+                                HAL_InterruptHandlerFunction handler,
+                                void* param, int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  anInterrupt->manager->registerHandler(handler, param, status);
+  anInterrupt->param = param;
+}
+
+void HAL_AttachInterruptHandlerThreaded(HAL_InterruptHandle interrupt_handle,
+                                        HAL_InterruptHandlerFunction handler,
+                                        void* param, int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interrupt_handle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  anInterrupt->threadOwner = std::make_unique<InterruptThreadOwner>();
+  anInterrupt->threadOwner->Start();
+  anInterrupt->threadOwner->SetFunc(handler, param);
+
+  HAL_AttachInterruptHandler(interrupt_handle, threadedInterruptHandler,
+                             anInterrupt->threadOwner.get(), status);
+
+  if (*status != 0) {
+    anInterrupt->threadOwner = nullptr;
+  }
+  anInterrupt->param = param;
+}
+
+void HAL_SetInterruptUpSourceEdge(HAL_InterruptHandle interruptHandle,
+                                  HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                  int32_t* status) {
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  if (anInterrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  anInterrupt->anInterrupt->writeConfig_RisingEdge(risingEdge, status);
+  anInterrupt->anInterrupt->writeConfig_FallingEdge(fallingEdge, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Notifier.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Notifier.cpp
new file mode 100644
index 0000000..c457cd1
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Notifier.cpp
@@ -0,0 +1,233 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Notifier.h"
+
+#include <atomic>
+#include <cstdlib>  // For std::atexit()
+#include <memory>
+
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "HALInitializer.h"
+#include "hal/ChipObject.h"
+#include "hal/Errors.h"
+#include "hal/HAL.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+
+using namespace hal;
+
+static constexpr int32_t kTimerInterruptNumber = 28;
+
+static wpi::mutex notifierMutex;
+static std::unique_ptr<tAlarm> notifierAlarm;
+static std::unique_ptr<tInterruptManager> notifierManager;
+static uint64_t closestTrigger{UINT64_MAX};
+
+namespace {
+
+struct Notifier {
+  uint64_t triggerTime = UINT64_MAX;
+  uint64_t triggeredTime = UINT64_MAX;
+  bool active = true;
+  wpi::mutex mutex;
+  wpi::condition_variable cond;
+};
+
+}  // namespace
+
+static std::atomic_flag notifierAtexitRegistered{ATOMIC_FLAG_INIT};
+static std::atomic_int notifierRefCount{0};
+
+using namespace hal;
+
+class NotifierHandleContainer
+    : public UnlimitedHandleResource<HAL_NotifierHandle, Notifier,
+                                     HAL_HandleEnum::Notifier> {
+ public:
+  ~NotifierHandleContainer() {
+    ForEach([](HAL_NotifierHandle handle, Notifier* notifier) {
+      {
+        std::lock_guard<wpi::mutex> lock(notifier->mutex);
+        notifier->triggerTime = UINT64_MAX;
+        notifier->triggeredTime = 0;
+        notifier->active = false;
+      }
+      notifier->cond.notify_all();  // wake up any waiting threads
+    });
+  }
+};
+
+static NotifierHandleContainer* notifierHandles;
+
+static void alarmCallback(uint32_t, void*) {
+  std::lock_guard<wpi::mutex> lock(notifierMutex);
+  int32_t status = 0;
+  uint64_t currentTime = 0;
+
+  // the hardware disables itself after each alarm
+  closestTrigger = UINT64_MAX;
+
+  // process all notifiers
+  notifierHandles->ForEach([&](HAL_NotifierHandle handle, Notifier* notifier) {
+    if (notifier->triggerTime == UINT64_MAX) return;
+    if (currentTime == 0) currentTime = HAL_GetFPGATime(&status);
+    std::unique_lock<wpi::mutex> lock(notifier->mutex);
+    if (notifier->triggerTime < currentTime) {
+      notifier->triggerTime = UINT64_MAX;
+      notifier->triggeredTime = currentTime;
+      lock.unlock();
+      notifier->cond.notify_all();
+    } else if (notifier->triggerTime < closestTrigger) {
+      closestTrigger = notifier->triggerTime;
+    }
+  });
+
+  if (notifierAlarm && closestTrigger != UINT64_MAX) {
+    // Simply truncate the hardware trigger time to 32-bit.
+    notifierAlarm->writeTriggerTime(static_cast<uint32_t>(closestTrigger),
+                                    &status);
+    // Enable the alarm.  The hardware disables itself after each alarm.
+    notifierAlarm->writeEnable(true, &status);
+  }
+}
+
+static void cleanupNotifierAtExit() {
+  notifierAlarm = nullptr;
+  notifierManager = nullptr;
+}
+
+namespace hal {
+namespace init {
+void InitializeNotifier() {
+  static NotifierHandleContainer nH;
+  notifierHandles = &nH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_NotifierHandle HAL_InitializeNotifier(int32_t* status) {
+  hal::init::CheckInit();
+  if (!notifierAtexitRegistered.test_and_set())
+    std::atexit(cleanupNotifierAtExit);
+
+  if (notifierRefCount.fetch_add(1) == 0) {
+    std::lock_guard<wpi::mutex> lock(notifierMutex);
+    // create manager and alarm if not already created
+    if (!notifierManager) {
+      notifierManager = std::make_unique<tInterruptManager>(
+          1 << kTimerInterruptNumber, false, status);
+      notifierManager->registerHandler(alarmCallback, nullptr, status);
+      notifierManager->enable(status);
+    }
+    if (!notifierAlarm) notifierAlarm.reset(tAlarm::create(status));
+  }
+
+  std::shared_ptr<Notifier> notifier = std::make_shared<Notifier>();
+  HAL_NotifierHandle handle = notifierHandles->Allocate(notifier);
+  if (handle == HAL_kInvalidHandle) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  return handle;
+}
+
+void HAL_StopNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return;
+
+  {
+    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    notifier->triggerTime = UINT64_MAX;
+    notifier->triggeredTime = 0;
+    notifier->active = false;
+  }
+  notifier->cond.notify_all();  // wake up any waiting threads
+}
+
+void HAL_CleanNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
+  auto notifier = notifierHandles->Free(notifierHandle);
+  if (!notifier) return;
+
+  // Just in case HAL_StopNotifier() wasn't called...
+  {
+    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    notifier->triggerTime = UINT64_MAX;
+    notifier->triggeredTime = 0;
+    notifier->active = false;
+  }
+  notifier->cond.notify_all();
+
+  if (notifierRefCount.fetch_sub(1) == 1) {
+    // if this was the last notifier, clean up alarm and manager
+    // the notifier can call back into our callback, so don't hold the lock
+    // here (the atomic fetch_sub will prevent multiple parallel entries
+    // into this function)
+
+    // Cleaning up the manager takes up to a second to complete, so don't do
+    // that here. Fix it more permanently in 2019...
+
+    // if (notifierAlarm) notifierAlarm->writeEnable(false, status);
+    // if (notifierManager) notifierManager->disable(status);
+
+    // std::lock_guard<wpi::mutex> lock(notifierMutex);
+    // notifierAlarm = nullptr;
+    // notifierManager = nullptr;
+    // closestTrigger = UINT64_MAX;
+  }
+}
+
+void HAL_UpdateNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                             uint64_t triggerTime, int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return;
+
+  {
+    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    notifier->triggerTime = triggerTime;
+    notifier->triggeredTime = UINT64_MAX;
+  }
+
+  std::lock_guard<wpi::mutex> lock(notifierMutex);
+  // Update alarm time if closer than current.
+  if (triggerTime < closestTrigger) {
+    bool wasActive = (closestTrigger != UINT64_MAX);
+    closestTrigger = triggerTime;
+    // Simply truncate the hardware trigger time to 32-bit.
+    notifierAlarm->writeTriggerTime(static_cast<uint32_t>(closestTrigger),
+                                    status);
+    // Enable the alarm.
+    if (!wasActive) notifierAlarm->writeEnable(true, status);
+  }
+}
+
+void HAL_CancelNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                             int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return;
+
+  {
+    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    notifier->triggerTime = UINT64_MAX;
+  }
+}
+
+uint64_t HAL_WaitForNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                                  int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return 0;
+  std::unique_lock<wpi::mutex> lock(notifier->mutex);
+  notifier->cond.wait(lock, [&] {
+    return !notifier->active || notifier->triggeredTime != UINT64_MAX;
+  });
+  return notifier->active ? notifier->triggeredTime : 0;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/PCMInternal.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/PCMInternal.cpp
new file mode 100644
index 0000000..dee64cf
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/PCMInternal.cpp
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "PCMInternal.h"
+
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Errors.h"
+#include "hal/Solenoid.h"
+
+namespace hal {
+
+std::unique_ptr<PCM> PCM_modules[kNumPCMModules];
+
+namespace init {
+void InitializePCMInternal() {
+  for (int i = 0; i < kNumPCMModules; i++) {
+    PCM_modules[i] = nullptr;
+  }
+}
+}  // namespace init
+
+void initializePCM(int32_t module, int32_t* status) {
+  hal::init::CheckInit();
+  if (!HAL_CheckSolenoidModule(module)) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return;
+  }
+  if (!PCM_modules[module]) {
+    PCM_modules[module] = std::make_unique<PCM>(module);
+  }
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/PCMInternal.h b/third_party/allwpilib_2019/hal/src/main/native/athena/PCMInternal.h
new file mode 100644
index 0000000..52f0f75
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/PCMInternal.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+
+#include "PortsInternal.h"
+#include "ctre/PCM.h"
+#include "hal/Errors.h"
+#include "hal/Ports.h"
+#include "hal/Solenoid.h"
+
+namespace hal {
+
+extern std::unique_ptr<PCM> PCM_modules[kNumPCMModules];
+
+static inline bool checkPCMInit(int32_t module, int32_t* status) {
+  if (!HAL_CheckSolenoidModule(module)) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return false;
+  }
+  if (!PCM_modules[module]) {
+    *status = INCOMPATIBLE_STATE;
+    return false;
+  }
+  return true;
+}
+
+void initializePCM(int32_t module, int32_t* status);
+
+}  // namespace hal
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
new file mode 100644
index 0000000..ff1eb81
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/PDP.cpp
@@ -0,0 +1,341 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/PDP.h"
+
+#include <memory>
+
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/CANAPI.h"
+#include "hal/Errors.h"
+#include "hal/Ports.h"
+#include "hal/handles/IndexedHandleResource.h"
+
+using namespace hal;
+
+static constexpr HAL_CANManufacturer manufacturer =
+    HAL_CANManufacturer::HAL_CAN_Man_kCTRE;
+
+static constexpr HAL_CANDeviceType deviceType =
+    HAL_CANDeviceType::HAL_CAN_Dev_kPowerDistribution;
+
+static constexpr int32_t Status1 = 0x50;
+static constexpr int32_t Status2 = 0x51;
+static constexpr int32_t Status3 = 0x52;
+static constexpr int32_t StatusEnergy = 0x5D;
+
+static constexpr int32_t Control1 = 0x70;
+
+static constexpr int32_t TimeoutMs = 100;
+static constexpr int32_t StatusPeriodMs = 25;
+
+/* encoder/decoders */
+union PdpStatus1 {
+  uint8_t data[8];
+  struct Bits {
+    unsigned chan1_h8 : 8;
+    unsigned chan2_h6 : 6;
+    unsigned chan1_l2 : 2;
+    unsigned chan3_h4 : 4;
+    unsigned chan2_l4 : 4;
+    unsigned chan4_h2 : 2;
+    unsigned chan3_l6 : 6;
+    unsigned chan4_l8 : 8;
+    unsigned chan5_h8 : 8;
+    unsigned chan6_h6 : 6;
+    unsigned chan5_l2 : 2;
+    unsigned reserved4 : 4;
+    unsigned chan6_l4 : 4;
+  } bits;
+};
+
+union PdpStatus2 {
+  uint8_t data[8];
+  struct Bits {
+    unsigned chan7_h8 : 8;
+    unsigned chan8_h6 : 6;
+    unsigned chan7_l2 : 2;
+    unsigned chan9_h4 : 4;
+    unsigned chan8_l4 : 4;
+    unsigned chan10_h2 : 2;
+    unsigned chan9_l6 : 6;
+    unsigned chan10_l8 : 8;
+    unsigned chan11_h8 : 8;
+    unsigned chan12_h6 : 6;
+    unsigned chan11_l2 : 2;
+    unsigned reserved4 : 4;
+    unsigned chan12_l4 : 4;
+  } bits;
+};
+
+union PdpStatus3 {
+  uint8_t data[8];
+  struct Bits {
+    unsigned chan13_h8 : 8;
+    unsigned chan14_h6 : 6;
+    unsigned chan13_l2 : 2;
+    unsigned chan15_h4 : 4;
+    unsigned chan14_l4 : 4;
+    unsigned chan16_h2 : 2;
+    unsigned chan15_l6 : 6;
+    unsigned chan16_l8 : 8;
+    unsigned internalResBattery_mOhms : 8;
+    unsigned busVoltage : 8;
+    unsigned temp : 8;
+  } bits;
+};
+
+union PdpStatusEnergy {
+  uint8_t data[8];
+  struct Bits {
+    unsigned TmeasMs_likelywillbe20ms_ : 8;
+    unsigned TotalCurrent_125mAperunit_h8 : 8;
+    unsigned Power_125mWperunit_h4 : 4;
+    unsigned TotalCurrent_125mAperunit_l4 : 4;
+    unsigned Power_125mWperunit_m8 : 8;
+    unsigned Energy_125mWPerUnitXTmeas_h4 : 4;
+    unsigned Power_125mWperunit_l4 : 4;
+    unsigned Energy_125mWPerUnitXTmeas_mh8 : 8;
+    unsigned Energy_125mWPerUnitXTmeas_ml8 : 8;
+    unsigned Energy_125mWPerUnitXTmeas_l8 : 8;
+  } bits;
+};
+
+namespace hal {
+namespace init {
+void InitializePDP() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_PDPHandle HAL_InitializePDP(int32_t module, int32_t* status) {
+  hal::init::CheckInit();
+  if (!HAL_CheckPDPModule(module)) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  auto handle = HAL_InitializeCAN(manufacturer, module, deviceType, status);
+
+  if (*status != 0) {
+    HAL_CleanCAN(handle);
+    return HAL_kInvalidHandle;
+  }
+
+  return handle;
+}
+
+void HAL_CleanPDP(HAL_PDPHandle handle) { HAL_CleanCAN(handle); }
+
+HAL_Bool HAL_CheckPDPModule(int32_t module) {
+  return module < kNumPDPModules && module >= 0;
+}
+
+HAL_Bool HAL_CheckPDPChannel(int32_t channel) {
+  return channel < kNumPDPChannels && channel >= 0;
+}
+
+double HAL_GetPDPTemperature(HAL_PDPHandle handle, int32_t* status) {
+  PdpStatus3 pdpStatus;
+  int32_t length = 0;
+  uint64_t receivedTimestamp = 0;
+
+  HAL_ReadCANPeriodicPacket(handle, Status3, pdpStatus.data, &length,
+                            &receivedTimestamp, TimeoutMs, StatusPeriodMs,
+                            status);
+
+  return pdpStatus.bits.temp * 1.03250836957542 - 67.8564500484966;
+}
+
+double HAL_GetPDPVoltage(HAL_PDPHandle handle, int32_t* status) {
+  PdpStatus3 pdpStatus;
+  int32_t length = 0;
+  uint64_t receivedTimestamp = 0;
+
+  HAL_ReadCANPeriodicPacket(handle, Status3, pdpStatus.data, &length,
+                            &receivedTimestamp, TimeoutMs, StatusPeriodMs,
+                            status);
+
+  return pdpStatus.bits.busVoltage * 0.05 + 4.0; /* 50mV per unit plus 4V. */
+}
+
+double HAL_GetPDPChannelCurrent(HAL_PDPHandle handle, int32_t channel,
+                                int32_t* status) {
+  if (!HAL_CheckPDPChannel(channel)) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return 0;
+  }
+
+  int32_t length = 0;
+  uint64_t receivedTimestamp = 0;
+
+  double raw = 0;
+
+  if (channel <= 5) {
+    PdpStatus1 pdpStatus;
+    HAL_ReadCANPeriodicPacket(handle, Status1, pdpStatus.data, &length,
+                              &receivedTimestamp, TimeoutMs, StatusPeriodMs,
+                              status);
+    switch (channel) {
+      case 0:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan1_h8) << 2) |
+              pdpStatus.bits.chan1_l2;
+        break;
+      case 1:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan2_h6) << 4) |
+              pdpStatus.bits.chan2_l4;
+        break;
+      case 2:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan3_h4) << 6) |
+              pdpStatus.bits.chan3_l6;
+        break;
+      case 3:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan4_h2) << 8) |
+              pdpStatus.bits.chan4_l8;
+        break;
+      case 4:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan5_h8) << 2) |
+              pdpStatus.bits.chan5_l2;
+        break;
+      case 5:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan6_h6) << 4) |
+              pdpStatus.bits.chan6_l4;
+        break;
+    }
+  } else if (channel <= 11) {
+    PdpStatus2 pdpStatus;
+    HAL_ReadCANPeriodicPacket(handle, Status2, pdpStatus.data, &length,
+                              &receivedTimestamp, TimeoutMs, StatusPeriodMs,
+                              status);
+    switch (channel) {
+      case 6:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan7_h8) << 2) |
+              pdpStatus.bits.chan7_l2;
+        break;
+      case 7:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan8_h6) << 4) |
+              pdpStatus.bits.chan8_l4;
+        break;
+      case 8:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan9_h4) << 6) |
+              pdpStatus.bits.chan9_l6;
+        break;
+      case 9:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan10_h2) << 8) |
+              pdpStatus.bits.chan10_l8;
+        break;
+      case 10:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan11_h8) << 2) |
+              pdpStatus.bits.chan11_l2;
+        break;
+      case 11:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan12_h6) << 4) |
+              pdpStatus.bits.chan12_l4;
+        break;
+    }
+  } else {
+    PdpStatus3 pdpStatus;
+    HAL_ReadCANPeriodicPacket(handle, Status3, pdpStatus.data, &length,
+                              &receivedTimestamp, TimeoutMs, StatusPeriodMs,
+                              status);
+    switch (channel) {
+      case 12:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan13_h8) << 2) |
+              pdpStatus.bits.chan13_l2;
+        break;
+      case 13:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan14_h6) << 4) |
+              pdpStatus.bits.chan14_l4;
+        break;
+      case 14:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan15_h4) << 6) |
+              pdpStatus.bits.chan15_l6;
+        break;
+      case 15:
+        raw = (static_cast<uint32_t>(pdpStatus.bits.chan16_h2) << 8) |
+              pdpStatus.bits.chan16_l8;
+        break;
+    }
+  }
+
+  /* convert to amps */
+  return raw * 0.125; /* 7.3 fixed pt value in Amps */
+}
+
+double HAL_GetPDPTotalCurrent(HAL_PDPHandle handle, int32_t* status) {
+  PdpStatusEnergy pdpStatus;
+  int32_t length = 0;
+  uint64_t receivedTimestamp = 0;
+
+  HAL_ReadCANPeriodicPacket(handle, StatusEnergy, pdpStatus.data, &length,
+                            &receivedTimestamp, TimeoutMs, StatusPeriodMs,
+                            status);
+
+  uint32_t raw;
+  raw = pdpStatus.bits.TotalCurrent_125mAperunit_h8;
+  raw <<= 4;
+  raw |= pdpStatus.bits.TotalCurrent_125mAperunit_l4;
+  return 0.125 * raw; /* 7.3 fixed pt value in Amps */
+}
+
+double HAL_GetPDPTotalPower(HAL_PDPHandle handle, int32_t* status) {
+  PdpStatusEnergy pdpStatus;
+  int32_t length = 0;
+  uint64_t receivedTimestamp = 0;
+
+  HAL_ReadCANPeriodicPacket(handle, StatusEnergy, pdpStatus.data, &length,
+                            &receivedTimestamp, TimeoutMs, StatusPeriodMs,
+                            status);
+
+  uint32_t raw;
+  raw = pdpStatus.bits.Power_125mWperunit_h4;
+  raw <<= 8;
+  raw |= pdpStatus.bits.Power_125mWperunit_m8;
+  raw <<= 4;
+  raw |= pdpStatus.bits.Power_125mWperunit_l4;
+  return 0.125 * raw; /* 7.3 fixed pt value in Watts */
+}
+
+double HAL_GetPDPTotalEnergy(HAL_PDPHandle handle, int32_t* status) {
+  PdpStatusEnergy pdpStatus;
+  int32_t length = 0;
+  uint64_t receivedTimestamp = 0;
+
+  HAL_ReadCANPeriodicPacket(handle, StatusEnergy, pdpStatus.data, &length,
+                            &receivedTimestamp, TimeoutMs, StatusPeriodMs,
+                            status);
+
+  uint32_t raw;
+  raw = pdpStatus.bits.Energy_125mWPerUnitXTmeas_h4;
+  raw <<= 8;
+  raw |= pdpStatus.bits.Energy_125mWPerUnitXTmeas_mh8;
+  raw <<= 8;
+  raw |= pdpStatus.bits.Energy_125mWPerUnitXTmeas_ml8;
+  raw <<= 8;
+  raw |= pdpStatus.bits.Energy_125mWPerUnitXTmeas_l8;
+
+  double energyJoules = 0.125 * raw; /* mW integrated every TmeasMs */
+  energyJoules *= 0.001;             /* convert from mW to W */
+  energyJoules *=
+      pdpStatus.bits
+          .TmeasMs_likelywillbe20ms_; /* multiplied by TmeasMs = joules */
+  return 0.125 * raw;
+}
+
+void HAL_ResetPDPTotalEnergy(HAL_PDPHandle handle, int32_t* status) {
+  uint8_t pdpControl[] = {0x40}; /* only bit set is ResetEnergy */
+  HAL_WriteCANPacket(handle, pdpControl, 1, Control1, status);
+}
+
+void HAL_ClearPDPStickyFaults(HAL_PDPHandle handle, int32_t* status) {
+  uint8_t pdpControl[] = {0x80}; /* only bit set is ClearStickyFaults */
+  HAL_WriteCANPacket(handle, pdpControl, 1, Control1, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/PWM.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/PWM.cpp
new file mode 100644
index 0000000..06b527c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/PWM.cpp
@@ -0,0 +1,458 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/PWM.h"
+
+#include <cmath>
+#include <thread>
+
+#include <wpi/raw_ostream.h>
+
+#include "ConstantsInternal.h"
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/cpp/fpga_clock.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace hal;
+
+static inline int32_t GetMaxPositivePwm(DigitalPort* port) {
+  return port->maxPwm;
+}
+
+static inline int32_t GetMinPositivePwm(DigitalPort* port) {
+  if (port->eliminateDeadband) {
+    return port->deadbandMaxPwm;
+  } else {
+    return port->centerPwm + 1;
+  }
+}
+
+static inline int32_t GetCenterPwm(DigitalPort* port) {
+  return port->centerPwm;
+}
+
+static inline int32_t GetMaxNegativePwm(DigitalPort* port) {
+  if (port->eliminateDeadband) {
+    return port->deadbandMinPwm;
+  } else {
+    return port->centerPwm - 1;
+  }
+}
+
+static inline int32_t GetMinNegativePwm(DigitalPort* port) {
+  return port->minPwm;
+}
+
+static inline int32_t GetPositiveScaleFactor(DigitalPort* port) {
+  return GetMaxPositivePwm(port) - GetMinPositivePwm(port);
+}  ///< The scale for positive speeds.
+
+static inline int32_t GetNegativeScaleFactor(DigitalPort* port) {
+  return GetMaxNegativePwm(port) - GetMinNegativePwm(port);
+}  ///< The scale for negative speeds.
+
+static inline int32_t GetFullRangeScaleFactor(DigitalPort* port) {
+  return GetMaxPositivePwm(port) - GetMinNegativePwm(port);
+}  ///< The scale for positions.
+
+namespace hal {
+namespace init {
+void InitializePWM() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_DigitalHandle HAL_InitializePWMPort(HAL_PortHandle portHandle,
+                                        int32_t* status) {
+  hal::init::CheckInit();
+  initializeDigital(status);
+
+  if (*status != 0) return HAL_kInvalidHandle;
+
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex || channel >= kNumPWMChannels) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  uint8_t origChannel = static_cast<uint8_t>(channel);
+
+  if (origChannel < kNumPWMHeaders) {
+    channel += kNumDigitalChannels;  // remap Headers to end of allocations
+  } else {
+    channel = remapMXPPWMChannel(channel) + 10;  // remap MXP to proper channel
+  }
+
+  auto handle =
+      digitalChannelHandles->Allocate(channel, HAL_HandleEnum::PWM, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  auto port = digitalChannelHandles->Get(handle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  port->channel = origChannel;
+
+  if (port->channel > tPWM::kNumHdrRegisters - 1) {
+    int32_t bitToSet = 1 << remapMXPPWMChannel(port->channel);
+    uint16_t specialFunctions =
+        digitalSystem->readEnableMXPSpecialFunction(status);
+    digitalSystem->writeEnableMXPSpecialFunction(specialFunctions | bitToSet,
+                                                 status);
+  }
+
+  // Defaults to allow an always valid config.
+  HAL_SetPWMConfig(handle, 2.0, 1.501, 1.5, 1.499, 1.0, status);
+
+  return handle;
+}
+void HAL_FreePWMPort(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  digitalChannelHandles->Free(pwmPortHandle, HAL_HandleEnum::PWM);
+
+  // Wait for no other object to hold this handle.
+  auto start = hal::fpga_clock::now();
+  while (port.use_count() != 1) {
+    auto current = hal::fpga_clock::now();
+    if (start + std::chrono::seconds(1) < current) {
+      wpi::outs() << "PWM handle free timeout\n";
+      wpi::outs().flush();
+      break;
+    }
+    std::this_thread::yield();
+  }
+
+  if (port->channel > tPWM::kNumHdrRegisters - 1) {
+    int32_t bitToUnset = 1 << remapMXPPWMChannel(port->channel);
+    uint16_t specialFunctions =
+        digitalSystem->readEnableMXPSpecialFunction(status);
+    digitalSystem->writeEnableMXPSpecialFunction(specialFunctions & ~bitToUnset,
+                                                 status);
+  }
+}
+
+HAL_Bool HAL_CheckPWMChannel(int32_t channel) {
+  return channel < kNumPWMChannels && channel >= 0;
+}
+
+void HAL_SetPWMConfig(HAL_DigitalHandle pwmPortHandle, double max,
+                      double deadbandMax, double center, double deadbandMin,
+                      double min, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  // calculate the loop time in milliseconds
+  double loopTime =
+      HAL_GetPWMLoopTiming(status) / (kSystemClockTicksPerMicrosecond * 1e3);
+  if (*status != 0) return;
+
+  int32_t maxPwm = static_cast<int32_t>((max - kDefaultPwmCenter) / loopTime +
+                                        kDefaultPwmStepsDown - 1);
+  int32_t deadbandMaxPwm = static_cast<int32_t>(
+      (deadbandMax - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
+  int32_t centerPwm = static_cast<int32_t>(
+      (center - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
+  int32_t deadbandMinPwm = static_cast<int32_t>(
+      (deadbandMin - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
+  int32_t minPwm = static_cast<int32_t>((min - kDefaultPwmCenter) / loopTime +
+                                        kDefaultPwmStepsDown - 1);
+
+  port->maxPwm = maxPwm;
+  port->deadbandMaxPwm = deadbandMaxPwm;
+  port->deadbandMinPwm = deadbandMinPwm;
+  port->centerPwm = centerPwm;
+  port->minPwm = minPwm;
+  port->configSet = true;
+}
+
+void HAL_SetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t maxPwm,
+                         int32_t deadbandMaxPwm, int32_t centerPwm,
+                         int32_t deadbandMinPwm, int32_t minPwm,
+                         int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  port->maxPwm = maxPwm;
+  port->deadbandMaxPwm = deadbandMaxPwm;
+  port->deadbandMinPwm = deadbandMinPwm;
+  port->centerPwm = centerPwm;
+  port->minPwm = minPwm;
+}
+
+void HAL_GetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t* maxPwm,
+                         int32_t* deadbandMaxPwm, int32_t* centerPwm,
+                         int32_t* deadbandMinPwm, int32_t* minPwm,
+                         int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  *maxPwm = port->maxPwm;
+  *deadbandMaxPwm = port->deadbandMaxPwm;
+  *deadbandMinPwm = port->deadbandMinPwm;
+  *centerPwm = port->centerPwm;
+  *minPwm = port->minPwm;
+}
+
+void HAL_SetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
+                                 HAL_Bool eliminateDeadband, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  port->eliminateDeadband = eliminateDeadband;
+}
+
+HAL_Bool HAL_GetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
+                                     int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  return port->eliminateDeadband;
+}
+
+void HAL_SetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t value,
+                   int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (port->channel < tPWM::kNumHdrRegisters) {
+    pwmSystem->writeHdr(port->channel, value, status);
+  } else {
+    pwmSystem->writeMXP(port->channel - tPWM::kNumHdrRegisters, value, status);
+  }
+}
+
+void HAL_SetPWMSpeed(HAL_DigitalHandle pwmPortHandle, double speed,
+                     int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (!port->configSet) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  DigitalPort* dPort = port.get();
+
+  if (speed < -1.0) {
+    speed = -1.0;
+  } else if (speed > 1.0) {
+    speed = 1.0;
+  } else if (!std::isfinite(speed)) {
+    speed = 0.0;
+  }
+
+  // calculate the desired output pwm value by scaling the speed appropriately
+  int32_t rawValue;
+  if (speed == 0.0) {
+    rawValue = GetCenterPwm(dPort);
+  } else if (speed > 0.0) {
+    rawValue = static_cast<int32_t>(
+        speed * static_cast<double>(GetPositiveScaleFactor(dPort)) +
+        static_cast<double>(GetMinPositivePwm(dPort)) + 0.5);
+  } else {
+    rawValue = static_cast<int32_t>(
+        speed * static_cast<double>(GetNegativeScaleFactor(dPort)) +
+        static_cast<double>(GetMaxNegativePwm(dPort)) + 0.5);
+  }
+
+  if (!((rawValue >= GetMinNegativePwm(dPort)) &&
+        (rawValue <= GetMaxPositivePwm(dPort))) ||
+      rawValue == kPwmDisabled) {
+    *status = HAL_PWM_SCALE_ERROR;
+    return;
+  }
+
+  HAL_SetPWMRaw(pwmPortHandle, rawValue, status);
+}
+
+void HAL_SetPWMPosition(HAL_DigitalHandle pwmPortHandle, double pos,
+                        int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (!port->configSet) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+  DigitalPort* dPort = port.get();
+
+  if (pos < 0.0) {
+    pos = 0.0;
+  } else if (pos > 1.0) {
+    pos = 1.0;
+  }
+
+  // note, need to perform the multiplication below as floating point before
+  // converting to int
+  int32_t rawValue = static_cast<int32_t>(
+      (pos * static_cast<double>(GetFullRangeScaleFactor(dPort))) +
+      GetMinNegativePwm(dPort));
+
+  if (rawValue == kPwmDisabled) {
+    *status = HAL_PWM_SCALE_ERROR;
+    return;
+  }
+
+  HAL_SetPWMRaw(pwmPortHandle, rawValue, status);
+}
+
+void HAL_SetPWMDisabled(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  HAL_SetPWMRaw(pwmPortHandle, kPwmDisabled, status);
+}
+
+int32_t HAL_GetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  if (port->channel < tPWM::kNumHdrRegisters) {
+    return pwmSystem->readHdr(port->channel, status);
+  } else {
+    return pwmSystem->readMXP(port->channel - tPWM::kNumHdrRegisters, status);
+  }
+}
+
+double HAL_GetPWMSpeed(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  if (!port->configSet) {
+    *status = INCOMPATIBLE_STATE;
+    return 0;
+  }
+
+  int32_t value = HAL_GetPWMRaw(pwmPortHandle, status);
+  if (*status != 0) return 0;
+  DigitalPort* dPort = port.get();
+
+  if (value == kPwmDisabled) {
+    return 0.0;
+  } else if (value > GetMaxPositivePwm(dPort)) {
+    return 1.0;
+  } else if (value < GetMinNegativePwm(dPort)) {
+    return -1.0;
+  } else if (value > GetMinPositivePwm(dPort)) {
+    return static_cast<double>(value - GetMinPositivePwm(dPort)) /
+           static_cast<double>(GetPositiveScaleFactor(dPort));
+  } else if (value < GetMaxNegativePwm(dPort)) {
+    return static_cast<double>(value - GetMaxNegativePwm(dPort)) /
+           static_cast<double>(GetNegativeScaleFactor(dPort));
+  } else {
+    return 0.0;
+  }
+}
+
+double HAL_GetPWMPosition(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  if (!port->configSet) {
+    *status = INCOMPATIBLE_STATE;
+    return 0;
+  }
+
+  int32_t value = HAL_GetPWMRaw(pwmPortHandle, status);
+  if (*status != 0) return 0;
+  DigitalPort* dPort = port.get();
+
+  if (value < GetMinNegativePwm(dPort)) {
+    return 0.0;
+  } else if (value > GetMaxPositivePwm(dPort)) {
+    return 1.0;
+  } else {
+    return static_cast<double>(value - GetMinNegativePwm(dPort)) /
+           static_cast<double>(GetFullRangeScaleFactor(dPort));
+  }
+}
+
+void HAL_LatchPWMZero(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  pwmSystem->writeZeroLatch(port->channel, true, status);
+  pwmSystem->writeZeroLatch(port->channel, false, status);
+}
+
+void HAL_SetPWMPeriodScale(HAL_DigitalHandle pwmPortHandle, int32_t squelchMask,
+                           int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (port->channel < tPWM::kNumPeriodScaleHdrElements) {
+    pwmSystem->writePeriodScaleHdr(port->channel, squelchMask, status);
+  } else {
+    pwmSystem->writePeriodScaleMXP(
+        port->channel - tPWM::kNumPeriodScaleHdrElements, squelchMask, status);
+  }
+}
+
+int32_t HAL_GetPWMLoopTiming(int32_t* status) {
+  initializeDigital(status);
+  if (*status != 0) return 0;
+  return pwmSystem->readLoopTiming(status);
+}
+
+uint64_t HAL_GetPWMCycleStartTime(int32_t* status) {
+  initializeDigital(status);
+  if (*status != 0) return 0;
+
+  uint64_t upper1 = pwmSystem->readCycleStartTimeUpper(status);
+  uint32_t lower = pwmSystem->readCycleStartTime(status);
+  uint64_t upper2 = pwmSystem->readCycleStartTimeUpper(status);
+  if (*status != 0) return 0;
+  if (upper1 != upper2) {
+    // Rolled over between the lower call, reread lower
+    lower = pwmSystem->readCycleStartTime(status);
+    if (*status != 0) return 0;
+  }
+  return (upper2 << 32) + lower;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Ports.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Ports.cpp
new file mode 100644
index 0000000..9a52736
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Ports.cpp
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Ports.h"
+
+#include "PortsInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializePorts() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+int32_t HAL_GetNumAccumulators(void) { return kNumAccumulators; }
+int32_t HAL_GetNumAnalogTriggers(void) { return kNumAnalogTriggers; }
+int32_t HAL_GetNumAnalogInputs(void) { return kNumAnalogInputs; }
+int32_t HAL_GetNumAnalogOutputs(void) { return kNumAnalogOutputs; }
+int32_t HAL_GetNumCounters(void) { return kNumCounters; }
+int32_t HAL_GetNumDigitalHeaders(void) { return kNumDigitalHeaders; }
+int32_t HAL_GetNumPWMHeaders(void) { return kNumPWMHeaders; }
+int32_t HAL_GetNumDigitalChannels(void) { return kNumDigitalChannels; }
+int32_t HAL_GetNumPWMChannels(void) { return kNumPWMChannels; }
+int32_t HAL_GetNumDigitalPWMOutputs(void) { return kNumDigitalPWMOutputs; }
+int32_t HAL_GetNumEncoders(void) { return kNumEncoders; }
+int32_t HAL_GetNumInterrupts(void) { return kNumInterrupts; }
+int32_t HAL_GetNumRelayChannels(void) { return kNumRelayChannels; }
+int32_t HAL_GetNumRelayHeaders(void) { return kNumRelayHeaders; }
+int32_t HAL_GetNumPCMModules(void) { return kNumPCMModules; }
+int32_t HAL_GetNumSolenoidChannels(void) { return kNumSolenoidChannels; }
+int32_t HAL_GetNumPDPModules(void) { return kNumPDPModules; }
+int32_t HAL_GetNumPDPChannels(void) { return kNumPDPChannels; }
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/PortsInternal.h b/third_party/allwpilib_2019/hal/src/main/native/athena/PortsInternal.h
new file mode 100644
index 0000000..b3eb6b0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/PortsInternal.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/ChipObject.h"
+
+namespace hal {
+
+constexpr int32_t kNumAccumulators = tAccumulator::kNumSystems;
+constexpr int32_t kNumAnalogTriggers = tAnalogTrigger::kNumSystems;
+constexpr int32_t kNumAnalogInputs = 8;
+constexpr int32_t kNumAnalogOutputs = tAO::kNumMXPRegisters;
+constexpr int32_t kNumCounters = tCounter::kNumSystems;
+constexpr int32_t kNumDigitalHeaders = 10;
+constexpr int32_t kNumDigitalMXPChannels = 16;
+constexpr int32_t kNumDigitalSPIPortChannels = 5;
+constexpr int32_t kNumPWMHeaders = tPWM::kNumHdrRegisters;
+constexpr int32_t kNumDigitalChannels =
+    kNumDigitalHeaders + kNumDigitalMXPChannels + kNumDigitalSPIPortChannels;
+constexpr int32_t kNumPWMChannels = tPWM::kNumMXPRegisters + kNumPWMHeaders;
+constexpr int32_t kNumDigitalPWMOutputs =
+    tDIO::kNumPWMDutyCycleAElements + tDIO::kNumPWMDutyCycleBElements;
+constexpr int32_t kNumEncoders = tEncoder::kNumSystems;
+constexpr int32_t kNumInterrupts = tInterrupt::kNumSystems;
+constexpr int32_t kNumRelayChannels = 8;
+constexpr int32_t kNumRelayHeaders = kNumRelayChannels / 2;
+constexpr int32_t kNumPCMModules = 63;
+constexpr int32_t kNumSolenoidChannels = 8;
+constexpr int32_t kNumPDPModules = 63;
+constexpr int32_t kNumPDPChannels = 16;
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Power.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Power.cpp
new file mode 100644
index 0000000..2cf4d33
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Power.cpp
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Power.h"
+
+#include <memory>
+
+#include "HALInitializer.h"
+#include "hal/ChipObject.h"
+
+using namespace hal;
+
+namespace hal {
+
+static std::unique_ptr<tPower> power{nullptr};
+
+static void initializePower(int32_t* status) {
+  hal::init::CheckInit();
+  if (power == nullptr) {
+    power.reset(tPower::create(status));
+  }
+}
+
+}  // namespace hal
+
+namespace hal {
+namespace init {
+void InitializePower() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+double HAL_GetVinVoltage(int32_t* status) {
+  initializePower(status);
+  return power->readVinVoltage(status) / 4.096 * 0.025733 - 0.029;
+}
+
+double HAL_GetVinCurrent(int32_t* status) {
+  initializePower(status);
+  return power->readVinCurrent(status) / 4.096 * 0.017042 - 0.071;
+}
+
+double HAL_GetUserVoltage6V(int32_t* status) {
+  initializePower(status);
+  return power->readUserVoltage6V(status) / 4.096 * 0.007019 - 0.014;
+}
+
+double HAL_GetUserCurrent6V(int32_t* status) {
+  initializePower(status);
+  return power->readUserCurrent6V(status) / 4.096 * 0.005566 - 0.009;
+}
+
+HAL_Bool HAL_GetUserActive6V(int32_t* status) {
+  initializePower(status);
+  return power->readStatus_User6V(status) == 4;
+}
+
+int32_t HAL_GetUserCurrentFaults6V(int32_t* status) {
+  initializePower(status);
+  return static_cast<int32_t>(
+      power->readFaultCounts_OverCurrentFaultCount6V(status));
+}
+
+double HAL_GetUserVoltage5V(int32_t* status) {
+  initializePower(status);
+  return power->readUserVoltage5V(status) / 4.096 * 0.005962 - 0.013;
+}
+
+double HAL_GetUserCurrent5V(int32_t* status) {
+  initializePower(status);
+  return power->readUserCurrent5V(status) / 4.096 * 0.001996 - 0.002;
+}
+
+HAL_Bool HAL_GetUserActive5V(int32_t* status) {
+  initializePower(status);
+  return power->readStatus_User5V(status) == 4;
+}
+
+int32_t HAL_GetUserCurrentFaults5V(int32_t* status) {
+  initializePower(status);
+  return static_cast<int32_t>(
+      power->readFaultCounts_OverCurrentFaultCount5V(status));
+}
+
+double HAL_GetUserVoltage3V3(int32_t* status) {
+  initializePower(status);
+  return power->readUserVoltage3V3(status) / 4.096 * 0.004902 - 0.01;
+}
+
+double HAL_GetUserCurrent3V3(int32_t* status) {
+  initializePower(status);
+  return power->readUserCurrent3V3(status) / 4.096 * 0.002486 - 0.003;
+}
+
+HAL_Bool HAL_GetUserActive3V3(int32_t* status) {
+  initializePower(status);
+  return power->readStatus_User3V3(status) == 4;
+}
+
+int32_t HAL_GetUserCurrentFaults3V3(int32_t* status) {
+  initializePower(status);
+  return static_cast<int32_t>(
+      power->readFaultCounts_OverCurrentFaultCount3V3(status));
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Relay.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Relay.cpp
new file mode 100644
index 0000000..9f7d6c0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Relay.cpp
@@ -0,0 +1,143 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Relay.h"
+
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/handles/IndexedHandleResource.h"
+
+using namespace hal;
+
+namespace {
+
+struct Relay {
+  uint8_t channel;
+  bool fwd;
+};
+
+}  // namespace
+
+static IndexedHandleResource<HAL_RelayHandle, Relay, kNumRelayChannels,
+                             HAL_HandleEnum::Relay>* relayHandles;
+
+// Create a mutex to protect changes to the relay values
+static wpi::mutex digitalRelayMutex;
+
+namespace hal {
+namespace init {
+void InitializeRelay() {
+  static IndexedHandleResource<HAL_RelayHandle, Relay, kNumRelayChannels,
+                               HAL_HandleEnum::Relay>
+      rH;
+  relayHandles = &rH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_RelayHandle HAL_InitializeRelayPort(HAL_PortHandle portHandle, HAL_Bool fwd,
+                                        int32_t* status) {
+  hal::init::CheckInit();
+  initializeDigital(status);
+
+  if (*status != 0) return HAL_kInvalidHandle;
+
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  if (!fwd) channel += kNumRelayHeaders;  // add 4 to reverse channels
+
+  auto handle = relayHandles->Allocate(channel, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  auto port = relayHandles->Get(handle);
+  if (port == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  if (!fwd) {
+    // Subtract number of headers to put channel in range
+    channel -= kNumRelayHeaders;
+
+    port->fwd = false;  // set to reverse
+  } else {
+    port->fwd = true;  // set to forward
+  }
+
+  port->channel = static_cast<uint8_t>(channel);
+  return handle;
+}
+
+void HAL_FreeRelayPort(HAL_RelayHandle relayPortHandle) {
+  // no status, so no need to check for a proper free.
+  relayHandles->Free(relayPortHandle);
+}
+
+HAL_Bool HAL_CheckRelayChannel(int32_t channel) {
+  // roboRIO only has 4 headers, and the FPGA has
+  // seperate functions for forward and reverse,
+  // instead of seperate channel IDs
+  return channel < kNumRelayHeaders && channel >= 0;
+}
+
+void HAL_SetRelay(HAL_RelayHandle relayPortHandle, HAL_Bool on,
+                  int32_t* status) {
+  auto port = relayHandles->Get(relayPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  std::lock_guard<wpi::mutex> lock(digitalRelayMutex);
+  uint8_t relays = 0;
+  if (port->fwd) {
+    relays = relaySystem->readValue_Forward(status);
+  } else {
+    relays = relaySystem->readValue_Reverse(status);
+  }
+
+  if (*status != 0) return;  // bad status read
+
+  if (on) {
+    relays |= 1 << port->channel;
+  } else {
+    relays &= ~(1 << port->channel);
+  }
+
+  if (port->fwd) {
+    relaySystem->writeValue_Forward(relays, status);
+  } else {
+    relaySystem->writeValue_Reverse(relays, status);
+  }
+}
+
+HAL_Bool HAL_GetRelay(HAL_RelayHandle relayPortHandle, int32_t* status) {
+  auto port = relayHandles->Get(relayPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+
+  uint8_t relays = 0;
+  if (port->fwd) {
+    relays = relaySystem->readValue_Forward(status);
+  } else {
+    relays = relaySystem->readValue_Reverse(status);
+  }
+
+  return (relays & (1 << port->channel)) != 0;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/SPI.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/SPI.cpp
new file mode 100644
index 0000000..ddced41
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/SPI.cpp
@@ -0,0 +1,634 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/SPI.h"
+
+#include <fcntl.h>
+#include <linux/spi/spidev.h>
+#include <sys/ioctl.h>
+#include <unistd.h>
+
+#include <array>
+#include <atomic>
+#include <cstring>
+
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "hal/DIO.h"
+#include "hal/HAL.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace hal;
+
+static int32_t m_spiCS0Handle{0};
+static int32_t m_spiCS1Handle{0};
+static int32_t m_spiCS2Handle{0};
+static int32_t m_spiCS3Handle{0};
+static int32_t m_spiMXPHandle{0};
+
+static constexpr int32_t kSpiMaxHandles = 5;
+
+// Indices 0-3 are for onboard CS0-CS2. Index 4 is for MXP.
+static std::array<wpi::mutex, kSpiMaxHandles> spiHandleMutexes;
+static std::array<wpi::mutex, kSpiMaxHandles> spiApiMutexes;
+static std::array<wpi::mutex, kSpiMaxHandles> spiAccumulatorMutexes;
+
+// MXP SPI does not count towards this
+static std::atomic<int32_t> spiPortCount{0};
+
+static HAL_DigitalHandle digitalHandles[9]{HAL_kInvalidHandle};
+
+static wpi::mutex spiAutoMutex;
+static int32_t spiAutoPort = kSpiMaxHandles;
+static std::atomic_bool spiAutoRunning{false};
+static std::unique_ptr<tDMAManager> spiAutoDMA;
+
+static bool SPIInUseByAuto(HAL_SPIPort port) {
+  // SPI engine conflicts with any other chip selects on the same SPI device.
+  // There are two SPI devices: one for ports 0-3 (onboard), the other for port
+  // 4 (MXP).
+  if (!spiAutoRunning) return false;
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  return (spiAutoPort >= 0 && spiAutoPort <= 3 && port >= 0 && port <= 3) ||
+         (spiAutoPort == 4 && port == 4);
+}
+
+namespace hal {
+namespace init {
+void InitializeSPI() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+static void CommonSPIPortInit(int32_t* status) {
+  // All false cases will set
+  if (spiPortCount.fetch_add(1) == 0) {
+    // Have not been initialized yet
+    initializeDigital(status);
+    if (*status != 0) return;
+    // MISO
+    if ((digitalHandles[3] = HAL_InitializeDIOPort(createPortHandleForSPI(29),
+                                                   false, status)) ==
+        HAL_kInvalidHandle) {
+      std::printf("Failed to allocate DIO 29 (MISO)\n");
+      return;
+    }
+    // MOSI
+    if ((digitalHandles[4] = HAL_InitializeDIOPort(createPortHandleForSPI(30),
+                                                   false, status)) ==
+        HAL_kInvalidHandle) {
+      std::printf("Failed to allocate DIO 30 (MOSI)\n");
+      HAL_FreeDIOPort(digitalHandles[3]);  // free the first port allocated
+      return;
+    }
+  }
+}
+
+static void CommonSPIPortFree(void) {
+  if (spiPortCount.fetch_sub(1) == 1) {
+    // Clean up SPI Handles
+    HAL_FreeDIOPort(digitalHandles[3]);
+    HAL_FreeDIOPort(digitalHandles[4]);
+  }
+}
+
+void HAL_InitializeSPI(HAL_SPIPort port, int32_t* status) {
+  hal::init::CheckInit();
+  if (port < 0 || port >= kSpiMaxHandles) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  int handle;
+  if (HAL_GetSPIHandle(port) != 0) return;
+  switch (port) {
+    case HAL_SPI_kOnboardCS0:
+      CommonSPIPortInit(status);
+      if (*status != 0) return;
+      // CS0 is not a DIO port, so nothing to allocate
+      handle = open("/dev/spidev0.0", O_RDWR);
+      if (handle < 0) {
+        std::printf("Failed to open SPI port %d: %s\n", port,
+                    std::strerror(errno));
+        CommonSPIPortFree();
+        return;
+      }
+      HAL_SetSPIHandle(HAL_SPI_kOnboardCS0, handle);
+      break;
+    case HAL_SPI_kOnboardCS1:
+      CommonSPIPortInit(status);
+      if (*status != 0) return;
+      // CS1, Allocate
+      if ((digitalHandles[0] = HAL_InitializeDIOPort(createPortHandleForSPI(26),
+                                                     false, status)) ==
+          HAL_kInvalidHandle) {
+        std::printf("Failed to allocate DIO 26 (CS1)\n");
+        CommonSPIPortFree();
+        return;
+      }
+      handle = open("/dev/spidev0.1", O_RDWR);
+      if (handle < 0) {
+        std::printf("Failed to open SPI port %d: %s\n", port,
+                    std::strerror(errno));
+        CommonSPIPortFree();
+        HAL_FreeDIOPort(digitalHandles[0]);
+        return;
+      }
+      HAL_SetSPIHandle(HAL_SPI_kOnboardCS1, handle);
+      break;
+    case HAL_SPI_kOnboardCS2:
+      CommonSPIPortInit(status);
+      if (*status != 0) return;
+      // CS2, Allocate
+      if ((digitalHandles[1] = HAL_InitializeDIOPort(createPortHandleForSPI(27),
+                                                     false, status)) ==
+          HAL_kInvalidHandle) {
+        std::printf("Failed to allocate DIO 27 (CS2)\n");
+        CommonSPIPortFree();
+        return;
+      }
+      handle = open("/dev/spidev0.2", O_RDWR);
+      if (handle < 0) {
+        std::printf("Failed to open SPI port %d: %s\n", port,
+                    std::strerror(errno));
+        CommonSPIPortFree();
+        HAL_FreeDIOPort(digitalHandles[1]);
+        return;
+      }
+      HAL_SetSPIHandle(HAL_SPI_kOnboardCS2, handle);
+      break;
+    case HAL_SPI_kOnboardCS3:
+      CommonSPIPortInit(status);
+      if (*status != 0) return;
+      // CS3, Allocate
+      if ((digitalHandles[2] = HAL_InitializeDIOPort(createPortHandleForSPI(28),
+                                                     false, status)) ==
+          HAL_kInvalidHandle) {
+        std::printf("Failed to allocate DIO 28 (CS3)\n");
+        CommonSPIPortFree();
+        return;
+      }
+      handle = open("/dev/spidev0.3", O_RDWR);
+      if (handle < 0) {
+        std::printf("Failed to open SPI port %d: %s\n", port,
+                    std::strerror(errno));
+        CommonSPIPortFree();
+        HAL_FreeDIOPort(digitalHandles[2]);
+        return;
+      }
+      HAL_SetSPIHandle(HAL_SPI_kOnboardCS3, handle);
+      break;
+    case HAL_SPI_kMXP:
+      initializeDigital(status);
+      if (*status != 0) return;
+      if ((digitalHandles[5] = HAL_InitializeDIOPort(createPortHandleForSPI(14),
+                                                     false, status)) ==
+          HAL_kInvalidHandle) {
+        wpi::outs() << "Failed to allocate DIO 14\n";
+        return;
+      }
+      if ((digitalHandles[6] = HAL_InitializeDIOPort(createPortHandleForSPI(15),
+                                                     false, status)) ==
+          HAL_kInvalidHandle) {
+        wpi::outs() << "Failed to allocate DIO 15\n";
+        HAL_FreeDIOPort(digitalHandles[5]);  // free the first port allocated
+        return;
+      }
+      if ((digitalHandles[7] = HAL_InitializeDIOPort(createPortHandleForSPI(16),
+                                                     false, status)) ==
+          HAL_kInvalidHandle) {
+        wpi::outs() << "Failed to allocate DIO 16\n";
+        HAL_FreeDIOPort(digitalHandles[5]);  // free the first port allocated
+        HAL_FreeDIOPort(digitalHandles[6]);  // free the second port allocated
+        return;
+      }
+      if ((digitalHandles[8] = HAL_InitializeDIOPort(createPortHandleForSPI(17),
+                                                     false, status)) ==
+          HAL_kInvalidHandle) {
+        wpi::outs() << "Failed to allocate DIO 17\n";
+        HAL_FreeDIOPort(digitalHandles[5]);  // free the first port allocated
+        HAL_FreeDIOPort(digitalHandles[6]);  // free the second port allocated
+        HAL_FreeDIOPort(digitalHandles[7]);  // free the third port allocated
+        return;
+      }
+      digitalSystem->writeEnableMXPSpecialFunction(
+          digitalSystem->readEnableMXPSpecialFunction(status) | 0x00F0, status);
+      handle = open("/dev/spidev1.0", O_RDWR);
+      if (handle < 0) {
+        std::printf("Failed to open SPI port %d: %s\n", port,
+                    std::strerror(errno));
+        HAL_FreeDIOPort(digitalHandles[5]);  // free the first port allocated
+        HAL_FreeDIOPort(digitalHandles[6]);  // free the second port allocated
+        HAL_FreeDIOPort(digitalHandles[7]);  // free the third port allocated
+        HAL_FreeDIOPort(digitalHandles[8]);  // free the fourth port allocated
+        return;
+      }
+      HAL_SetSPIHandle(HAL_SPI_kMXP, handle);
+      break;
+    default:
+      *status = PARAMETER_OUT_OF_RANGE;
+      break;
+  }
+}
+
+int32_t HAL_TransactionSPI(HAL_SPIPort port, const uint8_t* dataToSend,
+                           uint8_t* dataReceived, int32_t size) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return -1;
+  }
+
+  if (SPIInUseByAuto(port)) return -1;
+
+  struct spi_ioc_transfer xfer;
+  std::memset(&xfer, 0, sizeof(xfer));
+  xfer.tx_buf = (__u64)dataToSend;
+  xfer.rx_buf = (__u64)dataReceived;
+  xfer.len = size;
+
+  std::lock_guard<wpi::mutex> lock(spiApiMutexes[port]);
+  return ioctl(HAL_GetSPIHandle(port), SPI_IOC_MESSAGE(1), &xfer);
+}
+
+int32_t HAL_WriteSPI(HAL_SPIPort port, const uint8_t* dataToSend,
+                     int32_t sendSize) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return -1;
+  }
+
+  if (SPIInUseByAuto(port)) return -1;
+
+  struct spi_ioc_transfer xfer;
+  std::memset(&xfer, 0, sizeof(xfer));
+  xfer.tx_buf = (__u64)dataToSend;
+  xfer.len = sendSize;
+
+  std::lock_guard<wpi::mutex> lock(spiApiMutexes[port]);
+  return ioctl(HAL_GetSPIHandle(port), SPI_IOC_MESSAGE(1), &xfer);
+}
+
+int32_t HAL_ReadSPI(HAL_SPIPort port, uint8_t* buffer, int32_t count) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return -1;
+  }
+
+  if (SPIInUseByAuto(port)) return -1;
+
+  struct spi_ioc_transfer xfer;
+  std::memset(&xfer, 0, sizeof(xfer));
+  xfer.rx_buf = (__u64)buffer;
+  xfer.len = count;
+
+  std::lock_guard<wpi::mutex> lock(spiApiMutexes[port]);
+  return ioctl(HAL_GetSPIHandle(port), SPI_IOC_MESSAGE(1), &xfer);
+}
+
+void HAL_CloseSPI(HAL_SPIPort port) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return;
+  }
+
+  int32_t status = 0;
+  HAL_FreeSPIAuto(port, &status);
+
+  {
+    std::lock_guard<wpi::mutex> lock(spiApiMutexes[port]);
+    close(HAL_GetSPIHandle(port));
+  }
+
+  HAL_SetSPIHandle(port, 0);
+  if (port < 4) {
+    CommonSPIPortFree();
+  }
+
+  switch (port) {
+    // Case 0 does not need to do anything
+    case 1:
+      HAL_FreeDIOPort(digitalHandles[0]);
+      break;
+    case 2:
+      HAL_FreeDIOPort(digitalHandles[1]);
+      break;
+    case 3:
+      HAL_FreeDIOPort(digitalHandles[2]);
+      break;
+    case 4:
+      HAL_FreeDIOPort(digitalHandles[5]);
+      HAL_FreeDIOPort(digitalHandles[6]);
+      HAL_FreeDIOPort(digitalHandles[7]);
+      HAL_FreeDIOPort(digitalHandles[8]);
+      break;
+    default:
+      break;
+  }
+}
+
+void HAL_SetSPISpeed(HAL_SPIPort port, int32_t speed) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return;
+  }
+
+  std::lock_guard<wpi::mutex> lock(spiApiMutexes[port]);
+  ioctl(HAL_GetSPIHandle(port), SPI_IOC_WR_MAX_SPEED_HZ, &speed);
+}
+
+void HAL_SetSPIOpts(HAL_SPIPort port, HAL_Bool msbFirst,
+                    HAL_Bool sampleOnTrailing, HAL_Bool clkIdleHigh) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return;
+  }
+
+  uint8_t mode = 0;
+  mode |= (!msbFirst ? 8 : 0);
+  mode |= (clkIdleHigh ? 2 : 0);
+  mode |= (sampleOnTrailing ? 1 : 0);
+
+  std::lock_guard<wpi::mutex> lock(spiApiMutexes[port]);
+  ioctl(HAL_GetSPIHandle(port), SPI_IOC_WR_MODE, &mode);
+}
+
+void HAL_SetSPIChipSelectActiveHigh(HAL_SPIPort port, int32_t* status) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  std::lock_guard<wpi::mutex> lock(spiApiMutexes[port]);
+  if (port < 4) {
+    spiSystem->writeChipSelectActiveHigh_Hdr(
+        spiSystem->readChipSelectActiveHigh_Hdr(status) | (1 << port), status);
+  } else {
+    spiSystem->writeChipSelectActiveHigh_MXP(1, status);
+  }
+}
+
+void HAL_SetSPIChipSelectActiveLow(HAL_SPIPort port, int32_t* status) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  std::lock_guard<wpi::mutex> lock(spiApiMutexes[port]);
+  if (port < 4) {
+    spiSystem->writeChipSelectActiveHigh_Hdr(
+        spiSystem->readChipSelectActiveHigh_Hdr(status) & ~(1 << port), status);
+  } else {
+    spiSystem->writeChipSelectActiveHigh_MXP(0, status);
+  }
+}
+
+int32_t HAL_GetSPIHandle(HAL_SPIPort port) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return 0;
+  }
+
+  std::lock_guard<wpi::mutex> lock(spiHandleMutexes[port]);
+  switch (port) {
+    case 0:
+      return m_spiCS0Handle;
+    case 1:
+      return m_spiCS1Handle;
+    case 2:
+      return m_spiCS2Handle;
+    case 3:
+      return m_spiCS3Handle;
+    case 4:
+      return m_spiMXPHandle;
+    default:
+      return 0;
+  }
+}
+
+void HAL_SetSPIHandle(HAL_SPIPort port, int32_t handle) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    return;
+  }
+
+  std::lock_guard<wpi::mutex> lock(spiHandleMutexes[port]);
+  switch (port) {
+    case 0:
+      m_spiCS0Handle = handle;
+      break;
+    case 1:
+      m_spiCS1Handle = handle;
+      break;
+    case 2:
+      m_spiCS2Handle = handle;
+      break;
+    case 3:
+      m_spiCS3Handle = handle;
+      break;
+    case 4:
+      m_spiMXPHandle = handle;
+      break;
+    default:
+      break;
+  }
+}
+
+void HAL_InitSPIAuto(HAL_SPIPort port, int32_t bufferSize, int32_t* status) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  // FPGA only has one auto SPI engine
+  if (spiAutoPort != kSpiMaxHandles) {
+    *status = RESOURCE_IS_ALLOCATED;
+    return;
+  }
+
+  // remember the initialized port for other entry points
+  spiAutoPort = port;
+
+  // configure the correct chip select
+  if (port < 4) {
+    spiSystem->writeAutoSPI1Select(false, status);
+    spiSystem->writeAutoChipSelect(port, status);
+  } else {
+    spiSystem->writeAutoSPI1Select(true, status);
+    spiSystem->writeAutoChipSelect(0, status);
+  }
+
+  // configure DMA
+  tDMAChannelDescriptor desc;
+  spiSystem->getSystemInterface()->getDmaDescriptor(g_SpiAutoData_index, &desc);
+  spiAutoDMA = std::make_unique<tDMAManager>(desc.channel, bufferSize, status);
+}
+
+void HAL_FreeSPIAuto(HAL_SPIPort port, int32_t* status) {
+  if (port < 0 || port >= kSpiMaxHandles) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  if (spiAutoPort != port) return;
+  spiAutoPort = kSpiMaxHandles;
+
+  // disable by setting to internal clock and setting rate=0
+  spiSystem->writeAutoRate(0, status);
+  spiSystem->writeAutoTriggerConfig_ExternalClock(false, status);
+
+  // stop the DMA
+  spiAutoDMA->stop(status);
+
+  spiAutoDMA.reset(nullptr);
+
+  spiAutoRunning = false;
+}
+
+void HAL_StartSPIAutoRate(HAL_SPIPort port, double period, int32_t* status) {
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  // FPGA only has one auto SPI engine
+  if (port != spiAutoPort) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  spiAutoRunning = true;
+
+  // start the DMA
+  spiAutoDMA->start(status);
+
+  // auto rate is in microseconds
+  spiSystem->writeAutoRate(period * 1000000, status);
+
+  // disable the external clock
+  spiSystem->writeAutoTriggerConfig_ExternalClock(false, status);
+}
+
+void HAL_StartSPIAutoTrigger(HAL_SPIPort port, HAL_Handle digitalSourceHandle,
+                             HAL_AnalogTriggerType analogTriggerType,
+                             HAL_Bool triggerRising, HAL_Bool triggerFalling,
+                             int32_t* status) {
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  // FPGA only has one auto SPI engine
+  if (port != spiAutoPort) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  spiAutoRunning = true;
+
+  // start the DMA
+  spiAutoDMA->start(status);
+
+  // get channel routing
+  bool routingAnalogTrigger = false;
+  uint8_t routingChannel = 0;
+  uint8_t routingModule = 0;
+  if (!remapDigitalSource(digitalSourceHandle, analogTriggerType,
+                          routingChannel, routingModule,
+                          routingAnalogTrigger)) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  // configure external trigger and enable it
+  tSPI::tAutoTriggerConfig config;
+  config.ExternalClock = 1;
+  config.FallingEdge = triggerFalling ? 1 : 0;
+  config.RisingEdge = triggerRising ? 1 : 0;
+  config.ExternalClockSource_AnalogTrigger = routingAnalogTrigger ? 1 : 0;
+  config.ExternalClockSource_Module = routingModule;
+  config.ExternalClockSource_Channel = routingChannel;
+  spiSystem->writeAutoTriggerConfig(config, status);
+}
+
+void HAL_StopSPIAuto(HAL_SPIPort port, int32_t* status) {
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  // FPGA only has one auto SPI engine
+  if (port != spiAutoPort) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  // disable by setting to internal clock and setting rate=0
+  spiSystem->writeAutoRate(0, status);
+  spiSystem->writeAutoTriggerConfig_ExternalClock(false, status);
+
+  // stop the DMA
+  spiAutoDMA->stop(status);
+
+  spiAutoRunning = false;
+}
+
+void HAL_SetSPIAutoTransmitData(HAL_SPIPort port, const uint8_t* dataToSend,
+                                int32_t dataSize, int32_t zeroSize,
+                                int32_t* status) {
+  if (dataSize < 0 || dataSize > 16) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  if (zeroSize < 0 || zeroSize > 127) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  // FPGA only has one auto SPI engine
+  if (port != spiAutoPort) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  // set tx data registers
+  for (int32_t i = 0; i < dataSize; ++i)
+    spiSystem->writeAutoTx(i >> 2, i & 3, dataToSend[i], status);
+
+  // set byte counts
+  tSPI::tAutoByteCount config;
+  config.ZeroByteCount = static_cast<unsigned>(zeroSize) & 0x7f;
+  config.TxByteCount = static_cast<unsigned>(dataSize) & 0xf;
+  spiSystem->writeAutoByteCount(config, status);
+}
+
+void HAL_ForceSPIAutoRead(HAL_SPIPort port, int32_t* status) {
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  // FPGA only has one auto SPI engine
+  if (port != spiAutoPort) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  spiSystem->strobeAutoForceOne(status);
+}
+
+int32_t HAL_ReadSPIAutoReceivedData(HAL_SPIPort port, uint32_t* buffer,
+                                    int32_t numToRead, double timeout,
+                                    int32_t* status) {
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  // FPGA only has one auto SPI engine
+  if (port != spiAutoPort) {
+    *status = INCOMPATIBLE_STATE;
+    return 0;
+  }
+
+  size_t numRemaining = 0;
+  // timeout is in ms
+  spiAutoDMA->read(buffer, numToRead, timeout * 1000, &numRemaining, status);
+  return numRemaining;
+}
+
+int32_t HAL_GetSPIAutoDroppedCount(HAL_SPIPort port, int32_t* status) {
+  std::lock_guard<wpi::mutex> lock(spiAutoMutex);
+  // FPGA only has one auto SPI engine
+  if (port != spiAutoPort) {
+    *status = INCOMPATIBLE_STATE;
+    return 0;
+  }
+
+  return spiSystem->readTransferSkippedFullCount(status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/SerialPort.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/SerialPort.cpp
new file mode 100644
index 0000000..d2597a9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/SerialPort.cpp
@@ -0,0 +1,174 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/SerialPort.h"
+
+#include <string>
+
+#include "HALInitializer.h"
+#include "hal/cpp/SerialHelper.h"
+#include "visa/visa.h"
+
+static int32_t resourceManagerHandle{0};
+static HAL_SerialPort portHandles[4];
+
+namespace hal {
+namespace init {
+void InitializeSerialPort() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+void HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status) {
+  hal::init::CheckInit();
+  std::string portName;
+
+  if (resourceManagerHandle == 0)
+    viOpenDefaultRM(reinterpret_cast<ViSession*>(&resourceManagerHandle));
+
+  hal::SerialHelper serialHelper;
+
+  portName = serialHelper.GetVISASerialPortName(port, status);
+
+  if (*status < 0) {
+    return;
+  }
+
+  *status = viOpen(resourceManagerHandle, const_cast<char*>(portName.c_str()),
+                   VI_NULL, VI_NULL,
+                   reinterpret_cast<ViSession*>(&portHandles[port]));
+  if (*status > 0) *status = 0;
+}
+
+void HAL_InitializeSerialPortDirect(HAL_SerialPort port, const char* portName,
+                                    int32_t* status) {
+  *status = viOpen(resourceManagerHandle, const_cast<char*>(portName), VI_NULL,
+                   VI_NULL, reinterpret_cast<ViSession*>(&portHandles[port]));
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialBaudRate(HAL_SerialPort port, int32_t baud, int32_t* status) {
+  *status = viSetAttribute(portHandles[port], VI_ATTR_ASRL_BAUD, baud);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialDataBits(HAL_SerialPort port, int32_t bits, int32_t* status) {
+  *status = viSetAttribute(portHandles[port], VI_ATTR_ASRL_DATA_BITS, bits);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialParity(HAL_SerialPort port, int32_t parity, int32_t* status) {
+  *status = viSetAttribute(portHandles[port], VI_ATTR_ASRL_PARITY, parity);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialStopBits(HAL_SerialPort port, int32_t stopBits,
+                           int32_t* status) {
+  *status = viSetAttribute(portHandles[port], VI_ATTR_ASRL_STOP_BITS, stopBits);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialWriteMode(HAL_SerialPort port, int32_t mode,
+                            int32_t* status) {
+  *status = viSetAttribute(portHandles[port], VI_ATTR_WR_BUF_OPER_MODE, mode);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialFlowControl(HAL_SerialPort port, int32_t flow,
+                              int32_t* status) {
+  *status = viSetAttribute(portHandles[port], VI_ATTR_ASRL_FLOW_CNTRL, flow);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialTimeout(HAL_SerialPort port, double timeout,
+                          int32_t* status) {
+  *status = viSetAttribute(portHandles[port], VI_ATTR_TMO_VALUE,
+                           static_cast<uint32_t>(timeout * 1e3));
+  if (*status > 0) *status = 0;
+}
+
+void HAL_EnableSerialTermination(HAL_SerialPort port, char terminator,
+                                 int32_t* status) {
+  viSetAttribute(portHandles[port], VI_ATTR_TERMCHAR_EN, VI_TRUE);
+  viSetAttribute(portHandles[port], VI_ATTR_TERMCHAR, terminator);
+  *status = viSetAttribute(portHandles[port], VI_ATTR_ASRL_END_IN,
+                           VI_ASRL_END_TERMCHAR);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_DisableSerialTermination(HAL_SerialPort port, int32_t* status) {
+  viSetAttribute(portHandles[port], VI_ATTR_TERMCHAR_EN, VI_FALSE);
+  *status =
+      viSetAttribute(portHandles[port], VI_ATTR_ASRL_END_IN, VI_ASRL_END_NONE);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialReadBufferSize(HAL_SerialPort port, int32_t size,
+                                 int32_t* status) {
+  *status = viSetBuf(portHandles[port], VI_READ_BUF, size);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_SetSerialWriteBufferSize(HAL_SerialPort port, int32_t size,
+                                  int32_t* status) {
+  *status = viSetBuf(portHandles[port], VI_WRITE_BUF, size);
+  if (*status > 0) *status = 0;
+}
+
+int32_t HAL_GetSerialBytesReceived(HAL_SerialPort port, int32_t* status) {
+  int32_t bytes = 0;
+
+  *status = viGetAttribute(portHandles[port], VI_ATTR_ASRL_AVAIL_NUM, &bytes);
+  if (*status > 0) *status = 0;
+  return bytes;
+}
+
+int32_t HAL_ReadSerial(HAL_SerialPort port, char* buffer, int32_t count,
+                       int32_t* status) {
+  uint32_t retCount = 0;
+
+  *status =
+      viRead(portHandles[port], (ViPBuf)buffer, count, (ViPUInt32)&retCount);
+
+  if (*status == VI_ERROR_IO || *status == VI_ERROR_ASRL_OVERRUN ||
+      *status == VI_ERROR_ASRL_FRAMING || *status == VI_ERROR_ASRL_PARITY) {
+    int32_t localStatus = 0;
+    HAL_ClearSerial(port, &localStatus);
+  }
+
+  if (*status == VI_ERROR_TMO || *status > 0) *status = 0;
+  return static_cast<int32_t>(retCount);
+}
+
+int32_t HAL_WriteSerial(HAL_SerialPort port, const char* buffer, int32_t count,
+                        int32_t* status) {
+  uint32_t retCount = 0;
+
+  *status =
+      viWrite(portHandles[port], (ViPBuf)buffer, count, (ViPUInt32)&retCount);
+
+  if (*status > 0) *status = 0;
+  return static_cast<int32_t>(retCount);
+}
+
+void HAL_FlushSerial(HAL_SerialPort port, int32_t* status) {
+  *status = viFlush(portHandles[port], VI_WRITE_BUF);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_ClearSerial(HAL_SerialPort port, int32_t* status) {
+  *status = viClear(portHandles[port]);
+  if (*status > 0) *status = 0;
+}
+
+void HAL_CloseSerial(HAL_SerialPort port, int32_t* status) {
+  *status = viClose(portHandles[port]);
+  if (*status > 0) *status = 0;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Solenoid.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Solenoid.cpp
new file mode 100644
index 0000000..c53db11
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Solenoid.cpp
@@ -0,0 +1,191 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Solenoid.h"
+
+#include <FRC_NetworkCommunication/LoadOut.h>
+
+#include "HALInitializer.h"
+#include "PCMInternal.h"
+#include "PortsInternal.h"
+#include "ctre/PCM.h"
+#include "hal/ChipObject.h"
+#include "hal/Errors.h"
+#include "hal/Ports.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/IndexedHandleResource.h"
+
+namespace {
+
+struct Solenoid {
+  uint8_t module;
+  uint8_t channel;
+};
+
+}  // namespace
+
+using namespace hal;
+
+static IndexedHandleResource<HAL_SolenoidHandle, Solenoid,
+                             kNumPCMModules * kNumSolenoidChannels,
+                             HAL_HandleEnum::Solenoid>* solenoidHandles;
+
+namespace hal {
+namespace init {
+void InitializeSolenoid() {
+  static IndexedHandleResource<HAL_SolenoidHandle, Solenoid,
+                               kNumPCMModules * kNumSolenoidChannels,
+                               HAL_HandleEnum::Solenoid>
+      sH;
+  solenoidHandles = &sH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_SolenoidHandle HAL_InitializeSolenoidPort(HAL_PortHandle portHandle,
+                                              int32_t* status) {
+  hal::init::CheckInit();
+  int16_t channel = getPortHandleChannel(portHandle);
+  int16_t module = getPortHandleModule(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  // initializePCM will check the module
+  if (!HAL_CheckSolenoidChannel(channel)) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  initializePCM(module, status);
+  if (*status != 0) {
+    return HAL_kInvalidHandle;
+  }
+
+  auto handle = solenoidHandles->Allocate(
+      module * kNumSolenoidChannels + channel, status);
+  if (*status != 0) {
+    return HAL_kInvalidHandle;
+  }
+  auto solenoidPort = solenoidHandles->Get(handle);
+  if (solenoidPort == nullptr) {  // would only occur on thread issues
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  solenoidPort->module = static_cast<uint8_t>(module);
+  solenoidPort->channel = static_cast<uint8_t>(channel);
+
+  return handle;
+}
+
+void HAL_FreeSolenoidPort(HAL_SolenoidHandle solenoidPortHandle) {
+  solenoidHandles->Free(solenoidPortHandle);
+}
+
+HAL_Bool HAL_CheckSolenoidModule(int32_t module) {
+  return module < kNumPCMModules && module >= 0;
+}
+
+HAL_Bool HAL_CheckSolenoidChannel(int32_t channel) {
+  return channel < kNumSolenoidChannels && channel >= 0;
+}
+
+HAL_Bool HAL_GetSolenoid(HAL_SolenoidHandle solenoidPortHandle,
+                         int32_t* status) {
+  auto port = solenoidHandles->Get(solenoidPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  bool value;
+
+  *status = PCM_modules[port->module]->GetSolenoid(port->channel, value);
+
+  return value;
+}
+
+int32_t HAL_GetAllSolenoids(int32_t module, int32_t* status) {
+  if (!checkPCMInit(module, status)) return 0;
+  uint8_t value;
+
+  *status = PCM_modules[module]->GetAllSolenoids(value);
+
+  return value;
+}
+
+void HAL_SetSolenoid(HAL_SolenoidHandle solenoidPortHandle, HAL_Bool value,
+                     int32_t* status) {
+  auto port = solenoidHandles->Get(solenoidPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  *status = PCM_modules[port->module]->SetSolenoid(port->channel, value);
+}
+
+void HAL_SetAllSolenoids(int32_t module, int32_t state, int32_t* status) {
+  if (!checkPCMInit(module, status)) return;
+
+  *status = PCM_modules[module]->SetAllSolenoids(state);
+}
+
+int32_t HAL_GetPCMSolenoidBlackList(int32_t module, int32_t* status) {
+  if (!checkPCMInit(module, status)) return 0;
+  uint8_t value;
+
+  *status = PCM_modules[module]->GetSolenoidBlackList(value);
+
+  return value;
+}
+HAL_Bool HAL_GetPCMSolenoidVoltageStickyFault(int32_t module, int32_t* status) {
+  if (!checkPCMInit(module, status)) return 0;
+  bool value;
+
+  *status = PCM_modules[module]->GetSolenoidStickyFault(value);
+
+  return value;
+}
+HAL_Bool HAL_GetPCMSolenoidVoltageFault(int32_t module, int32_t* status) {
+  if (!checkPCMInit(module, status)) return false;
+  bool value;
+
+  *status = PCM_modules[module]->GetSolenoidFault(value);
+
+  return value;
+}
+void HAL_ClearAllPCMStickyFaults(int32_t module, int32_t* status) {
+  if (!checkPCMInit(module, status)) return;
+
+  *status = PCM_modules[module]->ClearStickyFaults();
+}
+
+void HAL_SetOneShotDuration(HAL_SolenoidHandle solenoidPortHandle,
+                            int32_t durMS, int32_t* status) {
+  auto port = solenoidHandles->Get(solenoidPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  *status =
+      PCM_modules[port->module]->SetOneShotDurationMs(port->channel, durMS);
+}
+
+void HAL_FireOneShot(HAL_SolenoidHandle solenoidPortHandle, int32_t* status) {
+  auto port = solenoidHandles->Get(solenoidPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  *status = PCM_modules[port->module]->FireOneShotSolenoid(port->channel);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/Threads.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/Threads.cpp
new file mode 100644
index 0000000..95d1f59
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/Threads.cpp
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Threads.h"
+
+#include <pthread.h>
+#include <sched.h>
+
+#include "hal/Errors.h"
+
+namespace hal {
+namespace init {
+void InitializeThreads() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+int32_t HAL_GetThreadPriority(NativeThreadHandle handle, HAL_Bool* isRealTime,
+                              int32_t* status) {
+  sched_param sch;
+  int policy;
+  int success = pthread_getschedparam(
+      *reinterpret_cast<const pthread_t*>(handle), &policy, &sch);
+  if (success == 0) {
+    *status = 0;
+  } else {
+    *status = HAL_THREAD_PRIORITY_ERROR;
+    return -1;
+  }
+  if (policy == SCHED_FIFO || policy == SCHED_RR) {
+    *isRealTime = true;
+    return sch.sched_priority;
+  } else {
+    *isRealTime = false;
+    // 0 is the only suppored priority for non-realtime, so scale to 1
+    return 1;
+  }
+}
+
+int32_t HAL_GetCurrentThreadPriority(HAL_Bool* isRealTime, int32_t* status) {
+  auto thread = pthread_self();
+  return HAL_GetThreadPriority(&thread, isRealTime, status);
+}
+
+HAL_Bool HAL_SetThreadPriority(NativeThreadHandle handle, HAL_Bool realTime,
+                               int32_t priority, int32_t* status) {
+  if (handle == nullptr) {
+    *status = NULL_PARAMETER;
+    return false;
+  }
+
+  int scheduler = realTime ? SCHED_FIFO : SCHED_OTHER;
+  if (realTime) {
+    // We don't support setting priorities for non RT threads
+    // so we don't need to check for proper range
+    if (priority < sched_get_priority_min(scheduler) ||
+        priority > sched_get_priority_max(scheduler)) {
+      *status = HAL_THREAD_PRIORITY_RANGE_ERROR;
+      return false;
+    }
+  }
+
+  sched_param sch;
+  int policy;
+  pthread_getschedparam(*reinterpret_cast<const pthread_t*>(handle), &policy,
+                        &sch);
+  if (scheduler == SCHED_FIFO || scheduler == SCHED_RR)
+    sch.sched_priority = priority;
+  else
+    // Only need to set 0 priority for non RT thread
+    sch.sched_priority = 0;
+  if (pthread_setschedparam(*reinterpret_cast<const pthread_t*>(handle),
+                            scheduler, &sch)) {
+    *status = HAL_THREAD_PRIORITY_ERROR;
+    return false;
+  } else {
+    *status = 0;
+    return true;
+  }
+}
+
+HAL_Bool HAL_SetCurrentThreadPriority(HAL_Bool realTime, int32_t priority,
+                                      int32_t* status) {
+  auto thread = pthread_self();
+  return HAL_SetThreadPriority(&thread, realTime, priority, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/cpp/SerialHelper.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/cpp/SerialHelper.cpp
new file mode 100644
index 0000000..98b22db
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/cpp/SerialHelper.cpp
@@ -0,0 +1,333 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/cpp/SerialHelper.h"
+
+#include <algorithm>
+#include <cstdio>
+#include <cstring>
+
+#include <wpi/FileSystem.h>
+#include <wpi/StringRef.h>
+
+#include "../visa/visa.h"
+#include "hal/Errors.h"
+
+constexpr const char* OnboardResourceVISA = "ASRL1::INSTR";
+constexpr const char* MxpResourceVISA = "ASRL2::INSTR";
+
+constexpr const char* OnboardResourceOS = "/dev/ttyS0";
+constexpr const char* MxpResourceOS = "/dev/ttyS1";
+
+namespace hal {
+
+std::string SerialHelper::m_usbNames[2]{"", ""};
+
+wpi::mutex SerialHelper::m_nameMutex;
+
+SerialHelper::SerialHelper() {
+  viOpenDefaultRM(reinterpret_cast<ViSession*>(&m_resourceHandle));
+}
+
+std::string SerialHelper::GetVISASerialPortName(HAL_SerialPort port,
+                                                int32_t* status) {
+  if (port == HAL_SerialPort::HAL_SerialPort_Onboard) {
+    return OnboardResourceVISA;
+  } else if (port == HAL_SerialPort::HAL_SerialPort_MXP) {
+    return MxpResourceVISA;
+  }
+
+  QueryHubPaths(status);
+
+  // If paths are empty or status error, return error
+  if (*status != 0 || m_visaResource.empty() || m_osResource.empty() ||
+      m_sortedHubPath.empty()) {
+    *status = HAL_SERIAL_PORT_NOT_FOUND;
+    return "";
+  }
+
+  int32_t visaIndex = GetIndexForPort(port, status);
+  if (visaIndex == -1) {
+    *status = HAL_SERIAL_PORT_NOT_FOUND;
+    return "";
+    // Error
+  } else {
+    return m_visaResource[visaIndex].str();
+  }
+}
+
+std::string SerialHelper::GetOSSerialPortName(HAL_SerialPort port,
+                                              int32_t* status) {
+  if (port == HAL_SerialPort::HAL_SerialPort_Onboard) {
+    return OnboardResourceOS;
+  } else if (port == HAL_SerialPort::HAL_SerialPort_MXP) {
+    return MxpResourceOS;
+  }
+
+  QueryHubPaths(status);
+
+  // If paths are empty or status error, return error
+  if (*status != 0 || m_visaResource.empty() || m_osResource.empty() ||
+      m_sortedHubPath.empty()) {
+    *status = HAL_SERIAL_PORT_NOT_FOUND;
+    return "";
+  }
+
+  int32_t osIndex = GetIndexForPort(port, status);
+  if (osIndex == -1) {
+    *status = HAL_SERIAL_PORT_NOT_FOUND;
+    return "";
+    // Error
+  } else {
+    return m_osResource[osIndex].str();
+  }
+}
+
+std::vector<std::string> SerialHelper::GetVISASerialPortList(int32_t* status) {
+  std::vector<std::string> retVec;
+
+  // Always add 2 onboard ports
+  retVec.emplace_back(OnboardResourceVISA);
+  retVec.emplace_back(MxpResourceVISA);
+
+  QueryHubPaths(status);
+
+  // If paths are empty or status error, return only onboard list
+  if (*status != 0 || m_visaResource.empty() || m_osResource.empty() ||
+      m_sortedHubPath.empty()) {
+    *status = 0;
+    return retVec;
+  }
+
+  for (auto& i : m_visaResource) {
+    retVec.emplace_back(i.str());
+  }
+
+  return retVec;
+}
+
+std::vector<std::string> SerialHelper::GetOSSerialPortList(int32_t* status) {
+  std::vector<std::string> retVec;
+
+  // Always add 2 onboard ports
+  retVec.emplace_back(OnboardResourceOS);
+  retVec.emplace_back(MxpResourceOS);
+
+  QueryHubPaths(status);
+
+  // If paths are empty or status error, return only onboard list
+  if (*status != 0 || m_visaResource.empty() || m_osResource.empty() ||
+      m_sortedHubPath.empty()) {
+    *status = 0;
+    return retVec;
+  }
+
+  for (auto& i : m_osResource) {
+    retVec.emplace_back(i.str());
+  }
+
+  return retVec;
+}
+
+void SerialHelper::SortHubPathVector() {
+  m_sortedHubPath.clear();
+  m_sortedHubPath = m_unsortedHubPath;
+  std::sort(m_sortedHubPath.begin(), m_sortedHubPath.end(),
+            [](const wpi::SmallVectorImpl<char>& lhs,
+               const wpi::SmallVectorImpl<char>& rhs) -> int {
+              wpi::StringRef lhsRef(lhs.begin(), lhs.size());
+              wpi::StringRef rhsRef(rhs.begin(), rhs.size());
+              return lhsRef.compare(rhsRef);
+            });
+}
+
+void SerialHelper::CoiteratedSort(
+    wpi::SmallVectorImpl<wpi::SmallString<16>>& vec) {
+  wpi::SmallVector<wpi::SmallString<16>, 4> sortedVec;
+  for (auto& str : m_sortedHubPath) {
+    for (size_t i = 0; i < m_unsortedHubPath.size(); i++) {
+      if (wpi::StringRef{m_unsortedHubPath[i].begin(),
+                         m_unsortedHubPath[i].size()}
+              .equals(wpi::StringRef{str.begin(), str.size()})) {
+        sortedVec.push_back(vec[i]);
+        break;
+      }
+    }
+  }
+  vec = sortedVec;
+}
+
+void SerialHelper::QueryHubPaths(int32_t* status) {
+  // VISA resource matching string
+  const char* str = "?*";
+  // Items needed for VISA
+  ViUInt32 retCnt = 0;
+  ViFindList viList = 0;
+  ViChar desc[VI_FIND_BUFLEN];
+  *status = viFindRsrc(m_resourceHandle, const_cast<char*>(str), &viList,
+                       &retCnt, desc);
+
+  if (*status < 0) {
+    // Handle the bad status elsewhere
+    // Note let positive statii (warnings) continue
+    goto done;
+  }
+  // Status might be positive, so reset it to 0
+  *status = 0;
+
+  // Storage buffer for Visa call
+  char osName[256];
+
+  // Loop through all returned VISA objects.
+  // Increment the internal VISA ptr every loop
+  for (size_t i = 0; i < retCnt; i++, viFindNext(viList, desc)) {
+    // Ignore any matches to the 2 onboard ports
+    if (std::strcmp(OnboardResourceVISA, desc) == 0 ||
+        std::strcmp(MxpResourceVISA, desc) == 0) {
+      continue;
+    }
+
+    // Open the resource, grab its interface name, and close it.
+    ViSession vSession;
+    *status = viOpen(m_resourceHandle, desc, VI_NULL, VI_NULL, &vSession);
+    if (*status < 0) goto done;
+    *status = 0;
+
+    *status = viGetAttribute(vSession, VI_ATTR_INTF_INST_NAME, &osName);
+    // Ignore an error here, as we want to close the session on an error
+    // Use a seperate close variable so we can check
+    ViStatus closeStatus = viClose(vSession);
+    if (*status < 0) goto done;
+    if (closeStatus < 0) goto done;
+    *status = 0;
+
+    // split until (/dev/
+    wpi::StringRef devNameRef = wpi::StringRef{osName}.split("(/dev/").second;
+    // String not found, continue
+    if (devNameRef.equals("")) continue;
+
+    // Split at )
+    wpi::StringRef matchString = devNameRef.split(')').first;
+    if (matchString.equals(devNameRef)) continue;
+
+    // Search directories to get a list of system accessors
+    // The directories we need are not symbolic, so we can safely
+    // disable symbolic links.
+    std::error_code ec;
+    for (auto p = wpi::sys::fs::recursive_directory_iterator(
+             "/sys/devices/soc0", ec, false);
+         p != wpi::sys::fs::recursive_directory_iterator(); p.increment(ec)) {
+      if (ec) break;
+      wpi::StringRef path{p->path()};
+      if (path.find("amba") == wpi::StringRef::npos) continue;
+      if (path.find("usb") == wpi::StringRef::npos) continue;
+      if (path.find(matchString) == wpi::StringRef::npos) continue;
+
+      wpi::SmallVector<wpi::StringRef, 16> pathSplitVec;
+      // Split path into individual directories
+      path.split(pathSplitVec, '/', -1, false);
+
+      // Find each individual item index
+      int findusb = -1;
+      int findtty = -1;
+      int findregex = -1;
+      for (size_t i = 0; i < pathSplitVec.size(); i++) {
+        if (findusb == -1 && pathSplitVec[i].equals("usb1")) {
+          findusb = i;
+        }
+        if (findtty == -1 && pathSplitVec[i].equals("tty")) {
+          findtty = i;
+        }
+        if (findregex == -1 && pathSplitVec[i].equals(matchString)) {
+          findregex = i;
+        }
+      }
+
+      // Get the index for our device
+      int hubIndex = findtty;
+      if (findtty == -1) hubIndex = findregex;
+
+      int devStart = findusb + 1;
+
+      if (hubIndex < devStart) continue;
+
+      // Add our devices to our list
+      m_unsortedHubPath.emplace_back(
+          wpi::StringRef{pathSplitVec[hubIndex - 2]});
+      m_visaResource.emplace_back(desc);
+      m_osResource.emplace_back(
+          wpi::StringRef{osName}.split("(").second.split(")").first);
+      break;
+    }
+  }
+
+  SortHubPathVector();
+
+  CoiteratedSort(m_visaResource);
+  CoiteratedSort(m_osResource);
+done:
+  viClose(viList);
+}
+
+int32_t SerialHelper::GetIndexForPort(HAL_SerialPort port, int32_t* status) {
+  // Hold lock whenever we're using the names array
+  std::lock_guard<wpi::mutex> lock(m_nameMutex);
+
+  std::string portString = m_usbNames[port - 2];
+
+  wpi::SmallVector<int32_t, 4> indices;
+
+  // If port has not been assigned, find the one to assign
+  if (portString.empty()) {
+    for (size_t i = 0; i < 2; i++) {
+      // Remove all used ports
+      auto idx = std::find(m_sortedHubPath.begin(), m_sortedHubPath.end(),
+                           m_usbNames[i]);
+      if (idx != m_sortedHubPath.end()) {
+        // found
+        m_sortedHubPath.erase(idx);
+      }
+      if (m_usbNames[i] == "") {
+        indices.push_back(i);
+      }
+    }
+
+    int32_t idx = -1;
+    for (size_t i = 0; i < indices.size(); i++) {
+      if (indices[i] == port - 2) {
+        idx = i;
+        break;
+      }
+    }
+
+    if (idx == -1) {
+      *status = HAL_SERIAL_PORT_NOT_FOUND;
+      return -1;
+    }
+
+    if (idx >= static_cast<int32_t>(m_sortedHubPath.size())) {
+      *status = HAL_SERIAL_PORT_NOT_FOUND;
+      return -1;
+    }
+
+    portString = m_sortedHubPath[idx].str();
+    m_usbNames[port - 2] = portString;
+  }
+
+  int retIndex = -1;
+
+  for (size_t i = 0; i < m_sortedHubPath.size(); i++) {
+    if (m_sortedHubPath[i].equals(portString)) {
+      retIndex = i;
+      break;
+    }
+  }
+
+  return retIndex;
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/CtreCanNode.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/CtreCanNode.cpp
new file mode 100644
index 0000000..bd3c9e8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/CtreCanNode.cpp
@@ -0,0 +1,157 @@
+#pragma GCC diagnostic ignored "-Wmissing-field-initializers"
+
+#include "CtreCanNode.h"
+#include "FRC_NetworkCommunication/CANSessionMux.h"
+#include <string.h> // memset
+
+static const UINT32 kFullMessageIDMask = 0x1fffffff;
+
+CtreCanNode::CtreCanNode(UINT8 deviceNumber)
+{
+	_deviceNumber = deviceNumber;
+}
+CtreCanNode::~CtreCanNode()
+{
+}
+void CtreCanNode::RegisterRx(uint32_t arbId)
+{
+	/* no need to do anything, we just use new API to poll last received message */
+}
+/**
+ * Schedule a CAN Frame for periodic transmit.
+ * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.
+ * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.
+ * @param dlc 		Number of bytes to transmit (0 to 8).
+ * @param initialFrame	Ptr to the frame data to schedule for transmitting.  Passing null will result
+ *						in defaulting to zero data value.
+ */
+void CtreCanNode::RegisterTx(uint32_t arbId, uint32_t periodMs, uint32_t dlc, const uint8_t * initialFrame)
+{
+	int32_t status = 0;
+	if(dlc > 8)
+		dlc = 8;
+	txJob_t job = {0};
+	job.arbId = arbId;
+	job.periodMs = periodMs;
+	job.dlc = dlc;
+	if(initialFrame){
+		/* caller wants to specify original data */
+		memcpy(job.toSend, initialFrame, dlc);
+	}
+	_txJobs[arbId] = job;
+	FRC_NetworkCommunication_CANSessionMux_sendMessage(	job.arbId,
+														job.toSend,
+														job.dlc,
+														job.periodMs,
+														&status);
+}
+/**
+ * Schedule a CAN Frame for periodic transmit.  Assume eight byte DLC and zero value for initial transmission.
+ * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.
+ * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.
+ */
+void CtreCanNode::RegisterTx(uint32_t arbId, uint32_t periodMs)
+{
+	RegisterTx(arbId,periodMs, 8, 0);
+}
+/**
+ * Remove a CAN frame Arbid to stop transmission.
+ * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.
+ */
+void CtreCanNode::UnregisterTx(uint32_t arbId)
+{
+	/* set period to zero */
+	ChangeTxPeriod(arbId, 0);
+	/* look and remove */
+	txJobs_t::iterator iter = _txJobs.find(arbId);
+	if(iter != _txJobs.end()) {
+		_txJobs.erase(iter);
+	}
+}
+static int64_t GetTimeMs() {
+	std::chrono::time_point < std::chrono::system_clock > now;
+	now = std::chrono::system_clock::now();
+	auto duration = now.time_since_epoch();
+	auto millis = std::chrono::duration_cast < std::chrono::milliseconds
+					> (duration).count();
+	return (int64_t) millis;
+}
+CTR_Code CtreCanNode::GetRx(uint32_t arbId,uint8_t * dataBytes, uint32_t timeoutMs)
+{
+	CTR_Code retval = CTR_OKAY;
+	int32_t status = 0;
+	uint8_t len = 0;
+	uint32_t timeStamp;
+	/* cap timeout at 999ms */
+	if(timeoutMs > 999)
+		timeoutMs = 999;
+	FRC_NetworkCommunication_CANSessionMux_receiveMessage(&arbId,kFullMessageIDMask,dataBytes,&len,&timeStamp,&status);
+	std::lock_guard<wpi::mutex> lock(_lck);
+	if(status == 0){
+		/* fresh update */
+		rxEvent_t & r = _rxRxEvents[arbId]; /* lookup entry or make a default new one with all zeroes */
+		r.time = GetTimeMs();
+		memcpy(r.bytes,  dataBytes,  8);	/* fill in databytes */
+	}else{
+		/* did not get the message */
+		rxRxEvents_t::iterator i = _rxRxEvents.find(arbId);
+		if(i == _rxRxEvents.end()){
+			/* we've never gotten this mesage */
+			retval = CTR_RxTimeout;
+			/* fill caller's buffer with zeros */
+			memset(dataBytes,0,8);
+		}else{
+			/* we've gotten this message before but not recently */
+			memcpy(dataBytes,i->second.bytes,8);
+			/* get the time now */
+			int64_t now = GetTimeMs(); /* get now */
+			/* how long has it been? */
+			int64_t temp = now - i->second.time; /* temp = now - last */
+			if (temp > ((int64_t) timeoutMs)) {
+					retval = CTR_RxTimeout;
+			} else {
+					/* our last update was recent enough */
+			}
+		}
+	}
+
+	return retval;
+}
+void CtreCanNode::FlushTx(uint32_t arbId)
+{
+	int32_t status = 0;
+	txJobs_t::iterator iter = _txJobs.find(arbId);
+	if(iter != _txJobs.end())
+		FRC_NetworkCommunication_CANSessionMux_sendMessage(	iter->second.arbId,
+															iter->second.toSend,
+															iter->second.dlc,
+															iter->second.periodMs,
+															&status);
+}
+/**
+ * Change the transmit period of an already scheduled CAN frame.
+ * This keeps the frame payload contents the same without caller having to perform
+ * a read-modify-write.
+ * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.
+ * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.
+ * @return true if scheduled job was found and updated, false if there was no preceding job for the specified arbID.
+ */
+bool CtreCanNode::ChangeTxPeriod(uint32_t arbId, uint32_t periodMs)
+{
+	int32_t status = 0;
+	/* lookup the data bytes and period for this message */
+	txJobs_t::iterator iter = _txJobs.find(arbId);
+	if(iter != _txJobs.end()) {
+		/* modify th periodMs */
+		iter->second.periodMs = periodMs;
+		/* reinsert into scheduler with the same data bytes, only the period changed. */
+		FRC_NetworkCommunication_CANSessionMux_sendMessage(	iter->second.arbId,
+															iter->second.toSend,
+															iter->second.dlc,
+															iter->second.periodMs,
+															&status);
+		return true;
+	}
+	return false;
+}
+
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/CtreCanNode.h b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/CtreCanNode.h
new file mode 100644
index 0000000..f00060d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/CtreCanNode.h
@@ -0,0 +1,134 @@
+#ifndef CtreCanNode_H_
+#define CtreCanNode_H_
+#include "ctre.h"				//BIT Defines + Typedefs
+#include <map>
+#include <string.h> // memcpy
+#include <sys/time.h>
+#include <wpi/mutex.h>
+class CtreCanNode
+{
+public:
+	CtreCanNode(UINT8 deviceNumber);
+    ~CtreCanNode();
+
+	UINT8 GetDeviceNumber()
+	{
+		return _deviceNumber;
+	}
+protected:
+
+
+	template <typename T> class txTask{
+		public:
+			uint32_t arbId;
+			T * toSend;
+			T * operator -> ()
+			{
+				return toSend;
+			}
+			T & operator*()
+			{
+				return *toSend;
+			}
+			bool IsEmpty()
+			{
+				if(toSend == 0)
+					return true;
+				return false;
+			}
+	};
+	template <typename T> class recMsg{
+		public:
+			uint32_t arbId;
+			uint8_t bytes[8];
+			CTR_Code err;
+			T * operator -> ()
+			{
+				return (T *)bytes;
+			}
+			T & operator*()
+			{
+				return *(T *)bytes;
+			}
+	};
+	UINT8 _deviceNumber;
+	void RegisterRx(uint32_t arbId);
+	/**
+	 * Schedule a CAN Frame for periodic transmit.  Assume eight byte DLC and zero value for initial transmission.
+	 * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.
+	 * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.
+	 */
+	void RegisterTx(uint32_t arbId, uint32_t periodMs);
+	/**
+	 * Schedule a CAN Frame for periodic transmit.
+	 * @param arbId 	CAN Frame Arbitration ID.  Set BIT31 for 11bit ids, otherwise we use 29bit ids.
+	 * @param periodMs	Period to transmit CAN frame.  Pass 0 for one-shot, which also disables that ArbID's preceding periodic transmit.
+	 * @param dlc 		Number of bytes to transmit (0 to 8).
+	 * @param initialFrame	Ptr to the frame data to schedule for transmitting.  Passing null will result
+	 *						in defaulting to zero data value.
+	 */
+	void RegisterTx(uint32_t arbId, uint32_t periodMs, uint32_t dlc, const uint8_t * initialFrame);
+	void UnregisterTx(uint32_t arbId);
+
+	CTR_Code GetRx(uint32_t arbId,uint8_t * dataBytes,uint32_t timeoutMs);
+	void FlushTx(uint32_t arbId);
+	bool ChangeTxPeriod(uint32_t arbId, uint32_t periodMs);
+
+	template<typename T> txTask<T> GetTx(uint32_t arbId)
+	{
+		txTask<T> retval = {0, nullptr};
+		txJobs_t::iterator i = _txJobs.find(arbId);
+		if(i != _txJobs.end()){
+			retval.arbId = i->second.arbId;
+			retval.toSend = (T*)i->second.toSend;
+		}
+		return retval;
+	}
+	template<class T> void FlushTx(T & par)
+	{
+		FlushTx(par.arbId);
+	}
+
+	template<class T> recMsg<T> GetRx(uint32_t arbId, uint32_t timeoutMs)
+	{
+		recMsg<T> retval;
+		retval.err = GetRx(arbId,retval.bytes, timeoutMs);
+		return retval;
+	}
+
+private:
+
+	class txJob_t {
+		public:
+			uint32_t arbId;
+			uint8_t toSend[8];
+			uint32_t periodMs;
+			uint8_t dlc;
+	};
+
+	class rxEvent_t{
+		public:
+			uint8_t bytes[8];
+			int64_t time;
+			rxEvent_t()
+			{
+				bytes[0] = 0;
+				bytes[1] = 0;
+				bytes[2] = 0;
+				bytes[3] = 0;
+				bytes[4] = 0;
+				bytes[5] = 0;
+				bytes[6] = 0;
+				bytes[7] = 0;
+			}
+	};
+
+	typedef std::map<uint32_t,txJob_t> txJobs_t;
+	txJobs_t _txJobs;
+
+	typedef std::map<uint32_t,rxEvent_t> rxRxEvents_t;
+	rxRxEvents_t _rxRxEvents;
+
+	wpi::mutex _lck;
+};
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/PCM.cpp b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/PCM.cpp
new file mode 100644
index 0000000..e05d4d4
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/PCM.cpp
@@ -0,0 +1,574 @@
+#pragma GCC diagnostic ignored "-Wmissing-field-initializers"
+
+#include "PCM.h"
+#include "FRC_NetworkCommunication/CANSessionMux.h"
+#include <string.h> // memset
+/* This can be a constant, as long as nobody needs to update solenoids within
+    1/50 of a second. */
+static const INT32 kCANPeriod = 20;
+
+#define STATUS_1  			0x9041400
+#define STATUS_SOL_FAULTS  	0x9041440
+#define STATUS_DEBUG  		0x9041480
+
+#define EXPECTED_RESPONSE_TIMEOUT_MS	(50)
+#define GET_PCM_STATUS()			CtreCanNode::recMsg<PcmStatus_t> 		rx = GetRx<PcmStatus_t>			(STATUS_1|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_PCM_SOL_FAULTS()		CtreCanNode::recMsg<PcmStatusFault_t> 	rx = GetRx<PcmStatusFault_t>	(STATUS_SOL_FAULTS|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)
+#define GET_PCM_DEBUG()				CtreCanNode::recMsg<PcmDebug_t> 		rx = GetRx<PcmDebug_t>			(STATUS_DEBUG|GetDeviceNumber(),EXPECTED_RESPONSE_TIMEOUT_MS)
+
+#define CONTROL_1 			0x09041C00	/* PCM_Control */
+#define CONTROL_2 			0x09041C40	/* PCM_SupplemControl */
+#define CONTROL_3 			0x09041C80	/* PcmControlSetOneShotDur_t */
+
+/* encoder/decoders */
+typedef struct _PcmStatus_t{
+	/* Byte 0 */
+	unsigned SolenoidBits:8;
+	/* Byte 1 */
+	unsigned compressorOn:1;
+	unsigned stickyFaultFuseTripped:1;
+	unsigned stickyFaultCompCurrentTooHigh:1;
+	unsigned faultFuseTripped:1;
+	unsigned faultCompCurrentTooHigh:1;
+	unsigned faultHardwareFailure:1;
+	unsigned isCloseloopEnabled:1;
+	unsigned pressureSwitchEn:1;
+	/* Byte 2*/
+	unsigned battVoltage:8;
+	/* Byte 3 */
+	unsigned solenoidVoltageTop8:8;
+	/* Byte 4 */
+	unsigned compressorCurrentTop6:6;
+	unsigned solenoidVoltageBtm2:2;
+	/* Byte 5 */
+	unsigned StickyFault_dItooHigh :1;
+	unsigned Fault_dItooHigh :1;
+	unsigned moduleEnabled:1;
+	unsigned closedLoopOutput:1;
+	unsigned compressorCurrentBtm4:4;
+	/* Byte 6 */
+	unsigned tokenSeedTop8:8;
+	/* Byte 7 */
+	unsigned tokenSeedBtm8:8;
+}PcmStatus_t;
+
+typedef struct _PcmControl_t{
+	/* Byte 0 */
+	unsigned tokenTop8:8;
+	/* Byte 1 */
+	unsigned tokenBtm8:8;
+	/* Byte 2 */
+	unsigned solenoidBits:8;
+	/* Byte 3*/
+	unsigned reserved:4;
+	unsigned closeLoopOutput:1;
+	unsigned compressorOn:1;
+	unsigned closedLoopEnable:1;
+	unsigned clearStickyFaults:1;
+	/* Byte 4 */
+	unsigned OneShotField_h8:8;
+	/* Byte 5 */
+	unsigned OneShotField_l8:8;
+}PcmControl_t;
+
+typedef struct _PcmControlSetOneShotDur_t{
+	uint8_t sol10MsPerUnit[8];
+}PcmControlSetOneShotDur_t;
+
+typedef struct _PcmStatusFault_t{
+	/* Byte 0 */
+	unsigned SolenoidBlacklist:8;
+	/* Byte 1 */
+	unsigned reserved_bit0 :1;
+	unsigned reserved_bit1 :1;
+	unsigned reserved_bit2 :1;
+	unsigned reserved_bit3 :1;
+	unsigned StickyFault_CompNoCurrent :1;
+	unsigned Fault_CompNoCurrent :1;
+	unsigned StickyFault_SolenoidJumper :1;
+	unsigned Fault_SolenoidJumper :1;
+}PcmStatusFault_t;
+
+typedef struct _PcmDebug_t{
+	unsigned tokFailsTop8:8;
+	unsigned tokFailsBtm8:8;
+	unsigned lastFailedTokTop8:8;
+	unsigned lastFailedTokBtm8:8;
+	unsigned tokSuccessTop8:8;
+	unsigned tokSuccessBtm8:8;
+}PcmDebug_t;
+
+
+/* PCM Constructor - Clears all vars, establishes default settings, starts PCM background process
+ *
+ * @Return	-	void
+ *
+ * @Param 	-	deviceNumber	- 	Device ID of PCM to be controlled
+ */
+PCM::PCM(UINT8 deviceNumber): CtreCanNode(deviceNumber)
+{
+	RegisterRx(STATUS_1 | deviceNumber );
+	RegisterRx(STATUS_SOL_FAULTS | deviceNumber );
+	RegisterRx(STATUS_DEBUG | deviceNumber );
+	RegisterTx(CONTROL_1 | deviceNumber, kCANPeriod);
+	/* enable close loop */
+	SetClosedLoopControl(1);
+}
+/* PCM D'tor
+ */
+PCM::~PCM()
+{
+
+}
+
+/* Set PCM solenoid state
+ *
+ * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid
+ *
+ * @Param 	-	idx			- 	ID of solenoid (0-7)
+ * @Param 	-	en			- 	Enable / Disable identified solenoid
+ */
+CTR_Code PCM::SetSolenoid(unsigned char idx, bool en)
+{
+	CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());
+	if(toFill.IsEmpty())return CTR_UnexpectedArbId;
+	if (en)
+		toFill->solenoidBits |= (1ul << (idx));
+	else
+		toFill->solenoidBits &= ~(1ul << (idx));
+	FlushTx(toFill);
+	return CTR_OKAY;
+}
+
+/* Set all PCM solenoid states
+ *
+ * @Return	-	CTR_Code	-	Error code (if any) for setting solenoids
+ * @Param 	-	state			Bitfield to set all solenoids to
+ */
+CTR_Code PCM::SetAllSolenoids(UINT8 state) {
+	CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());
+	if(toFill.IsEmpty())return CTR_UnexpectedArbId;
+	toFill->solenoidBits = state;
+	FlushTx(toFill);
+	return CTR_OKAY;
+}
+
+/* Clears PCM sticky faults (indicators of past faults
+ *
+ * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid
+ *
+ * @Param 	-	clr		- 	Clear / do not clear faults
+ */
+CTR_Code PCM::ClearStickyFaults()
+{
+	int32_t status = 0;
+	uint8_t pcmSupplemControl[] = { 0, 0, 0, 0x80 }; /* only bit set is ClearStickyFaults */
+	FRC_NetworkCommunication_CANSessionMux_sendMessage(CONTROL_2  | GetDeviceNumber(), pcmSupplemControl, sizeof(pcmSupplemControl), 0, &status);
+	if(status)
+		return CTR_TxFailed;
+	return CTR_OKAY;
+}
+
+/* Enables PCM Closed Loop Control of Compressor via pressure switch
+ *
+ * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid
+ *
+ * @Param 	-	en		- 	Enable / Disable Closed Loop Control
+ */
+CTR_Code PCM::SetClosedLoopControl(bool en)
+{
+	CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());
+	if(toFill.IsEmpty())return CTR_UnexpectedArbId;
+	toFill->closedLoopEnable = en;
+	FlushTx(toFill);
+	return CTR_OKAY;
+}
+/* Get solenoid Blacklist status
+ * @Return	-	CTR_Code	-	Error code (if any)
+ * @Param	-	idx			-	ID of solenoid [0,7] to fire one shot pulse.
+ */
+CTR_Code PCM::FireOneShotSolenoid(UINT8 idx)
+{
+	CtreCanNode::txTask<PcmControl_t> toFill = GetTx<PcmControl_t>(CONTROL_1 | GetDeviceNumber());
+	if(toFill.IsEmpty())return CTR_UnexpectedArbId;
+	/* grab field as it is now */
+	uint16_t oneShotField;
+	oneShotField = toFill->OneShotField_h8;
+	oneShotField <<= 8;
+	oneShotField |= toFill->OneShotField_l8;
+	/* get the caller's channel */
+	uint16_t shift = 2*idx;
+	uint16_t mask = 3; /* two bits wide */
+	uint8_t chBits = (oneShotField >> shift) & mask;
+	/* flip it */
+	chBits = (chBits)%3 + 1;
+	/* clear out 2bits for this channel*/
+	oneShotField &= ~(mask << shift);
+	/* put new field in */
+	oneShotField |= chBits << shift;
+	/* apply field as it is now */
+	toFill->OneShotField_h8 = oneShotField >> 8;
+	toFill->OneShotField_l8 = oneShotField;
+	FlushTx(toFill);
+	return CTR_OKAY;
+}
+/* Configure the pulse width of a solenoid channel for one-shot pulse.
+ * Preprogrammed pulsewidth is 10ms resolution and can be between 10ms and
+ * 2.55s.
+ *
+ * @Return	-	CTR_Code	-	Error code (if any)
+ * @Param	-	idx			-	ID of solenoid [0,7] to configure.
+ * @Param	-	durMs		-	pulse width in ms.
+ */
+CTR_Code PCM::SetOneShotDurationMs(UINT8 idx,uint32_t durMs)
+{
+	/* sanity check caller's param */
+	if(idx > 7)
+		return CTR_InvalidParamValue;
+	/* get latest tx frame */
+	CtreCanNode::txTask<PcmControlSetOneShotDur_t> toFill = GetTx<PcmControlSetOneShotDur_t>(CONTROL_3 | GetDeviceNumber());
+	if(toFill.IsEmpty()){
+		/* only send this out if caller wants to do one-shots */
+		RegisterTx(CONTROL_3 | _deviceNumber, kCANPeriod);
+		/* grab it */
+		toFill = GetTx<PcmControlSetOneShotDur_t>(CONTROL_3 | GetDeviceNumber());
+	}
+	toFill->sol10MsPerUnit[idx] = std::min(durMs/10,(uint32_t)0xFF);
+	/* apply the new data bytes */
+	FlushTx(toFill);
+	return CTR_OKAY;
+}
+
+/* Get solenoid state
+ *
+ * @Return	-	True/False	-	True if solenoid enabled, false otherwise
+ *
+ * @Param 	-	idx		- 	ID of solenoid (0-7) to return status of
+ */
+CTR_Code PCM::GetSolenoid(UINT8 idx, bool &status)
+{
+	GET_PCM_STATUS();
+	status = (rx->SolenoidBits & (1ul<<(idx)) ) ? 1 : 0;
+	return rx.err;
+}
+
+/* Get solenoid state for all solenoids on the PCM
+ *
+ * @Return	-	Bitfield of solenoid states
+ */
+CTR_Code PCM::GetAllSolenoids(UINT8 &status)
+{
+	GET_PCM_STATUS();
+	status = rx->SolenoidBits;
+	return rx.err;
+}
+
+/* Get pressure switch state
+ *
+ * @Return	-	True/False	-	True if pressure adequate, false if low
+ */
+CTR_Code PCM::GetPressure(bool &status)
+{
+	GET_PCM_STATUS();
+	status = (rx->pressureSwitchEn ) ? 1 : 0;
+	return rx.err;
+}
+
+/* Get compressor state
+ *
+ * @Return	-	True/False	-	True if enabled, false if otherwise
+ */
+CTR_Code PCM::GetCompressor(bool &status)
+{
+	GET_PCM_STATUS();
+	status = (rx->compressorOn);
+	return rx.err;
+}
+
+/* Get closed loop control state
+ *
+ * @Return	-	True/False	-	True if closed loop enabled, false if otherwise
+ */
+CTR_Code PCM::GetClosedLoopControl(bool &status)
+{
+	GET_PCM_STATUS();
+	status = (rx->isCloseloopEnabled);
+	return rx.err;
+}
+
+/* Get compressor current draw
+ *
+ * @Return	-	Amperes	-	Compressor current
+ */
+CTR_Code PCM::GetCompressorCurrent(float &status)
+{
+	GET_PCM_STATUS();
+	uint32_t temp =(rx->compressorCurrentTop6);
+	temp <<= 4;
+	temp |=  rx->compressorCurrentBtm4;
+	status = temp * 0.03125; /* 5.5 fixed pt value in Amps */
+	return rx.err;
+}
+
+/* Get voltage across solenoid rail
+ *
+ * @Return	-	Volts	-	Voltage across solenoid rail
+ */
+CTR_Code PCM::GetSolenoidVoltage(float &status)
+{
+	GET_PCM_STATUS();
+	uint32_t raw =(rx->solenoidVoltageTop8);
+	raw <<= 2;
+	raw |=  rx->solenoidVoltageBtm2;
+	status = (double) raw * 0.03125; /* 5.5 fixed pt value in Volts */
+	return rx.err;
+}
+
+/* Get hardware fault value
+ *
+ * @Return	-	True/False	-	True if hardware failure detected, false if otherwise
+ */
+CTR_Code PCM::GetHardwareFault(bool &status)
+{
+	GET_PCM_STATUS();
+	status = rx->faultHardwareFailure;
+	return rx.err;
+}
+
+/* Get compressor fault value
+ *
+ * @Return	-	True/False	-	True if shorted compressor detected, false if otherwise
+ */
+CTR_Code PCM::GetCompressorCurrentTooHighFault(bool &status)
+{
+	GET_PCM_STATUS();
+	status = rx->faultCompCurrentTooHigh;
+	return rx.err;
+}
+CTR_Code PCM::GetCompressorShortedStickyFault(bool &status)
+{
+	GET_PCM_STATUS();
+	status = rx->StickyFault_dItooHigh;
+	return rx.err;
+}
+CTR_Code PCM::GetCompressorShortedFault(bool &status)
+{
+	GET_PCM_STATUS();
+	status = rx->Fault_dItooHigh;
+	return rx.err;
+}
+CTR_Code PCM::GetCompressorNotConnectedStickyFault(bool &status)
+{
+	GET_PCM_SOL_FAULTS();
+	status = rx->StickyFault_CompNoCurrent;
+	return rx.err;
+}
+CTR_Code PCM::GetCompressorNotConnectedFault(bool &status)
+{
+	GET_PCM_SOL_FAULTS();
+	status = rx->Fault_CompNoCurrent;
+	return rx.err;
+}
+
+/* Get solenoid fault value
+ *
+ * @Return	-	True/False	-	True if shorted solenoid detected, false if otherwise
+ */
+CTR_Code PCM::GetSolenoidFault(bool &status)
+{
+	GET_PCM_STATUS();
+	status = rx->faultFuseTripped;
+	return rx.err;
+}
+
+/* Get compressor sticky fault value
+ *
+ * @Return	-	True/False	-	True if solenoid had previously been shorted
+ * 								(and sticky fault was not cleared), false if otherwise
+ */
+CTR_Code PCM::GetCompressorCurrentTooHighStickyFault(bool &status)
+{
+	GET_PCM_STATUS();
+	status = rx->stickyFaultCompCurrentTooHigh;
+	return rx.err;
+}
+
+/* Get solenoid sticky fault value
+ *
+ * @Return	-	True/False	-	True if compressor had previously been shorted
+ * 								(and sticky fault was not cleared), false if otherwise
+ */
+CTR_Code PCM::GetSolenoidStickyFault(bool &status)
+{
+	GET_PCM_STATUS();
+	status = rx->stickyFaultFuseTripped;
+	return rx.err;
+}
+/* Get battery voltage
+ *
+ * @Return	-	Volts	-	Voltage across PCM power ports
+ */
+CTR_Code PCM::GetBatteryVoltage(float &status)
+{
+	GET_PCM_STATUS();
+	status = (float)rx->battVoltage * 0.05 + 4.0; /* 50mV per unit plus 4V. */
+	return rx.err;
+}
+/* Return status of module enable/disable
+ *
+ * @Return	-	bool		-	Returns TRUE if PCM is enabled, FALSE if disabled
+ */
+CTR_Code PCM::isModuleEnabled(bool &status)
+{
+	GET_PCM_STATUS();
+	status = rx->moduleEnabled;
+	return rx.err;
+}
+/* Get number of total failed PCM Control Frame
+ *
+ * @Return	-	Failed Control Frames	-	Number of failed control frames (tokenization fails)
+ *
+ * @WARNING	-	Return only valid if [SeekDebugFrames] is enabled
+ * 				See function SeekDebugFrames
+ * 				See function EnableSeekDebugFrames
+ */
+CTR_Code PCM::GetNumberOfFailedControlFrames(UINT16 &status)
+{
+	GET_PCM_DEBUG();
+	status = rx->tokFailsTop8;
+	status <<= 8;
+	status |= rx->tokFailsBtm8;
+	return rx.err;
+}
+/* Get raw Solenoid Blacklist
+ *
+ * @Return	-	BINARY	-	Raw binary breakdown of Solenoid Blacklist
+ * 							BIT7 = Solenoid 1, BIT6 = Solenoid 2, etc.
+ *
+ * @WARNING	-	Return only valid if [SeekStatusFaultFrames] is enabled
+ * 				See function SeekStatusFaultFrames
+ * 				See function EnableSeekStatusFaultFrames
+ */
+CTR_Code PCM::GetSolenoidBlackList(UINT8 &status)
+{
+	GET_PCM_SOL_FAULTS();
+	status = rx->SolenoidBlacklist;
+	return rx.err;
+}
+/* Get solenoid Blacklist status
+ * - Blacklisted solenoids cannot be enabled until PCM is power cycled
+ *
+ * @Return	-	True/False	-	True if Solenoid is blacklisted, false if otherwise
+ *
+ * @Param	-	idx			-	ID of solenoid [0,7]
+ *
+ * @WARNING	-	Return only valid if [SeekStatusFaultFrames] is enabled
+ * 				See function SeekStatusFaultFrames
+ * 				See function EnableSeekStatusFaultFrames
+ */
+CTR_Code PCM::IsSolenoidBlacklisted(UINT8 idx, bool &status)
+{
+	GET_PCM_SOL_FAULTS();
+	status = (rx->SolenoidBlacklist & (1ul<<(idx)) )? 1 : 0;
+	return rx.err;
+}
+//------------------ C interface --------------------------------------------//
+extern "C" {
+	void * c_PCM_Init(void) {
+		return new PCM();
+	}
+	CTR_Code c_SetSolenoid(void * handle, unsigned char idx, INT8 param) {
+		return ((PCM*) handle)->SetSolenoid(idx, param);
+	}
+	CTR_Code c_SetAllSolenoids(void * handle, UINT8 state) {
+		return ((PCM*) handle)->SetAllSolenoids(state);
+	}
+	CTR_Code c_SetClosedLoopControl(void * handle, INT8 param) {
+		return ((PCM*) handle)->SetClosedLoopControl(param);
+	}
+	CTR_Code c_ClearStickyFaults(void * handle, INT8 param) {
+		return ((PCM*) handle)->ClearStickyFaults();
+	}
+	CTR_Code c_GetSolenoid(void * handle, UINT8 idx, INT8 * status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetSolenoid(idx, bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetAllSolenoids(void * handle, UINT8 * status) {
+		return ((PCM*) handle)->GetAllSolenoids(*status);
+	}
+	CTR_Code c_GetPressure(void * handle, INT8 * status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetPressure(bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetCompressor(void * handle, INT8 * status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetCompressor(bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetClosedLoopControl(void * handle, INT8 * status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetClosedLoopControl(bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetCompressorCurrent(void * handle, float * status) {
+		CTR_Code retval = ((PCM*) handle)->GetCompressorCurrent(*status);
+		return retval;
+	}
+	CTR_Code c_GetSolenoidVoltage(void * handle, float*status) {
+		return ((PCM*) handle)->GetSolenoidVoltage(*status);
+	}
+	CTR_Code c_GetHardwareFault(void * handle, INT8*status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetHardwareFault(bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetCompressorFault(void * handle, INT8*status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetCompressorCurrentTooHighFault(bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetSolenoidFault(void * handle, INT8*status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetSolenoidFault(bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetCompressorStickyFault(void * handle, INT8*status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetCompressorCurrentTooHighStickyFault(bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetSolenoidStickyFault(void * handle, INT8*status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->GetSolenoidStickyFault(bstatus);
+		*status = bstatus;
+		return retval;
+	}
+	CTR_Code c_GetBatteryVoltage(void * handle, float*status) {
+		CTR_Code retval = ((PCM*) handle)->GetBatteryVoltage(*status);
+		return retval;
+	}
+	void c_SetDeviceNumber_PCM(void * handle, UINT8 deviceNumber) {
+	}
+	CTR_Code c_GetNumberOfFailedControlFrames(void * handle, UINT16*status) {
+		return ((PCM*) handle)->GetNumberOfFailedControlFrames(*status);
+	}
+	CTR_Code c_GetSolenoidBlackList(void * handle, UINT8 *status) {
+		return ((PCM*) handle)->GetSolenoidBlackList(*status);
+	}
+	CTR_Code c_IsSolenoidBlacklisted(void * handle, UINT8 idx, INT8*status) {
+		bool bstatus;
+		CTR_Code retval = ((PCM*) handle)->IsSolenoidBlacklisted(idx, bstatus);
+		*status = bstatus;
+		return retval;
+	}
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/PCM.h b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/PCM.h
new file mode 100644
index 0000000..b485219
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/PCM.h
@@ -0,0 +1,226 @@
+#ifndef PCM_H_
+#define PCM_H_
+#include "ctre.h"				//BIT Defines + Typedefs
+#include "CtreCanNode.h"
+class PCM : public CtreCanNode
+{
+public:
+    PCM(UINT8 deviceNumber=0);
+    ~PCM();
+
+    /* Set PCM solenoid state
+     *
+     * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid
+     * @Param 	-	idx			- 	ID of solenoid (0-7)
+     * @Param 	-	en			- 	Enable / Disable identified solenoid
+     */
+    CTR_Code 	SetSolenoid(unsigned char idx, bool en);
+
+    /* Set all PCM solenoid states
+     *
+     * @Return	-	CTR_Code	-	Error code (if any) for setting solenoids
+     * @Param 	-	state			Bitfield to set all solenoids to
+     */
+    CTR_Code 	SetAllSolenoids(UINT8 state);
+
+    /* Enables PCM Closed Loop Control of Compressor via pressure switch
+     * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid
+     * @Param 	-	en		- 	Enable / Disable Closed Loop Control
+     */
+    CTR_Code 	SetClosedLoopControl(bool en);
+
+    /* Clears PCM sticky faults (indicators of past faults
+     * @Return	-	CTR_Code	-	Error code (if any) for setting solenoid
+     */
+    CTR_Code 	ClearStickyFaults();
+
+    /* Get solenoid state
+     *
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param 	-	idx		- 	ID of solenoid (0-7) to return if solenoid is on.
+     * @Param	-	status	-	true if solenoid enabled, false otherwise
+     */
+    CTR_Code 	GetSolenoid(UINT8 idx, bool &status);
+
+    /* Get state of all solenoids
+     *
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status	-	bitfield of solenoid states
+     */
+    CTR_Code 	GetAllSolenoids(UINT8 &status);
+
+    /* Get pressure switch state
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if pressure adequate, false if low
+     */
+    CTR_Code 	GetPressure(bool &status);
+
+    /* Get compressor state
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if compress ouput is on, false if otherwise
+     */
+    CTR_Code	GetCompressor(bool &status);
+
+    /* Get closed loop control state
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status	-	True if closed loop enabled, false if otherwise
+     */
+    CTR_Code 	GetClosedLoopControl(bool &status);
+
+    /* Get compressor current draw
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	Compressor current returned in Amperes (A)
+     */
+    CTR_Code 	GetCompressorCurrent(float &status);
+
+    /* Get voltage across solenoid rail
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	Voltage across solenoid rail in Volts (V)
+     */
+    CTR_Code 	GetSolenoidVoltage(float &status);
+
+    /* Get hardware fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if hardware failure detected, false if otherwise
+     */
+    CTR_Code 	GetHardwareFault(bool &status);
+
+    /* Get compressor fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if abnormally high compressor current detected, false if otherwise
+     */
+    CTR_Code 	GetCompressorCurrentTooHighFault(bool &status);
+
+    /* Get solenoid fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if shorted solenoid detected, false if otherwise
+     */
+    CTR_Code 	GetSolenoidFault(bool &status);
+
+    /* Get compressor sticky fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if solenoid had previously been shorted
+     * 								(and sticky fault was not cleared), false if otherwise
+     */
+    CTR_Code 	GetCompressorCurrentTooHighStickyFault(bool &status);
+    /* Get compressor shorted sticky fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if compressor output is shorted, false if otherwise
+     */
+    CTR_Code 	GetCompressorShortedStickyFault(bool &status);
+    /* Get compressor shorted fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if compressor output is shorted, false if otherwise
+     */
+    CTR_Code 	GetCompressorShortedFault(bool &status);
+    /* Get compressor is not connected sticky fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if compressor current is too low,
+     * 					indicating compressor is not connected, false if otherwise
+     */
+    CTR_Code 	GetCompressorNotConnectedStickyFault(bool &status);
+    /* Get compressor is not connected fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if compressor current is too low,
+     * 					indicating compressor is not connected, false if otherwise
+     */
+    CTR_Code 	GetCompressorNotConnectedFault(bool &status);
+
+    /* Get solenoid sticky fault value
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	True if compressor had previously been shorted
+     * 								(and sticky fault was not cleared), false if otherwise
+     */
+    CTR_Code 	GetSolenoidStickyFault(bool &status);
+
+    /* Get battery voltage
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	Voltage across PCM power ports in Volts (V)
+     */
+    CTR_Code 	GetBatteryVoltage(float &status);
+
+    /* Set PCM Device Number and according CAN frame IDs
+     * @Return	-	void
+     * @Param	-	deviceNumber	-	Device number of PCM to control
+     */
+    void	SetDeviceNumber(UINT8 deviceNumber);
+    /* Get number of total failed PCM Control Frame
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	Number of failed control frames (tokenization fails)
+     * @WARNING	-	Return only valid if [SeekDebugFrames] is enabled
+     * 				See function SeekDebugFrames
+     * 				See function EnableSeekDebugFrames
+     */
+	CTR_Code GetNumberOfFailedControlFrames(UINT16 &status);
+
+    /* Get raw Solenoid Blacklist
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	Raw binary breakdown of Solenoid Blacklist
+     * 								BIT7 = Solenoid 1, BIT6 = Solenoid 2, etc.
+     * @WARNING	-	Return only valid if [SeekStatusFaultFrames] is enabled
+     * 				See function SeekStatusFaultFrames
+     * 				See function EnableSeekStatusFaultFrames
+     */
+    CTR_Code 	GetSolenoidBlackList(UINT8 &status);
+
+    /* Get solenoid Blacklist status
+     * - Blacklisted solenoids cannot be enabled until PCM is power cycled
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	idx			-	ID of solenoid [0,7]
+     * @Param	-	status		-	True if Solenoid is blacklisted, false if otherwise
+     * @WARNING	-	Return only valid if [SeekStatusFaultFrames] is enabled
+     * 				See function SeekStatusFaultFrames
+     * 				See function EnableSeekStatusFaultFrames
+     */
+    CTR_Code 	IsSolenoidBlacklisted(UINT8 idx, bool &status);
+
+    /* Return status of module enable/disable
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	status		-	Returns TRUE if PCM is enabled, FALSE if disabled
+     */
+    CTR_Code	isModuleEnabled(bool &status);
+
+    /* Get solenoid Blacklist status
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	idx			-	ID of solenoid [0,7] to fire one shot pulse.
+     */
+    CTR_Code FireOneShotSolenoid(UINT8 idx);
+
+    /* Configure the pulse width of a solenoid channel for one-shot pulse.
+	 * Preprogrammed pulsewidth is 10ms resolute and can be between 20ms and 5.1s.
+     * @Return	-	CTR_Code	-	Error code (if any)
+     * @Param	-	idx			-	ID of solenoid [0,7] to configure.
+     * @Param	-	durMs		-	pulse width in ms.
+     */
+    CTR_Code SetOneShotDurationMs(UINT8 idx,uint32_t durMs);
+
+};
+//------------------ C interface --------------------------------------------//
+extern "C" {
+	void * c_PCM_Init(void);
+	CTR_Code c_SetSolenoid(void * handle,unsigned char idx,INT8 param);
+	CTR_Code c_SetAllSolenoids(void * handle,UINT8 state);
+	CTR_Code c_SetClosedLoopControl(void * handle,INT8 param);
+	CTR_Code c_ClearStickyFaults(void * handle,INT8 param);
+	CTR_Code c_GetSolenoid(void * handle,UINT8 idx,INT8 * status);
+	CTR_Code c_GetAllSolenoids(void * handle,UINT8 * status);
+	CTR_Code c_GetPressure(void * handle,INT8 * status);
+	CTR_Code c_GetCompressor(void * handle,INT8 * status);
+	CTR_Code c_GetClosedLoopControl(void * handle,INT8 * status);
+	CTR_Code c_GetCompressorCurrent(void * handle,float * status);
+	CTR_Code c_GetSolenoidVoltage(void * handle,float*status);
+	CTR_Code c_GetHardwareFault(void * handle,INT8*status);
+	CTR_Code c_GetCompressorFault(void * handle,INT8*status);
+	CTR_Code c_GetSolenoidFault(void * handle,INT8*status);
+	CTR_Code c_GetCompressorStickyFault(void * handle,INT8*status);
+	CTR_Code c_GetSolenoidStickyFault(void * handle,INT8*status);
+	CTR_Code c_GetBatteryVoltage(void * handle,float*status);
+	void c_SetDeviceNumber_PCM(void * handle,UINT8 deviceNumber);
+	void c_EnableSeekStatusFrames(void * handle,INT8 enable);
+	void c_EnableSeekStatusFaultFrames(void * handle,INT8 enable);
+	void c_EnableSeekDebugFrames(void * handle,INT8 enable);
+	CTR_Code c_GetNumberOfFailedControlFrames(void * handle,UINT16*status);
+	CTR_Code c_GetSolenoidBlackList(void * handle,UINT8 *status);
+	CTR_Code c_IsSolenoidBlacklisted(void * handle,UINT8 idx,INT8*status);
+}
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/ctre.h b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/ctre.h
new file mode 100644
index 0000000..90d33c1
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/ctre/ctre.h
@@ -0,0 +1,55 @@
+/**
+ * @file ctre.h
+ * Common header for all CTRE HAL modules.
+ */
+#ifndef CTRE_H
+#define CTRE_H
+
+//Bit Defines
+#define BIT0 0x01
+#define BIT1 0x02
+#define BIT2 0x04
+#define BIT3 0x08
+#define BIT4 0x10
+#define BIT5 0x20
+#define BIT6 0x40
+#define BIT7 0x80
+#define BIT8  0x0100
+#define BIT9  0x0200
+#define BIT10 0x0400
+#define BIT11 0x0800
+#define BIT12 0x1000
+#define BIT13 0x2000
+#define BIT14 0x4000
+#define BIT15 0x8000
+
+//Signed
+typedef	signed char	INT8;
+typedef	signed short	INT16;
+typedef	signed int	INT32;
+typedef	signed long long INT64;
+
+//Unsigned
+typedef	unsigned char	UINT8;
+typedef	unsigned short	UINT16;
+typedef	unsigned int	UINT32;
+typedef	unsigned long long UINT64;
+
+//Other
+typedef	unsigned char	UCHAR;
+typedef unsigned short	USHORT;
+typedef	unsigned int	UINT;
+typedef unsigned long	ULONG;
+
+typedef enum {
+		CTR_OKAY,				//!< No Error - Function executed as expected
+		CTR_RxTimeout,			//!< CAN frame has not been received within specified period of time.
+		CTR_TxTimeout,			//!< Not used.
+		CTR_InvalidParamValue, 	//!< Caller passed an invalid param
+		CTR_UnexpectedArbId,	//!< Specified CAN Id is invalid.
+		CTR_TxFailed,			//!< Could not transmit the CAN frame.
+		CTR_SigNotUpdated,		//!< Have not received an value response for signal.
+		CTR_BufferFull,			//!< Caller attempted to insert data into a buffer that is full.
+}CTR_Code;
+
+#endif /* CTRE_H */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/frccansae/CANDeviceInterface.h b/third_party/allwpilib_2019/hal/src/main/native/athena/frccansae/CANDeviceInterface.h
new file mode 100644
index 0000000..8fe4235
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/frccansae/CANDeviceInterface.h
@@ -0,0 +1,156 @@
+#ifndef __CAN_DEVICE_INTERFACE_H__
+#define __CAN_DEVICE_INTERFACE_H__
+
+#define MAX_STRING_LEN 64
+
+#define SUPPORT_UNIQUE_ID	(1) /* depends entirely on old vs new build */
+#define USE_NTH_ORDER		(0) /* zero to user deviceId */
+#define SUPPORT_MOTOR_CONTROLLER_PROFILE	(1)
+namespace CANDeviceInterface1
+{
+
+struct PIDSlot
+{
+	// Proportional gain
+	float pGain;
+	// Integral gain
+	float iGain;
+	// Differential gain
+	float dGain;
+	// Feed-forward gain
+	float fGain;
+	// Integral zone
+	float iZone;
+	// Closed-loop ramp rate
+	float clRampRate;
+};
+
+struct DeviceDescriptor
+{
+   // The full device ID, including the device number, manufacturer, and device type.
+   // The mask of a message the device supports is 0x1FFF003F.
+   unsigned int deviceID;
+#if SUPPORT_UNIQUE_ID != 0
+   // This is the ID that uniquely identifies the device node in the UI.
+   // The purpose of this is to be able to track the device across renames or deviceID changes.
+   unsigned int uniqueID;
+#endif
+   // An dynamically assigned ID that will make setting deviceIDs robust,
+   //  Never again will you need to isolate a CAN node just to fix it's ID.
+   unsigned int dynamicID;
+   // User visible name.  This can be customized by the user, but should have a
+   // reasonable default.
+   char name[MAX_STRING_LEN];
+   // This is a user visible model name that should match the can_devices.ini section.
+   char model[MAX_STRING_LEN];
+   // This is a version number that represents the version of firmware currently
+   // installed on the device.
+   char currentVersion[MAX_STRING_LEN];
+   // Hardware revision.
+   char hardwareRev[MAX_STRING_LEN];
+   // Bootloader version.  Will not change for the life of the product, but additional
+   // field upgrade features could be added in newer hardware.
+   char bootloaderRev[MAX_STRING_LEN];
+   // Manufacture Date.  Could be a calender date or just the FRC season year.
+   // Also helps troubleshooting "old ones" vs "new ones".
+   char manufactureDate[MAX_STRING_LEN];
+   // General status of the hardware.  For example if the device is in bootloader
+   // due to a bad flash UI could emphasize that.
+   char softwareStatus[MAX_STRING_LEN];
+   // Is the LED currently on?
+   bool led;
+	// Reserved fields for future use by CTRE.  Not touched by frccansae
+   unsigned int dynFlags;
+   unsigned int flags; 		/* bitfield */
+   unsigned int ptrToString;
+   //unsigned int reserved0;
+   //unsigned int reserved1;
+   //unsigned int reserved2;
+#if SUPPORT_MOTOR_CONTROLLER_PROFILE != 0
+	// Motor controller properties (ignored if SupportsMotorControllerProperties is false or unset for this model)
+	unsigned int brakeMode; // 0=Coast, 1=Brake
+	unsigned int limitSwitchFwdMode; // 0=disabled, 1=Normally Closed, 2=Normally Open
+	unsigned int limitSwitchRevMode; // 0=disabled, 1=Normally Closed, 2=Normally Open
+	// Limit-switch soft limits
+	bool bFwdSoftLimitEnable;
+	bool bRevSoftLimitEnable;
+	float softLimitFwd;
+	float softLimitRev;
+	// PID constants for slot 0
+	struct PIDSlot slot0;
+	// PID constants for slot 1
+	struct PIDSlot slot1;
+#endif
+};
+
+#define kLimitSwitchMode_Disabled		(0)
+#define kLimitSwitchMode_NormallyClosed	(1)
+#define kLimitSwitchMode_NormallyOpen	(2)
+
+// Interface functions that must be implemented by the CAN Firmware Update Library
+
+// Returns the number of devices that will be returned in a call to
+// getListOfDevices().  The calling library will use this info to allocate enough
+// memory to accept all device info.
+int getNumberOfDevices();
+
+// Return info about discovered devices.  The array of structs should be
+// populated before returning.  The numDescriptors input describes how many
+// elements were allocated to prevent memory corruption.  The number of devices
+// populated should be returned from this function as well.
+int getListOfDevices(DeviceDescriptor *devices, int numDescriptors);
+
+// When the user requests to update the firmware of a device a thread will be
+// spawned and this function is called from that thread.  This function should
+// complete the firmware update process before returning.  The image
+// contents and size are directly from the file selected by the user.  The
+// error message string can be filled with a NULL-terminated message to show the
+// user if there was a problem updating firmware.  The error message is only
+// displayed if a non-zero value is returned from this function.
+int updateFirmware(const DeviceDescriptor *device, const unsigned char *imageContents, unsigned int imageSize, char *errorMessage, int errorMessageMaxSize);
+
+// This function is called periodically from the UI thread while the firmware
+// update is in progress.  The percentComplete parameter should the filled in
+// with the current progress of the firmware update process to update a progress
+// bar in the UI.
+void checkUpdateProgress(const DeviceDescriptor *device, int *percentComplete);
+
+// This is called when the user selects a new ID to assign on the bus and
+// chooses to save.  The newDeviceID is really just the device number. The
+// manufacturer and device type will remain unchanged.  If a problem is detected
+// when assigning a new ID, this function should return a non-zero value.
+int assignBroadcastDeviceID(unsigned int newDeviceID);
+// The device descriptor should be updated with the new device ID.  The name may
+// also change in the descriptor and will be updated in the UI immediately.
+// Be sure to modify the descriptor first since the refresh from the UI is
+// asynchronous.
+int assignDeviceID(DeviceDescriptor *device, unsigned int newDeviceID);
+
+// This entry-point will get called when the user chooses to change the value
+// of the device's LED.  This will allow the user to identify devices which
+// support dynamic addresses or are otherwise unknown.  If this function returns
+// a non-zero value, the UI will report an error.
+int saveLightLed(const DeviceDescriptor *device, bool newLEDStatus);
+
+// This entry-point will get called when the user chooses to change the alias
+// of the device with the device specified.  If this function returns a non-
+// zero value, the UI will report an error.  The device descriptor must be
+// updated with the new name that was selected. If a different name is saved
+// to the descriptor than the user specified, this will require a manual
+// refresh by the user.  This is reported as CAR #505139
+int saveDeviceName(DeviceDescriptor *device, const char *newName);
+
+// This entry-point will get called when the user changes any of the motor
+// controller specific properties. If this function returns a non-zero value,
+// the UI will report an error.  The device descriptor may be updated with
+// coerced values.
+int saveMotorParameters(DeviceDescriptor *device);
+
+// Run some sort of self-test functionality on the device.  This can be anything
+// and the results will be displayed to the user.  A non-zero return value
+// indicates an error.
+int selfTest(const DeviceDescriptor *device, char *detailedResults, int detailedResultsMaxSize);
+
+} /* CANDeviceInterface */
+
+#endif /* __CAN_DEVICE_INTERFACE_H__ */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/visa/visa.h b/third_party/allwpilib_2019/hal/src/main/native/athena/visa/visa.h
new file mode 100644
index 0000000..3c6ad30
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/visa/visa.h
@@ -0,0 +1,1064 @@
+/*---------------------------------------------------------------------------*/
+/* Distributed by IVI Foundation Inc.                                        */
+/* Contains National Instruments extensions.                                 */
+/* Do not modify the contents of this file.                                  */
+/*---------------------------------------------------------------------------*/
+/*                                                                           */
+/* Title   : VISA.H                                                          */
+/* Date    : 10-09-2006                                                      */
+/* Purpose : Include file for the VISA Library 4.0 specification             */
+/*                                                                           */
+/*---------------------------------------------------------------------------*/
+/* When using NI-VISA extensions, you must link with the VISA library that   */
+/* comes with NI-VISA.  Currently, the extensions provided by NI-VISA are:   */
+/*                                                                           */
+/* PXI (Compact PCI eXtensions for Instrumentation) and PCI support.  To use */
+/* this, you must define the macro NIVISA_PXI before including this header.  */
+/* You must also create an INF file with the VISA Driver Development Wizard. */
+/*                                                                           */
+/* A fast set of macros for viPeekXX/viPokeXX that guarantees binary         */
+/* compatibility with other implementations of VISA.  To use this, you must  */
+/* define the macro NIVISA_PEEKPOKE before including this header.            */
+/*                                                                           */
+/* Support for USB devices that do not conform to a specific class.  To use  */
+/* this, you must define the macro NIVISA_USB before including this header.  */
+/* You must also create an INF file with the VISA Driver Development Wizard. */
+/*---------------------------------------------------------------------------*/
+
+#ifndef __VISA_HEADER__
+#define __VISA_HEADER__
+
+#include <stdarg.h>
+
+#if !defined(__VISATYPE_HEADER__)
+#include "visatype.h"
+#endif
+
+#define VI_SPEC_VERSION     (0x00400000UL)
+
+#if defined(__cplusplus) || defined(__cplusplus__)
+   extern "C" {
+#endif
+
+#if defined(_CVI_)
+#pragma EnableLibraryRuntimeChecking
+#endif
+
+/*- VISA Types --------------------------------------------------------------*/
+
+typedef ViObject             ViEvent;
+typedef ViEvent      _VI_PTR ViPEvent;
+typedef ViObject             ViFindList;
+typedef ViFindList   _VI_PTR ViPFindList;
+
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+typedef ViUInt64             ViBusAddress;
+typedef ViUInt64             ViBusSize;
+typedef ViUInt64             ViAttrState;
+#else
+typedef ViUInt32             ViBusAddress;
+typedef ViUInt32             ViBusSize;
+typedef ViUInt32             ViAttrState;
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+typedef ViUInt64             ViBusAddress64;
+typedef ViBusAddress64 _VI_PTR ViPBusAddress64;
+#endif
+
+typedef ViUInt32             ViEventType;
+typedef ViEventType  _VI_PTR ViPEventType;
+typedef ViEventType  _VI_PTR ViAEventType;
+typedef void         _VI_PTR ViPAttrState;
+typedef ViAttr       _VI_PTR ViPAttr;
+typedef ViAttr       _VI_PTR ViAAttr;
+
+typedef ViString             ViKeyId;
+typedef ViPString            ViPKeyId;
+typedef ViUInt32             ViJobId;
+typedef ViJobId      _VI_PTR ViPJobId;
+typedef ViUInt32             ViAccessMode;
+typedef ViAccessMode _VI_PTR ViPAccessMode;
+typedef ViBusAddress _VI_PTR ViPBusAddress;
+typedef ViUInt32             ViEventFilter;
+
+typedef va_list              ViVAList;
+
+typedef ViStatus (_VI_FUNCH _VI_PTR ViHndlr)
+   (ViSession vi, ViEventType eventType, ViEvent event, ViAddr userHandle);
+
+/*- Resource Manager Functions and Operations -------------------------------*/
+
+ViStatus _VI_FUNC  viOpenDefaultRM (ViPSession vi);
+ViStatus _VI_FUNC  viFindRsrc      (ViSession sesn, ViString expr, ViPFindList vi,
+                                    ViPUInt32 retCnt, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC  viFindNext      (ViFindList vi, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC  viParseRsrc     (ViSession rmSesn, ViRsrc rsrcName,
+                                    ViPUInt16 intfType, ViPUInt16 intfNum);
+ViStatus _VI_FUNC  viParseRsrcEx   (ViSession rmSesn, ViRsrc rsrcName, ViPUInt16 intfType,
+                                    ViPUInt16 intfNum, ViChar _VI_FAR rsrcClass[],
+                                    ViChar _VI_FAR expandedUnaliasedName[],
+                                    ViChar _VI_FAR aliasIfExists[]);
+ViStatus _VI_FUNC  viOpen          (ViSession sesn, ViRsrc name, ViAccessMode mode,
+                                    ViUInt32 timeout, ViPSession vi);
+
+/*- Resource Template Operations --------------------------------------------*/
+
+ViStatus _VI_FUNC  viClose         (ViObject vi);
+ViStatus _VI_FUNC  viSetAttribute  (ViObject vi, ViAttr attrName, ViAttrState attrValue);
+ViStatus _VI_FUNC  viGetAttribute  (ViObject vi, ViAttr attrName, void _VI_PTR attrValue);
+ViStatus _VI_FUNC  viStatusDesc    (ViObject vi, ViStatus status, ViChar _VI_FAR desc[]);
+ViStatus _VI_FUNC  viTerminate     (ViObject vi, ViUInt16 degree, ViJobId jobId);
+
+ViStatus _VI_FUNC  viLock          (ViSession vi, ViAccessMode lockType, ViUInt32 timeout,
+                                    ViKeyId requestedKey, ViChar _VI_FAR accessKey[]);
+ViStatus _VI_FUNC  viUnlock        (ViSession vi);
+ViStatus _VI_FUNC  viEnableEvent   (ViSession vi, ViEventType eventType, ViUInt16 mechanism,
+                                    ViEventFilter context);
+ViStatus _VI_FUNC  viDisableEvent  (ViSession vi, ViEventType eventType, ViUInt16 mechanism);
+ViStatus _VI_FUNC  viDiscardEvents (ViSession vi, ViEventType eventType, ViUInt16 mechanism);
+ViStatus _VI_FUNC  viWaitOnEvent   (ViSession vi, ViEventType inEventType, ViUInt32 timeout,
+                                    ViPEventType outEventType, ViPEvent outContext);
+ViStatus _VI_FUNC  viInstallHandler(ViSession vi, ViEventType eventType, ViHndlr handler,
+                                    ViAddr userHandle);
+ViStatus _VI_FUNC  viUninstallHandler(ViSession vi, ViEventType eventType, ViHndlr handler,
+                                      ViAddr userHandle);
+
+/*- Basic I/O Operations ----------------------------------------------------*/
+
+ViStatus _VI_FUNC  viRead          (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viReadAsync     (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPJobId  jobId);
+ViStatus _VI_FUNC  viReadToFile    (ViSession vi, ViConstString filename, ViUInt32 cnt,
+                                    ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viWrite         (ViSession vi, ViBuf  buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viWriteAsync    (ViSession vi, ViBuf  buf, ViUInt32 cnt, ViPJobId  jobId);
+ViStatus _VI_FUNC  viWriteFromFile (ViSession vi, ViConstString filename, ViUInt32 cnt,
+                                    ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viAssertTrigger (ViSession vi, ViUInt16 protocol);
+ViStatus _VI_FUNC  viReadSTB       (ViSession vi, ViPUInt16 status);
+ViStatus _VI_FUNC  viClear         (ViSession vi);
+
+/*- Formatted and Buffered I/O Operations -----------------------------------*/
+
+ViStatus _VI_FUNC  viSetBuf        (ViSession vi, ViUInt16 mask, ViUInt32 size);
+ViStatus _VI_FUNC  viFlush         (ViSession vi, ViUInt16 mask);
+
+ViStatus _VI_FUNC  viBufWrite      (ViSession vi, ViBuf  buf, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viBufRead       (ViSession vi, ViPBuf buf, ViUInt32 cnt, ViPUInt32 retCnt);
+
+ViStatus _VI_FUNCC viPrintf        (ViSession vi, ViString writeFmt, ...);
+ViStatus _VI_FUNC  viVPrintf       (ViSession vi, ViString writeFmt, ViVAList params);
+ViStatus _VI_FUNCC viSPrintf       (ViSession vi, ViPBuf buf, ViString writeFmt, ...);
+ViStatus _VI_FUNC  viVSPrintf      (ViSession vi, ViPBuf buf, ViString writeFmt,
+                                    ViVAList parms);
+
+ViStatus _VI_FUNCC viScanf         (ViSession vi, ViString readFmt, ...);
+ViStatus _VI_FUNC  viVScanf        (ViSession vi, ViString readFmt, ViVAList params);
+ViStatus _VI_FUNCC viSScanf        (ViSession vi, ViBuf buf, ViString readFmt, ...);
+ViStatus _VI_FUNC  viVSScanf       (ViSession vi, ViBuf buf, ViString readFmt,
+                                    ViVAList parms);
+
+ViStatus _VI_FUNCC viQueryf        (ViSession vi, ViString writeFmt, ViString readFmt, ...);
+ViStatus _VI_FUNC  viVQueryf       (ViSession vi, ViString writeFmt, ViString readFmt, 
+                                    ViVAList params);
+
+/*- Memory I/O Operations ---------------------------------------------------*/
+
+ViStatus _VI_FUNC  viIn8           (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViPUInt8  val8);
+ViStatus _VI_FUNC  viOut8          (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViUInt8   val8);
+ViStatus _VI_FUNC  viIn16          (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViPUInt16 val16);
+ViStatus _VI_FUNC  viOut16         (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViUInt16  val16);
+ViStatus _VI_FUNC  viIn32          (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViPUInt32 val32);
+ViStatus _VI_FUNC  viOut32         (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViUInt32  val32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viIn64          (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViPUInt64 val64);
+ViStatus _VI_FUNC  viOut64         (ViSession vi, ViUInt16 space,
+                                    ViBusAddress offset, ViUInt64  val64);
+
+ViStatus _VI_FUNC  viIn8Ex         (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViPUInt8  val8);
+ViStatus _VI_FUNC  viOut8Ex        (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViUInt8   val8);
+ViStatus _VI_FUNC  viIn16Ex        (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViPUInt16 val16);
+ViStatus _VI_FUNC  viOut16Ex       (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViUInt16  val16);
+ViStatus _VI_FUNC  viIn32Ex        (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViPUInt32 val32);
+ViStatus _VI_FUNC  viOut32Ex       (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViUInt32  val32);
+ViStatus _VI_FUNC  viIn64Ex        (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViPUInt64 val64);
+ViStatus _VI_FUNC  viOut64Ex       (ViSession vi, ViUInt16 space,
+                                    ViBusAddress64 offset, ViUInt64  val64);
+#endif
+
+ViStatus _VI_FUNC  viMoveIn8       (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt8  buf8);
+ViStatus _VI_FUNC  viMoveOut8      (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt8  buf8);
+ViStatus _VI_FUNC  viMoveIn16      (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC  viMoveOut16     (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC  viMoveIn32      (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC  viMoveOut32     (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt32 buf32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viMoveIn64      (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt64 buf64);
+ViStatus _VI_FUNC  viMoveOut64     (ViSession vi, ViUInt16 space, ViBusAddress offset,
+                                    ViBusSize length, ViAUInt64 buf64);
+
+ViStatus _VI_FUNC  viMoveIn8Ex     (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt8  buf8);
+ViStatus _VI_FUNC  viMoveOut8Ex    (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt8  buf8);
+ViStatus _VI_FUNC  viMoveIn16Ex    (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC  viMoveOut16Ex   (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt16 buf16);
+ViStatus _VI_FUNC  viMoveIn32Ex    (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC  viMoveOut32Ex   (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt32 buf32);
+ViStatus _VI_FUNC  viMoveIn64Ex    (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt64 buf64);
+ViStatus _VI_FUNC  viMoveOut64Ex   (ViSession vi, ViUInt16 space, ViBusAddress64 offset,
+                                    ViBusSize length, ViAUInt64 buf64);
+#endif
+
+ViStatus _VI_FUNC  viMove          (ViSession vi, ViUInt16 srcSpace, ViBusAddress srcOffset,
+                                    ViUInt16 srcWidth, ViUInt16 destSpace, 
+                                    ViBusAddress destOffset, ViUInt16 destWidth, 
+                                    ViBusSize srcLength); 
+ViStatus _VI_FUNC  viMoveAsync     (ViSession vi, ViUInt16 srcSpace, ViBusAddress srcOffset,
+                                    ViUInt16 srcWidth, ViUInt16 destSpace, 
+                                    ViBusAddress destOffset, ViUInt16 destWidth, 
+                                    ViBusSize srcLength, ViPJobId jobId);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viMoveEx        (ViSession vi, ViUInt16 srcSpace, ViBusAddress64 srcOffset,
+                                    ViUInt16 srcWidth, ViUInt16 destSpace, 
+                                    ViBusAddress64 destOffset, ViUInt16 destWidth, 
+                                    ViBusSize srcLength); 
+ViStatus _VI_FUNC  viMoveAsyncEx   (ViSession vi, ViUInt16 srcSpace, ViBusAddress64 srcOffset,
+                                    ViUInt16 srcWidth, ViUInt16 destSpace, 
+                                    ViBusAddress64 destOffset, ViUInt16 destWidth, 
+                                    ViBusSize srcLength, ViPJobId jobId);
+#endif
+
+ViStatus _VI_FUNC  viMapAddress    (ViSession vi, ViUInt16 mapSpace, ViBusAddress mapOffset,
+                                    ViBusSize mapSize, ViBoolean access,
+                                    ViAddr suggested, ViPAddr address);
+ViStatus _VI_FUNC  viUnmapAddress  (ViSession vi);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viMapAddressEx  (ViSession vi, ViUInt16 mapSpace, ViBusAddress64 mapOffset,
+                                    ViBusSize mapSize, ViBoolean access,
+                                    ViAddr suggested, ViPAddr address);
+#endif
+
+void     _VI_FUNC  viPeek8         (ViSession vi, ViAddr address, ViPUInt8  val8);
+void     _VI_FUNC  viPoke8         (ViSession vi, ViAddr address, ViUInt8   val8);
+void     _VI_FUNC  viPeek16        (ViSession vi, ViAddr address, ViPUInt16 val16);
+void     _VI_FUNC  viPoke16        (ViSession vi, ViAddr address, ViUInt16  val16);
+void     _VI_FUNC  viPeek32        (ViSession vi, ViAddr address, ViPUInt32 val32);
+void     _VI_FUNC  viPoke32        (ViSession vi, ViAddr address, ViUInt32  val32);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+void     _VI_FUNC  viPeek64        (ViSession vi, ViAddr address, ViPUInt64 val64);
+void     _VI_FUNC  viPoke64        (ViSession vi, ViAddr address, ViUInt64  val64);
+#endif
+
+/*- Shared Memory Operations ------------------------------------------------*/
+
+ViStatus _VI_FUNC  viMemAlloc      (ViSession vi, ViBusSize size, ViPBusAddress offset);
+ViStatus _VI_FUNC  viMemFree       (ViSession vi, ViBusAddress offset);
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+ViStatus _VI_FUNC  viMemAllocEx    (ViSession vi, ViBusSize size, ViPBusAddress64 offset);
+ViStatus _VI_FUNC  viMemFreeEx     (ViSession vi, ViBusAddress64 offset);
+#endif
+
+/*- Interface Specific Operations -------------------------------------------*/
+
+ViStatus _VI_FUNC  viGpibControlREN(ViSession vi, ViUInt16 mode);
+ViStatus _VI_FUNC  viGpibControlATN(ViSession vi, ViUInt16 mode);
+ViStatus _VI_FUNC  viGpibSendIFC   (ViSession vi);
+ViStatus _VI_FUNC  viGpibCommand   (ViSession vi, ViBuf cmd, ViUInt32 cnt, ViPUInt32 retCnt);
+ViStatus _VI_FUNC  viGpibPassControl(ViSession vi, ViUInt16 primAddr, ViUInt16 secAddr);
+
+ViStatus _VI_FUNC  viVxiCommandQuery(ViSession vi, ViUInt16 mode, ViUInt32 cmd,
+                                     ViPUInt32 response);
+ViStatus _VI_FUNC  viAssertUtilSignal(ViSession vi, ViUInt16 line);
+ViStatus _VI_FUNC  viAssertIntrSignal(ViSession vi, ViInt16 mode, ViUInt32 statusID);
+ViStatus _VI_FUNC  viMapTrigger    (ViSession vi, ViInt16 trigSrc, ViInt16 trigDest, 
+                                    ViUInt16 mode);
+ViStatus _VI_FUNC  viUnmapTrigger  (ViSession vi, ViInt16 trigSrc, ViInt16 trigDest);
+ViStatus _VI_FUNC  viUsbControlOut (ViSession vi, ViInt16 bmRequestType, ViInt16 bRequest,
+                                    ViUInt16 wValue, ViUInt16 wIndex, ViUInt16 wLength,
+                                    ViBuf buf);
+ViStatus _VI_FUNC  viUsbControlIn  (ViSession vi, ViInt16 bmRequestType, ViInt16 bRequest,
+                                    ViUInt16 wValue, ViUInt16 wIndex, ViUInt16 wLength,
+                                    ViPBuf buf, ViPUInt16 retCnt);
+
+/*- Attributes (platform independent size) ----------------------------------*/
+
+#define VI_ATTR_RSRC_CLASS          (0xBFFF0001UL)
+#define VI_ATTR_RSRC_NAME           (0xBFFF0002UL)
+#define VI_ATTR_RSRC_IMPL_VERSION   (0x3FFF0003UL)
+#define VI_ATTR_RSRC_LOCK_STATE     (0x3FFF0004UL)
+#define VI_ATTR_MAX_QUEUE_LENGTH    (0x3FFF0005UL)
+#define VI_ATTR_USER_DATA_32        (0x3FFF0007UL)
+#define VI_ATTR_FDC_CHNL            (0x3FFF000DUL)
+#define VI_ATTR_FDC_MODE            (0x3FFF000FUL)
+#define VI_ATTR_FDC_GEN_SIGNAL_EN   (0x3FFF0011UL)
+#define VI_ATTR_FDC_USE_PAIR        (0x3FFF0013UL)
+#define VI_ATTR_SEND_END_EN         (0x3FFF0016UL)
+#define VI_ATTR_TERMCHAR            (0x3FFF0018UL)
+#define VI_ATTR_TMO_VALUE           (0x3FFF001AUL)
+#define VI_ATTR_GPIB_READDR_EN      (0x3FFF001BUL)
+#define VI_ATTR_IO_PROT             (0x3FFF001CUL)
+#define VI_ATTR_DMA_ALLOW_EN        (0x3FFF001EUL)
+#define VI_ATTR_ASRL_BAUD           (0x3FFF0021UL)
+#define VI_ATTR_ASRL_DATA_BITS      (0x3FFF0022UL)
+#define VI_ATTR_ASRL_PARITY         (0x3FFF0023UL)
+#define VI_ATTR_ASRL_STOP_BITS      (0x3FFF0024UL)
+#define VI_ATTR_ASRL_FLOW_CNTRL     (0x3FFF0025UL)
+#define VI_ATTR_RD_BUF_OPER_MODE    (0x3FFF002AUL)
+#define VI_ATTR_RD_BUF_SIZE         (0x3FFF002BUL)
+#define VI_ATTR_WR_BUF_OPER_MODE    (0x3FFF002DUL)
+#define VI_ATTR_WR_BUF_SIZE         (0x3FFF002EUL)
+#define VI_ATTR_SUPPRESS_END_EN     (0x3FFF0036UL)
+#define VI_ATTR_TERMCHAR_EN         (0x3FFF0038UL)
+#define VI_ATTR_DEST_ACCESS_PRIV    (0x3FFF0039UL)
+#define VI_ATTR_DEST_BYTE_ORDER     (0x3FFF003AUL)
+#define VI_ATTR_SRC_ACCESS_PRIV     (0x3FFF003CUL)
+#define VI_ATTR_SRC_BYTE_ORDER      (0x3FFF003DUL)
+#define VI_ATTR_SRC_INCREMENT       (0x3FFF0040UL)
+#define VI_ATTR_DEST_INCREMENT      (0x3FFF0041UL)
+#define VI_ATTR_WIN_ACCESS_PRIV     (0x3FFF0045UL)
+#define VI_ATTR_WIN_BYTE_ORDER      (0x3FFF0047UL)
+#define VI_ATTR_GPIB_ATN_STATE      (0x3FFF0057UL)
+#define VI_ATTR_GPIB_ADDR_STATE     (0x3FFF005CUL)
+#define VI_ATTR_GPIB_CIC_STATE      (0x3FFF005EUL)
+#define VI_ATTR_GPIB_NDAC_STATE     (0x3FFF0062UL)
+#define VI_ATTR_GPIB_SRQ_STATE      (0x3FFF0067UL)
+#define VI_ATTR_GPIB_SYS_CNTRL_STATE (0x3FFF0068UL)
+#define VI_ATTR_GPIB_HS488_CBL_LEN  (0x3FFF0069UL)
+#define VI_ATTR_CMDR_LA             (0x3FFF006BUL)
+#define VI_ATTR_VXI_DEV_CLASS       (0x3FFF006CUL)
+#define VI_ATTR_MAINFRAME_LA        (0x3FFF0070UL)
+#define VI_ATTR_MANF_NAME           (0xBFFF0072UL)
+#define VI_ATTR_MODEL_NAME          (0xBFFF0077UL)
+#define VI_ATTR_VXI_VME_INTR_STATUS (0x3FFF008BUL)
+#define VI_ATTR_VXI_TRIG_STATUS     (0x3FFF008DUL)
+#define VI_ATTR_VXI_VME_SYSFAIL_STATE (0x3FFF0094UL)
+#define VI_ATTR_WIN_BASE_ADDR_32    (0x3FFF0098UL)
+#define VI_ATTR_WIN_SIZE_32         (0x3FFF009AUL)
+#define VI_ATTR_ASRL_AVAIL_NUM      (0x3FFF00ACUL)
+#define VI_ATTR_MEM_BASE_32         (0x3FFF00ADUL)
+#define VI_ATTR_ASRL_CTS_STATE      (0x3FFF00AEUL)
+#define VI_ATTR_ASRL_DCD_STATE      (0x3FFF00AFUL)
+#define VI_ATTR_ASRL_DSR_STATE      (0x3FFF00B1UL)
+#define VI_ATTR_ASRL_DTR_STATE      (0x3FFF00B2UL)
+#define VI_ATTR_ASRL_END_IN         (0x3FFF00B3UL)
+#define VI_ATTR_ASRL_END_OUT        (0x3FFF00B4UL)
+#define VI_ATTR_ASRL_REPLACE_CHAR   (0x3FFF00BEUL)
+#define VI_ATTR_ASRL_RI_STATE       (0x3FFF00BFUL)
+#define VI_ATTR_ASRL_RTS_STATE      (0x3FFF00C0UL)
+#define VI_ATTR_ASRL_XON_CHAR       (0x3FFF00C1UL)
+#define VI_ATTR_ASRL_XOFF_CHAR      (0x3FFF00C2UL)
+#define VI_ATTR_WIN_ACCESS          (0x3FFF00C3UL)
+#define VI_ATTR_RM_SESSION          (0x3FFF00C4UL)
+#define VI_ATTR_VXI_LA              (0x3FFF00D5UL)
+#define VI_ATTR_MANF_ID             (0x3FFF00D9UL)
+#define VI_ATTR_MEM_SIZE_32         (0x3FFF00DDUL)
+#define VI_ATTR_MEM_SPACE           (0x3FFF00DEUL)
+#define VI_ATTR_MODEL_CODE          (0x3FFF00DFUL)
+#define VI_ATTR_SLOT                (0x3FFF00E8UL)
+#define VI_ATTR_INTF_INST_NAME      (0xBFFF00E9UL)
+#define VI_ATTR_IMMEDIATE_SERV      (0x3FFF0100UL)
+#define VI_ATTR_INTF_PARENT_NUM     (0x3FFF0101UL)
+#define VI_ATTR_RSRC_SPEC_VERSION   (0x3FFF0170UL)
+#define VI_ATTR_INTF_TYPE           (0x3FFF0171UL)
+#define VI_ATTR_GPIB_PRIMARY_ADDR   (0x3FFF0172UL)
+#define VI_ATTR_GPIB_SECONDARY_ADDR (0x3FFF0173UL)
+#define VI_ATTR_RSRC_MANF_NAME      (0xBFFF0174UL)
+#define VI_ATTR_RSRC_MANF_ID        (0x3FFF0175UL)
+#define VI_ATTR_INTF_NUM            (0x3FFF0176UL)
+#define VI_ATTR_TRIG_ID             (0x3FFF0177UL)
+#define VI_ATTR_GPIB_REN_STATE      (0x3FFF0181UL)
+#define VI_ATTR_GPIB_UNADDR_EN      (0x3FFF0184UL)
+#define VI_ATTR_DEV_STATUS_BYTE     (0x3FFF0189UL)
+#define VI_ATTR_FILE_APPEND_EN      (0x3FFF0192UL)
+#define VI_ATTR_VXI_TRIG_SUPPORT    (0x3FFF0194UL)
+#define VI_ATTR_TCPIP_ADDR          (0xBFFF0195UL)
+#define VI_ATTR_TCPIP_HOSTNAME      (0xBFFF0196UL)
+#define VI_ATTR_TCPIP_PORT          (0x3FFF0197UL)
+#define VI_ATTR_TCPIP_DEVICE_NAME   (0xBFFF0199UL)
+#define VI_ATTR_TCPIP_NODELAY       (0x3FFF019AUL)
+#define VI_ATTR_TCPIP_KEEPALIVE     (0x3FFF019BUL)
+#define VI_ATTR_4882_COMPLIANT      (0x3FFF019FUL)
+#define VI_ATTR_USB_SERIAL_NUM      (0xBFFF01A0UL)
+#define VI_ATTR_USB_INTFC_NUM       (0x3FFF01A1UL)
+#define VI_ATTR_USB_PROTOCOL        (0x3FFF01A7UL)
+#define VI_ATTR_USB_MAX_INTR_SIZE   (0x3FFF01AFUL)
+#define VI_ATTR_PXI_DEV_NUM         (0x3FFF0201UL)
+#define VI_ATTR_PXI_FUNC_NUM        (0x3FFF0202UL)
+#define VI_ATTR_PXI_BUS_NUM         (0x3FFF0205UL)
+#define VI_ATTR_PXI_CHASSIS         (0x3FFF0206UL)
+#define VI_ATTR_PXI_SLOTPATH        (0xBFFF0207UL)
+#define VI_ATTR_PXI_SLOT_LBUS_LEFT  (0x3FFF0208UL)
+#define VI_ATTR_PXI_SLOT_LBUS_RIGHT (0x3FFF0209UL)
+#define VI_ATTR_PXI_TRIG_BUS        (0x3FFF020AUL)
+#define VI_ATTR_PXI_STAR_TRIG_BUS   (0x3FFF020BUL)
+#define VI_ATTR_PXI_STAR_TRIG_LINE  (0x3FFF020CUL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR0   (0x3FFF0211UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR1   (0x3FFF0212UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR2   (0x3FFF0213UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR3   (0x3FFF0214UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR4   (0x3FFF0215UL)
+#define VI_ATTR_PXI_MEM_TYPE_BAR5   (0x3FFF0216UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR0   (0x3FFF0221UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR1   (0x3FFF0222UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR2   (0x3FFF0223UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR3   (0x3FFF0224UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR4   (0x3FFF0225UL)
+#define VI_ATTR_PXI_MEM_BASE_BAR5   (0x3FFF0226UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR0   (0x3FFF0231UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR1   (0x3FFF0232UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR2   (0x3FFF0233UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR3   (0x3FFF0234UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR4   (0x3FFF0235UL)
+#define VI_ATTR_PXI_MEM_SIZE_BAR5   (0x3FFF0236UL)
+#define VI_ATTR_PXI_IS_EXPRESS      (0x3FFF0240UL)
+#define VI_ATTR_PXI_SLOT_LWIDTH     (0x3FFF0241UL)
+#define VI_ATTR_PXI_MAX_LWIDTH      (0x3FFF0242UL)
+#define VI_ATTR_PXI_ACTUAL_LWIDTH   (0x3FFF0243UL)
+#define VI_ATTR_PXI_DSTAR_BUS       (0x3FFF0244UL)
+#define VI_ATTR_PXI_DSTAR_SET       (0x3FFF0245UL)
+
+#define VI_ATTR_JOB_ID              (0x3FFF4006UL)
+#define VI_ATTR_EVENT_TYPE          (0x3FFF4010UL)
+#define VI_ATTR_SIGP_STATUS_ID      (0x3FFF4011UL)
+#define VI_ATTR_RECV_TRIG_ID        (0x3FFF4012UL)
+#define VI_ATTR_INTR_STATUS_ID      (0x3FFF4023UL)
+#define VI_ATTR_STATUS              (0x3FFF4025UL)
+#define VI_ATTR_RET_COUNT_32        (0x3FFF4026UL)
+#define VI_ATTR_BUFFER              (0x3FFF4027UL)
+#define VI_ATTR_RECV_INTR_LEVEL     (0x3FFF4041UL)
+#define VI_ATTR_OPER_NAME           (0xBFFF4042UL)
+#define VI_ATTR_GPIB_RECV_CIC_STATE (0x3FFF4193UL)
+#define VI_ATTR_RECV_TCPIP_ADDR     (0xBFFF4198UL)
+#define VI_ATTR_USB_RECV_INTR_SIZE  (0x3FFF41B0UL)
+#define VI_ATTR_USB_RECV_INTR_DATA  (0xBFFF41B1UL)
+
+/*- Attributes (platform dependent size) ------------------------------------*/
+
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+#define VI_ATTR_USER_DATA_64        (0x3FFF000AUL)
+#define VI_ATTR_RET_COUNT_64        (0x3FFF4028UL)
+#define VI_ATTR_USER_DATA           (VI_ATTR_USER_DATA_64)
+#define VI_ATTR_RET_COUNT           (VI_ATTR_RET_COUNT_64)
+#else
+#define VI_ATTR_USER_DATA           (VI_ATTR_USER_DATA_32)
+#define VI_ATTR_RET_COUNT           (VI_ATTR_RET_COUNT_32)
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+#define VI_ATTR_WIN_BASE_ADDR_64    (0x3FFF009BUL)
+#define VI_ATTR_WIN_SIZE_64         (0x3FFF009CUL)
+#define VI_ATTR_MEM_BASE_64         (0x3FFF00D0UL)
+#define VI_ATTR_MEM_SIZE_64         (0x3FFF00D1UL)
+#endif
+#if defined(_VI_INT64_UINT64_DEFINED) && defined(_VISA_ENV_IS_64_BIT)
+#define VI_ATTR_WIN_BASE_ADDR       (VI_ATTR_WIN_BASE_ADDR_64)
+#define VI_ATTR_WIN_SIZE            (VI_ATTR_WIN_SIZE_64)
+#define VI_ATTR_MEM_BASE            (VI_ATTR_MEM_BASE_64)
+#define VI_ATTR_MEM_SIZE            (VI_ATTR_MEM_SIZE_64)
+#else
+#define VI_ATTR_WIN_BASE_ADDR       (VI_ATTR_WIN_BASE_ADDR_32)
+#define VI_ATTR_WIN_SIZE            (VI_ATTR_WIN_SIZE_32)
+#define VI_ATTR_MEM_BASE            (VI_ATTR_MEM_BASE_32)
+#define VI_ATTR_MEM_SIZE            (VI_ATTR_MEM_SIZE_32)
+#endif
+
+/*- Event Types -------------------------------------------------------------*/
+
+#define VI_EVENT_IO_COMPLETION      (0x3FFF2009UL)
+#define VI_EVENT_TRIG               (0xBFFF200AUL)
+#define VI_EVENT_SERVICE_REQ        (0x3FFF200BUL)
+#define VI_EVENT_CLEAR              (0x3FFF200DUL)
+#define VI_EVENT_EXCEPTION          (0xBFFF200EUL)
+#define VI_EVENT_GPIB_CIC           (0x3FFF2012UL)
+#define VI_EVENT_GPIB_TALK          (0x3FFF2013UL)
+#define VI_EVENT_GPIB_LISTEN        (0x3FFF2014UL)
+#define VI_EVENT_VXI_VME_SYSFAIL    (0x3FFF201DUL)
+#define VI_EVENT_VXI_VME_SYSRESET   (0x3FFF201EUL)
+#define VI_EVENT_VXI_SIGP           (0x3FFF2020UL)
+#define VI_EVENT_VXI_VME_INTR       (0xBFFF2021UL)
+#define VI_EVENT_PXI_INTR           (0x3FFF2022UL)
+#define VI_EVENT_TCPIP_CONNECT      (0x3FFF2036UL)
+#define VI_EVENT_USB_INTR           (0x3FFF2037UL)
+
+#define VI_ALL_ENABLED_EVENTS       (0x3FFF7FFFUL)
+
+/*- Completion and Error Codes ----------------------------------------------*/
+
+#define VI_SUCCESS_EVENT_EN                   (0x3FFF0002L) /* 3FFF0002,  1073676290 */
+#define VI_SUCCESS_EVENT_DIS                  (0x3FFF0003L) /* 3FFF0003,  1073676291 */
+#define VI_SUCCESS_QUEUE_EMPTY                (0x3FFF0004L) /* 3FFF0004,  1073676292 */
+#define VI_SUCCESS_TERM_CHAR                  (0x3FFF0005L) /* 3FFF0005,  1073676293 */
+#define VI_SUCCESS_MAX_CNT                    (0x3FFF0006L) /* 3FFF0006,  1073676294 */
+#define VI_SUCCESS_DEV_NPRESENT               (0x3FFF007DL) /* 3FFF007D,  1073676413 */
+#define VI_SUCCESS_TRIG_MAPPED                (0x3FFF007EL) /* 3FFF007E,  1073676414 */
+#define VI_SUCCESS_QUEUE_NEMPTY               (0x3FFF0080L) /* 3FFF0080,  1073676416 */
+#define VI_SUCCESS_NCHAIN                     (0x3FFF0098L) /* 3FFF0098,  1073676440 */
+#define VI_SUCCESS_NESTED_SHARED              (0x3FFF0099L) /* 3FFF0099,  1073676441 */
+#define VI_SUCCESS_NESTED_EXCLUSIVE           (0x3FFF009AL) /* 3FFF009A,  1073676442 */
+#define VI_SUCCESS_SYNC                       (0x3FFF009BL) /* 3FFF009B,  1073676443 */
+
+#define VI_WARN_QUEUE_OVERFLOW                (0x3FFF000CL) /* 3FFF000C,  1073676300 */
+#define VI_WARN_CONFIG_NLOADED                (0x3FFF0077L) /* 3FFF0077,  1073676407 */
+#define VI_WARN_NULL_OBJECT                   (0x3FFF0082L) /* 3FFF0082,  1073676418 */
+#define VI_WARN_NSUP_ATTR_STATE               (0x3FFF0084L) /* 3FFF0084,  1073676420 */
+#define VI_WARN_UNKNOWN_STATUS                (0x3FFF0085L) /* 3FFF0085,  1073676421 */
+#define VI_WARN_NSUP_BUF                      (0x3FFF0088L) /* 3FFF0088,  1073676424 */
+#define VI_WARN_EXT_FUNC_NIMPL                (0x3FFF00A9L) /* 3FFF00A9,  1073676457 */
+
+#define VI_ERROR_SYSTEM_ERROR       (_VI_ERROR+0x3FFF0000L) /* BFFF0000, -1073807360 */
+#define VI_ERROR_INV_OBJECT         (_VI_ERROR+0x3FFF000EL) /* BFFF000E, -1073807346 */
+#define VI_ERROR_RSRC_LOCKED        (_VI_ERROR+0x3FFF000FL) /* BFFF000F, -1073807345 */
+#define VI_ERROR_INV_EXPR           (_VI_ERROR+0x3FFF0010L) /* BFFF0010, -1073807344 */
+#define VI_ERROR_RSRC_NFOUND        (_VI_ERROR+0x3FFF0011L) /* BFFF0011, -1073807343 */
+#define VI_ERROR_INV_RSRC_NAME      (_VI_ERROR+0x3FFF0012L) /* BFFF0012, -1073807342 */
+#define VI_ERROR_INV_ACC_MODE       (_VI_ERROR+0x3FFF0013L) /* BFFF0013, -1073807341 */
+#define VI_ERROR_TMO                (_VI_ERROR+0x3FFF0015L) /* BFFF0015, -1073807339 */
+#define VI_ERROR_CLOSING_FAILED     (_VI_ERROR+0x3FFF0016L) /* BFFF0016, -1073807338 */
+#define VI_ERROR_INV_DEGREE         (_VI_ERROR+0x3FFF001BL) /* BFFF001B, -1073807333 */
+#define VI_ERROR_INV_JOB_ID         (_VI_ERROR+0x3FFF001CL) /* BFFF001C, -1073807332 */
+#define VI_ERROR_NSUP_ATTR          (_VI_ERROR+0x3FFF001DL) /* BFFF001D, -1073807331 */
+#define VI_ERROR_NSUP_ATTR_STATE    (_VI_ERROR+0x3FFF001EL) /* BFFF001E, -1073807330 */
+#define VI_ERROR_ATTR_READONLY      (_VI_ERROR+0x3FFF001FL) /* BFFF001F, -1073807329 */
+#define VI_ERROR_INV_LOCK_TYPE      (_VI_ERROR+0x3FFF0020L) /* BFFF0020, -1073807328 */
+#define VI_ERROR_INV_ACCESS_KEY     (_VI_ERROR+0x3FFF0021L) /* BFFF0021, -1073807327 */
+#define VI_ERROR_INV_EVENT          (_VI_ERROR+0x3FFF0026L) /* BFFF0026, -1073807322 */
+#define VI_ERROR_INV_MECH           (_VI_ERROR+0x3FFF0027L) /* BFFF0027, -1073807321 */
+#define VI_ERROR_HNDLR_NINSTALLED   (_VI_ERROR+0x3FFF0028L) /* BFFF0028, -1073807320 */
+#define VI_ERROR_INV_HNDLR_REF      (_VI_ERROR+0x3FFF0029L) /* BFFF0029, -1073807319 */
+#define VI_ERROR_INV_CONTEXT        (_VI_ERROR+0x3FFF002AL) /* BFFF002A, -1073807318 */
+#define VI_ERROR_QUEUE_OVERFLOW     (_VI_ERROR+0x3FFF002DL) /* BFFF002D, -1073807315 */
+#define VI_ERROR_NENABLED           (_VI_ERROR+0x3FFF002FL) /* BFFF002F, -1073807313 */
+#define VI_ERROR_ABORT              (_VI_ERROR+0x3FFF0030L) /* BFFF0030, -1073807312 */
+#define VI_ERROR_RAW_WR_PROT_VIOL   (_VI_ERROR+0x3FFF0034L) /* BFFF0034, -1073807308 */
+#define VI_ERROR_RAW_RD_PROT_VIOL   (_VI_ERROR+0x3FFF0035L) /* BFFF0035, -1073807307 */
+#define VI_ERROR_OUTP_PROT_VIOL     (_VI_ERROR+0x3FFF0036L) /* BFFF0036, -1073807306 */
+#define VI_ERROR_INP_PROT_VIOL      (_VI_ERROR+0x3FFF0037L) /* BFFF0037, -1073807305 */
+#define VI_ERROR_BERR               (_VI_ERROR+0x3FFF0038L) /* BFFF0038, -1073807304 */
+#define VI_ERROR_IN_PROGRESS        (_VI_ERROR+0x3FFF0039L) /* BFFF0039, -1073807303 */
+#define VI_ERROR_INV_SETUP          (_VI_ERROR+0x3FFF003AL) /* BFFF003A, -1073807302 */
+#define VI_ERROR_QUEUE_ERROR        (_VI_ERROR+0x3FFF003BL) /* BFFF003B, -1073807301 */
+#define VI_ERROR_ALLOC              (_VI_ERROR+0x3FFF003CL) /* BFFF003C, -1073807300 */
+#define VI_ERROR_INV_MASK           (_VI_ERROR+0x3FFF003DL) /* BFFF003D, -1073807299 */
+#define VI_ERROR_IO                 (_VI_ERROR+0x3FFF003EL) /* BFFF003E, -1073807298 */
+#define VI_ERROR_INV_FMT            (_VI_ERROR+0x3FFF003FL) /* BFFF003F, -1073807297 */
+#define VI_ERROR_NSUP_FMT           (_VI_ERROR+0x3FFF0041L) /* BFFF0041, -1073807295 */
+#define VI_ERROR_LINE_IN_USE        (_VI_ERROR+0x3FFF0042L) /* BFFF0042, -1073807294 */
+#define VI_ERROR_NSUP_MODE          (_VI_ERROR+0x3FFF0046L) /* BFFF0046, -1073807290 */
+#define VI_ERROR_SRQ_NOCCURRED      (_VI_ERROR+0x3FFF004AL) /* BFFF004A, -1073807286 */
+#define VI_ERROR_INV_SPACE          (_VI_ERROR+0x3FFF004EL) /* BFFF004E, -1073807282 */
+#define VI_ERROR_INV_OFFSET         (_VI_ERROR+0x3FFF0051L) /* BFFF0051, -1073807279 */
+#define VI_ERROR_INV_WIDTH          (_VI_ERROR+0x3FFF0052L) /* BFFF0052, -1073807278 */
+#define VI_ERROR_NSUP_OFFSET        (_VI_ERROR+0x3FFF0054L) /* BFFF0054, -1073807276 */
+#define VI_ERROR_NSUP_VAR_WIDTH     (_VI_ERROR+0x3FFF0055L) /* BFFF0055, -1073807275 */
+#define VI_ERROR_WINDOW_NMAPPED     (_VI_ERROR+0x3FFF0057L) /* BFFF0057, -1073807273 */
+#define VI_ERROR_RESP_PENDING       (_VI_ERROR+0x3FFF0059L) /* BFFF0059, -1073807271 */
+#define VI_ERROR_NLISTENERS         (_VI_ERROR+0x3FFF005FL) /* BFFF005F, -1073807265 */
+#define VI_ERROR_NCIC               (_VI_ERROR+0x3FFF0060L) /* BFFF0060, -1073807264 */
+#define VI_ERROR_NSYS_CNTLR         (_VI_ERROR+0x3FFF0061L) /* BFFF0061, -1073807263 */
+#define VI_ERROR_NSUP_OPER          (_VI_ERROR+0x3FFF0067L) /* BFFF0067, -1073807257 */
+#define VI_ERROR_INTR_PENDING       (_VI_ERROR+0x3FFF0068L) /* BFFF0068, -1073807256 */
+#define VI_ERROR_ASRL_PARITY        (_VI_ERROR+0x3FFF006AL) /* BFFF006A, -1073807254 */
+#define VI_ERROR_ASRL_FRAMING       (_VI_ERROR+0x3FFF006BL) /* BFFF006B, -1073807253 */
+#define VI_ERROR_ASRL_OVERRUN       (_VI_ERROR+0x3FFF006CL) /* BFFF006C, -1073807252 */
+#define VI_ERROR_TRIG_NMAPPED       (_VI_ERROR+0x3FFF006EL) /* BFFF006E, -1073807250 */
+#define VI_ERROR_NSUP_ALIGN_OFFSET  (_VI_ERROR+0x3FFF0070L) /* BFFF0070, -1073807248 */
+#define VI_ERROR_USER_BUF           (_VI_ERROR+0x3FFF0071L) /* BFFF0071, -1073807247 */
+#define VI_ERROR_RSRC_BUSY          (_VI_ERROR+0x3FFF0072L) /* BFFF0072, -1073807246 */
+#define VI_ERROR_NSUP_WIDTH         (_VI_ERROR+0x3FFF0076L) /* BFFF0076, -1073807242 */
+#define VI_ERROR_INV_PARAMETER      (_VI_ERROR+0x3FFF0078L) /* BFFF0078, -1073807240 */
+#define VI_ERROR_INV_PROT           (_VI_ERROR+0x3FFF0079L) /* BFFF0079, -1073807239 */
+#define VI_ERROR_INV_SIZE           (_VI_ERROR+0x3FFF007BL) /* BFFF007B, -1073807237 */
+#define VI_ERROR_WINDOW_MAPPED      (_VI_ERROR+0x3FFF0080L) /* BFFF0080, -1073807232 */
+#define VI_ERROR_NIMPL_OPER         (_VI_ERROR+0x3FFF0081L) /* BFFF0081, -1073807231 */
+#define VI_ERROR_INV_LENGTH         (_VI_ERROR+0x3FFF0083L) /* BFFF0083, -1073807229 */
+#define VI_ERROR_INV_MODE           (_VI_ERROR+0x3FFF0091L) /* BFFF0091, -1073807215 */
+#define VI_ERROR_SESN_NLOCKED       (_VI_ERROR+0x3FFF009CL) /* BFFF009C, -1073807204 */
+#define VI_ERROR_MEM_NSHARED        (_VI_ERROR+0x3FFF009DL) /* BFFF009D, -1073807203 */
+#define VI_ERROR_LIBRARY_NFOUND     (_VI_ERROR+0x3FFF009EL) /* BFFF009E, -1073807202 */
+#define VI_ERROR_NSUP_INTR          (_VI_ERROR+0x3FFF009FL) /* BFFF009F, -1073807201 */
+#define VI_ERROR_INV_LINE           (_VI_ERROR+0x3FFF00A0L) /* BFFF00A0, -1073807200 */
+#define VI_ERROR_FILE_ACCESS        (_VI_ERROR+0x3FFF00A1L) /* BFFF00A1, -1073807199 */
+#define VI_ERROR_FILE_IO            (_VI_ERROR+0x3FFF00A2L) /* BFFF00A2, -1073807198 */
+#define VI_ERROR_NSUP_LINE          (_VI_ERROR+0x3FFF00A3L) /* BFFF00A3, -1073807197 */
+#define VI_ERROR_NSUP_MECH          (_VI_ERROR+0x3FFF00A4L) /* BFFF00A4, -1073807196 */
+#define VI_ERROR_INTF_NUM_NCONFIG   (_VI_ERROR+0x3FFF00A5L) /* BFFF00A5, -1073807195 */
+#define VI_ERROR_CONN_LOST          (_VI_ERROR+0x3FFF00A6L) /* BFFF00A6, -1073807194 */
+#define VI_ERROR_MACHINE_NAVAIL     (_VI_ERROR+0x3FFF00A7L) /* BFFF00A7, -1073807193 */
+#define VI_ERROR_NPERMISSION        (_VI_ERROR+0x3FFF00A8L) /* BFFF00A8, -1073807192 */
+
+/*- Other VISA Definitions --------------------------------------------------*/
+
+#define VI_VERSION_MAJOR(ver)       ((((ViVersion)ver) & 0xFFF00000UL) >> 20)
+#define VI_VERSION_MINOR(ver)       ((((ViVersion)ver) & 0x000FFF00UL) >>  8)
+#define VI_VERSION_SUBMINOR(ver)    ((((ViVersion)ver) & 0x000000FFUL)      )
+
+#define VI_FIND_BUFLEN              (256)
+
+#define VI_INTF_GPIB                (1)
+#define VI_INTF_VXI                 (2)
+#define VI_INTF_GPIB_VXI            (3)
+#define VI_INTF_ASRL                (4)
+#define VI_INTF_PXI                 (5)
+#define VI_INTF_TCPIP               (6)
+#define VI_INTF_USB                 (7)
+
+#define VI_PROT_NORMAL              (1)
+#define VI_PROT_FDC                 (2)
+#define VI_PROT_HS488               (3)
+#define VI_PROT_4882_STRS           (4)
+#define VI_PROT_USBTMC_VENDOR       (5)
+
+#define VI_FDC_NORMAL               (1)
+#define VI_FDC_STREAM               (2)
+
+#define VI_LOCAL_SPACE              (0)
+#define VI_A16_SPACE                (1)
+#define VI_A24_SPACE                (2)
+#define VI_A32_SPACE                (3)
+#define VI_A64_SPACE                (4)
+#define VI_PXI_ALLOC_SPACE          (9)
+#define VI_PXI_CFG_SPACE            (10)
+#define VI_PXI_BAR0_SPACE           (11)
+#define VI_PXI_BAR1_SPACE           (12)
+#define VI_PXI_BAR2_SPACE           (13)
+#define VI_PXI_BAR3_SPACE           (14)
+#define VI_PXI_BAR4_SPACE           (15)
+#define VI_PXI_BAR5_SPACE           (16)
+#define VI_OPAQUE_SPACE             (0xFFFF)
+
+#define VI_UNKNOWN_LA               (-1)
+#define VI_UNKNOWN_SLOT             (-1)
+#define VI_UNKNOWN_LEVEL            (-1)
+#define VI_UNKNOWN_CHASSIS          (-1)
+
+#define VI_QUEUE                    (1)
+#define VI_HNDLR                    (2)
+#define VI_SUSPEND_HNDLR            (4)
+#define VI_ALL_MECH                 (0xFFFF)
+
+#define VI_ANY_HNDLR                (0)
+
+#define VI_TRIG_ALL                 (-2)
+#define VI_TRIG_SW                  (-1)
+#define VI_TRIG_TTL0                (0)
+#define VI_TRIG_TTL1                (1)
+#define VI_TRIG_TTL2                (2)
+#define VI_TRIG_TTL3                (3)
+#define VI_TRIG_TTL4                (4)
+#define VI_TRIG_TTL5                (5)
+#define VI_TRIG_TTL6                (6)
+#define VI_TRIG_TTL7                (7)
+#define VI_TRIG_ECL0                (8)
+#define VI_TRIG_ECL1                (9)
+#define VI_TRIG_PANEL_IN            (27)
+#define VI_TRIG_PANEL_OUT           (28)
+
+#define VI_TRIG_PROT_DEFAULT        (0)
+#define VI_TRIG_PROT_ON             (1)
+#define VI_TRIG_PROT_OFF            (2)
+#define VI_TRIG_PROT_SYNC           (5)
+#define VI_TRIG_PROT_RESERVE        (6)
+#define VI_TRIG_PROT_UNRESERVE      (7)
+
+#define VI_READ_BUF                 (1)
+#define VI_WRITE_BUF                (2)
+#define VI_READ_BUF_DISCARD         (4)
+#define VI_WRITE_BUF_DISCARD        (8)
+#define VI_IO_IN_BUF                (16)
+#define VI_IO_OUT_BUF               (32)
+#define VI_IO_IN_BUF_DISCARD        (64)
+#define VI_IO_OUT_BUF_DISCARD       (128)
+
+#define VI_FLUSH_ON_ACCESS          (1)
+#define VI_FLUSH_WHEN_FULL          (2)
+#define VI_FLUSH_DISABLE            (3)
+
+#define VI_NMAPPED                  (1)
+#define VI_USE_OPERS                (2)
+#define VI_DEREF_ADDR               (3)
+#define VI_DEREF_ADDR_BYTE_SWAP     (4)
+
+#define VI_TMO_IMMEDIATE            (0L)
+#define VI_TMO_INFINITE             (0xFFFFFFFFUL)
+
+#define VI_NO_LOCK                  (0)
+#define VI_EXCLUSIVE_LOCK           (1)
+#define VI_SHARED_LOCK              (2)
+#define VI_LOAD_CONFIG              (4)
+
+#define VI_NO_SEC_ADDR              (0xFFFF)
+
+#define VI_ASRL_PAR_NONE            (0)
+#define VI_ASRL_PAR_ODD             (1)
+#define VI_ASRL_PAR_EVEN            (2)
+#define VI_ASRL_PAR_MARK            (3)
+#define VI_ASRL_PAR_SPACE           (4)
+
+#define VI_ASRL_STOP_ONE            (10)
+#define VI_ASRL_STOP_ONE5           (15)
+#define VI_ASRL_STOP_TWO            (20)
+
+#define VI_ASRL_FLOW_NONE           (0)
+#define VI_ASRL_FLOW_XON_XOFF       (1)
+#define VI_ASRL_FLOW_RTS_CTS        (2)
+#define VI_ASRL_FLOW_DTR_DSR        (4)
+
+#define VI_ASRL_END_NONE            (0)
+#define VI_ASRL_END_LAST_BIT        (1)
+#define VI_ASRL_END_TERMCHAR        (2)
+#define VI_ASRL_END_BREAK           (3)
+
+#define VI_STATE_ASSERTED           (1)
+#define VI_STATE_UNASSERTED         (0)
+#define VI_STATE_UNKNOWN            (-1)
+
+#define VI_BIG_ENDIAN               (0)
+#define VI_LITTLE_ENDIAN            (1)
+
+#define VI_DATA_PRIV                (0)
+#define VI_DATA_NPRIV               (1)
+#define VI_PROG_PRIV                (2)
+#define VI_PROG_NPRIV               (3)
+#define VI_BLCK_PRIV                (4)
+#define VI_BLCK_NPRIV               (5)
+#define VI_D64_PRIV                 (6)
+#define VI_D64_NPRIV                (7)
+
+#define VI_WIDTH_8                  (1)
+#define VI_WIDTH_16                 (2)
+#define VI_WIDTH_32                 (4)
+#define VI_WIDTH_64                 (8)
+
+#define VI_GPIB_REN_DEASSERT        (0)
+#define VI_GPIB_REN_ASSERT          (1)
+#define VI_GPIB_REN_DEASSERT_GTL    (2)
+#define VI_GPIB_REN_ASSERT_ADDRESS  (3)
+#define VI_GPIB_REN_ASSERT_LLO      (4)
+#define VI_GPIB_REN_ASSERT_ADDRESS_LLO (5)
+#define VI_GPIB_REN_ADDRESS_GTL     (6)
+
+#define VI_GPIB_ATN_DEASSERT        (0)
+#define VI_GPIB_ATN_ASSERT          (1)
+#define VI_GPIB_ATN_DEASSERT_HANDSHAKE (2)
+#define VI_GPIB_ATN_ASSERT_IMMEDIATE (3)
+
+#define VI_GPIB_HS488_DISABLED      (0)
+#define VI_GPIB_HS488_NIMPL         (-1)
+
+#define VI_GPIB_UNADDRESSED         (0)
+#define VI_GPIB_TALKER              (1)
+#define VI_GPIB_LISTENER            (2)
+
+#define VI_VXI_CMD16                (0x0200)
+#define VI_VXI_CMD16_RESP16         (0x0202)
+#define VI_VXI_RESP16               (0x0002)
+#define VI_VXI_CMD32                (0x0400)
+#define VI_VXI_CMD32_RESP16         (0x0402)
+#define VI_VXI_CMD32_RESP32         (0x0404)
+#define VI_VXI_RESP32               (0x0004)
+
+#define VI_ASSERT_SIGNAL            (-1)
+#define VI_ASSERT_USE_ASSIGNED      (0)
+#define VI_ASSERT_IRQ1              (1)
+#define VI_ASSERT_IRQ2              (2)
+#define VI_ASSERT_IRQ3              (3)
+#define VI_ASSERT_IRQ4              (4)
+#define VI_ASSERT_IRQ5              (5)
+#define VI_ASSERT_IRQ6              (6)
+#define VI_ASSERT_IRQ7              (7)
+
+#define VI_UTIL_ASSERT_SYSRESET     (1)
+#define VI_UTIL_ASSERT_SYSFAIL      (2)
+#define VI_UTIL_DEASSERT_SYSFAIL    (3)
+
+#define VI_VXI_CLASS_MEMORY         (0)
+#define VI_VXI_CLASS_EXTENDED       (1)
+#define VI_VXI_CLASS_MESSAGE        (2)
+#define VI_VXI_CLASS_REGISTER       (3)
+#define VI_VXI_CLASS_OTHER          (4)
+
+#define VI_PXI_ADDR_NONE            (0)
+#define VI_PXI_ADDR_MEM             (1)
+#define VI_PXI_ADDR_IO              (2)
+#define VI_PXI_ADDR_CFG             (3)
+
+#define VI_TRIG_UNKNOWN             (-1)
+
+#define VI_PXI_LBUS_UNKNOWN         (-1)
+#define VI_PXI_LBUS_NONE            (0)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_0 (1000)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_1 (1001)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_2 (1002)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_3 (1003)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_4 (1004)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_5 (1005)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_6 (1006)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_7 (1007)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_8 (1008)
+#define VI_PXI_LBUS_STAR_TRIG_BUS_9 (1009)
+#define VI_PXI_STAR_TRIG_CONTROLLER (1413)
+
+/*- Backward Compatibility Macros -------------------------------------------*/
+
+#define viGetDefaultRM(vi)          viOpenDefaultRM(vi)
+#define VI_ERROR_INV_SESSION        (VI_ERROR_INV_OBJECT)
+#define VI_INFINITE                 (VI_TMO_INFINITE)
+#define VI_NORMAL                   (VI_PROT_NORMAL)
+#define VI_FDC                      (VI_PROT_FDC)
+#define VI_HS488                    (VI_PROT_HS488)
+#define VI_ASRL488                  (VI_PROT_4882_STRS)
+#define VI_ASRL_IN_BUF              (VI_IO_IN_BUF)
+#define VI_ASRL_OUT_BUF             (VI_IO_OUT_BUF)
+#define VI_ASRL_IN_BUF_DISCARD      (VI_IO_IN_BUF_DISCARD)
+#define VI_ASRL_OUT_BUF_DISCARD     (VI_IO_OUT_BUF_DISCARD)
+
+/*- National Instruments ----------------------------------------------------*/
+
+#define VI_INTF_RIO                 (8)
+#define VI_INTF_FIREWIRE            (9) 
+
+#define VI_ATTR_SYNC_MXI_ALLOW_EN   (0x3FFF0161UL) /* ViBoolean, read/write */
+
+/* This is for VXI SERVANT resources */
+
+#define VI_EVENT_VXI_DEV_CMD        (0xBFFF200FUL)
+#define VI_ATTR_VXI_DEV_CMD_TYPE    (0x3FFF4037UL) /* ViInt16, read-only */
+#define VI_ATTR_VXI_DEV_CMD_VALUE   (0x3FFF4038UL) /* ViUInt32, read-only */
+
+#define VI_VXI_DEV_CMD_TYPE_16      (16)
+#define VI_VXI_DEV_CMD_TYPE_32      (32)
+
+ViStatus _VI_FUNC viVxiServantResponse(ViSession vi, ViInt16 mode, ViUInt32 resp);
+/* mode values include VI_VXI_RESP16, VI_VXI_RESP32, and the next 2 values */
+#define VI_VXI_RESP_NONE            (0)
+#define VI_VXI_RESP_PROT_ERROR      (-1)
+
+/* This allows extended Serial support on Win32 and on NI ENET Serial products */
+
+#define VI_ATTR_ASRL_DISCARD_NULL   (0x3FFF00B0UL)
+#define VI_ATTR_ASRL_CONNECTED      (0x3FFF01BBUL)
+#define VI_ATTR_ASRL_BREAK_STATE    (0x3FFF01BCUL)
+#define VI_ATTR_ASRL_BREAK_LEN      (0x3FFF01BDUL)
+#define VI_ATTR_ASRL_ALLOW_TRANSMIT (0x3FFF01BEUL)
+#define VI_ATTR_ASRL_WIRE_MODE      (0x3FFF01BFUL)
+
+#define VI_ASRL_WIRE_485_4          (0)
+#define VI_ASRL_WIRE_485_2_DTR_ECHO (1)
+#define VI_ASRL_WIRE_485_2_DTR_CTRL (2)
+#define VI_ASRL_WIRE_485_2_AUTO     (3)
+#define VI_ASRL_WIRE_232_DTE        (128)
+#define VI_ASRL_WIRE_232_DCE        (129)
+#define VI_ASRL_WIRE_232_AUTO       (130)
+
+#define VI_EVENT_ASRL_BREAK         (0x3FFF2023UL)
+#define VI_EVENT_ASRL_CTS           (0x3FFF2029UL)
+#define VI_EVENT_ASRL_DSR           (0x3FFF202AUL)
+#define VI_EVENT_ASRL_DCD           (0x3FFF202CUL)
+#define VI_EVENT_ASRL_RI            (0x3FFF202EUL)
+#define VI_EVENT_ASRL_CHAR          (0x3FFF2035UL)
+#define VI_EVENT_ASRL_TERMCHAR      (0x3FFF2024UL)
+
+/* This is for fast viPeek/viPoke macros */
+
+#if defined(NIVISA_PEEKPOKE)
+
+#if defined(NIVISA_PEEKPOKE_SUPP)
+#undef NIVISA_PEEKPOKE_SUPP
+#endif
+
+#if (defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_)
+/* This macro is supported for all Win32 compilers, including CVI. */
+#define NIVISA_PEEKPOKE_SUPP
+#elif (defined(_WINDOWS) || defined(_Windows)) && !defined(_CVI_) && !defined(_NI_mswin16_)
+/* This macro is supported for Borland and Microsoft compilers on Win16, but not CVI. */
+#define NIVISA_PEEKPOKE_SUPP
+#elif defined(_CVI_) && defined(_NI_sparc_)
+/* This macro is supported for Solaris 1 and 2, from CVI only. */
+#define NIVISA_PEEKPOKE_SUPP
+#else
+/* This macro is not supported on other platforms. */
+#endif
+
+#if defined(NIVISA_PEEKPOKE_SUPP)
+
+extern ViBoolean NI_viImplVISA1;
+ViStatus _VI_FUNC NI_viOpenDefaultRM (ViPSession vi);
+#define viOpenDefaultRM(vi) NI_viOpenDefaultRM(vi)
+
+#define viPeek8(vi,addr,val)                                                \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((ViPUInt8)(val)) = *((volatile ViUInt8 _VI_PTR)(addr)));     \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPeek8)((vi),(addr),(val));                                      \
+      }                                                                     \
+   }
+
+#define viPoke8(vi,addr,val)                                                \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((volatile ViUInt8 _VI_PTR)(addr)) = ((ViUInt8)(val)));       \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPoke8)((vi),(addr),(val));                                      \
+      }                                                                     \
+   }
+
+#define viPeek16(vi,addr,val)                                               \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((ViPUInt16)(val)) = *((volatile ViUInt16 _VI_PTR)(addr)));   \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPeek16)((vi),(addr),(val));                                     \
+      }                                                                     \
+   }
+
+#define viPoke16(vi,addr,val)                                               \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((volatile ViUInt16 _VI_PTR)(addr)) = ((ViUInt16)(val)));     \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPoke16)((vi),(addr),(val));                                     \
+      }                                                                     \
+   }
+
+#define viPeek32(vi,addr,val)                                               \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((ViPUInt32)(val)) = *((volatile ViUInt32 _VI_PTR)(addr)));   \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPeek32)((vi),(addr),(val));                                     \
+      }                                                                     \
+   }
+
+#define viPoke32(vi,addr,val)                                               \
+   {                                                                        \
+      if ((NI_viImplVISA1) && (*((ViPUInt32)(vi))))                         \
+      {                                                                     \
+         do (*((volatile ViUInt32 _VI_PTR)(addr)) = ((ViUInt32)(val)));     \
+         while (**((volatile ViUInt8 _VI_PTR _VI_PTR)(vi)) & 0x10);         \
+      }                                                                     \
+      else                                                                  \
+      {                                                                     \
+         (viPoke32)((vi),(addr),(val));                                     \
+      }                                                                     \
+   }
+
+#endif
+
+#endif
+
+#if defined(NIVISA_PXI) || defined(PXISAVISA_PXI)
+
+#if 0
+/* The following 2 attributes were incorrectly implemented in earlier
+   versions of NI-VISA.  You should now query VI_ATTR_MANF_ID or
+   VI_ATTR_MODEL_CODE.  Those attributes contain sub-vendor information
+   when it exists.  To get both the actual primary and subvendor codes
+   from the device, you should call viIn16 using VI_PXI_CFG_SPACE. */
+#define VI_ATTR_PXI_SUB_MANF_ID     (0x3FFF0203UL)
+#define VI_ATTR_PXI_SUB_MODEL_CODE  (0x3FFF0204UL)
+#endif
+
+#define VI_ATTR_PXI_SRC_TRIG_BUS    (0x3FFF020DUL)
+#define VI_ATTR_PXI_DEST_TRIG_BUS   (0x3FFF020EUL)
+
+#define VI_ATTR_PXI_RECV_INTR_SEQ   (0x3FFF4240UL)
+#define VI_ATTR_PXI_RECV_INTR_DATA  (0x3FFF4241UL)
+
+#endif
+
+#if defined(NIVISA_USB)
+
+#define VI_ATTR_USB_BULK_OUT_PIPE   (0x3FFF01A2UL)
+#define VI_ATTR_USB_BULK_IN_PIPE    (0x3FFF01A3UL)
+#define VI_ATTR_USB_INTR_IN_PIPE    (0x3FFF01A4UL)
+#define VI_ATTR_USB_CLASS           (0x3FFF01A5UL)
+#define VI_ATTR_USB_SUBCLASS        (0x3FFF01A6UL)
+#define VI_ATTR_USB_ALT_SETTING     (0x3FFF01A8UL)
+#define VI_ATTR_USB_END_IN          (0x3FFF01A9UL)
+#define VI_ATTR_USB_NUM_INTFCS      (0x3FFF01AAUL)
+#define VI_ATTR_USB_NUM_PIPES       (0x3FFF01ABUL)
+#define VI_ATTR_USB_BULK_OUT_STATUS (0x3FFF01ACUL)
+#define VI_ATTR_USB_BULK_IN_STATUS  (0x3FFF01ADUL)
+#define VI_ATTR_USB_INTR_IN_STATUS  (0x3FFF01AEUL)
+#define VI_ATTR_USB_CTRL_PIPE       (0x3FFF01B0UL)
+
+#define VI_USB_PIPE_STATE_UNKNOWN   (-1)
+#define VI_USB_PIPE_READY           (0)
+#define VI_USB_PIPE_STALLED         (1)
+
+#define VI_USB_END_NONE             (0)
+#define VI_USB_END_SHORT            (4)
+#define VI_USB_END_SHORT_OR_COUNT   (5)
+
+#endif
+
+#define VI_ATTR_FIREWIRE_DEST_UPPER_OFFSET (0x3FFF01F0UL)
+#define VI_ATTR_FIREWIRE_SRC_UPPER_OFFSET  (0x3FFF01F1UL)
+#define VI_ATTR_FIREWIRE_WIN_UPPER_OFFSET  (0x3FFF01F2UL)
+#define VI_ATTR_FIREWIRE_VENDOR_ID         (0x3FFF01F3UL)
+#define VI_ATTR_FIREWIRE_LOWER_CHIP_ID     (0x3FFF01F4UL)
+#define VI_ATTR_FIREWIRE_UPPER_CHIP_ID     (0x3FFF01F5UL)
+
+#define VI_FIREWIRE_DFLT_SPACE           (5)
+
+#if defined(__cplusplus) || defined(__cplusplus__)
+   }
+#endif
+
+#endif
+
+/*- The End -----------------------------------------------------------------*/
diff --git a/third_party/allwpilib_2019/hal/src/main/native/athena/visa/visatype.h b/third_party/allwpilib_2019/hal/src/main/native/athena/visa/visatype.h
new file mode 100644
index 0000000..ef089dd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/athena/visa/visatype.h
@@ -0,0 +1,201 @@
+/*---------------------------------------------------------------------------*/
+/* Distributed by IVI Foundation Inc.                                        */
+/*                                                                           */
+/* Do not modify the contents of this file.                                  */
+/*---------------------------------------------------------------------------*/
+/*                                                                           */
+/* Title   : VISATYPE.H                                                      */
+/* Date    : 04-14-2006                                                      */
+/* Purpose : Fundamental VISA data types and macro definitions               */
+/*                                                                           */
+/*---------------------------------------------------------------------------*/
+
+#ifndef __VISATYPE_HEADER__
+#define __VISATYPE_HEADER__
+
+#if defined(_WIN64)
+#define _VI_FAR
+#define _VI_FUNC            __fastcall
+#define _VI_FUNCC           __fastcall
+#define _VI_FUNCH           __fastcall
+#define _VI_SIGNED          signed
+#elif (defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_)
+#define _VI_FAR
+#define _VI_FUNC            __stdcall
+#define _VI_FUNCC           __cdecl
+#define _VI_FUNCH           __stdcall
+#define _VI_SIGNED          signed
+#elif defined(_CVI_) && defined(_NI_i386_)
+#define _VI_FAR
+#define _VI_FUNC            _pascal
+#define _VI_FUNCC
+#define _VI_FUNCH           _pascal
+#define _VI_SIGNED          signed
+#elif (defined(_WINDOWS) || defined(_Windows)) && !defined(_NI_mswin16_)
+#define _VI_FAR             _far
+#define _VI_FUNC            _far _pascal _export
+#define _VI_FUNCC           _far _cdecl  _export
+#define _VI_FUNCH           _far _pascal
+#define _VI_SIGNED          signed
+#elif (defined(hpux) || defined(__hpux)) && (defined(__cplusplus) || defined(__cplusplus__))
+#define _VI_FAR
+#define _VI_FUNC
+#define _VI_FUNCC
+#define _VI_FUNCH
+#define _VI_SIGNED
+#else
+#define _VI_FAR
+#define _VI_FUNC
+#define _VI_FUNCC
+#define _VI_FUNCH
+#define _VI_SIGNED          signed
+#endif
+
+#define _VI_ERROR           (-2147483647L-1)  /* 0x80000000 */
+#define _VI_PTR             _VI_FAR *
+
+/*- VISA Types --------------------------------------------------------------*/
+
+#ifndef _VI_INT64_UINT64_DEFINED
+#if defined(_WIN64) || ((defined(WIN32) || defined(_WIN32) || defined(__WIN32__) || defined(__NT__)) && !defined(_NI_mswin16_))
+#if (defined(_MSC_VER) && (_MSC_VER >= 1200)) || (defined(_CVI_) && (_CVI_ >= 700)) || (defined(__BORLANDC__) && (__BORLANDC__ >= 0x0520))
+typedef unsigned   __int64  ViUInt64;
+typedef _VI_SIGNED __int64  ViInt64;
+#define _VI_INT64_UINT64_DEFINED
+#if defined(_WIN64)
+#define _VISA_ENV_IS_64_BIT
+#else
+/* This is a 32-bit OS, not a 64-bit OS */
+#endif
+#endif
+#elif defined(__GNUC__) && (__GNUC__ >= 3)
+#include <limits.h>
+#include <sys/types.h>
+typedef u_int64_t           ViUInt64;
+typedef int64_t             ViInt64;
+#define _VI_INT64_UINT64_DEFINED
+#if defined(LONG_MAX) && (LONG_MAX > 0x7FFFFFFFL)
+#define _VISA_ENV_IS_64_BIT
+#else
+/* This is a 32-bit OS, not a 64-bit OS */
+#endif
+#else
+/* This platform does not support 64-bit types */
+#endif
+#endif
+
+#if defined(_VI_INT64_UINT64_DEFINED)
+typedef ViUInt64    _VI_PTR ViPUInt64;
+typedef ViUInt64    _VI_PTR ViAUInt64;
+typedef ViInt64     _VI_PTR ViPInt64;
+typedef ViInt64     _VI_PTR ViAInt64;
+#endif
+
+#if defined(LONG_MAX) && (LONG_MAX > 0x7FFFFFFFL)
+typedef unsigned int        ViUInt32;
+typedef _VI_SIGNED int      ViInt32;
+#else
+typedef unsigned long       ViUInt32;
+typedef _VI_SIGNED long     ViInt32;
+#endif
+
+typedef ViUInt32    _VI_PTR ViPUInt32;
+typedef ViUInt32    _VI_PTR ViAUInt32;
+typedef ViInt32     _VI_PTR ViPInt32;
+typedef ViInt32     _VI_PTR ViAInt32;
+
+typedef unsigned short      ViUInt16;
+typedef ViUInt16    _VI_PTR ViPUInt16;
+typedef ViUInt16    _VI_PTR ViAUInt16;
+
+typedef _VI_SIGNED short    ViInt16;
+typedef ViInt16     _VI_PTR ViPInt16;
+typedef ViInt16     _VI_PTR ViAInt16;
+
+typedef unsigned char       ViUInt8;
+typedef ViUInt8     _VI_PTR ViPUInt8;
+typedef ViUInt8     _VI_PTR ViAUInt8;
+
+typedef _VI_SIGNED char     ViInt8;
+typedef ViInt8      _VI_PTR ViPInt8;
+typedef ViInt8      _VI_PTR ViAInt8;
+
+typedef char                ViChar;
+typedef ViChar      _VI_PTR ViPChar;
+typedef ViChar      _VI_PTR ViAChar;
+
+typedef unsigned char       ViByte;
+typedef ViByte      _VI_PTR ViPByte;
+typedef ViByte      _VI_PTR ViAByte;
+
+typedef void        _VI_PTR ViAddr;
+typedef ViAddr      _VI_PTR ViPAddr;
+typedef ViAddr      _VI_PTR ViAAddr;
+
+typedef float               ViReal32;
+typedef ViReal32    _VI_PTR ViPReal32;
+typedef ViReal32    _VI_PTR ViAReal32;
+
+typedef double              ViReal64;
+typedef ViReal64    _VI_PTR ViPReal64;
+typedef ViReal64    _VI_PTR ViAReal64;
+
+typedef ViPByte             ViBuf;
+typedef ViPByte             ViPBuf;
+typedef ViPByte     _VI_PTR ViABuf;
+
+typedef ViPChar             ViString;
+typedef ViPChar             ViPString;
+typedef ViPChar     _VI_PTR ViAString;
+
+typedef ViString            ViRsrc;
+typedef ViString            ViPRsrc;
+typedef ViString    _VI_PTR ViARsrc;
+
+typedef ViUInt16            ViBoolean;
+typedef ViBoolean   _VI_PTR ViPBoolean;
+typedef ViBoolean   _VI_PTR ViABoolean;
+
+typedef ViInt32             ViStatus;
+typedef ViStatus    _VI_PTR ViPStatus;
+typedef ViStatus    _VI_PTR ViAStatus;
+
+typedef ViUInt32            ViVersion;
+typedef ViVersion   _VI_PTR ViPVersion;
+typedef ViVersion   _VI_PTR ViAVersion;
+
+typedef ViUInt32            ViObject;
+typedef ViObject    _VI_PTR ViPObject;
+typedef ViObject    _VI_PTR ViAObject;
+
+typedef ViObject            ViSession;
+typedef ViSession   _VI_PTR ViPSession;
+typedef ViSession   _VI_PTR ViASession;
+
+typedef ViUInt32             ViAttr;
+
+#ifndef _VI_CONST_STRING_DEFINED
+typedef const ViChar * ViConstString;
+#define _VI_CONST_STRING_DEFINED
+#endif  
+
+/*- Completion and Error Codes ----------------------------------------------*/
+
+#define VI_SUCCESS          (0L)
+
+/*- Other VISA Definitions --------------------------------------------------*/
+
+#define VI_NULL             (0)
+
+#define VI_TRUE             (1)
+#define VI_FALSE            (0)
+
+/*- Backward Compatibility Macros -------------------------------------------*/
+
+#define VISAFN              _VI_FUNC
+#define ViPtr               _VI_PTR
+
+#endif
+
+/*- The End -----------------------------------------------------------------*/
+
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/cpp/fpga_clock.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/cpp/fpga_clock.cpp
new file mode 100644
index 0000000..751eae1
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/cpp/fpga_clock.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/cpp/fpga_clock.h"
+
+#include <wpi/raw_ostream.h>
+
+#include "hal/HAL.h"
+
+namespace hal {
+const fpga_clock::time_point fpga_clock::min_time =
+    fpga_clock::time_point(fpga_clock::duration(
+        std::numeric_limits<fpga_clock::duration::rep>::min()));
+
+fpga_clock::time_point fpga_clock::now() noexcept {
+  int32_t status = 0;
+  uint64_t currentTime = HAL_GetFPGATime(&status);
+  if (status != 0) {
+    wpi::errs()
+        << "Call to HAL_GetFPGATime failed."
+        << "Initialization might have failed. Time will not be correct\n";
+    wpi::errs().flush();
+    return epoch();
+  }
+  return time_point(std::chrono::microseconds(currentTime));
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/handles/HandlesInternal.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/handles/HandlesInternal.cpp
new file mode 100644
index 0000000..45ffb31
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/handles/HandlesInternal.cpp
@@ -0,0 +1,95 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/handles/HandlesInternal.h"
+
+#include <algorithm>
+
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+namespace hal {
+static wpi::SmallVector<HandleBase*, 32>* globalHandles = nullptr;
+static wpi::mutex globalHandleMutex;
+HandleBase::HandleBase() {
+  static wpi::SmallVector<HandleBase*, 32> gH;
+  std::lock_guard<wpi::mutex> lock(globalHandleMutex);
+  if (!globalHandles) {
+    globalHandles = &gH;
+  }
+
+  auto index = std::find(globalHandles->begin(), globalHandles->end(), this);
+  if (index == globalHandles->end()) {
+    globalHandles->push_back(this);
+  } else {
+    *index = this;
+  }
+}
+HandleBase::~HandleBase() {
+  std::lock_guard<wpi::mutex> lock(globalHandleMutex);
+  auto index = std::find(globalHandles->begin(), globalHandles->end(), this);
+  if (index != globalHandles->end()) {
+    *index = nullptr;
+  }
+}
+void HandleBase::ResetHandles() {
+  m_version++;
+  if (m_version > 255) {
+    m_version = 0;
+  }
+}
+void HandleBase::ResetGlobalHandles() {
+  std::unique_lock<wpi::mutex> lock(globalHandleMutex);
+  for (auto&& i : *globalHandles) {
+    if (i != nullptr) {
+      lock.unlock();
+      i->ResetHandles();
+      lock.lock();
+    }
+  }
+}
+HAL_PortHandle createPortHandle(uint8_t channel, uint8_t module) {
+  // set last 8 bits, then shift to first 8 bits
+  HAL_PortHandle handle = static_cast<HAL_PortHandle>(HAL_HandleEnum::Port);
+  handle = handle << 24;
+  // shift module and add to 3rd set of 8 bits
+  int32_t temp = module;
+  temp = (temp << 8) & 0xff00;
+  handle += temp;
+  // add channel to last 8 bits
+  handle += channel;
+  return handle;
+}
+HAL_PortHandle createPortHandleForSPI(uint8_t channel) {
+  // set last 8 bits, then shift to first 8 bits
+  HAL_PortHandle handle = static_cast<HAL_PortHandle>(HAL_HandleEnum::Port);
+  handle = handle << 16;
+  // set second set up bits to 1
+  int32_t temp = 1;
+  temp = (temp << 8) & 0xff00;
+  handle += temp;
+  // shift to last set of bits
+  handle = handle << 8;
+  // add channel to last 8 bits
+  handle += channel;
+  return handle;
+}
+HAL_Handle createHandle(int16_t index, HAL_HandleEnum handleType,
+                        int16_t version) {
+  if (index < 0) return HAL_kInvalidHandle;
+  uint8_t hType = static_cast<uint8_t>(handleType);
+  if (hType == 0 || hType > 127) return HAL_kInvalidHandle;
+  // set last 8 bits, then shift to first 8 bits
+  HAL_Handle handle = hType;
+  handle = handle << 8;
+  handle += static_cast<uint8_t>(version);
+  handle = handle << 16;
+  // add index to set last 16 bits
+  handle += index;
+  return handle;
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp
new file mode 100644
index 0000000..6d0d256
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AccelerometerJNI.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include "edu_wpi_first_hal_AccelerometerJNI.h"
+#include "hal/Accelerometer.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    setAccelerometerActive
+ * Signature: (Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_setAccelerometerActive
+  (JNIEnv*, jclass, jboolean active)
+{
+  HAL_SetAccelerometerActive(active);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    setAccelerometerRange
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_setAccelerometerRange
+  (JNIEnv*, jclass, jint range)
+{
+  HAL_SetAccelerometerRange((HAL_AccelerometerRange)range);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    getAccelerometerX
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerX
+  (JNIEnv*, jclass)
+{
+  return HAL_GetAccelerometerX();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    getAccelerometerY
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerY
+  (JNIEnv*, jclass)
+{
+  return HAL_GetAccelerometerY();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AccelerometerJNI
+ * Method:    getAccelerometerZ
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AccelerometerJNI_getAccelerometerZ
+  (JNIEnv*, jclass)
+{
+  return HAL_GetAccelerometerZ();
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AnalogGyroJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AnalogGyroJNI.cpp
new file mode 100644
index 0000000..74c1b49
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AnalogGyroJNI.cpp
@@ -0,0 +1,248 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_AnalogGyroJNI.h"
+#include "hal/AnalogGyro.h"
+#include "hal/cpp/Log.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel analogGyroJNILogLevel = logWARNING;
+
+#define ANALOGGYROJNI_LOG(level)     \
+  if (level > analogGyroJNILogLevel) \
+    ;                                \
+  else                               \
+    Log().Get(level)
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    initializeAnalogGyro
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_initializeAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI initializeAnalogGyro";
+  ANALOGGYROJNI_LOG(logDEBUG)
+      << "Analog Input Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  HAL_GyroHandle handle =
+      HAL_InitializeAnalogGyro((HAL_AnalogInputHandle)id, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << handle;
+  // Analog input does range checking, so we don't need to do so.
+  CheckStatusForceThrow(env, status);
+  return (jint)handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    setupAnalogGyro
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_setupAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setupAnalogGyro";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  HAL_SetupAnalogGyro((HAL_GyroHandle)id, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    freeAnalogGyro
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_freeAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI freeAnalogGyro";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  HAL_FreeAnalogGyro((HAL_GyroHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    setAnalogGyroParameters
+ * Signature: (IDDI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_setAnalogGyroParameters
+  (JNIEnv* env, jclass, jint id, jdouble vPDPS, jdouble offset, jint center)
+{
+  ANALOGGYROJNI_LOG(logDEBUG)
+      << "Calling ANALOGGYROJNI setAnalogGyroParameters";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  HAL_SetAnalogGyroParameters((HAL_GyroHandle)id, vPDPS, offset, center,
+                              &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    setAnalogGyroVoltsPerDegreePerSecond
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_setAnalogGyroVoltsPerDegreePerSecond
+  (JNIEnv* env, jclass, jint id, jdouble vPDPS)
+{
+  ANALOGGYROJNI_LOG(logDEBUG)
+      << "Calling ANALOGGYROJNI setAnalogGyroVoltsPerDegreePerSecond";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  ANALOGGYROJNI_LOG(logDEBUG) << "vPDPS = " << vPDPS;
+  int32_t status = 0;
+  HAL_SetAnalogGyroVoltsPerDegreePerSecond((HAL_GyroHandle)id, vPDPS, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    resetAnalogGyro
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_resetAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI resetAnalogGyro";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  HAL_ResetAnalogGyro((HAL_GyroHandle)id, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    calibrateAnalogGyro
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_calibrateAnalogGyro
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI calibrateAnalogGyro";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  HAL_CalibrateAnalogGyro((HAL_GyroHandle)id, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    setAnalogGyroDeadband
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_setAnalogGyroDeadband
+  (JNIEnv* env, jclass, jint id, jdouble deadband)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI setAnalogGyroDeadband";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  HAL_SetAnalogGyroDeadband((HAL_GyroHandle)id, deadband, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    getAnalogGyroAngle
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_getAnalogGyroAngle
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroAngle";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  jdouble value = HAL_GetAnalogGyroAngle((HAL_GyroHandle)id, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value;
+  CheckStatus(env, status);
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    getAnalogGyroRate
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_getAnalogGyroRate
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroRate";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  jdouble value = HAL_GetAnalogGyroRate((HAL_GyroHandle)id, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value;
+  CheckStatus(env, status);
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    getAnalogGyroOffset
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_getAnalogGyroOffset
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroOffset";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  jdouble value = HAL_GetAnalogGyroOffset((HAL_GyroHandle)id, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value;
+  CheckStatus(env, status);
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogGyroJNI
+ * Method:    getAnalogGyroCenter
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogGyroJNI_getAnalogGyroCenter
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGGYROJNI_LOG(logDEBUG) << "Calling ANALOGGYROJNI getAnalogGyroCenter";
+  ANALOGGYROJNI_LOG(logDEBUG) << "Gyro Handle = " << (HAL_GyroHandle)id;
+  int32_t status = 0;
+  jint value = HAL_GetAnalogGyroCenter((HAL_GyroHandle)id, &status);
+  ANALOGGYROJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGGYROJNI_LOG(logDEBUG) << "Result = " << value;
+  CheckStatus(env, status);
+  return value;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AnalogJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AnalogJNI.cpp
new file mode 100644
index 0000000..3b2aa2d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/AnalogJNI.cpp
@@ -0,0 +1,722 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_AnalogJNI.h"
+#include "hal/AnalogAccumulator.h"
+#include "hal/AnalogInput.h"
+#include "hal/AnalogOutput.h"
+#include "hal/AnalogTrigger.h"
+#include "hal/Ports.h"
+#include "hal/cpp/Log.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel analogJNILogLevel = logWARNING;
+
+#define ANALOGJNI_LOG(level)     \
+  if (level > analogJNILogLevel) \
+    ;                            \
+  else                           \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initializeAnalogInputPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogInputPort
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
+  int32_t status = 0;
+  auto analog = HAL_InitializeAnalogInputPort((HAL_PortHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << analog;
+  CheckStatusRange(env, status, 0, HAL_GetNumAnalogInputs(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)analog;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    freeAnalogInputPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_freeAnalogInputPort
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_AnalogInputHandle)id;
+  HAL_FreeAnalogInputPort((HAL_AnalogInputHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initializeAnalogOutputPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogOutputPort
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
+  int32_t status = 0;
+  HAL_AnalogOutputHandle analog =
+      HAL_InitializeAnalogOutputPort((HAL_PortHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << analog;
+  CheckStatusRange(env, status, 0, HAL_GetNumAnalogOutputs(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jlong)analog;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    freeAnalogOutputPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_freeAnalogOutputPort
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << id;
+  HAL_FreeAnalogOutputPort((HAL_AnalogOutputHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    checkAnalogModule
+ * Signature: (B)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_checkAnalogModule
+  (JNIEnv*, jclass, jbyte value)
+{
+  // ANALOGJNI_LOG(logDEBUG) << "Module = " << (jint)value;
+  jboolean returnValue = HAL_CheckAnalogModule(value);
+  // ANALOGJNI_LOG(logDEBUG) << "checkAnalogModuleResult = " <<
+  // (jint)returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    checkAnalogInputChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_checkAnalogInputChannel
+  (JNIEnv*, jclass, jint value)
+{
+  // ANALOGJNI_LOG(logDEBUG) << "Channel = " << value;
+  jboolean returnValue = HAL_CheckAnalogInputChannel(value);
+  // ANALOGJNI_LOG(logDEBUG) << "checkAnalogChannelResult = " <<
+  // (jint)returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    checkAnalogOutputChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_checkAnalogOutputChannel
+  (JNIEnv*, jclass, jint value)
+{
+  // ANALOGJNI_LOG(logDEBUG) << "Channel = " << value;
+  jboolean returnValue = HAL_CheckAnalogOutputChannel(value);
+  // ANALOGJNI_LOG(logDEBUG) << "checkAnalogChannelResult = " <<
+  // (jint)returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogOutput
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogOutput
+  (JNIEnv* env, jclass, jint id, jdouble voltage)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Calling setAnalogOutput";
+  ANALOGJNI_LOG(logDEBUG) << "Voltage = " << voltage;
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << id;
+  int32_t status = 0;
+  HAL_SetAnalogOutput((HAL_AnalogOutputHandle)id, voltage, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogOutput
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogOutput
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+  double val = HAL_GetAnalogOutput((HAL_AnalogOutputHandle)id, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogSampleRate
+ * Signature: (D)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogSampleRate
+  (JNIEnv* env, jclass, jdouble value)
+{
+  ANALOGJNI_LOG(logDEBUG) << "SampleRate = " << value;
+  int32_t status = 0;
+  HAL_SetAnalogSampleRate(value, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogSampleRate
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogSampleRate
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double returnValue = HAL_GetAnalogSampleRate(&status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "SampleRate = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogAverageBits
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogAverageBits
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  ANALOGJNI_LOG(logDEBUG) << "AverageBits = " << value;
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  HAL_SetAnalogAverageBits((HAL_AnalogInputHandle)id, value, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogAverageBits
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogAverageBits
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetAnalogAverageBits((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AverageBits = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogOversampleBits
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogOversampleBits
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  ANALOGJNI_LOG(logDEBUG) << "OversampleBits = " << value;
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  HAL_SetAnalogOversampleBits((HAL_AnalogInputHandle)id, value, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogOversampleBits
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogOversampleBits
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetAnalogOversampleBits((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "OversampleBits = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogValue
+ * Signature: (I)S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogValue
+  (JNIEnv* env, jclass, jint id)
+{
+  // ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (void*)id;
+  int32_t status = 0;
+  jshort returnValue = HAL_GetAnalogValue((HAL_AnalogInputHandle)id, &status);
+  // ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  // ANALOGJNI_LOG(logDEBUG) << "Value = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogAverageValue
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogAverageValue
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetAnalogAverageValue((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AverageValue = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogVoltsToValue
+ * Signature: (ID)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogVoltsToValue
+  (JNIEnv* env, jclass, jint id, jdouble voltageValue)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  ANALOGJNI_LOG(logDEBUG) << "VoltageValue = " << voltageValue;
+  int32_t status = 0;
+  jint returnValue = HAL_GetAnalogVoltsToValue((HAL_AnalogInputHandle)id,
+                                               voltageValue, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "Value = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogVoltage
+  (JNIEnv* env, jclass, jint id)
+{
+  // ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (void*)id;
+  int32_t status = 0;
+  jdouble returnValue =
+      HAL_GetAnalogVoltage((HAL_AnalogInputHandle)id, &status);
+  // ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  // ANALOGJNI_LOG(logDEBUG) << "Voltage = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogAverageVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogAverageVoltage
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  jdouble returnValue =
+      HAL_GetAnalogAverageVoltage((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AverageVoltage = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogLSBWeight
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogLSBWeight
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+
+  jint returnValue = HAL_GetAnalogLSBWeight((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AnalogLSBWeight = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogOffset
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogOffset
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+
+  jint returnValue = HAL_GetAnalogOffset((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AnalogOffset = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    isAccumulatorChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_isAccumulatorChannel
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "isAccumulatorChannel";
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+
+  jboolean returnValue =
+      HAL_IsAccumulatorChannel((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AnalogOffset = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initAccumulator
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initAccumulator
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  HAL_InitAccumulator((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    resetAccumulator
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_resetAccumulator
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  HAL_ResetAccumulator((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAccumulatorCenter
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAccumulatorCenter
+  (JNIEnv* env, jclass, jint id, jint center)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  HAL_SetAccumulatorCenter((HAL_AnalogInputHandle)id, center, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAccumulatorDeadband
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAccumulatorDeadband
+  (JNIEnv* env, jclass, jint id, jint deadband)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  HAL_SetAccumulatorDeadband((HAL_AnalogInputHandle)id, deadband, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAccumulatorValue
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAccumulatorValue
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  jlong returnValue =
+      HAL_GetAccumulatorValue((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AccumulatorValue = " << returnValue;
+  CheckStatus(env, status);
+
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAccumulatorCount
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAccumulatorCount
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetAccumulatorCount((HAL_AnalogInputHandle)id, &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AccumulatorCount = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAccumulatorOutput
+ * Signature: (ILjava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAccumulatorOutput
+  (JNIEnv* env, jclass, jint id, jobject accumulatorResult)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Handle = " << (HAL_AnalogInputHandle)id;
+  int32_t status = 0;
+  int64_t value = 0;
+  int64_t count = 0;
+  HAL_GetAccumulatorOutput((HAL_AnalogInputHandle)id, &value, &count, &status);
+  SetAccumulatorResultObject(env, accumulatorResult, value, count);
+  ANALOGJNI_LOG(logDEBUG) << "Value = " << value;
+  ANALOGJNI_LOG(logDEBUG) << "Count = " << count;
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    initializeAnalogTrigger
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_initializeAnalogTrigger
+  (JNIEnv* env, jclass, jint id, jobject index)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_AnalogInputHandle)id;
+  jint* indexHandle =
+      reinterpret_cast<jint*>(env->GetDirectBufferAddress(index));
+  ANALOGJNI_LOG(logDEBUG) << "Index Ptr = " << indexHandle;
+  int32_t status = 0;
+  HAL_AnalogTriggerHandle analogTrigger = HAL_InitializeAnalogTrigger(
+      (HAL_AnalogInputHandle)id, reinterpret_cast<int32_t*>(indexHandle),
+      &status);
+  ANALOGJNI_LOG(logDEBUG) << "Status = " << status;
+  ANALOGJNI_LOG(logDEBUG) << "AnalogTrigger Handle = " << analogTrigger;
+  CheckStatus(env, status);
+  return (jint)analogTrigger;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    cleanAnalogTrigger
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_cleanAnalogTrigger
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = "
+                          << (HAL_AnalogTriggerHandle)id;
+  int32_t status = 0;
+  HAL_CleanAnalogTrigger((HAL_AnalogTriggerHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerLimitsRaw
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerLimitsRaw
+  (JNIEnv* env, jclass, jint id, jint lower, jint upper)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = "
+                          << (HAL_AnalogTriggerHandle)id;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsRaw((HAL_AnalogTriggerHandle)id, lower, upper,
+                                &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerLimitsVoltage
+ * Signature: (IDD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerLimitsVoltage
+  (JNIEnv* env, jclass, jint id, jdouble lower, jdouble upper)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = "
+                          << (HAL_AnalogTriggerHandle)id;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsVoltage((HAL_AnalogTriggerHandle)id, lower, upper,
+                                    &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerAveraged
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerAveraged
+  (JNIEnv* env, jclass, jint id, jboolean averaged)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = "
+                          << (HAL_AnalogTriggerHandle)id;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerAveraged((HAL_AnalogTriggerHandle)id, averaged, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    setAnalogTriggerFiltered
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_setAnalogTriggerFiltered
+  (JNIEnv* env, jclass, jint id, jboolean filtered)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = "
+                          << (HAL_AnalogTriggerHandle)id;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerFiltered((HAL_AnalogTriggerHandle)id, filtered, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogTriggerInWindow
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerInWindow
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = "
+                          << (HAL_AnalogTriggerHandle)id;
+  int32_t status = 0;
+  jboolean val =
+      HAL_GetAnalogTriggerInWindow((HAL_AnalogTriggerHandle)id, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogTriggerTriggerState
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerTriggerState
+  (JNIEnv* env, jclass, jint id)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = "
+                          << (HAL_AnalogTriggerHandle)id;
+  int32_t status = 0;
+  jboolean val =
+      HAL_GetAnalogTriggerTriggerState((HAL_AnalogTriggerHandle)id, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_AnalogJNI
+ * Method:    getAnalogTriggerOutput
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_AnalogJNI_getAnalogTriggerOutput
+  (JNIEnv* env, jclass, jint id, jint type)
+{
+  ANALOGJNI_LOG(logDEBUG) << "Analog Trigger Handle = "
+                          << (HAL_AnalogTriggerHandle)id;
+  int32_t status = 0;
+  jboolean val = HAL_GetAnalogTriggerOutput(
+      (HAL_AnalogTriggerHandle)id, (HAL_AnalogTriggerType)type, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CANAPIJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CANAPIJNI.cpp
new file mode 100644
index 0000000..bcb285c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CANAPIJNI.cpp
@@ -0,0 +1,241 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_CANAPIJNI.h"
+#include "hal/CAN.h"
+#include "hal/CANAPI.h"
+#include "hal/Errors.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    initializeCAN
+ * Signature: (III)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_initializeCAN
+  (JNIEnv* env, jclass, jint manufacturer, jint deviceId, jint deviceType)
+{
+  int32_t status = 0;
+  auto handle =
+      HAL_InitializeCAN(static_cast<HAL_CANManufacturer>(manufacturer),
+                        static_cast<int32_t>(deviceId),
+                        static_cast<HAL_CANDeviceType>(deviceType), &status);
+
+  CheckStatusForceThrow(env, status);
+  return handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    cleanCAN
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_cleanCAN
+  (JNIEnv* env, jclass, jint handle)
+{
+  HAL_CleanCAN(static_cast<HAL_CANHandle>(handle));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    writeCANPacket
+ * Signature: (I[BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_writeCANPacket
+  (JNIEnv* env, jclass, jint handle, jbyteArray data, jint apiId)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  JByteArrayRef arr{env, data};
+  auto arrRef = arr.array();
+  int32_t status = 0;
+  HAL_WriteCANPacket(halHandle, reinterpret_cast<const uint8_t*>(arrRef.data()),
+                     arrRef.size(), apiId, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    writeCANPacketRepeating
+ * Signature: (I[BII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_writeCANPacketRepeating
+  (JNIEnv* env, jclass, jint handle, jbyteArray data, jint apiId,
+   jint timeoutMs)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  JByteArrayRef arr{env, data};
+  auto arrRef = arr.array();
+  int32_t status = 0;
+  HAL_WriteCANPacketRepeating(halHandle,
+                              reinterpret_cast<const uint8_t*>(arrRef.data()),
+                              arrRef.size(), apiId, timeoutMs, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    stopCANPacketRepeating
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_stopCANPacketRepeating
+  (JNIEnv* env, jclass, jint handle, jint apiId)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  int32_t status = 0;
+  HAL_StopCANPacketRepeating(halHandle, apiId, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    readCANPacketNew
+ * Signature: (IILjava/lang/Object;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_readCANPacketNew
+  (JNIEnv* env, jclass, jint handle, jint apiId, jobject data)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  uint8_t dataTemp[8];
+  int32_t dataLength = 0;
+  uint64_t timestamp = 0;
+  int32_t status = 0;
+  HAL_ReadCANPacketNew(halHandle, apiId, dataTemp, &dataLength, &timestamp,
+                       &status);
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (!CheckStatus(env, status)) {
+    return false;
+  }
+  if (dataLength > 8) dataLength = 8;
+
+  jbyteArray toSetArray = SetCANDataObject(env, data, dataLength, timestamp);
+  auto javaLen = env->GetArrayLength(toSetArray);
+  if (javaLen < dataLength) dataLength = javaLen;
+  env->SetByteArrayRegion(toSetArray, 0, dataLength,
+                          reinterpret_cast<jbyte*>(dataTemp));
+  return true;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    readCANPacketLatest
+ * Signature: (IILjava/lang/Object;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_readCANPacketLatest
+  (JNIEnv* env, jclass, jint handle, jint apiId, jobject data)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  uint8_t dataTemp[8];
+  int32_t dataLength = 0;
+  uint64_t timestamp = 0;
+  int32_t status = 0;
+  HAL_ReadCANPacketLatest(halHandle, apiId, dataTemp, &dataLength, &timestamp,
+                          &status);
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (!CheckStatus(env, status)) {
+    return false;
+  }
+  if (dataLength > 8) dataLength = 8;
+
+  jbyteArray toSetArray = SetCANDataObject(env, data, dataLength, timestamp);
+  auto javaLen = env->GetArrayLength(toSetArray);
+  if (javaLen < dataLength) dataLength = javaLen;
+  env->SetByteArrayRegion(toSetArray, 0, dataLength,
+                          reinterpret_cast<jbyte*>(dataTemp));
+  return true;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    readCANPacketTimeout
+ * Signature: (IIILjava/lang/Object;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_readCANPacketTimeout
+  (JNIEnv* env, jclass, jint handle, jint apiId, jint timeoutMs, jobject data)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  uint8_t dataTemp[8];
+  int32_t dataLength = 0;
+  uint64_t timestamp = 0;
+  int32_t status = 0;
+  HAL_ReadCANPacketTimeout(halHandle, apiId, dataTemp, &dataLength, &timestamp,
+                           timeoutMs, &status);
+  if (status == HAL_CAN_TIMEOUT ||
+      status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (!CheckStatus(env, status)) {
+    return false;
+  }
+  if (dataLength > 8) dataLength = 8;
+
+  jbyteArray toSetArray = SetCANDataObject(env, data, dataLength, timestamp);
+  auto javaLen = env->GetArrayLength(toSetArray);
+  if (javaLen < dataLength) dataLength = javaLen;
+  env->SetByteArrayRegion(toSetArray, 0, dataLength,
+                          reinterpret_cast<jbyte*>(dataTemp));
+  return true;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CANAPIJNI
+ * Method:    readCANPeriodicPacket
+ * Signature: (IIIILjava/lang/Object;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CANAPIJNI_readCANPeriodicPacket
+  (JNIEnv* env, jclass, jint handle, jint apiId, jint timeoutMs, jint periodMs,
+   jobject data)
+{
+  auto halHandle = static_cast<HAL_CANHandle>(handle);
+  uint8_t dataTemp[8];
+  int32_t dataLength = 0;
+  uint64_t timestamp = 0;
+  int32_t status = 0;
+  HAL_ReadCANPeriodicPacket(halHandle, apiId, dataTemp, &dataLength, &timestamp,
+                            timeoutMs, periodMs, &status);
+  if (status == HAL_CAN_TIMEOUT ||
+      status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (!CheckStatus(env, status)) {
+    return false;
+  }
+  if (dataLength > 8) dataLength = 8;
+
+  jbyteArray toSetArray = SetCANDataObject(env, data, dataLength, timestamp);
+  auto javaLen = env->GetArrayLength(toSetArray);
+  if (javaLen < dataLength) dataLength = javaLen;
+  env->SetByteArrayRegion(toSetArray, 0, dataLength,
+                          reinterpret_cast<jbyte*>(dataTemp));
+  return true;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CANJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CANJNI.cpp
new file mode 100644
index 0000000..0f46d15
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CANJNI.cpp
@@ -0,0 +1,158 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_can_CANJNI.h"
+#include "hal/CAN.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+// set the logging level
+// TLogLevel canJNILogLevel = logDEBUG;
+TLogLevel canJNILogLevel = logERROR;
+
+#define CANJNI_LOG(level)     \
+  if (level > canJNILogLevel) \
+    ;                         \
+  else                        \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    FRCNetCommCANSessionMuxSendMessage
+ * Signature: (I[BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_FRCNetCommCANSessionMuxSendMessage
+  (JNIEnv* env, jclass, jint messageID, jbyteArray data, jint periodMs)
+{
+  CANJNI_LOG(logDEBUG) << "Calling CANJNI FRCNetCommCANSessionMuxSendMessage";
+
+  JByteArrayRef dataArray{env, data};
+
+  const uint8_t* dataBuffer =
+      reinterpret_cast<const uint8_t*>(dataArray.array().data());
+  uint8_t dataSize = dataArray.array().size();
+
+  CANJNI_LOG(logDEBUG) << "Message ID ";
+  CANJNI_LOG(logDEBUG).write_hex(messageID);
+
+  if (logDEBUG <= canJNILogLevel) {
+    if (dataBuffer) {
+      wpi::SmallString<128> buf;
+      wpi::raw_svector_ostream str(buf);
+      for (int32_t i = 0; i < dataSize; i++) {
+        str.write_hex(dataBuffer[i]) << ' ';
+      }
+
+      Log().Get(logDEBUG) << "Data: " << str.str();
+    } else {
+      CANJNI_LOG(logDEBUG) << "Data: null";
+    }
+  }
+
+  CANJNI_LOG(logDEBUG) << "Period: " << periodMs;
+
+  int32_t status = 0;
+  HAL_CAN_SendMessage(messageID, dataBuffer, dataSize, periodMs, &status);
+
+  CANJNI_LOG(logDEBUG) << "Status: " << status;
+  CheckCANStatus(env, status, messageID);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    FRCNetCommCANSessionMuxReceiveMessage
+ * Signature: (Ljava/lang/Object;ILjava/lang/Object;)[B
+ */
+JNIEXPORT jbyteArray JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_FRCNetCommCANSessionMuxReceiveMessage
+  (JNIEnv* env, jclass, jobject messageID, jint messageIDMask,
+   jobject timeStamp)
+{
+  CANJNI_LOG(logDEBUG)
+      << "Calling CANJNI FRCNetCommCANSessionMuxReceiveMessage";
+
+  uint32_t* messageIDPtr =
+      reinterpret_cast<uint32_t*>(env->GetDirectBufferAddress(messageID));
+  uint32_t* timeStampPtr =
+      reinterpret_cast<uint32_t*>(env->GetDirectBufferAddress(timeStamp));
+
+  uint8_t dataSize = 0;
+  uint8_t buffer[8];
+
+  int32_t status = 0;
+  HAL_CAN_ReceiveMessage(messageIDPtr, messageIDMask, buffer, &dataSize,
+                         timeStampPtr, &status);
+
+  CANJNI_LOG(logDEBUG) << "Message ID ";
+  CANJNI_LOG(logDEBUG).write_hex(*messageIDPtr);
+
+  if (logDEBUG <= canJNILogLevel) {
+    wpi::SmallString<128> buf;
+    wpi::raw_svector_ostream str(buf);
+
+    for (int32_t i = 0; i < dataSize; i++) {
+      // Pad one-digit data with a zero
+      if (buffer[i] <= 16) {
+        str << '0';
+      }
+
+      str.write_hex(buffer[i]) << ' ';
+    }
+
+    Log().Get(logDEBUG) << "Data: " << str.str();
+  }
+
+  CANJNI_LOG(logDEBUG) << "Timestamp: " << *timeStampPtr;
+  CANJNI_LOG(logDEBUG) << "Status: " << status;
+
+  if (!CheckCANStatus(env, status, *messageIDPtr)) return nullptr;
+  return MakeJByteArray(env,
+                        wpi::StringRef{reinterpret_cast<const char*>(buffer),
+                                       static_cast<size_t>(dataSize)});
+}
+
+/*
+ * Class:     edu_wpi_first_hal_can_CANJNI
+ * Method:    GetCANStatus
+ * Signature: (Ljava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_can_CANJNI_GetCANStatus
+  (JNIEnv* env, jclass, jobject canStatus)
+{
+  CANJNI_LOG(logDEBUG) << "Calling CANJNI HAL_CAN_GetCANStatus";
+
+  float percentBusUtilization = 0;
+  uint32_t busOffCount = 0;
+  uint32_t txFullCount = 0;
+  uint32_t receiveErrorCount = 0;
+  uint32_t transmitErrorCount = 0;
+  int32_t status = 0;
+  HAL_CAN_GetCANStatus(&percentBusUtilization, &busOffCount, &txFullCount,
+                       &receiveErrorCount, &transmitErrorCount, &status);
+
+  if (!CheckStatus(env, status)) return;
+
+  SetCanStatusObject(env, canStatus, percentBusUtilization, busOffCount,
+                     txFullCount, receiveErrorCount, transmitErrorCount);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CompressorJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CompressorJNI.cpp
new file mode 100644
index 0000000..e38abb5
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CompressorJNI.cpp
@@ -0,0 +1,234 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "HALUtil.h"
+#include "edu_wpi_first_hal_CompressorJNI.h"
+#include "hal/Compressor.h"
+#include "hal/Ports.h"
+#include "hal/Solenoid.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    initializeCompressor
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_initializeCompressor
+  (JNIEnv* env, jclass, jbyte module)
+{
+  int32_t status = 0;
+  auto handle = HAL_InitializeCompressor(module, &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumPCMModules(), module);
+
+  return (jint)handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    checkCompressorModule
+ * Signature: (B)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_checkCompressorModule
+  (JNIEnv* env, jclass, jbyte module)
+{
+  return HAL_CheckCompressorModule(module);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressor
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressor
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressor((HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    setCompressorClosedLoopControl
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_setCompressorClosedLoopControl
+  (JNIEnv* env, jclass, jint compressorHandle, jboolean value)
+{
+  int32_t status = 0;
+  HAL_SetCompressorClosedLoopControl((HAL_CompressorHandle)compressorHandle,
+                                     value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorClosedLoopControl
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorClosedLoopControl
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorClosedLoopControl(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorPressureSwitch
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorPressureSwitch
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorPressureSwitch(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorCurrent
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorCurrent
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  double val =
+      HAL_GetCompressorCurrent((HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorCurrentTooHighFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorCurrentTooHighFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorCurrentTooHighFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorCurrentTooHighStickyFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorCurrentTooHighStickyFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorCurrentTooHighStickyFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorShortedStickyFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorShortedStickyFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorShortedStickyFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorShortedFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorShortedFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorShortedFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorNotConnectedStickyFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorNotConnectedStickyFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorNotConnectedStickyFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    getCompressorNotConnectedFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_getCompressorNotConnectedFault
+  (JNIEnv* env, jclass, jint compressorHandle)
+{
+  int32_t status = 0;
+  bool val = HAL_GetCompressorNotConnectedFault(
+      (HAL_CompressorHandle)compressorHandle, &status);
+  CheckStatus(env, status);
+  return val;
+}
+/*
+ * Class:     edu_wpi_first_hal_CompressorJNI
+ * Method:    clearAllPCMStickyFaults
+ * Signature: (B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CompressorJNI_clearAllPCMStickyFaults
+  (JNIEnv* env, jclass, jbyte module)
+{
+  int32_t status = 0;
+  HAL_ClearAllPCMStickyFaults(static_cast<int32_t>(module), &status);
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/ConstantsJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/ConstantsJNI.cpp
new file mode 100644
index 0000000..3db8f5a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/ConstantsJNI.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_ConstantsJNI.h"
+#include "hal/Constants.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel constantsJNILogLevel = logWARNING;
+
+#define CONSTANTSJNI_LOG(level)     \
+  if (level > constantsJNILogLevel) \
+    ;                               \
+  else                              \
+    Log().Get(level)
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_ConstantsJNI
+ * Method:    getSystemClockTicksPerMicrosecond
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_ConstantsJNI_getSystemClockTicksPerMicrosecond
+  (JNIEnv* env, jclass)
+{
+  CONSTANTSJNI_LOG(logDEBUG)
+      << "Calling ConstantsJNI getSystemClockTicksPerMicrosecond";
+  jint value = HAL_GetSystemClockTicksPerMicrosecond();
+  CONSTANTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CounterJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CounterJNI.cpp
new file mode 100644
index 0000000..70ec5be
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/CounterJNI.cpp
@@ -0,0 +1,476 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_CounterJNI.h"
+#include "hal/Counter.h"
+#include "hal/Errors.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel counterJNILogLevel = logWARNING;
+
+#define COUNTERJNI_LOG(level)     \
+  if (level > counterJNILogLevel) \
+    ;                             \
+  else                            \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    initializeCounter
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CounterJNI_initializeCounter
+  (JNIEnv* env, jclass, jint mode, jobject index)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI initializeCounter";
+  COUNTERJNI_LOG(logDEBUG) << "Mode = " << mode;
+  jint* indexPtr = reinterpret_cast<jint*>(env->GetDirectBufferAddress(index));
+  COUNTERJNI_LOG(logDEBUG) << "Index Ptr = "
+                           << reinterpret_cast<int32_t*>(indexPtr);
+  int32_t status = 0;
+  auto counter = HAL_InitializeCounter(
+      (HAL_Counter_Mode)mode, reinterpret_cast<int32_t*>(indexPtr), &status);
+  COUNTERJNI_LOG(logDEBUG) << "Index = " << *indexPtr;
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  COUNTERJNI_LOG(logDEBUG) << "COUNTER Handle = " << counter;
+  CheckStatusForceThrow(env, status);
+  return (jint)counter;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    freeCounter
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_freeCounter
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI freeCounter";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  HAL_FreeCounter((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterAverageSize
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterAverageSize
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterAverageSize";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "AverageSize = " << value;
+  int32_t status = 0;
+  HAL_SetCounterAverageSize((HAL_CounterHandle)id, value, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterUpSource
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterUpSource
+  (JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
+   jint analogTriggerType)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterUpSource";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "digitalSourceHandle = " << digitalSourceHandle;
+  COUNTERJNI_LOG(logDEBUG) << "analogTriggerType = " << analogTriggerType;
+  int32_t status = 0;
+  HAL_SetCounterUpSource((HAL_CounterHandle)id, (HAL_Handle)digitalSourceHandle,
+                         (HAL_AnalogTriggerType)analogTriggerType, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterUpSourceEdge
+ * Signature: (IZZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterUpSourceEdge
+  (JNIEnv* env, jclass, jint id, jboolean valueRise, jboolean valueFall)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterUpSourceEdge";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "Rise = " << (jint)valueRise;
+  COUNTERJNI_LOG(logDEBUG) << "Fall = " << (jint)valueFall;
+  int32_t status = 0;
+  HAL_SetCounterUpSourceEdge((HAL_CounterHandle)id, valueRise, valueFall,
+                             &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    clearCounterUpSource
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_clearCounterUpSource
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI clearCounterUpSource";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  HAL_ClearCounterUpSource((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterDownSource
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterDownSource
+  (JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
+   jint analogTriggerType)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterDownSource";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "digitalSourceHandle = " << digitalSourceHandle;
+  COUNTERJNI_LOG(logDEBUG) << "analogTriggerType = " << analogTriggerType;
+  int32_t status = 0;
+  HAL_SetCounterDownSource((HAL_CounterHandle)id,
+                           (HAL_Handle)digitalSourceHandle,
+                           (HAL_AnalogTriggerType)analogTriggerType, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  if (status == PARAMETER_OUT_OF_RANGE) {
+    ThrowIllegalArgumentException(env,
+                                  "Counter only supports DownSource in "
+                                  "TwoPulse and ExternalDirection modes.");
+    return;
+  }
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterDownSourceEdge
+ * Signature: (IZZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterDownSourceEdge
+  (JNIEnv* env, jclass, jint id, jboolean valueRise, jboolean valueFall)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterDownSourceEdge";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "Rise = " << (jint)valueRise;
+  COUNTERJNI_LOG(logDEBUG) << "Fall = " << (jint)valueFall;
+  int32_t status = 0;
+  HAL_SetCounterDownSourceEdge((HAL_CounterHandle)id, valueRise, valueFall,
+                               &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    clearCounterDownSource
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_clearCounterDownSource
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI clearCounterDownSource";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  HAL_ClearCounterDownSource((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterUpDownMode
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterUpDownMode
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterUpDownMode";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  HAL_SetCounterUpDownMode((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterExternalDirectionMode
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterExternalDirectionMode
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG)
+      << "Calling COUNTERJNI setCounterExternalDirectionMode";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  HAL_SetCounterExternalDirectionMode((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterSemiPeriodMode
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterSemiPeriodMode
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterSemiPeriodMode";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "SemiPeriodMode = " << (jint)value;
+  int32_t status = 0;
+  HAL_SetCounterSemiPeriodMode((HAL_CounterHandle)id, value, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterPulseLengthMode
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterPulseLengthMode
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterPulseLengthMode";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "PulseLengthMode = " << value;
+  int32_t status = 0;
+  HAL_SetCounterPulseLengthMode((HAL_CounterHandle)id, value, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounterSamplesToAverage
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounterSamplesToAverage
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounterSamplesToAverage";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetCounterSamplesToAverage((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  COUNTERJNI_LOG(logDEBUG) << "getCounterSamplesToAverageResult = "
+                           << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterSamplesToAverage
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterSamplesToAverage
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterSamplesToAverage";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "SamplesToAverage = " << value;
+  int32_t status = 0;
+  HAL_SetCounterSamplesToAverage((HAL_CounterHandle)id, value, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  if (status == PARAMETER_OUT_OF_RANGE) {
+    ThrowBoundaryException(env, value, 1, 127);
+    return;
+  }
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    resetCounter
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_resetCounter
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI resetCounter";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  HAL_ResetCounter((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounter
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounter
+  (JNIEnv* env, jclass, jint id)
+{
+  // COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounter";
+  // COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  jint returnValue = HAL_GetCounter((HAL_CounterHandle)id, &status);
+  // COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  // COUNTERJNI_LOG(logDEBUG) << "getCounterResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounterPeriod
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounterPeriod
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounterPeriod";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetCounterPeriod((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  COUNTERJNI_LOG(logDEBUG) << "getCounterPeriodResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterMaxPeriod
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterMaxPeriod
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterMaxPeriod";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "MaxPeriod = " << value;
+  int32_t status = 0;
+  HAL_SetCounterMaxPeriod((HAL_CounterHandle)id, value, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterUpdateWhenEmpty
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterUpdateWhenEmpty
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterMaxPeriod";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "UpdateWhenEmpty = " << (jint)value;
+  int32_t status = 0;
+  HAL_SetCounterUpdateWhenEmpty((HAL_CounterHandle)id, value, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounterStopped
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounterStopped
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounterStopped";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetCounterStopped((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  COUNTERJNI_LOG(logDEBUG) << "getCounterStoppedResult = " << (jint)returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    getCounterDirection
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_CounterJNI_getCounterDirection
+  (JNIEnv* env, jclass, jint id)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI getCounterDirection";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  int32_t status = 0;
+  jboolean returnValue =
+      HAL_GetCounterDirection((HAL_CounterHandle)id, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  COUNTERJNI_LOG(logDEBUG) << "getCounterDirectionResult = "
+                           << (jint)returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_CounterJNI
+ * Method:    setCounterReverseDirection
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_CounterJNI_setCounterReverseDirection
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  COUNTERJNI_LOG(logDEBUG) << "Calling COUNTERJNI setCounterReverseDirection";
+  COUNTERJNI_LOG(logDEBUG) << "Counter Handle = " << (HAL_CounterHandle)id;
+  COUNTERJNI_LOG(logDEBUG) << "ReverseDirection = " << (jint)value;
+  int32_t status = 0;
+  HAL_SetCounterReverseDirection((HAL_CounterHandle)id, value, &status);
+  COUNTERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/DIOJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/DIOJNI.cpp
new file mode 100644
index 0000000..e21edcf
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/DIOJNI.cpp
@@ -0,0 +1,319 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_DIOJNI.h"
+#include "hal/DIO.h"
+#include "hal/PWM.h"
+#include "hal/Ports.h"
+#include "hal/cpp/Log.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel dioJNILogLevel = logWARNING;
+
+#define DIOJNI_LOG(level)     \
+  if (level > dioJNILogLevel) \
+    ;                         \
+  else                        \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    initializeDIOPort
+ * Signature: (IZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DIOJNI_initializeDIOPort
+  (JNIEnv* env, jclass, jint id, jboolean input)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI initializeDIOPort";
+  DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
+  DIOJNI_LOG(logDEBUG) << "Input = " << (jint)input;
+  int32_t status = 0;
+  auto dio = HAL_InitializeDIOPort((HAL_PortHandle)id,
+                                   static_cast<uint8_t>(input), &status);
+  DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  DIOJNI_LOG(logDEBUG) << "DIO Handle = " << dio;
+  CheckStatusRange(env, status, 0, HAL_GetNumDigitalChannels(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)dio;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    checkDIOChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_checkDIOChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI checkDIOChannel";
+  DIOJNI_LOG(logDEBUG) << "Channel = " << channel;
+  return HAL_CheckDIOChannel(channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    freeDIOPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_freeDIOPort
+  (JNIEnv* env, jclass, jint id)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI freeDIOPort";
+  DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  HAL_FreeDIOPort((HAL_DigitalHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDIO
+ * Signature: (IS)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDIO
+  (JNIEnv* env, jclass, jint id, jshort value)
+{
+  // DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDIO";
+  // DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  // DIOJNI_LOG(logDEBUG) << "Value = " << value;
+  int32_t status = 0;
+  HAL_SetDIO((HAL_DigitalHandle)id, value, &status);
+  // DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDIODirection
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDIODirection
+  (JNIEnv* env, jclass, jint id, jboolean input)
+{
+  // DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDIO";
+  // DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  // DIOJNI_LOG(logDEBUG) << "IsInput = " << input;
+  int32_t status = 0;
+  HAL_SetDIODirection((HAL_DigitalHandle)id, input, &status);
+  // DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    getDIO
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_getDIO
+  (JNIEnv* env, jclass, jint id)
+{
+  // DIOJNI_LOG(logDEBUG) << "Calling DIOJNI getDIO";
+  // DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetDIO((HAL_DigitalHandle)id, &status);
+  // DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  // DIOJNI_LOG(logDEBUG) << "getDIOResult = " << (jint)returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    getDIODirection
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_getDIODirection
+  (JNIEnv* env, jclass, jint id)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI getDIODirection (RR upd)";
+  // DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetDIODirection((HAL_DigitalHandle)id, &status);
+  // DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  DIOJNI_LOG(logDEBUG) << "getDIODirectionResult = " << (jint)returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    pulse
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_pulse
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI pulse (RR upd)";
+  // DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  // DIOJNI_LOG(logDEBUG) << "Value = " << value;
+  int32_t status = 0;
+  HAL_Pulse((HAL_DigitalHandle)id, value, &status);
+  DIOJNI_LOG(logDEBUG) << "Did it work? Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    isPulsing
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_isPulsing
+  (JNIEnv* env, jclass, jint id)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI isPulsing (RR upd)";
+  // DIOJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  jboolean returnValue = HAL_IsPulsing((HAL_DigitalHandle)id, &status);
+  // DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  DIOJNI_LOG(logDEBUG) << "isPulsingResult = " << (jint)returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    isAnyPulsing
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_DIOJNI_isAnyPulsing
+  (JNIEnv* env, jclass)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI isAnyPulsing (RR upd)";
+  int32_t status = 0;
+  jboolean returnValue = HAL_IsAnyPulsing(&status);
+  // DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  DIOJNI_LOG(logDEBUG) << "isAnyPulsingResult = " << (jint)returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    getLoopTiming
+ * Signature: ()S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_DIOJNI_getLoopTiming
+  (JNIEnv* env, jclass)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI getLoopTimeing";
+  int32_t status = 0;
+  jshort returnValue = HAL_GetPWMLoopTiming(&status);
+  DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  DIOJNI_LOG(logDEBUG) << "LoopTiming = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    allocateDigitalPWM
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DIOJNI_allocateDigitalPWM
+  (JNIEnv* env, jclass)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI allocateDigitalPWM";
+  int32_t status = 0;
+  auto pwm = HAL_AllocateDigitalPWM(&status);
+  DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  DIOJNI_LOG(logDEBUG) << "PWM Handle = " << pwm;
+  CheckStatus(env, status);
+  return (jint)pwm;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    freeDigitalPWM
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_freeDigitalPWM
+  (JNIEnv* env, jclass, jint id)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI freeDigitalPWM";
+  DIOJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalPWMHandle)id;
+  int32_t status = 0;
+  HAL_FreeDigitalPWM((HAL_DigitalPWMHandle)id, &status);
+  DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDigitalPWMRate
+ * Signature: (D)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDigitalPWMRate
+  (JNIEnv* env, jclass, jdouble value)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDigitalPWMRate";
+  DIOJNI_LOG(logDEBUG) << "Rate= " << value;
+  int32_t status = 0;
+  HAL_SetDigitalPWMRate(value, &status);
+  DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDigitalPWMDutyCycle
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDigitalPWMDutyCycle
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDigitalPWMDutyCycle";
+  DIOJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalPWMHandle)id;
+  DIOJNI_LOG(logDEBUG) << "DutyCycle= " << value;
+  int32_t status = 0;
+  HAL_SetDigitalPWMDutyCycle((HAL_DigitalPWMHandle)id, value, &status);
+  DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DIOJNI
+ * Method:    setDigitalPWMOutputChannel
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DIOJNI_setDigitalPWMOutputChannel
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  DIOJNI_LOG(logDEBUG) << "Calling DIOJNI setDigitalPWMOutputChannel";
+  DIOJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalPWMHandle)id;
+  DIOJNI_LOG(logDEBUG) << "Channel= " << value;
+  int32_t status = 0;
+  HAL_SetDigitalPWMOutputChannel((HAL_DigitalPWMHandle)id,
+                                 static_cast<uint32_t>(value), &status);
+  DIOJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
new file mode 100644
index 0000000..3e39ac0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/DigitalGlitchFilterJNI.cpp
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_DigitalGlitchFilterJNI.h"
+#include "hal/DIO.h"
+
+using namespace frc;
+
+/*
+ * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
+ * Method:    setFilterSelect
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DigitalGlitchFilterJNI_setFilterSelect
+  (JNIEnv* env, jclass, jint id, jint filter_index)
+{
+  int32_t status = 0;
+
+  HAL_SetFilterSelect(static_cast<HAL_DigitalHandle>(id), filter_index,
+                      &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
+ * Method:    getFilterSelect
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DigitalGlitchFilterJNI_getFilterSelect
+  (JNIEnv* env, jclass, jint id)
+{
+  int32_t status = 0;
+
+  jint result =
+      HAL_GetFilterSelect(static_cast<HAL_DigitalHandle>(id), &status);
+  CheckStatus(env, status);
+  return result;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
+ * Method:    setFilterPeriod
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_DigitalGlitchFilterJNI_setFilterPeriod
+  (JNIEnv* env, jclass, jint filter_index, jint fpga_cycles)
+{
+  int32_t status = 0;
+
+  HAL_SetFilterPeriod(filter_index, fpga_cycles, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_DigitalGlitchFilterJNI
+ * Method:    getFilterPeriod
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_DigitalGlitchFilterJNI_getFilterPeriod
+  (JNIEnv* env, jclass, jint filter_index)
+{
+  int32_t status = 0;
+
+  jint result = HAL_GetFilterPeriod(filter_index, &status);
+  CheckStatus(env, status);
+  return result;
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/EncoderJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/EncoderJNI.cpp
new file mode 100644
index 0000000..10c4332
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/EncoderJNI.cpp
@@ -0,0 +1,488 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_EncoderJNI.h"
+#include "hal/Encoder.h"
+#include "hal/Errors.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel encoderJNILogLevel = logWARNING;
+
+#define ENCODERJNI_LOG(level)     \
+  if (level > encoderJNILogLevel) \
+    ;                             \
+  else                            \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    initializeEncoder
+ * Signature: (IIIIZI)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_initializeEncoder
+  (JNIEnv* env, jclass, jint digitalSourceHandleA, jint analogTriggerTypeA,
+   jint digitalSourceHandleB, jint analogTriggerTypeB,
+   jboolean reverseDirection, jint encodingType)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI initializeEncoder";
+  ENCODERJNI_LOG(logDEBUG) << "Source Handle A = " << digitalSourceHandleA;
+  ENCODERJNI_LOG(logDEBUG) << "Analog Trigger Type A = " << analogTriggerTypeA;
+  ENCODERJNI_LOG(logDEBUG) << "Source Handle B = " << digitalSourceHandleB;
+  ENCODERJNI_LOG(logDEBUG) << "Analog Trigger Type B = " << analogTriggerTypeB;
+  ENCODERJNI_LOG(logDEBUG) << "Reverse direction = " << (jint)reverseDirection;
+  ENCODERJNI_LOG(logDEBUG) << "EncodingType = " << encodingType;
+  int32_t status = 0;
+  auto encoder = HAL_InitializeEncoder(
+      (HAL_Handle)digitalSourceHandleA,
+      (HAL_AnalogTriggerType)analogTriggerTypeA,
+      (HAL_Handle)digitalSourceHandleB,
+      (HAL_AnalogTriggerType)analogTriggerTypeB, reverseDirection,
+      (HAL_EncoderEncodingType)encodingType, &status);
+
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "ENCODER Handle = " << encoder;
+  CheckStatusForceThrow(env, status);
+  return (jint)encoder;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    freeEncoder
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_freeEncoder
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI freeEncoder";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  HAL_FreeEncoder((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoder
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoder
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoder";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jint returnValue = HAL_GetEncoder((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncoderResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderRaw
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderRaw
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderRaw";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jint returnValue = HAL_GetEncoderRaw((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getRawEncoderResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncodingScaleFactor
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncodingScaleFactor
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncodingScaleFactor";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetEncoderEncodingScale((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncodingScaleFactorResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    resetEncoder
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_resetEncoder
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI resetEncoder";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  HAL_ResetEncoder((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderPeriod
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderPeriod
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderPeriod";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  double returnValue = HAL_GetEncoderPeriod((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncoderPeriodEncoderResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderMaxPeriod
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderMaxPeriod
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderMaxPeriod";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  HAL_SetEncoderMaxPeriod((HAL_EncoderHandle)id, value, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderStopped
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderStopped
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderStopped";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetEncoderStopped((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getStoppedEncoderResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderDirection
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderDirection
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderDirection";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jboolean returnValue =
+      HAL_GetEncoderDirection((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getDirectionEncoderResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderDistance
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderDistance
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderDistance";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetEncoderDistance((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getDistanceEncoderResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderRate
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderRate
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderRate";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetEncoderRate((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getRateEncoderResult = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderMinRate
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderMinRate
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderMinRate";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  HAL_SetEncoderMinRate((HAL_EncoderHandle)id, value, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderDistancePerPulse
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderDistancePerPulse
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderDistancePerPulse";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  HAL_SetEncoderDistancePerPulse((HAL_EncoderHandle)id, value, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderReverseDirection
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderReverseDirection
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderReverseDirection";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  HAL_SetEncoderReverseDirection((HAL_EncoderHandle)id, value, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderSamplesToAverage
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderSamplesToAverage
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderSamplesToAverage";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  HAL_SetEncoderSamplesToAverage((HAL_EncoderHandle)id, value, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  if (status == PARAMETER_OUT_OF_RANGE) {
+    ThrowBoundaryException(env, value, 1, 127);
+    return;
+  }
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderSamplesToAverage
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderSamplesToAverage
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetEncoderSamplesToAverage((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
+                           << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    setEncoderIndexSource
+ * Signature: (IIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_setEncoderIndexSource
+  (JNIEnv* env, jclass, jint id, jint digitalSourceHandle,
+   jint analogTriggerType, jint type)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI setEncoderIndexSource";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  ENCODERJNI_LOG(logDEBUG) << "Source Handle = " << digitalSourceHandle;
+  ENCODERJNI_LOG(logDEBUG) << "Analog Trigger Type = " << analogTriggerType;
+  ENCODERJNI_LOG(logDEBUG) << "IndexingType = " << type;
+  int32_t status = 0;
+  HAL_SetEncoderIndexSource((HAL_EncoderHandle)id,
+                            (HAL_Handle)digitalSourceHandle,
+                            (HAL_AnalogTriggerType)analogTriggerType,
+                            (HAL_EncoderIndexingType)type, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderFPGAIndex
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderFPGAIndex
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jint returnValue = HAL_GetEncoderFPGAIndex((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
+                           << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderEncodingScale
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderEncodingScale
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jint returnValue =
+      HAL_GetEncoderEncodingScale((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
+                           << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderDecodingScaleFactor
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderDecodingScaleFactor
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jdouble returnValue =
+      HAL_GetEncoderDecodingScaleFactor((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
+                           << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderDistancePerPulse
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderDistancePerPulse
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jdouble returnValue =
+      HAL_GetEncoderDistancePerPulse((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
+                           << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_EncoderJNI
+ * Method:    getEncoderEncodingType
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_EncoderJNI_getEncoderEncodingType
+  (JNIEnv* env, jclass, jint id)
+{
+  ENCODERJNI_LOG(logDEBUG) << "Calling ENCODERJNI getEncoderSamplesToAverage";
+  ENCODERJNI_LOG(logDEBUG) << "Encoder Handle = " << (HAL_EncoderHandle)id;
+  int32_t status = 0;
+  jint returnValue = HAL_GetEncoderEncodingType((HAL_EncoderHandle)id, &status);
+  ENCODERJNI_LOG(logDEBUG) << "Status = " << status;
+  ENCODERJNI_LOG(logDEBUG) << "getEncoderSamplesToAverageResult = "
+                           << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HAL.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HAL.cpp
new file mode 100644
index 0000000..cc5f7cf
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HAL.cpp
@@ -0,0 +1,482 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/HAL.h"
+
+#include <jni.h>
+
+#include <cassert>
+#include <cstring>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_HAL.h"
+#include "hal/DriverStation.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+// set the logging level
+static TLogLevel netCommLogLevel = logWARNING;
+
+#define NETCOMM_LOG(level)     \
+  if (level > netCommLogLevel) \
+    ;                          \
+  else                         \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    initialize
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_initialize
+  (JNIEnv*, jclass, jint timeout, jint mode)
+{
+  return HAL_Initialize(timeout, mode);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramStarting
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramStarting
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramStarting();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramDisabled
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramDisabled
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramDisabled();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramAutonomous
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramAutonomous
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramAutonomous();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramTeleop
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramTeleop
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramTeleop();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    observeUserProgramTest
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_observeUserProgramTest
+  (JNIEnv*, jclass)
+{
+  HAL_ObserveUserProgramTest();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    report
+ * Signature: (IIILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_report
+  (JNIEnv* paramEnv, jclass, jint paramResource, jint paramInstanceNumber,
+   jint paramContext, jstring paramFeature)
+{
+  JStringRef featureStr{paramEnv, paramFeature};
+  NETCOMM_LOG(logDEBUG) << "Calling HAL report "
+                        << "res:" << paramResource
+                        << " instance:" << paramInstanceNumber
+                        << " context:" << paramContext
+                        << " feature:" << featureStr.c_str();
+  jint returnValue = HAL_Report(paramResource, paramInstanceNumber,
+                                paramContext, featureStr.c_str());
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    nativeGetControlWord
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_nativeGetControlWord
+  (JNIEnv*, jclass)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HAL Control Word";
+  static_assert(sizeof(HAL_ControlWord) == sizeof(jint),
+                "Java int must match the size of control word");
+  HAL_ControlWord controlWord;
+  std::memset(&controlWord, 0, sizeof(HAL_ControlWord));
+  HAL_GetControlWord(&controlWord);
+  jint retVal = 0;
+  std::memcpy(&retVal, &controlWord, sizeof(HAL_ControlWord));
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    nativeGetAllianceStation
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_nativeGetAllianceStation
+  (JNIEnv*, jclass)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HAL Alliance Station";
+  int32_t status = 0;
+  auto allianceStation = HAL_GetAllianceStation(&status);
+  return static_cast<jint>(allianceStation);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickAxes
+ * Signature: (B[F)S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickAxes
+  (JNIEnv* env, jclass, jbyte joystickNum, jfloatArray axesArray)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HALJoystickAxes";
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(joystickNum, &axes);
+
+  jsize javaSize = env->GetArrayLength(axesArray);
+  if (axes.count > javaSize) {
+    wpi::SmallString<128> errStr;
+    wpi::raw_svector_ostream oss{errStr};
+    oss << "Native array size larger then passed in java array size "
+        << "Native Size: " << static_cast<int>(axes.count)
+        << " Java Size: " << static_cast<int>(javaSize);
+
+    ThrowIllegalArgumentException(env, errStr.str());
+    return 0;
+  }
+
+  env->SetFloatArrayRegion(axesArray, 0, axes.count, axes.axes);
+
+  return axes.count;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickPOVs
+ * Signature: (B[S)S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickPOVs
+  (JNIEnv* env, jclass, jbyte joystickNum, jshortArray povsArray)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HALJoystickPOVs";
+  HAL_JoystickPOVs povs;
+  HAL_GetJoystickPOVs(joystickNum, &povs);
+
+  jsize javaSize = env->GetArrayLength(povsArray);
+  if (povs.count > javaSize) {
+    wpi::SmallString<128> errStr;
+    wpi::raw_svector_ostream oss{errStr};
+    oss << "Native array size larger then passed in java array size "
+        << "Native Size: " << static_cast<int>(povs.count)
+        << " Java Size: " << static_cast<int>(javaSize);
+
+    ThrowIllegalArgumentException(env, errStr.str());
+    return 0;
+  }
+
+  env->SetShortArrayRegion(povsArray, 0, povs.count, povs.povs);
+
+  return povs.count;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickButtons
+ * Signature: (BLjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickButtons
+  (JNIEnv* env, jclass, jbyte joystickNum, jobject count)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HALJoystickButtons";
+  HAL_JoystickButtons joystickButtons;
+  HAL_GetJoystickButtons(joystickNum, &joystickButtons);
+  jbyte* countPtr =
+      reinterpret_cast<jbyte*>(env->GetDirectBufferAddress(count));
+  NETCOMM_LOG(logDEBUG) << "Buttons = " << joystickButtons.buttons;
+  NETCOMM_LOG(logDEBUG) << "Count = " << (jint)joystickButtons.count;
+  *countPtr = joystickButtons.count;
+  NETCOMM_LOG(logDEBUG) << "CountBuffer = " << (jint)*countPtr;
+  return joystickButtons.buttons;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    setJoystickOutputs
+ * Signature: (BISS)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_setJoystickOutputs
+  (JNIEnv*, jclass, jbyte port, jint outputs, jshort leftRumble,
+   jshort rightRumble)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HAL_SetJoystickOutputs on port " << port;
+  NETCOMM_LOG(logDEBUG) << "Outputs: " << outputs;
+  NETCOMM_LOG(logDEBUG) << "Left Rumble: " << leftRumble
+                        << " Right Rumble: " << rightRumble;
+  return HAL_SetJoystickOutputs(port, outputs, leftRumble, rightRumble);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickIsXbox
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickIsXbox
+  (JNIEnv*, jclass, jbyte port)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickIsXbox";
+  return HAL_GetJoystickIsXbox(port);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickType
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickType
+  (JNIEnv*, jclass, jbyte port)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickType";
+  return HAL_GetJoystickType(port);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickName
+ * Signature: (B)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickName
+  (JNIEnv* env, jclass, jbyte port)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickName";
+  char* joystickName = HAL_GetJoystickName(port);
+  jstring str = MakeJString(env, joystickName);
+  HAL_FreeJoystickName(joystickName);
+  return str;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getJoystickAxisType
+ * Signature: (BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getJoystickAxisType
+  (JNIEnv*, jclass, jbyte joystickNum, jbyte axis)
+{
+  NETCOMM_LOG(logDEBUG) << "Calling HAL_GetJoystickAxisType";
+  return HAL_GetJoystickAxisType(joystickNum, axis);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    isNewControlData
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_isNewControlData
+  (JNIEnv*, jclass)
+{
+  return static_cast<jboolean>(HAL_IsNewControlData());
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    waitForDSData
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_waitForDSData
+  (JNIEnv* env, jclass)
+{
+  HAL_WaitForDSData();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    releaseDSMutex
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_HAL_releaseDSMutex
+  (JNIEnv* env, jclass)
+{
+  HAL_ReleaseDSMutex();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    waitForDSDataTimeout
+ * Signature: (D)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_waitForDSDataTimeout
+  (JNIEnv*, jclass, jdouble timeout)
+{
+  return static_cast<jboolean>(HAL_WaitForDSDataTimeout(timeout));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getMatchTime
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_HAL_getMatchTime
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  return HAL_GetMatchTime(&status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getSystemActive
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_getSystemActive
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetSystemActive(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getBrownedOut
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HAL_getBrownedOut
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetBrownedOut(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getMatchInfo
+ * Signature: (Ljava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getMatchInfo
+  (JNIEnv* env, jclass, jobject info)
+{
+  HAL_MatchInfo matchInfo;
+  auto status = HAL_GetMatchInfo(&matchInfo);
+  if (status == 0) {
+    SetMatchInfoObject(env, info, matchInfo);
+  }
+  return status;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    sendError
+ * Signature: (ZIZLjava/lang/String;Ljava/lang/String;Ljava/lang/String;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_sendError
+  (JNIEnv* env, jclass, jboolean isError, jint errorCode, jboolean isLVCode,
+   jstring details, jstring location, jstring callStack, jboolean printMsg)
+{
+  JStringRef detailsStr{env, details};
+  JStringRef locationStr{env, location};
+  JStringRef callStackStr{env, callStack};
+
+  NETCOMM_LOG(logDEBUG) << "Send Error: " << detailsStr.c_str();
+  NETCOMM_LOG(logDEBUG) << "Location: " << locationStr.c_str();
+  NETCOMM_LOG(logDEBUG) << "Call Stack: " << callStackStr.c_str();
+  jint returnValue =
+      HAL_SendError(isError, errorCode, isLVCode, detailsStr.c_str(),
+                    locationStr.c_str(), callStackStr.c_str(), printMsg);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getPortWithModule
+ * Signature: (BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getPortWithModule
+  (JNIEnv* env, jclass, jbyte module, jbyte channel)
+{
+  // FILE_LOG(logDEBUG) << "Calling HAL getPortWithModlue";
+  // FILE_LOG(logDEBUG) << "Module = " << (jint)module;
+  // FILE_LOG(logDEBUG) << "Channel = " << (jint)channel;
+  HAL_PortHandle port = HAL_GetPortWithModule(module, channel);
+  // FILE_LOG(logDEBUG) << "Port Handle = " << port;
+  return (jint)port;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HAL
+ * Method:    getPort
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HAL_getPort
+  (JNIEnv* env, jclass, jbyte channel)
+{
+  // FILE_LOG(logDEBUG) << "Calling HAL getPortWithModlue";
+  // FILE_LOG(logDEBUG) << "Module = " << (jint)module;
+  // FILE_LOG(logDEBUG) << "Channel = " << (jint)channel;
+  HAL_PortHandle port = HAL_GetPort(channel);
+  // FILE_LOG(logDEBUG) << "Port Handle = " << port;
+  return (jint)port;
+}
+
+}  // extern "C"
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
new file mode 100644
index 0000000..72eb22c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HALUtil.cpp
@@ -0,0 +1,469 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "HALUtil.h"
+
+#include <jni.h>
+
+#include <cassert>
+#include <cerrno>
+#include <cstdio>
+#include <cstring>
+#include <string>
+
+#include <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "edu_wpi_first_hal_HALUtil.h"
+#include "hal/CAN.h"
+#include "hal/DriverStation.h"
+#include "hal/Errors.h"
+#include "hal/HAL.h"
+#include "hal/cpp/Log.h"
+
+using namespace wpi::java;
+
+// set the logging level
+TLogLevel halUtilLogLevel = logWARNING;
+
+#define HALUTIL_LOG(level)     \
+  if (level > halUtilLogLevel) \
+    ;                          \
+  else                         \
+    Log().Get(level)
+
+#define kRioStatusOffset -63000
+#define kRioStatusSuccess 0
+#define kRIOStatusBufferInvalidSize (kRioStatusOffset - 80)
+#define kRIOStatusOperationTimedOut -52007
+#define kRIOStatusFeatureNotSupported (kRioStatusOffset - 193)
+#define kRIOStatusResourceNotInitialized -52010
+
+static JavaVM* jvm = nullptr;
+static JException illegalArgExCls;
+static JException boundaryExCls;
+static JException allocationExCls;
+static JException halHandleExCls;
+static JException canInvalidBufferExCls;
+static JException canMessageNotFoundExCls;
+static JException canMessageNotAllowedExCls;
+static JException canNotInitializedExCls;
+static JException uncleanStatusExCls;
+static JClass pwmConfigDataResultCls;
+static JClass canStatusCls;
+static JClass matchInfoDataCls;
+static JClass accumulatorResultCls;
+static JClass canDataCls;
+
+static const JClassInit classes[] = {
+    {"edu/wpi/first/hal/PWMConfigDataResult", &pwmConfigDataResultCls},
+    {"edu/wpi/first/hal/can/CANStatus", &canStatusCls},
+    {"edu/wpi/first/hal/MatchInfoData", &matchInfoDataCls},
+    {"edu/wpi/first/hal/AccumulatorResult", &accumulatorResultCls},
+    {"edu/wpi/first/hal/CANData", &canDataCls}};
+
+static const JExceptionInit exceptions[] = {
+    {"java/lang/IllegalArgumentException", &illegalArgExCls},
+    {"edu/wpi/first/hal/util/BoundaryException", &boundaryExCls},
+    {"edu/wpi/first/hal/util/AllocationException", &allocationExCls},
+    {"edu/wpi/first/hal/util/HalHandleException", &halHandleExCls},
+    {"edu/wpi/first/hal/can/CANInvalidBufferException", &canInvalidBufferExCls},
+    {"edu/wpi/first/hal/can/CANMessageNotFoundException",
+     &canMessageNotFoundExCls},
+    {"edu/wpi/first/hal/can/CANMessageNotAllowedException",
+     &canMessageNotAllowedExCls},
+    {"edu/wpi/first/hal/can/CANNotInitializedException",
+     &canNotInitializedExCls},
+    {"edu/wpi/first/hal/util/UncleanStatusException", &uncleanStatusExCls}};
+
+namespace frc {
+
+void ThrowUncleanStatusException(JNIEnv* env, wpi::StringRef msg,
+                                 int32_t status) {
+  static jmethodID func =
+      env->GetMethodID(uncleanStatusExCls, "<init>", "(ILjava/lang/String;)V");
+
+  jobject exception =
+      env->NewObject(uncleanStatusExCls, func, static_cast<jint>(status),
+                     MakeJString(env, msg));
+  env->Throw(static_cast<jthrowable>(exception));
+}
+
+void ThrowAllocationException(JNIEnv* env, int32_t minRange, int32_t maxRange,
+                              int32_t requestedValue, int32_t status) {
+  const char* message = HAL_GetErrorMessage(status);
+  wpi::SmallString<1024> buf;
+  wpi::raw_svector_ostream oss(buf);
+  oss << " Code: " << status << ". " << message
+      << ", Minimum Value: " << minRange << ", Maximum Value: " << maxRange
+      << ", Requested Value: " << requestedValue;
+  env->ThrowNew(allocationExCls, buf.c_str());
+  allocationExCls.Throw(env, buf.c_str());
+}
+
+void ThrowHalHandleException(JNIEnv* env, int32_t status) {
+  const char* message = HAL_GetErrorMessage(status);
+  wpi::SmallString<1024> buf;
+  wpi::raw_svector_ostream oss(buf);
+  oss << " Code: " << status << ". " << message;
+  halHandleExCls.Throw(env, buf.c_str());
+}
+
+void ReportError(JNIEnv* env, int32_t status, bool doThrow) {
+  if (status == 0) return;
+  if (status == HAL_HANDLE_ERROR) {
+    ThrowHalHandleException(env, status);
+  }
+  const char* message = HAL_GetErrorMessage(status);
+  if (doThrow && status < 0) {
+    wpi::SmallString<1024> buf;
+    wpi::raw_svector_ostream oss(buf);
+    oss << " Code: " << status << ". " << message;
+    ThrowUncleanStatusException(env, buf.c_str(), status);
+  } else {
+    std::string func;
+    auto stack = GetJavaStackTrace(env, &func, "edu.wpi.first.wpilibj");
+    HAL_SendError(1, status, 0, message, func.c_str(), stack.c_str(), 1);
+  }
+}
+
+void ThrowError(JNIEnv* env, int32_t status, int32_t minRange, int32_t maxRange,
+                int32_t requestedValue) {
+  if (status == 0) return;
+  if (status == NO_AVAILABLE_RESOURCES || status == RESOURCE_IS_ALLOCATED ||
+      status == RESOURCE_OUT_OF_RANGE) {
+    ThrowAllocationException(env, minRange, maxRange, requestedValue, status);
+  }
+  if (status == HAL_HANDLE_ERROR) {
+    ThrowHalHandleException(env, status);
+  }
+  const char* message = HAL_GetErrorMessage(status);
+  wpi::SmallString<1024> buf;
+  wpi::raw_svector_ostream oss(buf);
+  oss << " Code: " << status << ". " << message;
+  ThrowUncleanStatusException(env, buf.c_str(), status);
+}
+
+void ReportCANError(JNIEnv* env, int32_t status, int message_id) {
+  if (status >= 0) return;
+  switch (status) {
+    case kRioStatusSuccess:
+      // Everything is ok... don't throw.
+      break;
+    case HAL_ERR_CANSessionMux_InvalidBuffer:
+    case kRIOStatusBufferInvalidSize: {
+      static jmethodID invalidBufConstruct = nullptr;
+      if (!invalidBufConstruct)
+        invalidBufConstruct =
+            env->GetMethodID(canInvalidBufferExCls, "<init>", "()V");
+      jobject exception =
+          env->NewObject(canInvalidBufferExCls, invalidBufConstruct);
+      env->Throw(static_cast<jthrowable>(exception));
+      break;
+    }
+    case HAL_ERR_CANSessionMux_MessageNotFound:
+    case kRIOStatusOperationTimedOut: {
+      static jmethodID messageNotFoundConstruct = nullptr;
+      if (!messageNotFoundConstruct)
+        messageNotFoundConstruct =
+            env->GetMethodID(canMessageNotFoundExCls, "<init>", "()V");
+      jobject exception =
+          env->NewObject(canMessageNotFoundExCls, messageNotFoundConstruct);
+      env->Throw(static_cast<jthrowable>(exception));
+      break;
+    }
+    case HAL_ERR_CANSessionMux_NotAllowed:
+    case kRIOStatusFeatureNotSupported: {
+      wpi::SmallString<100> buf;
+      wpi::raw_svector_ostream oss(buf);
+      oss << "MessageID = " << message_id;
+      canMessageNotAllowedExCls.Throw(env, buf.c_str());
+      break;
+    }
+    case HAL_ERR_CANSessionMux_NotInitialized:
+    case kRIOStatusResourceNotInitialized: {
+      static jmethodID notInitConstruct = nullptr;
+      if (!notInitConstruct)
+        notInitConstruct =
+            env->GetMethodID(canNotInitializedExCls, "<init>", "()V");
+      jobject exception =
+          env->NewObject(canNotInitializedExCls, notInitConstruct);
+      env->Throw(static_cast<jthrowable>(exception));
+      break;
+    }
+    default: {
+      wpi::SmallString<100> buf;
+      wpi::raw_svector_ostream oss(buf);
+      oss << "Fatal status code detected: " << status;
+      uncleanStatusExCls.Throw(env, buf.c_str());
+      break;
+    }
+  }
+}
+
+void ThrowIllegalArgumentException(JNIEnv* env, wpi::StringRef msg) {
+  illegalArgExCls.Throw(env, msg);
+}
+
+void ThrowBoundaryException(JNIEnv* env, double value, double lower,
+                            double upper) {
+  static jmethodID getMessage = nullptr;
+  if (!getMessage)
+    getMessage = env->GetStaticMethodID(boundaryExCls, "getMessage",
+                                        "(DDD)Ljava/lang/String;");
+
+  static jmethodID constructor = nullptr;
+  if (!constructor)
+    constructor =
+        env->GetMethodID(boundaryExCls, "<init>", "(Ljava/lang/String;)V");
+
+  jobject msg = env->CallStaticObjectMethod(
+      boundaryExCls, getMessage, static_cast<jdouble>(value),
+      static_cast<jdouble>(lower), static_cast<jdouble>(upper));
+  jobject ex = env->NewObject(boundaryExCls, constructor, msg);
+  env->Throw(static_cast<jthrowable>(ex));
+}
+
+jobject CreatePWMConfigDataResult(JNIEnv* env, int32_t maxPwm,
+                                  int32_t deadbandMaxPwm, int32_t centerPwm,
+                                  int32_t deadbandMinPwm, int32_t minPwm) {
+  static jmethodID constructor =
+      env->GetMethodID(pwmConfigDataResultCls, "<init>", "(IIIII)V");
+  return env->NewObject(pwmConfigDataResultCls, constructor, maxPwm,
+                        deadbandMaxPwm, centerPwm, deadbandMinPwm, minPwm);
+}
+
+void SetCanStatusObject(JNIEnv* env, jobject canStatus,
+                        float percentBusUtilization, uint32_t busOffCount,
+                        uint32_t txFullCount, uint32_t receiveErrorCount,
+                        uint32_t transmitErrorCount) {
+  static jmethodID func =
+      env->GetMethodID(canStatusCls, "setStatus", "(DIIII)V");
+  env->CallVoidMethod(canStatus, func, (jdouble)percentBusUtilization,
+                      (jint)busOffCount, (jint)txFullCount,
+                      (jint)receiveErrorCount, (jint)transmitErrorCount);
+}
+
+void SetMatchInfoObject(JNIEnv* env, jobject matchStatus,
+                        const HAL_MatchInfo& matchInfo) {
+  static jmethodID func =
+      env->GetMethodID(matchInfoDataCls, "setData",
+                       "(Ljava/lang/String;Ljava/lang/String;III)V");
+
+  env->CallVoidMethod(
+      matchStatus, func, MakeJString(env, matchInfo.eventName),
+      MakeJString(env, wpi::StringRef{reinterpret_cast<const char*>(
+                                          matchInfo.gameSpecificMessage),
+                                      matchInfo.gameSpecificMessageSize}),
+      (jint)matchInfo.matchNumber, (jint)matchInfo.replayNumber,
+      (jint)matchInfo.matchType);
+}
+
+void SetAccumulatorResultObject(JNIEnv* env, jobject accumulatorResult,
+                                int64_t value, int64_t count) {
+  static jmethodID func =
+      env->GetMethodID(accumulatorResultCls, "set", "(JJ)V");
+
+  env->CallVoidMethod(accumulatorResult, func, (jlong)value, (jlong)count);
+}
+
+jbyteArray SetCANDataObject(JNIEnv* env, jobject canData, int32_t length,
+                            uint64_t timestamp) {
+  static jmethodID func = env->GetMethodID(canDataCls, "setData", "(IJ)[B");
+
+  jbyteArray retVal = static_cast<jbyteArray>(
+      env->CallObjectMethod(canData, func, (jint)length, (jlong)timestamp));
+  return retVal;
+}
+
+JavaVM* GetJVM() { return jvm; }
+
+}  // namespace frc
+
+namespace sim {
+jint SimOnLoad(JavaVM* vm, void* reserved);
+void SimOnUnload(JavaVM* vm, void* reserved);
+}  // namespace sim
+
+using namespace frc;
+
+extern "C" {
+
+//
+// indicate JNI version support desired and load classes
+//
+JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) {
+  jvm = vm;
+
+  // set our logging level
+  Log::ReportingLevel() = logDEBUG;
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return JNI_ERR;
+
+  for (auto& c : classes) {
+    *c.cls = JClass(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  for (auto& c : exceptions) {
+    *c.cls = JException(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  return sim::SimOnLoad(vm, reserved);
+}
+
+JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) {
+  sim::SimOnUnload(vm, reserved);
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return;
+  // Delete global references
+
+  for (auto& c : classes) {
+    c.cls->free(env);
+  }
+  for (auto& c : exceptions) {
+    c.cls->free(env);
+  }
+  jvm = nullptr;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getFPGAVersion
+ * Signature: ()S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_HALUtil_getFPGAVersion
+  (JNIEnv* env, jclass)
+{
+  HALUTIL_LOG(logDEBUG) << "Calling HALUtil getFPGAVersion";
+  int32_t status = 0;
+  jshort returnValue = HAL_GetFPGAVersion(&status);
+  HALUTIL_LOG(logDEBUG) << "Status = " << status;
+  HALUTIL_LOG(logDEBUG) << "FPGAVersion = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getFPGARevision
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HALUtil_getFPGARevision
+  (JNIEnv* env, jclass)
+{
+  HALUTIL_LOG(logDEBUG) << "Calling HALUtil getFPGARevision";
+  int32_t status = 0;
+  jint returnValue = HAL_GetFPGARevision(&status);
+  HALUTIL_LOG(logDEBUG) << "Status = " << status;
+  HALUTIL_LOG(logDEBUG) << "FPGARevision = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getFPGATime
+ * Signature: ()J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_HALUtil_getFPGATime
+  (JNIEnv* env, jclass)
+{
+  // HALUTIL_LOG(logDEBUG) << "Calling HALUtil getFPGATime";
+  int32_t status = 0;
+  jlong returnValue = HAL_GetFPGATime(&status);
+  // HALUTIL_LOG(logDEBUG) << "Status = " << status;
+  // HALUTIL_LOG(logDEBUG) << "FPGATime = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getHALRuntimeType
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HALUtil_getHALRuntimeType
+  (JNIEnv* env, jclass)
+{
+  // HALUTIL_LOG(logDEBUG) << "Calling HALUtil getHALRuntimeType";
+  jint returnValue = HAL_GetRuntimeType();
+  // HALUTIL_LOG(logDEBUG) << "RuntimeType = " << returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getFPGAButton
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_HALUtil_getFPGAButton
+  (JNIEnv* env, jclass)
+{
+  // HALUTIL_LOG(logDEBUG) << "Calling HALUtil getFPGATime";
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetFPGAButton(&status);
+  // HALUTIL_LOG(logDEBUG) << "Status = " << status;
+  // HALUTIL_LOG(logDEBUG) << "FPGATime = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getHALErrorMessage
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_HALUtil_getHALErrorMessage
+  (JNIEnv* paramEnv, jclass, jint paramId)
+{
+  const char* msg = HAL_GetErrorMessage(paramId);
+  HALUTIL_LOG(logDEBUG) << "Calling HALUtil HAL_GetErrorMessage id=" << paramId
+                        << " msg=" << msg;
+  return MakeJString(paramEnv, msg);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getHALErrno
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_HALUtil_getHALErrno
+  (JNIEnv*, jclass)
+{
+  return errno;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_HALUtil
+ * Method:    getHALstrerror
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_hal_HALUtil_getHALstrerror
+  (JNIEnv* env, jclass, jint errorCode)
+{
+  const char* msg = std::strerror(errno);
+  HALUTIL_LOG(logDEBUG) << "Calling HALUtil getHALstrerror errorCode="
+                        << errorCode << " msg=" << msg;
+  return MakeJString(env, msg);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HALUtil.h b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HALUtil.h
new file mode 100644
index 0000000..8197e1a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/HALUtil.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef HAL_HAL_SRC_MAIN_NATIVE_CPP_JNI_HALUTIL_H_
+#define HAL_HAL_SRC_MAIN_NATIVE_CPP_JNI_HALUTIL_H_
+
+#include <jni.h>
+#include <stdint.h>
+
+#include <wpi/StringRef.h>
+
+struct HAL_MatchInfo;
+
+namespace frc {
+
+void ReportError(JNIEnv* env, int32_t status, bool doThrow = true);
+
+void ThrowError(JNIEnv* env, int32_t status, int32_t minRange, int32_t maxRange,
+                int32_t requestedValue);
+
+inline bool CheckStatus(JNIEnv* env, int32_t status, bool doThrow = true) {
+  if (status != 0) ReportError(env, status, doThrow);
+  return status == 0;
+}
+
+inline bool CheckStatusRange(JNIEnv* env, int32_t status, int32_t minRange,
+                             int32_t maxRange, int32_t requestedValue) {
+  if (status != 0) ThrowError(env, status, minRange, maxRange, requestedValue);
+  return status == 0;
+}
+
+inline bool CheckStatusForceThrow(JNIEnv* env, int32_t status) {
+  if (status != 0) ThrowError(env, status, 0, 0, 0);
+  return status == 0;
+}
+
+void ReportCANError(JNIEnv* env, int32_t status, int32_t message_id);
+
+inline bool CheckCANStatus(JNIEnv* env, int32_t status, int32_t message_id) {
+  if (status != 0) ReportCANError(env, status, message_id);
+  return status == 0;
+}
+
+void ThrowIllegalArgumentException(JNIEnv* env, wpi::StringRef msg);
+void ThrowBoundaryException(JNIEnv* env, double value, double lower,
+                            double upper);
+
+jobject CreatePWMConfigDataResult(JNIEnv* env, int32_t maxPwm,
+                                  int32_t deadbandMaxPwm, int32_t centerPwm,
+                                  int32_t deadbandMinPwm, int32_t minPwm);
+
+void SetCanStatusObject(JNIEnv* env, jobject canStatus,
+                        float percentBusUtilization, uint32_t busOffCount,
+                        uint32_t txFullCount, uint32_t receiveErrorCount,
+                        uint32_t transmitErrorCount);
+
+void SetMatchInfoObject(JNIEnv* env, jobject matchStatus,
+                        const HAL_MatchInfo& matchInfo);
+
+void SetAccumulatorResultObject(JNIEnv* env, jobject accumulatorResult,
+                                int64_t value, int64_t count);
+
+jbyteArray SetCANDataObject(JNIEnv* env, jobject canData, int32_t length,
+                            uint64_t timestamp);
+
+JavaVM* GetJVM();
+
+}  // namespace frc
+
+#endif  // HAL_HAL_SRC_MAIN_NATIVE_CPP_JNI_HALUTIL_H_
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/I2CJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/I2CJNI.cpp
new file mode 100644
index 0000000..9dafd4a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/I2CJNI.cpp
@@ -0,0 +1,221 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_I2CJNI.h"
+#include "hal/I2C.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+// set the logging level
+TLogLevel i2cJNILogLevel = logWARNING;
+
+#define I2CJNI_LOG(level)     \
+  if (level > i2cJNILogLevel) \
+    ;                         \
+  else                        \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CInitialize
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CInitialize
+  (JNIEnv* env, jclass, jint port)
+{
+  I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CInititalize";
+  I2CJNI_LOG(logDEBUG) << "Port: " << port;
+  int32_t status = 0;
+  HAL_InitializeI2C(static_cast<HAL_I2CPort>(port), &status);
+  I2CJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatusForceThrow(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CTransaction
+ * Signature: (IBLjava/lang/Object;BLjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CTransaction
+  (JNIEnv* env, jclass, jint port, jbyte address, jobject dataToSend,
+   jbyte sendSize, jobject dataReceived, jbyte receiveSize)
+{
+  I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CTransaction";
+  I2CJNI_LOG(logDEBUG) << "Port = " << port;
+  I2CJNI_LOG(logDEBUG) << "Address = " << (jint)address;
+  uint8_t* dataToSendPtr = nullptr;
+  if (dataToSend != 0) {
+    dataToSendPtr =
+        reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataToSend));
+  }
+  I2CJNI_LOG(logDEBUG) << "DataToSendPtr = "
+                       << reinterpret_cast<jint*>(dataToSendPtr);
+  I2CJNI_LOG(logDEBUG) << "SendSize = " << (jint)sendSize;
+  uint8_t* dataReceivedPtr =
+      reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
+  I2CJNI_LOG(logDEBUG) << "DataReceivedPtr = "
+                       << reinterpret_cast<jint*>(dataReceivedPtr);
+  I2CJNI_LOG(logDEBUG) << "ReceiveSize = " << (jint)receiveSize;
+  jint returnValue =
+      HAL_TransactionI2C(static_cast<HAL_I2CPort>(port), address, dataToSendPtr,
+                         sendSize, dataReceivedPtr, receiveSize);
+  I2CJNI_LOG(logDEBUG) << "ReturnValue = " << returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CTransactionB
+ * Signature: (IB[BB[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CTransactionB
+  (JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataToSend,
+   jbyte sendSize, jbyteArray dataReceived, jbyte receiveSize)
+{
+  I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CTransactionB";
+  I2CJNI_LOG(logDEBUG) << "Port = " << port;
+  I2CJNI_LOG(logDEBUG) << "Address = " << (jint)address;
+  I2CJNI_LOG(logDEBUG) << "SendSize = " << (jint)sendSize;
+  wpi::SmallVector<uint8_t, 128> recvBuf;
+  recvBuf.resize(receiveSize);
+  I2CJNI_LOG(logDEBUG) << "ReceiveSize = " << (jint)receiveSize;
+  jint returnValue =
+      HAL_TransactionI2C(static_cast<HAL_I2CPort>(port), address,
+                         reinterpret_cast<const uint8_t*>(
+                             JByteArrayRef(env, dataToSend).array().data()),
+                         sendSize, recvBuf.data(), receiveSize);
+  env->SetByteArrayRegion(dataReceived, 0, receiveSize,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  I2CJNI_LOG(logDEBUG) << "ReturnValue = " << returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CWrite
+ * Signature: (IBLjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CWrite
+  (JNIEnv* env, jclass, jint port, jbyte address, jobject dataToSend,
+   jbyte sendSize)
+{
+  I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CWrite";
+  I2CJNI_LOG(logDEBUG) << "Port = " << port;
+  I2CJNI_LOG(logDEBUG) << "Address = " << (jint)address;
+  uint8_t* dataToSendPtr = nullptr;
+
+  if (dataToSend != 0) {
+    dataToSendPtr =
+        reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataToSend));
+  }
+  I2CJNI_LOG(logDEBUG) << "DataToSendPtr = " << dataToSendPtr;
+  I2CJNI_LOG(logDEBUG) << "SendSize = " << (jint)sendSize;
+  jint returnValue = HAL_WriteI2C(static_cast<HAL_I2CPort>(port), address,
+                                  dataToSendPtr, sendSize);
+  I2CJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CWriteB
+ * Signature: (IB[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CWriteB
+  (JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataToSend,
+   jbyte sendSize)
+{
+  I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CWrite";
+  I2CJNI_LOG(logDEBUG) << "Port = " << port;
+  I2CJNI_LOG(logDEBUG) << "Address = " << (jint)address;
+  I2CJNI_LOG(logDEBUG) << "SendSize = " << (jint)sendSize;
+  jint returnValue =
+      HAL_WriteI2C(static_cast<HAL_I2CPort>(port), address,
+                   reinterpret_cast<const uint8_t*>(
+                       JByteArrayRef(env, dataToSend).array().data()),
+                   sendSize);
+  I2CJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CRead
+ * Signature: (IBLjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CRead
+  (JNIEnv* env, jclass, jint port, jbyte address, jobject dataReceived,
+   jbyte receiveSize)
+{
+  I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CRead";
+  I2CJNI_LOG(logDEBUG) << "Port = " << port;
+  I2CJNI_LOG(logDEBUG) << "Address = " << address;
+  uint8_t* dataReceivedPtr =
+      reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
+  I2CJNI_LOG(logDEBUG) << "DataReceivedPtr = " << dataReceivedPtr;
+  I2CJNI_LOG(logDEBUG) << "ReceiveSize = " << receiveSize;
+  jint returnValue = HAL_ReadI2C(static_cast<HAL_I2CPort>(port), address,
+                                 dataReceivedPtr, receiveSize);
+  I2CJNI_LOG(logDEBUG) << "ReturnValue = " << returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CReadB
+ * Signature: (IB[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CReadB
+  (JNIEnv* env, jclass, jint port, jbyte address, jbyteArray dataReceived,
+   jbyte receiveSize)
+{
+  I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CRead";
+  I2CJNI_LOG(logDEBUG) << "Port = " << port;
+  I2CJNI_LOG(logDEBUG) << "Address = " << address;
+  I2CJNI_LOG(logDEBUG) << "ReceiveSize = " << receiveSize;
+  wpi::SmallVector<uint8_t, 128> recvBuf;
+  recvBuf.resize(receiveSize);
+  jint returnValue = HAL_ReadI2C(static_cast<HAL_I2CPort>(port), address,
+                                 recvBuf.data(), receiveSize);
+  env->SetByteArrayRegion(dataReceived, 0, receiveSize,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  I2CJNI_LOG(logDEBUG) << "ReturnValue = " << returnValue;
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_I2CJNI
+ * Method:    i2CClose
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_I2CJNI_i2CClose
+  (JNIEnv*, jclass, jint port)
+{
+  I2CJNI_LOG(logDEBUG) << "Calling I2CJNI i2CClose";
+  HAL_CloseI2C(static_cast<HAL_I2CPort>(port));
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/InterruptJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/InterruptJNI.cpp
new file mode 100644
index 0000000..2dd4abf
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/InterruptJNI.cpp
@@ -0,0 +1,375 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <atomic>
+#include <cassert>
+#include <thread>
+
+#include <wpi/SafeThread.h>
+#include <wpi/mutex.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_InterruptJNI.h"
+#include "hal/Interrupts.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+
+TLogLevel interruptJNILogLevel = logERROR;
+
+#define INTERRUPTJNI_LOG(level)     \
+  if (level > interruptJNILogLevel) \
+    ;                               \
+  else                              \
+    Log().Get(level)
+
+// Thread where callbacks are actually performed.
+//
+// JNI's AttachCurrentThread() creates a Java Thread object on every
+// invocation, which is both time inefficient and causes issues with Eclipse
+// (which tries to keep a thread list up-to-date and thus gets swamped).
+//
+// Instead, this class attaches just once.  When a hardware notification
+// occurs, a condition variable wakes up this thread and this thread actually
+// makes the call into Java.
+//
+// We don't want to use a FIFO here. If the user code takes too long to
+// process, we will just ignore the redundant wakeup.
+class InterruptThreadJNI : public wpi::SafeThread {
+ public:
+  void Main();
+
+  bool m_notify = false;
+  uint32_t m_mask = 0;
+  jobject m_func = nullptr;
+  jmethodID m_mid;
+  jobject m_param = nullptr;
+};
+
+class InterruptJNI : public wpi::SafeThreadOwner<InterruptThreadJNI> {
+ public:
+  void SetFunc(JNIEnv* env, jobject func, jmethodID mid, jobject param);
+
+  void Notify(uint32_t mask) {
+    auto thr = GetThread();
+    if (!thr) return;
+    thr->m_notify = true;
+    thr->m_mask = mask;
+    thr->m_cond.notify_one();
+  }
+};
+
+void InterruptJNI::SetFunc(JNIEnv* env, jobject func, jmethodID mid,
+                           jobject param) {
+  auto thr = GetThread();
+  if (!thr) return;
+  // free global references
+  if (thr->m_func) env->DeleteGlobalRef(thr->m_func);
+  if (thr->m_param) env->DeleteGlobalRef(thr->m_param);
+  // create global references
+  thr->m_func = env->NewGlobalRef(func);
+  thr->m_param = param ? env->NewGlobalRef(param) : nullptr;
+  thr->m_mid = mid;
+}
+
+void InterruptThreadJNI::Main() {
+  JNIEnv* env;
+  JavaVMAttachArgs args;
+  args.version = JNI_VERSION_1_2;
+  args.name = const_cast<char*>("Interrupt");
+  args.group = nullptr;
+  jint rs = GetJVM()->AttachCurrentThreadAsDaemon(
+      reinterpret_cast<void**>(&env), &args);
+  if (rs != JNI_OK) return;
+
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  while (m_active) {
+    m_cond.wait(lock, [&] { return !m_active || m_notify; });
+    if (!m_active) break;
+    m_notify = false;
+    if (!m_func) continue;
+    jobject func = m_func;
+    jmethodID mid = m_mid;
+    uint32_t mask = m_mask;
+    jobject param = m_param;
+    lock.unlock();  // don't hold mutex during callback execution
+    env->CallVoidMethod(func, mid, static_cast<jint>(mask), param);
+    if (env->ExceptionCheck()) {
+      env->ExceptionDescribe();
+      env->ExceptionClear();
+    }
+    lock.lock();
+  }
+
+  // free global references
+  if (m_func) env->DeleteGlobalRef(m_func);
+  if (m_param) env->DeleteGlobalRef(m_param);
+
+  GetJVM()->DetachCurrentThread();
+}
+
+void interruptHandler(uint32_t mask, void* param) {
+  static_cast<InterruptJNI*>(param)->Notify(mask);
+}
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    initializeInterrupts
+ * Signature: (Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_initializeInterrupts
+  (JNIEnv* env, jclass, jboolean watcher)
+{
+  INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI initializeInterrupts";
+  INTERRUPTJNI_LOG(logDEBUG) << "watcher = " << static_cast<bool>(watcher);
+
+  int32_t status = 0;
+  HAL_InterruptHandle interrupt = HAL_InitializeInterrupts(watcher, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Interrupt Handle = " << interrupt;
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+
+  CheckStatusForceThrow(env, status);
+  return (jint)interrupt;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    cleanInterrupts
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_cleanInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI cleanInterrupts";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+
+  int32_t status = 0;
+  auto param =
+      HAL_CleanInterrupts((HAL_InterruptHandle)interruptHandle, &status);
+  if (param) {
+    delete static_cast<InterruptJNI*>(param);
+  }
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+
+  // ignore status, as an invalid handle just needs to be ignored.
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    waitForInterrupt
+ * Signature: (IDZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_waitForInterrupt
+  (JNIEnv* env, jclass, jint interruptHandle, jdouble timeout,
+   jboolean ignorePrevious)
+{
+  INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI waitForInterrupt";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+
+  int32_t status = 0;
+  int32_t result = HAL_WaitForInterrupt((HAL_InterruptHandle)interruptHandle,
+                                        timeout, ignorePrevious, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+
+  CheckStatus(env, status);
+  return result;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    enableInterrupts
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_enableInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI enableInterrupts";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+
+  int32_t status = 0;
+  HAL_EnableInterrupts((HAL_InterruptHandle)interruptHandle, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    disableInterrupts
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_disableInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI disableInterrupts";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+
+  int32_t status = 0;
+  HAL_DisableInterrupts((HAL_InterruptHandle)interruptHandle, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    readInterruptRisingTimestamp
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_readInterruptRisingTimestamp
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Calling INTERRUPTJNI readInterruptRisingTimestamp";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+
+  int32_t status = 0;
+  jlong timeStamp = HAL_ReadInterruptRisingTimestamp(
+      (HAL_InterruptHandle)interruptHandle, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+  return timeStamp;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    readInterruptFallingTimestamp
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_readInterruptFallingTimestamp
+  (JNIEnv* env, jclass, jint interruptHandle)
+{
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Calling INTERRUPTJNI readInterruptFallingTimestamp";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+
+  int32_t status = 0;
+  jlong timeStamp = HAL_ReadInterruptFallingTimestamp(
+      (HAL_InterruptHandle)interruptHandle, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+  return timeStamp;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    requestInterrupts
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_requestInterrupts
+  (JNIEnv* env, jclass, jint interruptHandle, jint digitalSourceHandle,
+   jint analogTriggerType)
+{
+  INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI requestInterrupts";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+  INTERRUPTJNI_LOG(logDEBUG) << "digitalSourceHandle = " << digitalSourceHandle;
+  INTERRUPTJNI_LOG(logDEBUG) << "analogTriggerType = " << analogTriggerType;
+
+  int32_t status = 0;
+  HAL_RequestInterrupts((HAL_InterruptHandle)interruptHandle,
+                        (HAL_Handle)digitalSourceHandle,
+                        (HAL_AnalogTriggerType)analogTriggerType, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    attachInterruptHandler
+ * Signature: (ILjava/lang/Object;Ljava/lang/Object;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_attachInterruptHandler
+  (JNIEnv* env, jclass, jint interruptHandle, jobject handler, jobject param)
+{
+  INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI attachInterruptHandler";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+
+  jclass cls = env->GetObjectClass(handler);
+  INTERRUPTJNI_LOG(logDEBUG) << "class = " << cls;
+  if (cls == 0) {
+    INTERRUPTJNI_LOG(logERROR) << "Error getting java class";
+    assert(false);
+    return;
+  }
+  jmethodID mid = env->GetMethodID(cls, "apply", "(ILjava/lang/Object;)V");
+  INTERRUPTJNI_LOG(logDEBUG) << "method = " << mid;
+  if (mid == 0) {
+    INTERRUPTJNI_LOG(logERROR) << "Error getting java method ID";
+    assert(false);
+    return;
+  }
+
+  InterruptJNI* intr = new InterruptJNI;
+  intr->Start();
+  intr->SetFunc(env, handler, mid, param);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "InterruptThreadJNI Ptr = " << intr;
+
+  int32_t status = 0;
+  HAL_AttachInterruptHandler((HAL_InterruptHandle)interruptHandle,
+                             interruptHandler, intr, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_InterruptJNI
+ * Method:    setInterruptUpSourceEdge
+ * Signature: (IZZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_InterruptJNI_setInterruptUpSourceEdge
+  (JNIEnv* env, jclass, jint interruptHandle, jboolean risingEdge,
+   jboolean fallingEdge)
+{
+  INTERRUPTJNI_LOG(logDEBUG) << "Calling INTERRUPTJNI setInterruptUpSourceEdge";
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Interrupt Handle = " << (HAL_InterruptHandle)interruptHandle;
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Rising Edge = " << static_cast<bool>(risingEdge);
+  INTERRUPTJNI_LOG(logDEBUG)
+      << "Falling Edge = " << static_cast<bool>(fallingEdge);
+
+  int32_t status = 0;
+  HAL_SetInterruptUpSourceEdge((HAL_InterruptHandle)interruptHandle, risingEdge,
+                               fallingEdge, &status);
+
+  INTERRUPTJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/NotifierJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/NotifierJNI.cpp
new file mode 100644
index 0000000..61fe32f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/NotifierJNI.cpp
@@ -0,0 +1,157 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+#include <cstdio>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_NotifierJNI.h"
+#include "hal/Notifier.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel notifierJNILogLevel = logWARNING;
+
+#define NOTIFIERJNI_LOG(level)     \
+  if (level > notifierJNILogLevel) \
+    ;                              \
+  else                             \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    initializeNotifier
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_initializeNotifier
+  (JNIEnv* env, jclass)
+{
+  NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI initializeNotifier";
+
+  int32_t status = 0;
+  HAL_NotifierHandle notifierHandle = HAL_InitializeNotifier(&status);
+
+  NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
+  NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
+
+  if (notifierHandle <= 0 || !CheckStatusForceThrow(env, status)) {
+    return 0;  // something went wrong in HAL
+  }
+
+  return (jint)notifierHandle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    stopNotifier
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_stopNotifier
+  (JNIEnv* env, jclass cls, jint notifierHandle)
+{
+  NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI stopNotifier";
+
+  NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
+
+  int32_t status = 0;
+  HAL_StopNotifier((HAL_NotifierHandle)notifierHandle, &status);
+  NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    cleanNotifier
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_cleanNotifier
+  (JNIEnv* env, jclass, jint notifierHandle)
+{
+  NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI cleanNotifier";
+
+  NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
+
+  int32_t status = 0;
+  HAL_CleanNotifier((HAL_NotifierHandle)notifierHandle, &status);
+  NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    updateNotifierAlarm
+ * Signature: (IJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_updateNotifierAlarm
+  (JNIEnv* env, jclass cls, jint notifierHandle, jlong triggerTime)
+{
+  NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI updateNotifierAlarm";
+
+  NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
+
+  NOTIFIERJNI_LOG(logDEBUG) << "triggerTime = " << triggerTime;
+
+  int32_t status = 0;
+  HAL_UpdateNotifierAlarm((HAL_NotifierHandle)notifierHandle,
+                          static_cast<uint64_t>(triggerTime), &status);
+  NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    cancelNotifierAlarm
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_cancelNotifierAlarm
+  (JNIEnv* env, jclass cls, jint notifierHandle)
+{
+  NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI cancelNotifierAlarm";
+
+  NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
+
+  int32_t status = 0;
+  HAL_CancelNotifierAlarm((HAL_NotifierHandle)notifierHandle, &status);
+  NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_NotifierJNI
+ * Method:    waitForNotifierAlarm
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_NotifierJNI_waitForNotifierAlarm
+  (JNIEnv* env, jclass cls, jint notifierHandle)
+{
+  NOTIFIERJNI_LOG(logDEBUG) << "Calling NOTIFIERJNI waitForNotifierAlarm";
+
+  NOTIFIERJNI_LOG(logDEBUG) << "Notifier Handle = " << notifierHandle;
+
+  int32_t status = 0;
+  uint64_t time =
+      HAL_WaitForNotifierAlarm((HAL_NotifierHandle)notifierHandle, &status);
+  NOTIFIERJNI_LOG(logDEBUG) << "Status = " << status;
+  NOTIFIERJNI_LOG(logDEBUG) << "Time = " << time;
+  CheckStatus(env, status);
+
+  return (jlong)time;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PDPJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PDPJNI.cpp
new file mode 100644
index 0000000..e8173be
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PDPJNI.cpp
@@ -0,0 +1,174 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "HALUtil.h"
+#include "edu_wpi_first_hal_PDPJNI.h"
+#include "hal/PDP.h"
+#include "hal/Ports.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    initializePDP
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PDPJNI_initializePDP
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  auto handle = HAL_InitializePDP(module, &status);
+  CheckStatusRange(env, status, 0, HAL_GetNumPDPModules(), module);
+  return static_cast<jint>(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    checkPDPChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PDPJNI_checkPDPChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  return HAL_CheckPDPChannel(channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    checkPDPModule
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PDPJNI_checkPDPModule
+  (JNIEnv* env, jclass, jint module)
+{
+  return HAL_CheckPDPModule(module);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPTemperature
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPTemperature
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double temperature = HAL_GetPDPTemperature(handle, &status);
+  CheckStatus(env, status, false);
+  return temperature;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPVoltage
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double voltage = HAL_GetPDPVoltage(handle, &status);
+  CheckStatus(env, status, false);
+  return voltage;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPChannelCurrent
+ * Signature: (BI)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPChannelCurrent
+  (JNIEnv* env, jclass, jbyte channel, jint handle)
+{
+  int32_t status = 0;
+  double current = HAL_GetPDPChannelCurrent(handle, channel, &status);
+  CheckStatus(env, status, false);
+  return current;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPTotalCurrent
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPTotalCurrent
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double current = HAL_GetPDPTotalCurrent(handle, &status);
+  CheckStatus(env, status, false);
+  return current;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPTotalPower
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPTotalPower
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double power = HAL_GetPDPTotalPower(handle, &status);
+  CheckStatus(env, status, false);
+  return power;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    getPDPTotalEnergy
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PDPJNI_getPDPTotalEnergy
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  double energy = HAL_GetPDPTotalEnergy(handle, &status);
+  CheckStatus(env, status, false);
+  return energy;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    resetPDPTotalEnergy
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PDPJNI_resetPDPTotalEnergy
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_ResetPDPTotalEnergy(handle, &status);
+  CheckStatus(env, status, false);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PDPJNI
+ * Method:    clearPDPStickyFaults
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PDPJNI_clearPDPStickyFaults
+  (JNIEnv* env, jclass, jint handle)
+{
+  int32_t status = 0;
+  HAL_ClearPDPStickyFaults(handle, &status);
+  CheckStatus(env, status, false);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PWMJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PWMJNI.cpp
new file mode 100644
index 0000000..1509f94
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PWMJNI.cpp
@@ -0,0 +1,330 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_PWMJNI.h"
+#include "hal/DIO.h"
+#include "hal/PWM.h"
+#include "hal/Ports.h"
+#include "hal/cpp/Log.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel pwmJNILogLevel = logWARNING;
+
+#define PWMJNI_LOG(level)     \
+  if (level > pwmJNILogLevel) \
+    ;                         \
+  else                        \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    initializePWMPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PWMJNI_initializePWMPort
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "Calling PWMJNI initializePWMPort";
+  PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
+  int32_t status = 0;
+  auto pwm = HAL_InitializePWMPort((HAL_PortHandle)id, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << pwm;
+  CheckStatusRange(env, status, 0, HAL_GetNumPWMChannels(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)pwm;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    checkPWMChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PWMJNI_checkPWMChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  PWMJNI_LOG(logDEBUG) << "Calling PWMJNI checkPWMChannel";
+  PWMJNI_LOG(logDEBUG) << "Channel = " << channel;
+  return HAL_CheckPWMChannel(channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    freePWMPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_freePWMPort
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "Calling PWMJNI freePWMPort";
+  PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  HAL_FreePWMPort((HAL_DigitalHandle)id, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMConfigRaw
+ * Signature: (IIIIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMConfigRaw
+  (JNIEnv* env, jclass, jint id, jint maxPwm, jint deadbandMaxPwm,
+   jint centerPwm, jint deadbandMinPwm, jint minPwm)
+{
+  PWMJNI_LOG(logDEBUG) << "Calling PWMJNI setPWMConfigRaw";
+  PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  HAL_SetPWMConfigRaw((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm, centerPwm,
+                      deadbandMinPwm, minPwm, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMConfig
+ * Signature: (IDDDDD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMConfig
+  (JNIEnv* env, jclass, jint id, jdouble maxPwm, jdouble deadbandMaxPwm,
+   jdouble centerPwm, jdouble deadbandMinPwm, jdouble minPwm)
+{
+  PWMJNI_LOG(logDEBUG) << "Calling PWMJNI setPWMConfig";
+  PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  HAL_SetPWMConfig((HAL_DigitalHandle)id, maxPwm, deadbandMaxPwm, centerPwm,
+                   deadbandMinPwm, minPwm, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMConfigRaw
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMConfigRaw
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "Calling PWMJNI getPWMConfigRaw";
+  PWMJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  int32_t maxPwm = 0;
+  int32_t deadbandMaxPwm = 0;
+  int32_t centerPwm = 0;
+  int32_t deadbandMinPwm = 0;
+  int32_t minPwm = 0;
+  HAL_GetPWMConfigRaw((HAL_DigitalHandle)id, &maxPwm, &deadbandMaxPwm,
+                      &centerPwm, &deadbandMinPwm, &minPwm, &status);
+  CheckStatus(env, status);
+  return CreatePWMConfigDataResult(env, maxPwm, deadbandMaxPwm, centerPwm,
+                                   deadbandMinPwm, minPwm);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMEliminateDeadband
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMEliminateDeadband
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  HAL_SetPWMEliminateDeadband((HAL_DigitalHandle)id, value, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMEliminateDeadband
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMEliminateDeadband
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  auto val = HAL_GetPWMEliminateDeadband((HAL_DigitalHandle)id, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+  return (jboolean)val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMRaw
+ * Signature: (IS)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMRaw
+  (JNIEnv* env, jclass, jint id, jshort value)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  PWMJNI_LOG(logDEBUG) << "PWM Value = " << value;
+  int32_t status = 0;
+  HAL_SetPWMRaw((HAL_DigitalHandle)id, value, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMSpeed
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMSpeed
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  PWMJNI_LOG(logDEBUG) << "PWM Value = " << value;
+  int32_t status = 0;
+  HAL_SetPWMSpeed((HAL_DigitalHandle)id, value, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMPosition
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMPosition
+  (JNIEnv* env, jclass, jint id, jdouble value)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  PWMJNI_LOG(logDEBUG) << "PWM Value = " << value;
+  int32_t status = 0;
+  HAL_SetPWMPosition((HAL_DigitalHandle)id, value, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMRaw
+ * Signature: (I)S
+ */
+JNIEXPORT jshort JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMRaw
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  jshort returnValue = HAL_GetPWMRaw((HAL_DigitalHandle)id, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  PWMJNI_LOG(logDEBUG) << "Value = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMSpeed
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMSpeed
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetPWMSpeed((HAL_DigitalHandle)id, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  PWMJNI_LOG(logDEBUG) << "Value = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    getPWMPosition
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PWMJNI_getPWMPosition
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  jdouble returnValue = HAL_GetPWMPosition((HAL_DigitalHandle)id, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  PWMJNI_LOG(logDEBUG) << "Value = " << returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMDisabled
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMDisabled
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  HAL_SetPWMDisabled((HAL_DigitalHandle)id, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    latchPWMZero
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_latchPWMZero
+  (JNIEnv* env, jclass, jint id)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  int32_t status = 0;
+  HAL_LatchPWMZero((HAL_DigitalHandle)id, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PWMJNI
+ * Method:    setPWMPeriodScale
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_PWMJNI_setPWMPeriodScale
+  (JNIEnv* env, jclass, jint id, jint value)
+{
+  PWMJNI_LOG(logDEBUG) << "PWM Handle = " << (HAL_DigitalHandle)id;
+  PWMJNI_LOG(logDEBUG) << "PeriodScale Value = " << value;
+  int32_t status = 0;
+  HAL_SetPWMPeriodScale((HAL_DigitalHandle)id, value, &status);
+  PWMJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PortsJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PortsJNI.cpp
new file mode 100644
index 0000000..4e14984
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PortsJNI.cpp
@@ -0,0 +1,298 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_PortsJNI.h"
+#include "hal/Ports.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel portsJNILogLevel = logWARNING;
+
+#define PORTSJNI_LOG(level)     \
+  if (level > portsJNILogLevel) \
+    ;                           \
+  else                          \
+    Log().Get(level)
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumAccumulators
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumAccumulators
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumAccumulators";
+  jint value = HAL_GetNumAccumulators();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumAnalogTriggers
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumAnalogTriggers
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumAnalogTriggers";
+  jint value = HAL_GetNumAnalogTriggers();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumAnalogInputs
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumAnalogInputs
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumAnalogInputs";
+  jint value = HAL_GetNumAnalogInputs();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumAnalogOutputs
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumAnalogOutputs
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumAnalogOutputs";
+  jint value = HAL_GetNumAnalogOutputs();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumCounters
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumCounters
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumCounters";
+  jint value = HAL_GetNumCounters();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumDigitalHeaders
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumDigitalHeaders
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumDigitalHeaders";
+  jint value = HAL_GetNumDigitalHeaders();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPWMHeaders
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPWMHeaders
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPWMHeaders";
+  jint value = HAL_GetNumPWMHeaders();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumDigitalChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumDigitalChannels
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumDigitalChannels";
+  jint value = HAL_GetNumDigitalChannels();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPWMChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPWMChannels
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPWMChannels";
+  jint value = HAL_GetNumPWMChannels();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumDigitalPWMOutputs
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumDigitalPWMOutputs
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumDigitalPWMOutputs";
+  jint value = HAL_GetNumDigitalPWMOutputs();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumEncoders
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumEncoders
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumEncoders";
+  jint value = HAL_GetNumEncoders();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumInterrupts
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumInterrupts
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumInterrupts";
+  jint value = HAL_GetNumInterrupts();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumRelayChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumRelayChannels
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumRelayChannels";
+  jint value = HAL_GetNumRelayChannels();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumRelayHeaders
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumRelayHeaders
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumRelayHeaders";
+  jint value = HAL_GetNumRelayHeaders();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPCMModules
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPCMModules
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPCMModules";
+  jint value = HAL_GetNumPCMModules();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumSolenoidChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumSolenoidChannels
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumSolenoidChannels";
+  jint value = HAL_GetNumSolenoidChannels();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPDPModules
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPDPModules
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPDPModules";
+  jint value = HAL_GetNumPDPModules();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PortsJNI
+ * Method:    getNumPDPChannels
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PortsJNI_getNumPDPChannels
+  (JNIEnv* env, jclass)
+{
+  PORTSJNI_LOG(logDEBUG) << "Calling PortsJNI getNumPDPChannels";
+  jint value = HAL_GetNumPDPChannels();
+  PORTSJNI_LOG(logDEBUG) << "Value = " << value;
+  return value;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PowerJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PowerJNI.cpp
new file mode 100644
index 0000000..9184e9e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/PowerJNI.cpp
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_PowerJNI.h"
+#include "hal/Power.h"
+
+using namespace frc;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getVinVoltage
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getVinVoltage
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetVinVoltage(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getVinCurrent
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getVinCurrent
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetVinCurrent(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserVoltage6V
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserVoltage6V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserVoltage6V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrent6V
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrent6V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserCurrent6V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserActive6V
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserActive6V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetUserActive6V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrentFaults6V
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrentFaults6V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  int32_t val = HAL_GetUserCurrentFaults6V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserVoltage5V
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserVoltage5V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserVoltage5V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrent5V
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrent5V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserCurrent5V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserActive5V
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserActive5V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetUserActive5V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrentFaults5V
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrentFaults5V
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  int32_t val = HAL_GetUserCurrentFaults5V(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserVoltage3V3
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserVoltage3V3
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserVoltage3V3(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrent3V3
+ * Signature: ()D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrent3V3
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  double val = HAL_GetUserCurrent3V3(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserActive3V3
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserActive3V3
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  bool val = HAL_GetUserActive3V3(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_PowerJNI
+ * Method:    getUserCurrentFaults3V3
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_PowerJNI_getUserCurrentFaults3V3
+  (JNIEnv* env, jclass)
+{
+  int32_t status = 0;
+  int32_t val = HAL_GetUserCurrentFaults3V3(&status);
+  CheckStatus(env, status);
+  return val;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/RelayJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/RelayJNI.cpp
new file mode 100644
index 0000000..0cc70fb
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/RelayJNI.cpp
@@ -0,0 +1,119 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_RelayJNI.h"
+#include "hal/Ports.h"
+#include "hal/Relay.h"
+#include "hal/cpp/Log.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel relayJNILogLevel = logWARNING;
+
+#define RELAYJNI_LOG(level)     \
+  if (level > relayJNILogLevel) \
+    ;                           \
+  else                          \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    initializeRelayPort
+ * Signature: (IZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_RelayJNI_initializeRelayPort
+  (JNIEnv* env, jclass, jint id, jboolean fwd)
+{
+  RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI initializeRelayPort";
+  RELAYJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
+  RELAYJNI_LOG(logDEBUG) << "Forward = " << (jint)fwd;
+  int32_t status = 0;
+  HAL_RelayHandle handle = HAL_InitializeRelayPort(
+      (HAL_PortHandle)id, static_cast<uint8_t>(fwd), &status);
+  RELAYJNI_LOG(logDEBUG) << "Status = " << status;
+  RELAYJNI_LOG(logDEBUG) << "Relay Handle = " << handle;
+  CheckStatusRange(env, status, 0, HAL_GetNumRelayChannels(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    freeRelayPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_RelayJNI_freeRelayPort
+  (JNIEnv* env, jclass, jint id)
+{
+  RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI freeRelayPort";
+  RELAYJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_RelayHandle)id;
+  HAL_FreeRelayPort((HAL_RelayHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    checkRelayChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_RelayJNI_checkRelayChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI checkRelayChannel";
+  RELAYJNI_LOG(logDEBUG) << "Channel = " << channel;
+  return (jboolean)HAL_CheckRelayChannel(static_cast<uint8_t>(channel));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    setRelay
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_RelayJNI_setRelay
+  (JNIEnv* env, jclass, jint id, jboolean value)
+{
+  RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI setRelay";
+  RELAYJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_RelayHandle)id;
+  RELAYJNI_LOG(logDEBUG) << "Flag = " << (jint)value;
+  int32_t status = 0;
+  HAL_SetRelay((HAL_RelayHandle)id, value, &status);
+  RELAYJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_RelayJNI
+ * Method:    getRelay
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_RelayJNI_getRelay
+  (JNIEnv* env, jclass, jint id)
+{
+  RELAYJNI_LOG(logDEBUG) << "Calling RELAYJNI getRelay";
+  RELAYJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_RelayHandle)id;
+  int32_t status = 0;
+  jboolean returnValue = HAL_GetRelay((HAL_RelayHandle)id, &status);
+  RELAYJNI_LOG(logDEBUG) << "Status = " << status;
+  RELAYJNI_LOG(logDEBUG) << "getRelayResult = " << (jint)returnValue;
+  CheckStatus(env, status);
+  return returnValue;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SPIJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SPIJNI.cpp
new file mode 100644
index 0000000..d594058
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SPIJNI.cpp
@@ -0,0 +1,500 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_SPIJNI.h"
+#include "hal/SPI.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+// set the logging level
+TLogLevel spiJNILogLevel = logWARNING;
+
+#define SPIJNI_LOG(level)     \
+  if (level > spiJNILogLevel) \
+    ;                         \
+  else                        \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiInitialize
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiInitialize
+  (JNIEnv* env, jclass, jint port)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiInitialize";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  int32_t status = 0;
+  HAL_InitializeSPI(static_cast<HAL_SPIPort>(port), &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatusForceThrow(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiTransaction
+ * Signature: (ILjava/lang/Object;Ljava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiTransaction
+  (JNIEnv* env, jclass, jint port, jobject dataToSend, jobject dataReceived,
+   jbyte size)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiTransaction";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  uint8_t* dataToSendPtr = nullptr;
+  if (dataToSend != 0) {
+    dataToSendPtr =
+        reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataToSend));
+  }
+  uint8_t* dataReceivedPtr =
+      reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
+  SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
+  SPIJNI_LOG(logDEBUG) << "DataToSendPtr = " << dataToSendPtr;
+  SPIJNI_LOG(logDEBUG) << "DataReceivedPtr = " << dataReceivedPtr;
+  jint retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port),
+                                   dataToSendPtr, dataReceivedPtr, size);
+  SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiTransactionB
+ * Signature: (I[B[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiTransactionB
+  (JNIEnv* env, jclass, jint port, jbyteArray dataToSend,
+   jbyteArray dataReceived, jbyte size)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiTransactionB";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
+  wpi::SmallVector<uint8_t, 128> recvBuf;
+  recvBuf.resize(size);
+  jint retVal =
+      HAL_TransactionSPI(static_cast<HAL_SPIPort>(port),
+                         reinterpret_cast<const uint8_t*>(
+                             JByteArrayRef(env, dataToSend).array().data()),
+                         recvBuf.data(), size);
+  env->SetByteArrayRegion(dataReceived, 0, size,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiWrite
+ * Signature: (ILjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiWrite
+  (JNIEnv* env, jclass, jint port, jobject dataToSend, jbyte size)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiWrite";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  uint8_t* dataToSendPtr = nullptr;
+  if (dataToSend != 0) {
+    dataToSendPtr =
+        reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataToSend));
+  }
+  SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
+  SPIJNI_LOG(logDEBUG) << "DataToSendPtr = " << dataToSendPtr;
+  jint retVal =
+      HAL_WriteSPI(static_cast<HAL_SPIPort>(port), dataToSendPtr, size);
+  SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiWriteB
+ * Signature: (I[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiWriteB
+  (JNIEnv* env, jclass, jint port, jbyteArray dataToSend, jbyte size)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiWriteB";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
+  jint retVal = HAL_WriteSPI(static_cast<HAL_SPIPort>(port),
+                             reinterpret_cast<const uint8_t*>(
+                                 JByteArrayRef(env, dataToSend).array().data()),
+                             size);
+  SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiRead
+ * Signature: (IZLjava/lang/Object;B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiRead
+  (JNIEnv* env, jclass, jint port, jboolean initiate, jobject dataReceived,
+   jbyte size)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiRead";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  SPIJNI_LOG(logDEBUG) << "Initiate = " << (jboolean)initiate;
+  uint8_t* dataReceivedPtr =
+      reinterpret_cast<uint8_t*>(env->GetDirectBufferAddress(dataReceived));
+  SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
+  SPIJNI_LOG(logDEBUG) << "DataReceivedPtr = " << dataReceivedPtr;
+  jint retVal;
+  if (initiate) {
+    wpi::SmallVector<uint8_t, 128> sendBuf;
+    sendBuf.resize(size);
+    retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port), sendBuf.data(),
+                                dataReceivedPtr, size);
+  } else {
+    retVal = HAL_ReadSPI(static_cast<HAL_SPIPort>(port),
+                         reinterpret_cast<uint8_t*>(dataReceivedPtr), size);
+  }
+  SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiReadB
+ * Signature: (IZ[BB)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiReadB
+  (JNIEnv* env, jclass, jint port, jboolean initiate, jbyteArray dataReceived,
+   jbyte size)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiReadB";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  SPIJNI_LOG(logDEBUG) << "Initiate = " << (jboolean)initiate;
+  SPIJNI_LOG(logDEBUG) << "Size = " << (jint)size;
+  jint retVal;
+  wpi::SmallVector<uint8_t, 128> recvBuf;
+  recvBuf.resize(size);
+  if (initiate) {
+    wpi::SmallVector<uint8_t, 128> sendBuf;
+    sendBuf.resize(size);
+    retVal = HAL_TransactionSPI(static_cast<HAL_SPIPort>(port), sendBuf.data(),
+                                recvBuf.data(), size);
+  } else {
+    retVal = HAL_ReadSPI(static_cast<HAL_SPIPort>(port), recvBuf.data(), size);
+  }
+  env->SetByteArrayRegion(dataReceived, 0, size,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  SPIJNI_LOG(logDEBUG) << "ReturnValue = " << (jint)retVal;
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiClose
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiClose
+  (JNIEnv*, jclass, jint port)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiClose";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  HAL_CloseSPI(static_cast<HAL_SPIPort>(port));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetSpeed
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetSpeed
+  (JNIEnv*, jclass, jint port, jint speed)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetSpeed";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  SPIJNI_LOG(logDEBUG) << "Speed = " << (jint)speed;
+  HAL_SetSPISpeed(static_cast<HAL_SPIPort>(port), speed);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetOpts
+ * Signature: (IIII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetOpts
+  (JNIEnv*, jclass, jint port, jint msb_first, jint sample_on_trailing,
+   jint clk_idle_high)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetOpts";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  SPIJNI_LOG(logDEBUG) << "msb_first = " << msb_first;
+  SPIJNI_LOG(logDEBUG) << "sample_on_trailing = " << sample_on_trailing;
+  SPIJNI_LOG(logDEBUG) << "clk_idle_high = " << clk_idle_high;
+  HAL_SetSPIOpts(static_cast<HAL_SPIPort>(port), msb_first, sample_on_trailing,
+                 clk_idle_high);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetChipSelectActiveHigh
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetChipSelectActiveHigh
+  (JNIEnv* env, jclass, jint port)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetCSActiveHigh";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveHigh(static_cast<HAL_SPIPort>(port), &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetChipSelectActiveLow
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetChipSelectActiveLow
+  (JNIEnv* env, jclass, jint port)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetCSActiveLow";
+  SPIJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveLow(static_cast<HAL_SPIPort>(port), &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiInitAuto
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiInitAuto
+  (JNIEnv* env, jclass, jint port, jint bufferSize)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiInitAuto";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  SPIJNI_LOG(logDEBUG) << "BufferSize = " << bufferSize;
+  int32_t status = 0;
+  HAL_InitSPIAuto(static_cast<HAL_SPIPort>(port), bufferSize, &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiFreeAuto
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiFreeAuto
+  (JNIEnv* env, jclass, jint port)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiFreeAuto";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  int32_t status = 0;
+  HAL_FreeSPIAuto(static_cast<HAL_SPIPort>(port), &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiStartAutoRate
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiStartAutoRate
+  (JNIEnv* env, jclass, jint port, jdouble period)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiStartAutoRate";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  SPIJNI_LOG(logDEBUG) << "Period = " << period;
+  int32_t status = 0;
+  HAL_StartSPIAutoRate(static_cast<HAL_SPIPort>(port), period, &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiStartAutoTrigger
+ * Signature: (IIIZZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiStartAutoTrigger
+  (JNIEnv* env, jclass, jint port, jint digitalSourceHandle,
+   jint analogTriggerType, jboolean triggerRising, jboolean triggerFalling)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiStartAutoTrigger";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  SPIJNI_LOG(logDEBUG) << "DigitalSourceHandle = " << digitalSourceHandle;
+  SPIJNI_LOG(logDEBUG) << "AnalogTriggerType = " << analogTriggerType;
+  SPIJNI_LOG(logDEBUG) << "TriggerRising = " << (jint)triggerRising;
+  SPIJNI_LOG(logDEBUG) << "TriggerFalling = " << (jint)triggerFalling;
+  int32_t status = 0;
+  HAL_StartSPIAutoTrigger(static_cast<HAL_SPIPort>(port), digitalSourceHandle,
+                          static_cast<HAL_AnalogTriggerType>(analogTriggerType),
+                          triggerRising, triggerFalling, &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiStopAuto
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiStopAuto
+  (JNIEnv* env, jclass, jint port)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiStopAuto";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  int32_t status = 0;
+  HAL_StopSPIAuto(static_cast<HAL_SPIPort>(port), &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiSetAutoTransmitData
+ * Signature: (I[BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiSetAutoTransmitData
+  (JNIEnv* env, jclass, jint port, jbyteArray dataToSend, jint zeroSize)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiSetAutoTransmitData";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  SPIJNI_LOG(logDEBUG) << "ZeroSize = " << zeroSize;
+  JByteArrayRef jarr(env, dataToSend);
+  int32_t status = 0;
+  HAL_SetSPIAutoTransmitData(
+      static_cast<HAL_SPIPort>(port),
+      reinterpret_cast<const uint8_t*>(jarr.array().data()),
+      jarr.array().size(), zeroSize, &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiForceAutoRead
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiForceAutoRead
+  (JNIEnv* env, jclass, jint port)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiForceAutoRead";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  int32_t status = 0;
+  HAL_ForceSPIAutoRead(static_cast<HAL_SPIPort>(port), &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiReadAutoReceivedData
+ * Signature: (ILjava/lang/Object;ID)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiReadAutoReceivedData__ILjava_nio_ByteBuffer_2ID
+  (JNIEnv* env, jclass, jint port, jobject buffer, jint numToRead,
+   jdouble timeout)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiReadAutoReceivedData";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  SPIJNI_LOG(logDEBUG) << "NumToRead = " << numToRead;
+  SPIJNI_LOG(logDEBUG) << "Timeout = " << timeout;
+  uint32_t* recvBuf =
+      reinterpret_cast<uint32_t*>(env->GetDirectBufferAddress(buffer));
+  int32_t status = 0;
+  jint retval = HAL_ReadSPIAutoReceivedData(
+      static_cast<HAL_SPIPort>(port), recvBuf, numToRead, timeout, &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  SPIJNI_LOG(logDEBUG) << "Return = " << retval;
+  CheckStatus(env, status);
+  return retval;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiReadAutoReceivedData
+ * Signature: (I[IID)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiReadAutoReceivedData__I_3IID
+  (JNIEnv* env, jclass, jint port, jintArray buffer, jint numToRead,
+   jdouble timeout)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiReadAutoReceivedData";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  SPIJNI_LOG(logDEBUG) << "NumToRead = " << numToRead;
+  SPIJNI_LOG(logDEBUG) << "Timeout = " << timeout;
+  wpi::SmallVector<uint32_t, 128> recvBuf;
+  recvBuf.resize(numToRead);
+  int32_t status = 0;
+  jint retval =
+      HAL_ReadSPIAutoReceivedData(static_cast<HAL_SPIPort>(port),
+                                  recvBuf.data(), numToRead, timeout, &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  SPIJNI_LOG(logDEBUG) << "Return = " << retval;
+  if (!CheckStatus(env, status)) return retval;
+  if (numToRead > 0) {
+    env->SetIntArrayRegion(buffer, 0, numToRead,
+                           reinterpret_cast<const jint*>(recvBuf.data()));
+  }
+  return retval;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SPIJNI
+ * Method:    spiGetAutoDroppedCount
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SPIJNI_spiGetAutoDroppedCount
+  (JNIEnv* env, jclass, jint port)
+{
+  SPIJNI_LOG(logDEBUG) << "Calling SPIJNI spiGetAutoDroppedCount";
+  SPIJNI_LOG(logDEBUG) << "Port = " << port;
+  int32_t status = 0;
+  auto retval =
+      HAL_GetSPIAutoDroppedCount(static_cast<HAL_SPIPort>(port), &status);
+  SPIJNI_LOG(logDEBUG) << "Status = " << status;
+  SPIJNI_LOG(logDEBUG) << "Return = " << retval;
+  CheckStatus(env, status);
+  return retval;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SerialPortJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SerialPortJNI.cpp
new file mode 100644
index 0000000..4524fe6
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SerialPortJNI.cpp
@@ -0,0 +1,369 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/jni_util.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_SerialPortJNI.h"
+#include "hal/SerialPort.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+using namespace wpi::java;
+
+// set the logging level
+TLogLevel serialJNILogLevel = logWARNING;
+
+#define SERIALJNI_LOG(level)     \
+  if (level > serialJNILogLevel) \
+    ;                            \
+  else                           \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialInitializePort
+ * Signature: (B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialInitializePort
+  (JNIEnv* env, jclass, jbyte port)
+{
+  SERIALJNI_LOG(logDEBUG) << "Calling Serial Initialize";
+  SERIALJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  int32_t status = 0;
+  HAL_InitializeSerialPort(static_cast<HAL_SerialPort>(port), &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatusForceThrow(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialInitializePortDirect
+ * Signature: (BLjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialInitializePortDirect
+  (JNIEnv* env, jclass, jbyte port, jstring portName)
+{
+  SERIALJNI_LOG(logDEBUG) << "Calling Serial Initialize Direct";
+  SERIALJNI_LOG(logDEBUG) << "Port = " << (jint)port;
+  JStringRef portNameRef{env, portName};
+  SERIALJNI_LOG(logDEBUG) << "PortName = " << portNameRef.c_str();
+  int32_t status = 0;
+  HAL_InitializeSerialPortDirect(static_cast<HAL_SerialPort>(port),
+                                 portNameRef.c_str(), &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatusForceThrow(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetBaudRate
+ * Signature: (BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetBaudRate
+  (JNIEnv* env, jclass, jbyte port, jint rate)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Baud Rate";
+  SERIALJNI_LOG(logDEBUG) << "Baud: " << rate;
+  int32_t status = 0;
+  HAL_SetSerialBaudRate(static_cast<HAL_SerialPort>(port), rate, &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetDataBits
+ * Signature: (BB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetDataBits
+  (JNIEnv* env, jclass, jbyte port, jbyte bits)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Data Bits";
+  SERIALJNI_LOG(logDEBUG) << "Data Bits: " << bits;
+  int32_t status = 0;
+  HAL_SetSerialDataBits(static_cast<HAL_SerialPort>(port), bits, &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetParity
+ * Signature: (BB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetParity
+  (JNIEnv* env, jclass, jbyte port, jbyte parity)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Parity";
+  SERIALJNI_LOG(logDEBUG) << "Parity: " << parity;
+  int32_t status = 0;
+  HAL_SetSerialParity(static_cast<HAL_SerialPort>(port), parity, &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetStopBits
+ * Signature: (BB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetStopBits
+  (JNIEnv* env, jclass, jbyte port, jbyte bits)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Stop Bits";
+  SERIALJNI_LOG(logDEBUG) << "Stop Bits: " << bits;
+  int32_t status = 0;
+  HAL_SetSerialStopBits(static_cast<HAL_SerialPort>(port), bits, &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetWriteMode
+ * Signature: (BB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetWriteMode
+  (JNIEnv* env, jclass, jbyte port, jbyte mode)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Write Mode";
+  SERIALJNI_LOG(logDEBUG) << "Write mode: " << mode;
+  int32_t status = 0;
+  HAL_SetSerialWriteMode(static_cast<HAL_SerialPort>(port), mode, &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetFlowControl
+ * Signature: (BB)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetFlowControl
+  (JNIEnv* env, jclass, jbyte port, jbyte flow)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Flow Control";
+  SERIALJNI_LOG(logDEBUG) << "Flow Control: " << flow;
+  int32_t status = 0;
+  HAL_SetSerialFlowControl(static_cast<HAL_SerialPort>(port), flow, &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetTimeout
+ * Signature: (BD)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetTimeout
+  (JNIEnv* env, jclass, jbyte port, jdouble timeout)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Timeout";
+  SERIALJNI_LOG(logDEBUG) << "Timeout: " << timeout;
+  int32_t status = 0;
+  HAL_SetSerialTimeout(static_cast<HAL_SerialPort>(port), timeout, &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialEnableTermination
+ * Signature: (BC)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialEnableTermination
+  (JNIEnv* env, jclass, jbyte port, jchar terminator)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Enable Termination";
+  SERIALJNI_LOG(logDEBUG) << "Terminator: " << terminator;
+  int32_t status = 0;
+  HAL_EnableSerialTermination(static_cast<HAL_SerialPort>(port), terminator,
+                              &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialDisableTermination
+ * Signature: (B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialDisableTermination
+  (JNIEnv* env, jclass, jbyte port)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Disable termination";
+  int32_t status = 0;
+  HAL_DisableSerialTermination(static_cast<HAL_SerialPort>(port), &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetReadBufferSize
+ * Signature: (BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetReadBufferSize
+  (JNIEnv* env, jclass, jbyte port, jint size)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Read Buffer Size";
+  SERIALJNI_LOG(logDEBUG) << "Size: " << size;
+  int32_t status = 0;
+  HAL_SetSerialReadBufferSize(static_cast<HAL_SerialPort>(port), size, &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialSetWriteBufferSize
+ * Signature: (BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialSetWriteBufferSize
+  (JNIEnv* env, jclass, jbyte port, jint size)
+{
+  SERIALJNI_LOG(logDEBUG) << "Setting Serial Write Buffer Size";
+  SERIALJNI_LOG(logDEBUG) << "Size: " << size;
+  int32_t status = 0;
+  HAL_SetSerialWriteBufferSize(static_cast<HAL_SerialPort>(port), size,
+                               &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialGetBytesReceived
+ * Signature: (B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialGetBytesReceived
+  (JNIEnv* env, jclass, jbyte port)
+{
+  SERIALJNI_LOG(logDEBUG) << "Serial Get Bytes Received";
+  int32_t status = 0;
+  jint retVal =
+      HAL_GetSerialBytesReceived(static_cast<HAL_SerialPort>(port), &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialRead
+ * Signature: (B[BI)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialRead
+  (JNIEnv* env, jclass, jbyte port, jbyteArray dataReceived, jint size)
+{
+  SERIALJNI_LOG(logDEBUG) << "Serial Read";
+  wpi::SmallVector<char, 128> recvBuf;
+  recvBuf.resize(size);
+  int32_t status = 0;
+  jint retVal = HAL_ReadSerial(static_cast<HAL_SerialPort>(port),
+                               recvBuf.data(), size, &status);
+  env->SetByteArrayRegion(dataReceived, 0, size,
+                          reinterpret_cast<const jbyte*>(recvBuf.data()));
+  SERIALJNI_LOG(logDEBUG) << "ReturnValue = " << retVal;
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialWrite
+ * Signature: (B[BI)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialWrite
+  (JNIEnv* env, jclass, jbyte port, jbyteArray dataToSend, jint size)
+{
+  SERIALJNI_LOG(logDEBUG) << "Serial Write";
+  int32_t status = 0;
+  jint retVal =
+      HAL_WriteSerial(static_cast<HAL_SerialPort>(port),
+                      reinterpret_cast<const char*>(
+                          JByteArrayRef(env, dataToSend).array().data()),
+                      size, &status);
+  SERIALJNI_LOG(logDEBUG) << "ReturnValue = " << retVal;
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+  return retVal;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialFlush
+ * Signature: (B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialFlush
+  (JNIEnv* env, jclass, jbyte port)
+{
+  SERIALJNI_LOG(logDEBUG) << "Serial Flush";
+  int32_t status = 0;
+  HAL_FlushSerial(static_cast<HAL_SerialPort>(port), &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialClear
+ * Signature: (B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialClear
+  (JNIEnv* env, jclass, jbyte port)
+{
+  SERIALJNI_LOG(logDEBUG) << "Serial Clear";
+  int32_t status = 0;
+  HAL_ClearSerial(static_cast<HAL_SerialPort>(port), &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SerialPortJNI
+ * Method:    serialClose
+ * Signature: (B)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SerialPortJNI_serialClose
+  (JNIEnv* env, jclass, jbyte port)
+{
+  SERIALJNI_LOG(logDEBUG) << "Serial Close";
+  int32_t status = 0;
+  HAL_CloseSerial(static_cast<HAL_SerialPort>(port), &status);
+  SERIALJNI_LOG(logDEBUG) << "Status = " << status;
+  CheckStatus(env, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SolenoidJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SolenoidJNI.cpp
new file mode 100644
index 0000000..524b70e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/SolenoidJNI.cpp
@@ -0,0 +1,242 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_SolenoidJNI.h"
+#include "hal/Ports.h"
+#include "hal/Solenoid.h"
+#include "hal/cpp/Log.h"
+#include "hal/handles/HandlesInternal.h"
+
+using namespace frc;
+
+TLogLevel solenoidJNILogLevel = logERROR;
+
+#define SOLENOIDJNI_LOG(level)     \
+  if (level > solenoidJNILogLevel) \
+    ;                              \
+  else                             \
+    Log().Get(level)
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    initializeSolenoidPort
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_initializeSolenoidPort
+  (JNIEnv* env, jclass, jint id)
+{
+  SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI initializeSolenoidPort";
+
+  SOLENOIDJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_PortHandle)id;
+
+  int32_t status = 0;
+  HAL_SolenoidHandle handle =
+      HAL_InitializeSolenoidPort((HAL_PortHandle)id, &status);
+
+  SOLENOIDJNI_LOG(logDEBUG) << "Status = " << status;
+  SOLENOIDJNI_LOG(logDEBUG) << "Solenoid Port Handle = " << handle;
+
+  // Use solenoid channels, as we have to pick one.
+  CheckStatusRange(env, status, 0, HAL_GetNumSolenoidChannels(),
+                   hal::getPortHandleChannel((HAL_PortHandle)id));
+  return (jint)handle;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    checkSolenoidChannel
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_checkSolenoidChannel
+  (JNIEnv* env, jclass, jint channel)
+{
+  SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI checkSolenoidChannel";
+  SOLENOIDJNI_LOG(logDEBUG) << "Channel = " << channel;
+  return HAL_CheckSolenoidChannel(channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    checkSolenoidModule
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_checkSolenoidModule
+  (JNIEnv* env, jclass, jint module)
+{
+  SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI checkSolenoidModule";
+  SOLENOIDJNI_LOG(logDEBUG) << "Module = " << module;
+  return HAL_CheckSolenoidModule(module);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    freeSolenoidPort
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_freeSolenoidPort
+  (JNIEnv* env, jclass, jint id)
+{
+  SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI initializeSolenoidPort";
+
+  SOLENOIDJNI_LOG(logDEBUG) << "Port Handle = " << (HAL_SolenoidHandle)id;
+  HAL_FreeSolenoidPort((HAL_SolenoidHandle)id);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    setSolenoid
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_setSolenoid
+  (JNIEnv* env, jclass, jint solenoid_port, jboolean value)
+{
+  SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI SetSolenoid";
+
+  SOLENOIDJNI_LOG(logDEBUG)
+      << "Solenoid Port Handle = " << (HAL_SolenoidHandle)solenoid_port;
+
+  int32_t status = 0;
+  HAL_SetSolenoid((HAL_SolenoidHandle)solenoid_port, value, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getSolenoid
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getSolenoid
+  (JNIEnv* env, jclass, jint solenoid_port)
+{
+  int32_t status = 0;
+  jboolean val = HAL_GetSolenoid((HAL_SolenoidHandle)solenoid_port, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getAllSolenoids
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getAllSolenoids
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  jint val = HAL_GetAllSolenoids(module, &status);
+  CheckStatus(env, status);
+  return val;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getPCMSolenoidBlackList
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getPCMSolenoidBlackList
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  jint val = HAL_GetPCMSolenoidBlackList(module, &status);
+  CheckStatus(env, status);
+  return val;
+}
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getPCMSolenoidVoltageStickyFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getPCMSolenoidVoltageStickyFault
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  bool val = HAL_GetPCMSolenoidVoltageStickyFault(module, &status);
+  CheckStatus(env, status);
+  return val;
+}
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    getPCMSolenoidVoltageFault
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_getPCMSolenoidVoltageFault
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  bool val = HAL_GetPCMSolenoidVoltageFault(module, &status);
+  CheckStatus(env, status);
+  return val;
+}
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    clearAllPCMStickyFaults
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_clearAllPCMStickyFaults
+  (JNIEnv* env, jclass, jint module)
+{
+  int32_t status = 0;
+  HAL_ClearAllPCMStickyFaults(module, &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    setOneShotDuration
+ * Signature: (IJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_setOneShotDuration
+  (JNIEnv* env, jclass, jint solenoid_port, jlong durationMS)
+{
+  SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI SetOneShotDuration";
+
+  SOLENOIDJNI_LOG(logDEBUG)
+      << "Solenoid Port Handle = " << (HAL_SolenoidHandle)solenoid_port;
+  SOLENOIDJNI_LOG(logDEBUG) << "Duration (MS) = " << durationMS;
+
+  int32_t status = 0;
+  HAL_SetOneShotDuration((HAL_SolenoidHandle)solenoid_port, durationMS,
+                         &status);
+  CheckStatus(env, status);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_SolenoidJNI
+ * Method:    fireOneShot
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_SolenoidJNI_fireOneShot
+  (JNIEnv* env, jclass, jint solenoid_port)
+{
+  SOLENOIDJNI_LOG(logDEBUG) << "Calling SolenoidJNI fireOneShot";
+
+  SOLENOIDJNI_LOG(logDEBUG)
+      << "Solenoid Port Handle = " << (HAL_SolenoidHandle)solenoid_port;
+
+  int32_t status = 0;
+  HAL_FireOneShot((HAL_SolenoidHandle)solenoid_port, &status);
+  CheckStatus(env, status);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/ThreadsJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/ThreadsJNI.cpp
new file mode 100644
index 0000000..ea3cac6
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/cpp/jni/ThreadsJNI.cpp
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <jni.h>
+
+#include <cassert>
+
+#include "HALUtil.h"
+#include "edu_wpi_first_hal_ThreadsJNI.h"
+#include "hal/Threads.h"
+#include "hal/cpp/Log.h"
+
+using namespace frc;
+
+// set the logging level
+TLogLevel threadsJNILogLevel = logWARNING;
+
+#define THREADSJNI_LOG(level)     \
+  if (level > threadsJNILogLevel) \
+    ;                             \
+  else                            \
+    Log().Get(level)
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_ThreadsJNI
+ * Method:    getCurrentThreadPriority
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_ThreadsJNI_getCurrentThreadPriority
+  (JNIEnv* env, jclass)
+{
+  THREADSJNI_LOG(logDEBUG) << "Callling GetCurrentThreadPriority";
+  int32_t status = 0;
+  HAL_Bool isRT = false;
+  auto ret = HAL_GetCurrentThreadPriority(&isRT, &status);
+  CheckStatus(env, status);
+  return (jint)ret;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_ThreadsJNI
+ * Method:    getCurrentThreadIsRealTime
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_ThreadsJNI_getCurrentThreadIsRealTime
+  (JNIEnv* env, jclass)
+{
+  THREADSJNI_LOG(logDEBUG) << "Callling GetCurrentThreadIsRealTime";
+  int32_t status = 0;
+  HAL_Bool isRT = false;
+  HAL_GetCurrentThreadPriority(&isRT, &status);
+  CheckStatus(env, status);
+  return (jboolean)isRT;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_ThreadsJNI
+ * Method:    setCurrentThreadPriority
+ * Signature: (ZI)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_ThreadsJNI_setCurrentThreadPriority
+  (JNIEnv* env, jclass, jboolean realTime, jint priority)
+{
+  THREADSJNI_LOG(logDEBUG) << "Callling SetCurrentThreadPriority";
+  int32_t status = 0;
+  auto ret = HAL_SetCurrentThreadPriority(
+      (HAL_Bool)realTime, static_cast<int32_t>(priority), &status);
+  CheckStatus(env, status);
+  return (jboolean)ret;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Accelerometer.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Accelerometer.h
new file mode 100644
index 0000000..9dc488b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Accelerometer.h
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_accelerometer Accelerometer Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+// clang-format off
+/**
+ * The acceptable accelerometer ranges.
+ */
+HAL_ENUM(HAL_AccelerometerRange) {
+  HAL_AccelerometerRange_k2G = 0,
+  HAL_AccelerometerRange_k4G = 1,
+  HAL_AccelerometerRange_k8G = 2,
+};
+// clang-format on
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+/**
+ * Sets the accelerometer to active or standby mode.
+ *
+ * It must be in standby mode to change any configuration.
+ *
+ * @param active true to set to active, false for standby
+ */
+void HAL_SetAccelerometerActive(HAL_Bool active);
+
+/**
+ * Sets the range of values that can be measured (either 2, 4, or 8 g-forces).
+ *
+ * The accelerometer should be in standby mode when this is called.
+ *
+ * @param range the accelerometer range
+ */
+void HAL_SetAccelerometerRange(HAL_AccelerometerRange range);
+
+/**
+ * Gets the x-axis acceleration.
+ *
+ * This is a floating point value in units of 1 g-force.
+ *
+ * @return the X acceleration
+ */
+double HAL_GetAccelerometerX(void);
+
+/**
+ * Gets the y-axis acceleration.
+ *
+ * This is a floating point value in units of 1 g-force.
+ *
+ * @return the Y acceleration
+ */
+double HAL_GetAccelerometerY(void);
+
+/**
+ * Gets the z-axis acceleration.
+ *
+ * This is a floating point value in units of 1 g-force.
+ *
+ * @return the Z acceleration
+ */
+double HAL_GetAccelerometerZ(void);
+#ifdef __cplusplus
+}  // extern "C"
+/** @} */
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogAccumulator.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogAccumulator.h
new file mode 100644
index 0000000..9e49e90
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogAccumulator.h
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_analogaccumulator Analog Accumulator Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Is the channel attached to an accumulator.
+ *
+ * @param analogPortHandle Handle to the analog port.
+ * @return The analog channel is attached to an accumulator.
+ */
+HAL_Bool HAL_IsAccumulatorChannel(HAL_AnalogInputHandle analogPortHandle,
+                                  int32_t* status);
+
+/**
+ * Initialize the accumulator.
+ *
+ * @param analogPortHandle Handle to the analog port.
+ */
+void HAL_InitAccumulator(HAL_AnalogInputHandle analogPortHandle,
+                         int32_t* status);
+
+/**
+ * Resets the accumulator to the initial value.
+ *
+ * @param analogPortHandle Handle to the analog port.
+ */
+void HAL_ResetAccumulator(HAL_AnalogInputHandle analogPortHandle,
+                          int32_t* status);
+
+/**
+ * Set the center value of the accumulator.
+ *
+ * The center value is subtracted from each A/D value before it is added to the
+ * accumulator. This is used for the center value of devices like gyros and
+ * accelerometers to make integration work and to take the device offset into
+ * account when integrating.
+ *
+ * This center value is based on the output of the oversampled and averaged
+ * source from channel 1. Because of this, any non-zero oversample bits will
+ * affect the size of the value for this field.
+ *
+ * @param analogPortHandle Handle to the analog port.
+ * @param center The center value of the accumulator.
+ */
+void HAL_SetAccumulatorCenter(HAL_AnalogInputHandle analogPortHandle,
+                              int32_t center, int32_t* status);
+
+/**
+ * Set the accumulator's deadband.
+ *
+ * @param analogPortHandle Handle to the analog port.
+ * @param deadband The deadband of the accumulator.
+ */
+void HAL_SetAccumulatorDeadband(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t deadband, int32_t* status);
+
+/**
+ * Read the accumulated value.
+ *
+ * Read the value that has been accumulating on channel 1.
+ * The accumulator is attached after the oversample and average engine.
+ *
+ * @param analogPortHandle Handle to the analog port.
+ * @return The 64-bit value accumulated since the last Reset().
+ */
+int64_t HAL_GetAccumulatorValue(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t* status);
+
+/**
+ * Read the number of accumulated values.
+ *
+ * Read the count of the accumulated values since the accumulator was last
+ * Reset().
+ *
+ * @param analogPortHandle Handle to the analog port.
+ * @return The number of times samples from the channel were accumulated.
+ */
+int64_t HAL_GetAccumulatorCount(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t* status);
+
+/**
+ * Read the accumulated value and the number of accumulated values atomically.
+ *
+ * This function reads the value and count from the FPGA atomically.
+ * This can be used for averaging.
+ *
+ * @param analogPortHandle Handle to the analog port.
+ * @param value Pointer to the 64-bit accumulated output.
+ * @param count Pointer to the number of accumulation cycles.
+ */
+void HAL_GetAccumulatorOutput(HAL_AnalogInputHandle analogPortHandle,
+                              int64_t* value, int64_t* count, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogGyro.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogGyro.h
new file mode 100644
index 0000000..54030bd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogGyro.h
@@ -0,0 +1,138 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_analoggyro Analog Gyro Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes an analog gyro.
+ *
+ * @param handle handle to the analog port
+ * @return       the initialized gyro handle
+ */
+HAL_GyroHandle HAL_InitializeAnalogGyro(HAL_AnalogInputHandle handle,
+                                        int32_t* status);
+
+/**
+ * Sets up an analog gyro with the proper offsets and settings for the KOP
+ * analog gyro.
+ *
+ * @param handle the gyro handle
+ */
+void HAL_SetupAnalogGyro(HAL_GyroHandle handle, int32_t* status);
+
+/**
+ * Frees an analog gyro.
+ *
+ * @param handle the gyro handle
+ */
+void HAL_FreeAnalogGyro(HAL_GyroHandle handle);
+
+/**
+ * Sets the analog gyro parameters to the specified values.
+ *
+ * This is meant to be used if you want to reuse the values from a previous
+ * calibration.
+ *
+ * @param handle                  the gyro handle
+ * @param voltsPerDegreePerSecond the gyro volts scaling
+ * @param offset                  the gyro offset
+ * @param center                  the gyro center
+ */
+void HAL_SetAnalogGyroParameters(HAL_GyroHandle handle,
+                                 double voltsPerDegreePerSecond, double offset,
+                                 int32_t center, int32_t* status);
+
+/**
+ * Sets the analog gyro volts per degrees per second scaling.
+ *
+ * @param handle                  the gyro handle
+ * @param voltsPerDegreePerSecond the gyro volts scaling
+ */
+void HAL_SetAnalogGyroVoltsPerDegreePerSecond(HAL_GyroHandle handle,
+                                              double voltsPerDegreePerSecond,
+                                              int32_t* status);
+
+/**
+ * Resets the analog gyro value to 0.
+ *
+ * @param handle the gyro handle
+ */
+void HAL_ResetAnalogGyro(HAL_GyroHandle handle, int32_t* status);
+
+/**
+ * Calibrates the analog gyro.
+ *
+ * This happens by calculating the average value of the gyro over 5 seconds, and
+ * setting that as the center. Note that this call blocks for 5 seconds to
+ * perform this.
+ *
+ * @param handle the gyro handle
+ */
+void HAL_CalibrateAnalogGyro(HAL_GyroHandle handle, int32_t* status);
+
+/**
+ * Sets the deadband of the analog gyro.
+ *
+ * @param handle the gyro handle
+ * @param volts  the voltage deadband
+ */
+void HAL_SetAnalogGyroDeadband(HAL_GyroHandle handle, double volts,
+                               int32_t* status);
+
+/**
+ * Gets the gyro angle in degrees.
+ *
+ * @param handle the gyro handle
+ * @return the gyro angle in degrees
+ */
+double HAL_GetAnalogGyroAngle(HAL_GyroHandle handle, int32_t* status);
+
+/**
+ * Gets the gyro rate in degrees/second.
+ *
+ * @param handle the gyro handle
+ * @return the gyro rate in degrees/second
+ */
+double HAL_GetAnalogGyroRate(HAL_GyroHandle handle, int32_t* status);
+
+/**
+ * Gets the calibrated gyro offset.
+ *
+ * Can be used to not repeat a calibration but reconstruct the gyro object.
+ *
+ * @param handle the gyro handle
+ * @return the gryo offset
+ */
+double HAL_GetAnalogGyroOffset(HAL_GyroHandle handle, int32_t* status);
+
+/**
+ * Gets the calibrated gyro center.
+ *
+ * Can be used to not repeat a calibration but reconstruct the gyro object.
+ *
+ * @param handle the gyro handle
+ * @return the gyro center
+ */
+int32_t HAL_GetAnalogGyroCenter(HAL_GyroHandle handle, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogInput.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogInput.h
new file mode 100644
index 0000000..45e6662
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogInput.h
@@ -0,0 +1,230 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_analoginput Analog Input Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes the analog input port using the given port object.
+ *
+ * @param portHandle Handle to the port to initialize.
+ * @return           the created analog input handle
+ */
+HAL_AnalogInputHandle HAL_InitializeAnalogInputPort(HAL_PortHandle portHandle,
+                                                    int32_t* status);
+
+/**
+ * Frees an analog input port.
+ *
+ * @param analogPortHandle Handle to the analog port.
+ */
+void HAL_FreeAnalogInputPort(HAL_AnalogInputHandle analogPortHandle);
+
+/**
+ * Checks that the analog module number is valid.
+ *
+ * @param module The analog module number.
+ * @return Analog module is valid and present
+ */
+HAL_Bool HAL_CheckAnalogModule(int32_t module);
+
+/**
+ * Checks that the analog output channel number is value.
+ * Verifies that the analog channel number is one of the legal channel numbers.
+ * Channel numbers are 0-based.
+ *
+ * @param channel The analog output channel number.
+ * @return Analog channel is valid
+ */
+HAL_Bool HAL_CheckAnalogInputChannel(int32_t channel);
+
+/**
+ * Sets the sample rate.
+ *
+ * This is a global setting for the Athena and effects all channels.
+ *
+ * @param samplesPerSecond The number of samples per channel per second.
+ */
+void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status);
+
+/**
+ * Gets the current sample rate.
+ *
+ * This assumes one entry in the scan list.
+ * This is a global setting for the Athena and effects all channels.
+ *
+ * @return Sample rate.
+ */
+double HAL_GetAnalogSampleRate(int32_t* status);
+
+/**
+ * Sets the number of averaging bits.
+ *
+ * This sets the number of averaging bits. The actual number of averaged samples
+ * is 2**bits. Use averaging to improve the stability of your measurement at the
+ * expense of sampling rate. The averaging is done automatically in the FPGA.
+ *
+ * @param analogPortHandle Handle to the analog port to configure.
+ * @param bits Number of bits to average.
+ */
+void HAL_SetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
+                              int32_t bits, int32_t* status);
+
+/**
+ * Gets the number of averaging bits.
+ *
+ * This gets the number of averaging bits from the FPGA. The actual number of
+ * averaged samples is 2**bits. The averaging is done automatically in the FPGA.
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @return Bits to average.
+ */
+int32_t HAL_GetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t* status);
+
+/**
+ * Sets the number of oversample bits.
+ *
+ * This sets the number of oversample bits. The actual number of oversampled
+ * values is 2**bits. Use oversampling to improve the resolution of your
+ * measurements at the expense of sampling rate. The oversampling is done
+ * automatically in the FPGA.
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @param bits Number of bits to oversample.
+ */
+void HAL_SetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t bits, int32_t* status);
+
+/**
+ * Gets the number of oversample bits.
+ *
+ * This gets the number of oversample bits from the FPGA. The actual number of
+ * oversampled values is 2**bits. The oversampling is done automatically in the
+ * FPGA.
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @return Bits to oversample.
+ */
+int32_t HAL_GetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
+                                    int32_t* status);
+
+/**
+ * Gets a sample straight from the channel on this module.
+ *
+ * The sample is a 12-bit value representing the 0V to 5V range of the A/D
+ * converter in the module. The units are in A/D converter codes.  Use
+ * GetVoltage() to get the analog value in calibrated units.
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @return A sample straight from the channel on this module.
+ */
+int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle,
+                           int32_t* status);
+
+/**
+ * Gets a sample from the output of the oversample and average engine for the
+ * channel.
+ *
+ * The sample is 12-bit + the value configured in SetOversampleBits().
+ * The value configured in SetAverageBits() will cause this value to be averaged
+ * 2**bits number of samples. This is not a sliding window.  The sample will not
+ * change until 2**(OversamplBits + AverageBits) samples have been acquired from
+ * the module on this channel. Use GetAverageVoltage() to get the analog value
+ * in calibrated units.
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @return A sample from the oversample and average engine for the channel.
+ */
+int32_t HAL_GetAnalogAverageValue(HAL_AnalogInputHandle analogPortHandle,
+                                  int32_t* status);
+
+/**
+ * Converts a voltage to a raw value for a specified channel.
+ *
+ * This process depends on the calibration of each channel, so the channel must
+ * be specified.
+ *
+ * @todo This assumes raw values.  Oversampling not supported as is.
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @param voltage The voltage to convert.
+ * @return The raw value for the channel.
+ */
+int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle,
+                                  double voltage, int32_t* status);
+
+/**
+ * Gets a scaled sample straight from the channel on this module.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from
+ * GetLSBWeight() and GetOffset().
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @return A scaled sample straight from the channel on this module.
+ */
+double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle,
+                            int32_t* status);
+
+/**
+ * Gets a scaled sample from the output of the oversample and average engine for
+ * the channel.
+ *
+ * The value is scaled to units of Volts using the calibrated scaling data from
+ * GetLSBWeight() and GetOffset(). Using oversampling will cause this value to
+ * be higher resolution, but it will update more slowly. Using averaging will
+ * cause this value to be more stable, but it will update more slowly.
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @return A scaled sample from the output of the oversample and average engine
+ * for the channel.
+ */
+double HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analogPortHandle,
+                                   int32_t* status);
+
+/**
+ * Gets the factory scaling least significant bit weight constant.
+ * The least significant bit weight constant for the channel that was calibrated
+ * in manufacturing and stored in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @return Least significant bit weight.
+ */
+int32_t HAL_GetAnalogLSBWeight(HAL_AnalogInputHandle analogPortHandle,
+                               int32_t* status);
+
+/**
+ * Gets the factory scaling offset constant.
+ * The offset constant for the channel that was calibrated in manufacturing and
+ * stored in an eeprom in the module.
+ *
+ * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+ *
+ * @param analogPortHandle Handle to the analog port to use.
+ * @return Offset constant.
+ */
+int32_t HAL_GetAnalogOffset(HAL_AnalogInputHandle analogPortHandle,
+                            int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogOutput.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogOutput.h
new file mode 100644
index 0000000..ba0d93b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogOutput.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_analogoutput Analog Output Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes the analog output port using the given port object.
+ *
+ * @param handle handle to the port
+ * @return       the created analog output handle
+ */
+HAL_AnalogOutputHandle HAL_InitializeAnalogOutputPort(HAL_PortHandle portHandle,
+                                                      int32_t* status);
+
+/**
+ * Frees an analog output port.
+ *
+ * @param analogOutputHandle the analog output handle
+ */
+void HAL_FreeAnalogOutputPort(HAL_AnalogOutputHandle analogOutputHandle);
+
+/**
+ * Sets an analog output value.
+ *
+ * @param analogOutputHandle the analog output handle
+ * @param voltage            the voltage (0-5v) to output
+ */
+void HAL_SetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle,
+                         double voltage, int32_t* status);
+
+/**
+ * Gets the current analog output value.
+ *
+ * @param analogOutputHandle the analog output handle
+ * @return                   the current output voltage (0-5v)
+ */
+double HAL_GetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle,
+                           int32_t* status);
+
+/**
+ * Checks that the analog output channel number is value.
+ *
+ * Verifies that the analog channel number is one of the legal channel numbers.
+ * Channel numbers are 0-based.
+ *
+ * @return Analog channel is valid
+ */
+HAL_Bool HAL_CheckAnalogOutputChannel(int32_t channel);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogTrigger.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogTrigger.h
new file mode 100644
index 0000000..f461f1d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/AnalogTrigger.h
@@ -0,0 +1,143 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_analogtrigger Analog Trigger Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+// clang-format off
+/**
+ * The type of analog trigger to trigger on.
+ */
+HAL_ENUM(HAL_AnalogTriggerType) {
+  HAL_Trigger_kInWindow = 0,
+  HAL_Trigger_kState = 1,
+  HAL_Trigger_kRisingPulse = 2,
+  HAL_Trigger_kFallingPulse = 3
+};
+// clang-format on
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes an analog trigger.
+ *
+ * @param portHandle the analog input to use for triggering
+ * @param index      the trigger index value (output)
+ * @return           the created analog trigger handle
+ */
+HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger(
+    HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status);
+
+/**
+ * Frees an analog trigger.
+ *
+ * @param analogTriggerHandle the trigger handle
+ */
+void HAL_CleanAnalogTrigger(HAL_AnalogTriggerHandle analogTriggerHandle,
+                            int32_t* status);
+
+/**
+ * Sets the raw ADC upper and lower limits of the analog trigger.
+ *
+ * HAL_SetAnalogTriggerLimitsVoltage is likely better in most cases.
+ *
+ * @param analogTriggerHandle the trigger handle
+ * @param lower               the lower ADC value
+ * @param upper               the upper ADC value
+ */
+void HAL_SetAnalogTriggerLimitsRaw(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                   int32_t lower, int32_t upper,
+                                   int32_t* status);
+
+/**
+ * Sets the upper and lower limits of the analog trigger.
+ *
+ * The limits are given as floating point voltage values.
+ *
+ * @param analogTriggerHandle the trigger handle
+ * @param lower               the lower voltage value
+ * @param upper               the upper voltage value
+ */
+void HAL_SetAnalogTriggerLimitsVoltage(
+    HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
+    int32_t* status);
+
+/**
+ * Configures the analog trigger to use the averaged vs. raw values.
+ *
+ * If the value is true, then the averaged value is selected for the analog
+ * trigger, otherwise the immediate value is used.
+ *
+ * @param analogTriggerHandle the trigger handle
+ * @param useAveragedValue    true to use averaged values, false for raw
+ */
+void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                  HAL_Bool useAveragedValue, int32_t* status);
+
+/**
+ * Configures the analog trigger to use a filtered value.
+ *
+ * The analog trigger will operate with a 3 point average rejection filter. This
+ * is designed to help with 360 degree pot applications for the period where the
+ * pot crosses through zero.
+ *
+ * @param analogTriggerHandle the trigger handle
+ * @param useFilteredValue    true to use filtered values, false for average or
+ * raw
+ */
+void HAL_SetAnalogTriggerFiltered(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                  HAL_Bool useFilteredValue, int32_t* status);
+
+/**
+ * Returns the InWindow output of the analog trigger.
+ *
+ * True if the analog input is between the upper and lower limits.
+ *
+ * @param analogTriggerHandle the trigger handle
+ * @return                    the InWindow output of the analog trigger
+ */
+HAL_Bool HAL_GetAnalogTriggerInWindow(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status);
+
+/**
+ * Returns the TriggerState output of the analog trigger.
+ *
+ * True if above upper limit.
+ * False if below lower limit.
+ * If in Hysteresis, maintain previous state.
+ *
+ * @param analogTriggerHandle the trigger handle
+ * @return                    the TriggerState output of the analog trigger
+ */
+HAL_Bool HAL_GetAnalogTriggerTriggerState(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status);
+
+/**
+ * Gets the state of the analog trigger output.
+ *
+ * @param analogTriggerHandle the trigger handle
+ * @param type                the type of trigger to trigger on
+ * @return                    the state of the analog trigger output
+ */
+HAL_Bool HAL_GetAnalogTriggerOutput(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                    HAL_AnalogTriggerType type,
+                                    int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/CAN.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/CAN.h
new file mode 100644
index 0000000..8cc9c17
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/CAN.h
@@ -0,0 +1,124 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_canstream CAN Stream Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+// These are copies of defines located in CANSessionMux.h prepended with HAL_
+
+#define HAL_CAN_SEND_PERIOD_NO_REPEAT 0
+#define HAL_CAN_SEND_PERIOD_STOP_REPEATING -1
+
+/* Flags in the upper bits of the messageID */
+#define HAL_CAN_IS_FRAME_REMOTE 0x80000000
+#define HAL_CAN_IS_FRAME_11BIT 0x40000000
+
+#define HAL_ERR_CANSessionMux_InvalidBuffer -44086
+#define HAL_ERR_CANSessionMux_MessageNotFound -44087
+#define HAL_WARN_CANSessionMux_NoToken 44087
+#define HAL_ERR_CANSessionMux_NotAllowed -44088
+#define HAL_ERR_CANSessionMux_NotInitialized -44089
+#define HAL_ERR_CANSessionMux_SessionOverrun 44050
+
+/**
+ * Storage for CAN Stream Messages.
+ */
+struct HAL_CANStreamMessage {
+  uint32_t messageID;
+  uint32_t timeStamp;
+  uint8_t data[8];
+  uint8_t dataSize;
+};
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Sends a CAN message.
+ *
+ * @param messageID the CAN ID to send
+ * @param data      the data to send (0-8 bytes)
+ * @param dataSize  the size of the data to send (0-8 bytes)
+ * @param periodMs  the period to repeat the packet at. Use
+ * HAL_CAN_SEND_PERIOD_NO_REPEAT to not repeat.
+ */
+void HAL_CAN_SendMessage(uint32_t messageID, const uint8_t* data,
+                         uint8_t dataSize, int32_t periodMs, int32_t* status);
+
+/**
+ * Receives a CAN message.
+ *
+ * @param messageID     store for the received message ID
+ * @param messageIDMask the message ID mask to look for
+ * @param data          data output (8 bytes)
+ * @param dataSize      data length (0-8 bytes)
+ * @param timeStamp     the packet received timestamp (based off of
+ * CLOCK_MONOTONIC)
+ */
+void HAL_CAN_ReceiveMessage(uint32_t* messageID, uint32_t messageIDMask,
+                            uint8_t* data, uint8_t* dataSize,
+                            uint32_t* timeStamp, int32_t* status);
+
+/**
+ * Opens a CAN stream.
+ *
+ * @param sessionHandle output for the session handle
+ * @param messageID     the message ID to read
+ * @param messageIDMask the mssage ID mask
+ * @param maxMessages   the maximum number of messages to stream
+ */
+void HAL_CAN_OpenStreamSession(uint32_t* sessionHandle, uint32_t messageID,
+                               uint32_t messageIDMask, uint32_t maxMessages,
+                               int32_t* status);
+
+/**
+ * Closes a CAN stream.
+ *
+ * @param sessionHandle the session to close
+ */
+void HAL_CAN_CloseStreamSession(uint32_t sessionHandle);
+
+/**
+ * Reads a CAN stream message.
+ *
+ * @param sessionHandle  the session handle
+ * @param messages       array of messages
+ * @param messagesToRead the max number of messages to read
+ * @param messageRead    the number of messages actually read
+ */
+void HAL_CAN_ReadStreamSession(uint32_t sessionHandle,
+                               struct HAL_CANStreamMessage* messages,
+                               uint32_t messagesToRead, uint32_t* messagesRead,
+                               int32_t* status);
+
+/**
+ * Gets CAN status information.
+ *
+ * @param percentBusUtilization the bus utilization
+ * @param busOffCount           the number of bus off errors
+ * @param txFullCount           the number of tx full errors
+ * @param receiveErrorCount     the number of receive errors
+ * @param transmitErrorCount    the number of transmit errors
+ */
+void HAL_CAN_GetCANStatus(float* percentBusUtilization, uint32_t* busOffCount,
+                          uint32_t* txFullCount, uint32_t* receiveErrorCount,
+                          uint32_t* transmitErrorCount, int32_t* status);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/CANAPI.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/CANAPI.h
new file mode 100644
index 0000000..48c254d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/CANAPI.h
@@ -0,0 +1,162 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/CANAPITypes.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_canapi CAN API Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a CAN device.
+ *
+ * These follow the FIRST standard CAN layout. Link TBD
+ *
+ * @param manufacturer the can manufacturer
+ * @param deviceId     the device ID (0-63)
+ * @param deviceType   the device type
+ * @return             the created CAN handle
+ */
+HAL_CANHandle HAL_InitializeCAN(HAL_CANManufacturer manufacturer,
+                                int32_t deviceId, HAL_CANDeviceType deviceType,
+                                int32_t* status);
+
+/**
+ * Frees a CAN device
+ *
+ * @param handle the CAN handle
+ */
+void HAL_CleanCAN(HAL_CANHandle handle);
+
+/**
+ * Writes a packet to the CAN device with a specific ID.
+ *
+ * This ID is 10 bits.
+ *
+ * @param handle the CAN handle
+ * @param data   the data to write (0-8 bytes)
+ * @param length the length of data (0-8)
+ * @param apiId  the ID to write (0-1023 bits)
+ */
+void HAL_WriteCANPacket(HAL_CANHandle handle, const uint8_t* data,
+                        int32_t length, int32_t apiId, int32_t* status);
+
+/**
+ * Writes a repeating packet to the CAN device with a specific ID.
+ *
+ * This ID is 10 bits.
+ *
+ * The RoboRIO will automatically repeat the packet at the specified interval
+ *
+ * @param handle   the CAN handle
+ * @param data     the data to write (0-8 bytes)
+ * @param length   the length of data (0-8)
+ * @param apiId    the ID to write (0-1023)
+ * @param repeatMs the period to repeat in ms
+ */
+void HAL_WriteCANPacketRepeating(HAL_CANHandle handle, const uint8_t* data,
+                                 int32_t length, int32_t apiId,
+                                 int32_t repeatMs, int32_t* status);
+
+/**
+ * Stops a repeating packet with a specific ID.
+ *
+ * This ID is 10 bits.
+ *
+ * @param handle the CAN handle
+ * @param apiId  the ID to stop repeating (0-1023)
+ */
+void HAL_StopCANPacketRepeating(HAL_CANHandle handle, int32_t apiId,
+                                int32_t* status);
+
+/**
+ * Reads a new CAN packet.
+ *
+ * This will only return properly once per packet received. Multiple calls
+ * without receiving another packet will return an error code.
+ *
+ * @param handle            the CAN handle
+ * @param apiId             the ID to read (0-1023)
+ * @param data              the packet data (8 bytes)
+ * @param length            the received length (0-8 bytes)
+ * @param receivedTimestamp the packet received timestamp (based off of
+ * CLOCK_MONOTONIC)
+ */
+void HAL_ReadCANPacketNew(HAL_CANHandle handle, int32_t apiId, uint8_t* data,
+                          int32_t* length, uint64_t* receivedTimestamp,
+                          int32_t* status);
+
+/**
+ * Reads a CAN packet. The will continuously return the last packet received,
+ * without accounting for packet age.
+ *
+ * @param handle            the CAN handle
+ * @param apiId             the ID to read (0-1023)
+ * @param data              the packet data (8 bytes)
+ * @param length            the received length (0-8 bytes)
+ * @param receivedTimestamp the packet received timestamp (based off of
+ * CLOCK_MONOTONIC)
+ */
+void HAL_ReadCANPacketLatest(HAL_CANHandle handle, int32_t apiId, uint8_t* data,
+                             int32_t* length, uint64_t* receivedTimestamp,
+                             int32_t* status);
+
+/**
+ * Reads a CAN packet. The will return the last packet received until the
+ * packet is older then the requested timeout. Then it will return an error
+ * code.
+ *
+ * @param handle            the CAN handle
+ * @param apiId             the ID to read (0-1023)
+ * @param data              the packet data (8 bytes)
+ * @param length            the received length (0-8 bytes)
+ * @param receivedTimestamp the packet received timestamp (based off of
+ * CLOCK_MONOTONIC)
+ * @param timeoutMs         the timeout time for the packet
+ */
+void HAL_ReadCANPacketTimeout(HAL_CANHandle handle, int32_t apiId,
+                              uint8_t* data, int32_t* length,
+                              uint64_t* receivedTimestamp, int32_t timeoutMs,
+                              int32_t* status);
+
+/**
+ * Reads a CAN packet. The will return the last packet received until the
+ * packet is older then the requested timeout. Then it will return an error
+ * code. The period parameter is used when you know the packet is sent at
+ * specific intervals, so calls will not attempt to read a new packet from the
+ * network until that period has passed. We do not recommend users use this
+ * API unless they know the implications.
+ *
+ * @param handle            the CAN handle
+ * @param apiId             the ID to read (0-1023)
+ * @param data              the packet data (8 bytes)
+ * @param length            the received length (0-8 bytes)
+ * @param receivedTimestamp the packet received timestamp (based off of
+ * CLOCK_MONOTONIC)
+ * @param timeoutMs         the timeout time for the packet
+ * @param periodMs          the standard period for the packet
+ */
+void HAL_ReadCANPeriodicPacket(HAL_CANHandle handle, int32_t apiId,
+                               uint8_t* data, int32_t* length,
+                               uint64_t* receivedTimestamp, int32_t timeoutMs,
+                               int32_t periodMs, int32_t* status);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/CANAPITypes.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/CANAPITypes.h
new file mode 100644
index 0000000..4bf98bd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/CANAPITypes.h
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/

+/* 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.                                                               */

+/*----------------------------------------------------------------------------*/

+

+#pragma once

+

+#include <stdint.h>

+

+#include "hal/Types.h"

+

+/**

+ * @defgroup hal_canapi CAN API Functions

+ * @ingroup hal_capi

+ * @{

+ */

+

+// clang-format off

+/**

+ * The CAN device type.

+ *

+ * Teams should use HAL_CAN_Dev_kMiscellaneous

+ */

+HAL_ENUM(HAL_CANDeviceType) {

+  HAL_CAN_Dev_kBroadcast = 0,

+  HAL_CAN_Dev_kRobotController = 1,

+  HAL_CAN_Dev_kMotorController = 2,

+  HAL_CAN_Dev_kRelayController = 3,

+  HAL_CAN_Dev_kGyroSensor = 4,

+  HAL_CAN_Dev_kAccelerometer = 5,

+  HAL_CAN_Dev_kUltrasonicSensor = 6,

+  HAL_CAN_Dev_kGearToothSensor = 7,

+  HAL_CAN_Dev_kPowerDistribution = 8,

+  HAL_CAN_Dev_kPneumatics = 9,

+  HAL_CAN_Dev_kMiscellaneous = 10,

+  HAL_CAN_Dev_kFirmwareUpdate = 31

+};

+

+/**

+ * The CAN manufacturer ID.

+ *

+ * Teams should use HAL_CAN_Man_kTeamUse.

+ */

+HAL_ENUM(HAL_CANManufacturer) {

+  HAL_CAN_Man_kBroadcast = 0,

+  HAL_CAN_Man_kNI = 1,

+  HAL_CAN_Man_kLM = 2,

+  HAL_CAN_Man_kDEKA = 3,

+  HAL_CAN_Man_kCTRE = 4,

+  HAL_CAN_Man_kMS = 7,

+  HAL_CAN_Man_kTeamUse = 8,

+};

+// clang-format on

+/** @} */

diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/ChipObject.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/ChipObject.h
new file mode 100644
index 0000000..878595b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/ChipObject.h
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wpedantic"
+#pragma GCC diagnostic ignored "-Wignored-qualifiers"
+
+#include <stdint.h>
+
+#include <FRC_FPGA_ChipObject/RoboRIO_FRC_ChipObject_Aliases.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/nInterfaceGlobals.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAI.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAO.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccel.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAccumulator.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAlarm.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tAnalogTrigger.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tBIST.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tCounter.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDIO.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tDMA.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tEncoder.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tGlobal.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tInterrupt.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPWM.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tPower.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tRelay.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSPI.h>
+#include <FRC_FPGA_ChipObject/nRoboRIO_FPGANamespace/tSysWatchdog.h>
+#include <FRC_FPGA_ChipObject/tDMAChannelDescriptor.h>
+#include <FRC_FPGA_ChipObject/tDMAManager.h>
+#include <FRC_FPGA_ChipObject/tInterruptManager.h>
+#include <FRC_FPGA_ChipObject/tSystem.h>
+#include <FRC_FPGA_ChipObject/tSystemInterface.h>
+
+namespace hal {
+using namespace nFPGA;
+using namespace nRoboRIO_FPGANamespace;
+}  // namespace hal
+
+#pragma GCC diagnostic pop
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Compressor.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Compressor.h
new file mode 100644
index 0000000..cb58e46
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Compressor.h
@@ -0,0 +1,143 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_compressor Compressor Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a compressor on the given PCM module.
+ *
+ * @param module the module number
+ * @return       the created handle
+ */
+HAL_CompressorHandle HAL_InitializeCompressor(int32_t module, int32_t* status);
+
+/**
+ * Gets if a compressor module is valid.
+ *
+ * @param module the module number
+ * @return       true if the module is valid, otherwise false
+ */
+HAL_Bool HAL_CheckCompressorModule(int32_t module);
+
+/**
+ * Gets the compressor state (on or off).
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if the compressor is on, otherwise false
+ */
+HAL_Bool HAL_GetCompressor(HAL_CompressorHandle compressorHandle,
+                           int32_t* status);
+
+/**
+ * Sets the compressor to closed loop mode.
+ *
+ * @param compressorHandle the compressor handle
+ * @param value            true for closed loop mode, false for off
+ */
+void HAL_SetCompressorClosedLoopControl(HAL_CompressorHandle compressorHandle,
+                                        HAL_Bool value, int32_t* status);
+
+/**
+ * Gets if the compressor is in closed loop mode.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if the compressor is in closed loop mode,
+ * otherwise false
+ */
+HAL_Bool HAL_GetCompressorClosedLoopControl(
+    HAL_CompressorHandle compressorHandle, int32_t* status);
+
+/**
+ * Gets the compressor pressure switch state.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if the pressure switch is triggered, otherwise
+ * false
+ */
+HAL_Bool HAL_GetCompressorPressureSwitch(HAL_CompressorHandle compressorHandle,
+                                         int32_t* status);
+
+/**
+ * Gets the compressor current.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 the compressor current in amps
+ */
+double HAL_GetCompressorCurrent(HAL_CompressorHandle compressorHandle,
+                                int32_t* status);
+
+/**
+ * Gets if the compressor is faulted because of too high of current.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if falted, otherwise false
+ */
+HAL_Bool HAL_GetCompressorCurrentTooHighFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status);
+
+/**
+ * Gets if a sticky fauly is triggered because of too high of current.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if falted, otherwise false
+ */
+HAL_Bool HAL_GetCompressorCurrentTooHighStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status);
+
+/**
+ * Gets if a sticky fauly is triggered because of a short.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if falted, otherwise false
+ */
+HAL_Bool HAL_GetCompressorShortedStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status);
+
+/**
+ * Gets if the compressor is faulted because of a short.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if shorted, otherwise false
+ */
+HAL_Bool HAL_GetCompressorShortedFault(HAL_CompressorHandle compressorHandle,
+                                       int32_t* status);
+
+/**
+ * Gets if a sticky fault is triggered of the compressor not connected.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if falted, otherwise false
+ */
+HAL_Bool HAL_GetCompressorNotConnectedStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status);
+
+/**
+ * Gets if the compressor is not connected.
+ *
+ * @param compressorHandle the compressor handle
+ * @return                 true if not connected, otherwise false
+ */
+HAL_Bool HAL_GetCompressorNotConnectedFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Constants.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Constants.h
new file mode 100644
index 0000000..2a4d409
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Constants.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+/**
+ * @defgroup hal_constants Constants Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Gets the number of FPGA system clock ticks per microsecond.
+ *
+ * @return the number of clock ticks per microsecond
+ */
+int32_t HAL_GetSystemClockTicksPerMicrosecond(void);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Counter.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Counter.h
new file mode 100644
index 0000000..c0dd057
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Counter.h
@@ -0,0 +1,307 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/AnalogTrigger.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_counter Counter Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+// clang-format off
+/**
+ * The counter mode.
+ */
+HAL_ENUM(HAL_Counter_Mode) {
+  HAL_Counter_kTwoPulse = 0,
+  HAL_Counter_kSemiperiod = 1,
+  HAL_Counter_kPulseLength = 2,
+  HAL_Counter_kExternalDirection = 3
+};
+// clang-format on
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a counter.
+ *
+ * @param mode  the counter mode
+ * @param index the compressor index (output)
+ * @return      the created handle
+ */
+HAL_CounterHandle HAL_InitializeCounter(HAL_Counter_Mode mode, int32_t* index,
+                                        int32_t* status);
+
+/**
+ * Frees a counter.
+ *
+ * @param counterHandle the counter handle
+ */
+void HAL_FreeCounter(HAL_CounterHandle counterHandle, int32_t* status);
+
+/**
+ * Sets the average sample size of a counter.
+ *
+ * @param counterHandle the counter handle
+ * @param size          the size of samples to average
+ */
+void HAL_SetCounterAverageSize(HAL_CounterHandle counterHandle, int32_t size,
+                               int32_t* status);
+
+/**
+ * Sets the source object that causes the counter to count up.
+ *
+ * @param counterHandle       the counter handle
+ * @param digitalSourceHandle the digital source handle (either a
+ * HAL_AnalogTriggerHandle of a HAL_DigitalHandle)
+ * @param analogTriggerType   the analog trigger type if the source is an analog
+ * trigger
+ */
+void HAL_SetCounterUpSource(HAL_CounterHandle counterHandle,
+                            HAL_Handle digitalSourceHandle,
+                            HAL_AnalogTriggerType analogTriggerType,
+                            int32_t* status);
+
+/**
+ * Sets the up source to either detect rising edges or falling edges.
+ *
+ * Note that both are allowed to be set true at the same time without issues.
+ *
+ * @param counterHandle the counter handle
+ * @param risingEdge    true to trigger on rising
+ * @param fallingEdge   true to trigger on falling
+ */
+void HAL_SetCounterUpSourceEdge(HAL_CounterHandle counterHandle,
+                                HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                int32_t* status);
+
+/**
+ * Disables the up counting source to the counter.
+ *
+ * @param counterHandle the counter handle
+ */
+void HAL_ClearCounterUpSource(HAL_CounterHandle counterHandle, int32_t* status);
+
+/**
+ * Sets the source object that causes the counter to count down.
+ *
+ * @param counterHandle       the counter handle
+ * @param digitalSourceHandle the digital source handle (either a
+ * HAL_AnalogTriggerHandle of a HAL_DigitalHandle)
+ * @param analogTriggerType   the analog trigger type if the source is an analog
+ * trigger
+ */
+void HAL_SetCounterDownSource(HAL_CounterHandle counterHandle,
+                              HAL_Handle digitalSourceHandle,
+                              HAL_AnalogTriggerType analogTriggerType,
+                              int32_t* status);
+
+/**
+ * Sets the down source to either detect rising edges or falling edges.
+ * Note that both are allowed to be set true at the same time without issues.
+ *
+ * @param counterHandle the counter handle
+ * @param risingEdge    true to trigger on rising
+ * @param fallingEdge   true to trigger on falling
+ */
+void HAL_SetCounterDownSourceEdge(HAL_CounterHandle counterHandle,
+                                  HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                  int32_t* status);
+
+/**
+ * Disables the down counting source to the counter.
+ *
+ * @param counterHandle the counter handle
+ */
+void HAL_ClearCounterDownSource(HAL_CounterHandle counterHandle,
+                                int32_t* status);
+
+/**
+ * Sets standard up / down counting mode on this counter.
+ *
+ * Up and down counts are sourced independently from two inputs.
+ *
+ * @param counterHandle the counter handle
+ */
+void HAL_SetCounterUpDownMode(HAL_CounterHandle counterHandle, int32_t* status);
+
+/**
+ * Sets directional counting mode on this counter.
+ *
+ * The direction is determined by the B input, with counting happening with the
+ * A input.
+ *
+ * @param counterHandle the counter handle
+ */
+void HAL_SetCounterExternalDirectionMode(HAL_CounterHandle counterHandle,
+                                         int32_t* status);
+
+/**
+ * Sets Semi-period mode on this counter.
+ *
+ * The counter counts up based on the time the input is triggered. High or Low
+ * depends on the highSemiPeriod parameter.
+ *
+ * @param counterHandle  the counter handle
+ * @param highSemiPeriod true for counting when the input is high, false for low
+ */
+void HAL_SetCounterSemiPeriodMode(HAL_CounterHandle counterHandle,
+                                  HAL_Bool highSemiPeriod, int32_t* status);
+
+/**
+ * Configures the counter to count in up or down based on the length of the
+ * input pulse.
+ *
+ * This mode is most useful for direction sensitive gear tooth sensors.
+ *
+ * @param counterHandle the counter handle
+ * @param threshold The pulse length beyond which the counter counts the
+ * opposite direction (seconds)
+ */
+void HAL_SetCounterPulseLengthMode(HAL_CounterHandle counterHandle,
+                                   double threshold, int32_t* status);
+
+/**
+ * Gets the Samples to Average which specifies the number of samples of the
+ * timer to average when calculating the period. Perform averaging to account
+ * for mechanical imperfections or as oversampling to increase resolution.
+ *
+ * @param counterHandle the counter handle
+ * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
+ */
+int32_t HAL_GetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
+                                       int32_t* status);
+
+/**
+ * Sets the Samples to Average which specifies the number of samples of the
+ * timer to average when calculating the period. Perform averaging to account
+ * for mechanical imperfections or as oversampling to increase resolution.
+ *
+ * @param counterHandle    the counter handle
+ * @param samplesToAverage The number of samples to average from 1 to 127
+ */
+void HAL_SetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
+                                    int32_t samplesToAverage, int32_t* status);
+
+/**
+ * Resets the Counter to zero.
+ *
+ * Sets the counter value to zero. This does not effect the running state of the
+ * counter, just sets the current value to zero.
+ *
+ * @param counterHandle the counter handle
+ */
+void HAL_ResetCounter(HAL_CounterHandle counterHandle, int32_t* status);
+
+/**
+ * Reads the current counter value.
+ *
+ * Reads the value at this instant. It may still be running, so it reflects the
+ * current value. Next time it is read, it might have a different value.
+ *
+ * @param counterHandle the counter handle
+ * @return              the current counter value
+ */
+int32_t HAL_GetCounter(HAL_CounterHandle counterHandle, int32_t* status);
+
+/*
+ * Gets the Period of the most recent count.
+ *
+ * Returns the time interval of the most recent count. This can be used for
+ * velocity calculations to determine shaft speed.
+ *
+ * @param counterHandle the counter handle
+ * @returns             the period of the last two pulses in units of seconds
+ */
+double HAL_GetCounterPeriod(HAL_CounterHandle counterHandle, int32_t* status);
+
+/**
+ * Sets the maximum period where the device is still considered "moving".
+ *
+ * Sets the maximum period where the device is considered moving. This value is
+ * used to determine the "stopped" state of the counter using the
+ * HAL_GetCounterStopped method.
+ *
+ * @param counterHandle the counter handle
+ * @param maxPeriod     the maximum period where the counted device is
+ * considered moving in seconds
+ */
+void HAL_SetCounterMaxPeriod(HAL_CounterHandle counterHandle, double maxPeriod,
+                             int32_t* status);
+
+/**
+ * Selects whether you want to continue updating the event timer output when
+ * there are no samples captured.
+ *
+ * The output of the event timer has a buffer of periods that are averaged and
+ * posted to a register on the FPGA.  When the timer detects that the event
+ * source has stopped (based on the MaxPeriod) the buffer of samples to be
+ * averaged is emptied.
+ *
+ * If you enable the update when empty, you will be
+ * notified of the stopped source and the event time will report 0 samples.
+ *
+ * If you disable update when empty, the most recent average will remain on the
+ * output until a new sample is acquired.
+ *
+ * You will never see 0 samples output (except when there have been no events
+ * since an FPGA reset) and you will likely not see the stopped bit become true
+ * (since it is updated at the end of an average and there are no samples to
+ * average).
+ *
+ * @param counterHandle the counter handle
+ * @param enabled       true to enable counter updating with no samples
+ */
+void HAL_SetCounterUpdateWhenEmpty(HAL_CounterHandle counterHandle,
+                                   HAL_Bool enabled, int32_t* status);
+
+/**
+ * Determines if the clock is stopped.
+ *
+ * Determine if the clocked input is stopped based on the MaxPeriod value set
+ * using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
+ * device (and counter) are assumed to be stopped and it returns true.
+ *
+ * @param counterHandle the counter handle
+ * @return              true if the most recent counter period exceeds the
+ * MaxPeriod value set by SetMaxPeriod
+ */
+HAL_Bool HAL_GetCounterStopped(HAL_CounterHandle counterHandle,
+                               int32_t* status);
+
+/**
+ * Gets the last direction the counter value changed.
+ *
+ * @param counterHandle the counter handle
+ * @return              the last direction the counter value changed
+ */
+HAL_Bool HAL_GetCounterDirection(HAL_CounterHandle counterHandle,
+                                 int32_t* status);
+
+/**
+ * Sets the Counter to return reversed sensing on the direction.
+ *
+ * This allows counters to change the direction they are counting in the case of
+ * 1X and 2X quadrature encoding only. Any other counter mode isn't supported.
+ *
+ * @param counterHandle    the counter handle
+ * @param reverseDirection true if the value counted should be negated.
+ */
+void HAL_SetCounterReverseDirection(HAL_CounterHandle counterHandle,
+                                    HAL_Bool reverseDirection, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/DIO.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/DIO.h
new file mode 100644
index 0000000..7812306
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/DIO.h
@@ -0,0 +1,200 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_dio DIO Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Creates a new instance of a digital port.
+ *
+ * @param portHandle the port handle to create from
+ * @param input      true for input, false for output
+ * @return           the created digital handle
+ */
+HAL_DigitalHandle HAL_InitializeDIOPort(HAL_PortHandle portHandle,
+                                        HAL_Bool input, int32_t* status);
+
+/**
+ * Checks if a DIO channel is valid.
+ *
+ * @param channel the channel number to check
+ * @return        true if the channel is correct, otherwise false
+ */
+HAL_Bool HAL_CheckDIOChannel(int32_t channel);
+
+void HAL_FreeDIOPort(HAL_DigitalHandle dioPortHandle);
+
+/**
+ * Allocates a DO PWM Generator.
+ *
+ * @return the allocated digital PWM handle
+ */
+HAL_DigitalPWMHandle HAL_AllocateDigitalPWM(int32_t* status);
+
+/**
+ * Frees the resource associated with a DO PWM generator.
+ *
+ * @param pwmGenerator the digital PWM handle
+ */
+void HAL_FreeDigitalPWM(HAL_DigitalPWMHandle pwmGenerator, int32_t* status);
+
+/**
+ * Changes the frequency of the DO PWM generator.
+ *
+ * The valid range is from 0.6 Hz to 19 kHz.
+ *
+ *  The frequency resolution is logarithmic.
+ *
+ * @param rate the frequency to output all digital output PWM signals
+ */
+void HAL_SetDigitalPWMRate(double rate, int32_t* status);
+
+/**
+ * Configures the duty-cycle of the PWM generator.
+ *
+ * @param pwmGenerator the digital PWM handle
+ * @param dutyCycle    the percent duty cycle to output [0..1]
+ */
+void HAL_SetDigitalPWMDutyCycle(HAL_DigitalPWMHandle pwmGenerator,
+                                double dutyCycle, int32_t* status);
+
+/**
+ * Configures which DO channel the PWM signal is output on.
+ *
+ * @param pwmGenerator the digital PWM handle
+ * @param channel      the channel to output on
+ */
+void HAL_SetDigitalPWMOutputChannel(HAL_DigitalPWMHandle pwmGenerator,
+                                    int32_t channel, int32_t* status);
+
+/**
+ * Writes a digital value to a DIO channel.
+ *
+ * @param dioPortHandle the digital port handle
+ * @param value         the state to set the digital channel (if it is
+ * configured as an output)
+ */
+void HAL_SetDIO(HAL_DigitalHandle dioPortHandle, HAL_Bool value,
+                int32_t* status);
+
+/**
+ * Sets the direction of a DIO channel.
+ *
+ * @param dioPortHandle the digital port handle
+ * @param input         true to set input, false for output
+ */
+void HAL_SetDIODirection(HAL_DigitalHandle dioPortHandle, HAL_Bool input,
+                         int32_t* status);
+
+/**
+ * Reads a digital value from a DIO channel.
+ *
+ * @param dioPortHandle the digital port handle
+ * @return              the state of the specified channel
+ */
+HAL_Bool HAL_GetDIO(HAL_DigitalHandle dioPortHandle, int32_t* status);
+
+/**
+ * Reads the direction of a DIO channel.
+ *
+ * @param dioPortHandle the digital port handle
+ * @return              true for input, false for output
+ */
+HAL_Bool HAL_GetDIODirection(HAL_DigitalHandle dioPortHandle, int32_t* status);
+
+/**
+ * Generates a single digital pulse.
+ *
+ * Write a pulse to the specified digital output channel. There can only be a
+ * single pulse going at any time.
+ *
+ * @param dioPortHandle the digital port handle
+ * @param pulseLength   the active length of the pulse (in seconds)
+ */
+void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLength,
+               int32_t* status);
+
+/**
+ * Checks a DIO line to see if it is currently generating a pulse.
+ *
+ * @return true if a pulse is in progress, otherwise false
+ */
+HAL_Bool HAL_IsPulsing(HAL_DigitalHandle dioPortHandle, int32_t* status);
+
+/**
+ * Checks if any DIO line is currently generating a pulse.
+ *
+ * @return true if a pulse on some line is in progress
+ */
+HAL_Bool HAL_IsAnyPulsing(int32_t* status);
+
+/**
+ * Writes the filter index from the FPGA.
+ *
+ * Set the filter index used to filter out short pulses.
+ *
+ * @param dioPortHandle the digital port handle
+ * @param filterIndex   the filter index (Must be in the range 0 - 3, where 0
+ * means "none" and 1 - 3 means filter # filterIndex - 1)
+ */
+void HAL_SetFilterSelect(HAL_DigitalHandle dioPortHandle, int32_t filterIndex,
+                         int32_t* status);
+
+/**
+ * Reads the filter index from the FPGA.
+ *
+ * Gets the filter index used to filter out short pulses.
+ *
+ * @param dioPortHandle the digital port handle
+ * @return filterIndex  the filter index (Must be in the range 0 - 3,
+ * where 0 means "none" and 1 - 3 means filter # filterIndex - 1)
+ */
+int32_t HAL_GetFilterSelect(HAL_DigitalHandle dioPortHandle, int32_t* status);
+
+/**
+ * Sets the filter period for the specified filter index.
+ *
+ * Sets the filter period in FPGA cycles.  Even though there are 2 different
+ * filter index domains (MXP vs HDR), ignore that distinction for now since it
+ * compilicates the interface.  That can be changed later.
+ *
+ * @param filterIndex the filter index, 0 - 2
+ * @param value       the number of cycles that the signal must not transition
+ * to be counted as a transition.
+ */
+void HAL_SetFilterPeriod(int32_t filterIndex, int64_t value, int32_t* status);
+
+/**
+ * Gets the filter period for the specified filter index.
+ *
+ * Gets the filter period in FPGA cycles.  Even though there are 2 different
+ * filter index domains (MXP vs HDR), ignore that distinction for now since it
+ * compilicates the interface.  Set status to NiFpga_Status_SoftwareFault if the
+ * filter values miss-match.
+ *
+ * @param filterIndex the filter index, 0 - 2
+ * @param value       the number of cycles that the signal must not transition
+ * to be counted as a transition.
+ */
+int64_t HAL_GetFilterPeriod(int32_t filterIndex, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/DriverStation.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/DriverStation.h
new file mode 100644
index 0000000..1c18681
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/DriverStation.h
@@ -0,0 +1,276 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2013-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/DriverStationTypes.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_driverstation Driver Station Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Sends an error to the driver station.
+ *
+ * @param isError   true for error, false for warning
+ * @param errorCode the error code
+ * @param isLVCode  true for a LV error code, false for a standard error code
+ * @param details   the details of the error
+ * @param location  the file location of the errror
+ * @param callstack the callstack of the error
+ * @param printMsg  true to print the error message to stdout as well as to the
+ * DS
+ */
+int32_t HAL_SendError(HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode,
+                      const char* details, const char* location,
+                      const char* callStack, HAL_Bool printMsg);
+
+/**
+ * Gets the current control word of the driver station.
+ *
+ * The control work contains the robot state.
+ *
+ * @param controlWord the control word (out)
+ * @return            the error code, or 0 for success
+ */
+int32_t HAL_GetControlWord(HAL_ControlWord* controlWord);
+
+/**
+ * Gets the current alliance station ID.
+ *
+ * @param status the error code, or 0 for success
+ * @return       the alliance station ID
+ */
+HAL_AllianceStationID HAL_GetAllianceStation(int32_t* status);
+
+/**
+ * Gets the axes of a specific joystick.
+ *
+ * @param joystickNum the joystick number
+ * @param axes        the axes values (output)
+ * @return            the error code, or 0 for success
+ */
+int32_t HAL_GetJoystickAxes(int32_t joystickNum, HAL_JoystickAxes* axes);
+
+/**
+ * Gets the POVs of a specific joystick.
+ *
+ * @param joystickNum the joystick number
+ * @param povs        the POV values (output)
+ * @return            the error code, or 0 for success
+ */
+int32_t HAL_GetJoystickPOVs(int32_t joystickNum, HAL_JoystickPOVs* povs);
+
+/**
+ * Gets the buttons of a specific joystick.
+ *
+ * @param joystickNum the joystick number
+ * @param buttons     the button values (output)
+ * @return            the error code, or 0 for success
+ */
+int32_t HAL_GetJoystickButtons(int32_t joystickNum,
+                               HAL_JoystickButtons* buttons);
+
+/**
+ * Retrieves the Joystick Descriptor for particular slot.
+ *
+ * @param desc [out] descriptor (data transfer object) to fill in.  desc is
+ * filled in regardless of success. In other words, if descriptor is not
+ * available, desc is filled in with default values matching the init-values in
+ * Java and C++ Driverstation for when caller requests a too-large joystick
+ * index.
+ *
+ * @return error code reported from Network Comm back-end.  Zero is good,
+ * nonzero is bad.
+ */
+int32_t HAL_GetJoystickDescriptor(int32_t joystickNum,
+                                  HAL_JoystickDescriptor* desc);
+
+/**
+ * Gets is a specific joystick is considered to be an XBox controller.
+ *
+ * @param joystickNum the joystick number
+ * @return            true if xbox, false otherwise
+ */
+HAL_Bool HAL_GetJoystickIsXbox(int32_t joystickNum);
+
+/**
+ * Gets the type of joystick connected.
+ *
+ * This is device specific, and different depending on what system input type
+ * the joystick uses.
+ *
+ * @param joystickNum the joystick number
+ * @return            the enumerated joystick type
+ */
+int32_t HAL_GetJoystickType(int32_t joystickNum);
+
+/**
+ * Gets the name of a joystick.
+ *
+ * The returned array must be freed with HAL_FreeJoystickName.
+ *
+ * Will be null terminated.
+ *
+ * @param joystickNum the joystick number
+ * @return            the joystick name
+ */
+char* HAL_GetJoystickName(int32_t joystickNum);
+
+/**
+ * Frees a joystick name received with HAL_GetJoystickName
+ *
+ * @param name the name storage
+ */
+void HAL_FreeJoystickName(char* name);
+
+/**
+ * Gets the type of a specific joystick axis.
+ *
+ * This is device specific, and different depending on what system input type
+ * the joystick uses.
+ *
+ * @param joystickNum the joystick number
+ * @param axis        the axis number
+ * @return            the enumerated axis type
+ */
+int32_t HAL_GetJoystickAxisType(int32_t joystickNum, int32_t axis);
+
+/**
+ * Set joystick outputs.
+ *
+ * @param joystickNum the joystick numer
+ * @param outputs     bitmask of outputs, 1 for on 0 for off
+ * @param leftRumble  the left rumble value (0-FFFF)
+ * @param rightRumble the right rumble value (0-FFFF)
+ * @return            the error code, or 0 for success
+ */
+int32_t HAL_SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
+                               int32_t leftRumble, int32_t rightRumble);
+
+/**
+ * Returns the approximate match time.
+ *
+ * The FMS does not send an official match time to the robots, but does send
+ * an approximate match time. The value will count down the time remaining in
+ * the current period (auto or teleop).
+ *
+ * Warning: This is not an official time (so it cannot be used to dispute ref
+ * calls or guarantee that a function will trigger before the match ends).
+ *
+ * The Practice Match function of the DS approximates the behaviour seen on
+ * the field.
+ *
+ * @param status the error code, or 0 for success
+ * @return time remaining in current match period (auto or teleop)
+ */
+double HAL_GetMatchTime(int32_t* status);
+
+/**
+ * Gets info about a specific match.
+ *
+ * @param info the match info (output)
+ * @return     the error code, or 0 for success
+ */
+int32_t HAL_GetMatchInfo(HAL_MatchInfo* info);
+
+#ifndef HAL_USE_LABVIEW
+
+/**
+ * Releases the DS Mutex to allow proper shutdown of any threads that are
+ * waiting on it.
+ */
+void HAL_ReleaseDSMutex(void);
+
+/**
+ * Has a new control packet from the driver station arrived since the last
+ * time this function was called?
+ *
+ * @return true if the control data has been updated since the last call
+ */
+HAL_Bool HAL_IsNewControlData(void);
+
+/**
+ * Waits for the newest DS packet to arrive. Note that this is a blocking call.
+ */
+void HAL_WaitForDSData(void);
+
+/**
+ * Waits for the newest DS packet to arrive. If timeout is <= 0, this will wait
+ * forever. Otherwise, it will wait until either a new packet, or the timeout
+ * time has passed.
+ *
+ * @param timeout timeout in seconds
+ * @return        true for new data, false for timeout
+ */
+HAL_Bool HAL_WaitForDSDataTimeout(double timeout);
+
+/**
+ * Initializes the driver station communication. This will properly
+ * handle multiple calls. However note that this CANNOT be called from a library
+ * that interfaces with LabVIEW.
+ */
+void HAL_InitializeDriverStation(void);
+
+/**
+ * Sets the program starting flag in the DS.
+ *
+ * This is what changes the DS to showing robot code ready.
+ */
+void HAL_ObserveUserProgramStarting(void);
+
+/**
+ * Sets the disabled flag in the DS.
+ *
+ * This is used for the DS to ensure the robot is properly responding to its
+ * state request. Ensure this get called about every 50ms, or the robot will be
+ * disabled by the DS.
+ */
+void HAL_ObserveUserProgramDisabled(void);
+
+/**
+ * Sets the autonomous enabled flag in the DS.
+ *
+ * This is used for the DS to ensure the robot is properly responding to its
+ * state request. Ensure this get called about every 50ms, or the robot will be
+ * disabled by the DS.
+ */
+void HAL_ObserveUserProgramAutonomous(void);
+
+/**
+ * Sets the teleoperated enabled flag in the DS.
+ *
+ * This is used for the DS to ensure the robot is properly responding to its
+ * state request. Ensure this get called about every 50ms, or the robot will be
+ * disabled by the DS.
+ */
+void HAL_ObserveUserProgramTeleop(void);
+
+/**
+ * Sets the test mode flag in the DS.
+ *
+ * This is used for the DS to ensure the robot is properly responding to its
+ * state request. Ensure this get called about every 50ms, or the robot will be
+ * disabled by the DS.
+ */
+void HAL_ObserveUserProgramTest(void);
+
+#endif  // HAL_USE_LABVIEW
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/DriverStationTypes.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/DriverStationTypes.h
new file mode 100644
index 0000000..7c5d6f6
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/DriverStationTypes.h
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_driverstation Driver Station Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#define HAL_IO_CONFIG_DATA_SIZE 32
+#define HAL_SYS_STATUS_DATA_SIZE 44
+#define HAL_USER_STATUS_DATA_SIZE \
+  (984 - HAL_IO_CONFIG_DATA_SIZE - HAL_SYS_STATUS_DATA_SIZE)
+
+#define HALFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Input 17
+#define HALFRC_NetworkCommunication_DynamicType_DSEnhancedIO_Output 18
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Header 19
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Extra1 20
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Vertices1 21
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Extra2 22
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Vertices2 23
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Joystick 24
+#define HALFRC_NetworkCommunication_DynamicType_Kinect_Custom 25
+
+struct HAL_ControlWord {
+  uint32_t enabled : 1;
+  uint32_t autonomous : 1;
+  uint32_t test : 1;
+  uint32_t eStop : 1;
+  uint32_t fmsAttached : 1;
+  uint32_t dsAttached : 1;
+  uint32_t control_reserved : 26;
+};
+typedef struct HAL_ControlWord HAL_ControlWord;
+
+// clang-format off
+HAL_ENUM(HAL_AllianceStationID) {
+  HAL_AllianceStationID_kRed1,
+  HAL_AllianceStationID_kRed2,
+  HAL_AllianceStationID_kRed3,
+  HAL_AllianceStationID_kBlue1,
+  HAL_AllianceStationID_kBlue2,
+  HAL_AllianceStationID_kBlue3,
+};
+
+HAL_ENUM(HAL_MatchType) {
+  HAL_kMatchType_none,
+  HAL_kMatchType_practice,
+  HAL_kMatchType_qualification,
+  HAL_kMatchType_elimination,
+};
+// clang-format on
+
+/* The maximum number of axes that will be stored in a single HALJoystickAxes
+ * struct. This is used for allocating buffers, not bounds checking, since
+ * there are usually less axes in practice.
+ */
+#define HAL_kMaxJoystickAxes 12
+#define HAL_kMaxJoystickPOVs 12
+#define HAL_kMaxJoysticks 6
+
+struct HAL_JoystickAxes {
+  int16_t count;
+  float axes[HAL_kMaxJoystickAxes];
+};
+typedef struct HAL_JoystickAxes HAL_JoystickAxes;
+
+struct HAL_JoystickPOVs {
+  int16_t count;
+  int16_t povs[HAL_kMaxJoystickPOVs];
+};
+typedef struct HAL_JoystickPOVs HAL_JoystickPOVs;
+
+struct HAL_JoystickButtons {
+  uint32_t buttons;
+  uint8_t count;
+};
+typedef struct HAL_JoystickButtons HAL_JoystickButtons;
+
+struct HAL_JoystickDescriptor {
+  uint8_t isXbox;
+  uint8_t type;
+  char name[256];
+  uint8_t axisCount;
+  uint8_t axisTypes[HAL_kMaxJoystickAxes];
+  uint8_t buttonCount;
+  uint8_t povCount;
+};
+typedef struct HAL_JoystickDescriptor HAL_JoystickDescriptor;
+
+struct HAL_MatchInfo {
+  char eventName[64];
+  HAL_MatchType matchType;
+  uint16_t matchNumber;
+  uint8_t replayNumber;
+  uint8_t gameSpecificMessage[64];
+  uint16_t gameSpecificMessageSize;
+};
+typedef struct HAL_MatchInfo HAL_MatchInfo;
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Encoder.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Encoder.h
new file mode 100644
index 0000000..449b814
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Encoder.h
@@ -0,0 +1,301 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/AnalogTrigger.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_encoder Encoder Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+// clang-format off
+/**
+ * The type of index pulse for the encoder.
+ */
+HAL_ENUM(HAL_EncoderIndexingType) {
+  HAL_kResetWhileHigh,
+  HAL_kResetWhileLow,
+  HAL_kResetOnFallingEdge,
+  HAL_kResetOnRisingEdge
+};
+
+/**
+ * The encoding scaling of the encoder.
+ */
+HAL_ENUM(HAL_EncoderEncodingType) {
+  HAL_Encoder_k1X,
+  HAL_Encoder_k2X,
+  HAL_Encoder_k4X
+};
+// clang-format on
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes an encoder.
+ *
+ * @param digitalSourceHandleA the A source (either a HAL_DigitalHandle or a
+ * HAL_AnalogTriggerHandle)
+ * @param analogTriggerTypeA   the analog trigger type of the A source if it is
+ * an analog trigger
+ * @param digitalSourceHandleB the B source (either a HAL_DigitalHandle or a
+ * HAL_AnalogTriggerHandle)
+ * @param analogTriggerTypeB   the analog trigger type of the B source if it is
+ * an analog trigger
+ * @param reverseDirection     true to reverse the counting direction from
+ * standard, otherwise false
+ * @param encodingType         the encoding type
+   @return                     the created encoder handle
+ */
+HAL_EncoderHandle HAL_InitializeEncoder(
+    HAL_Handle digitalSourceHandleA, HAL_AnalogTriggerType analogTriggerTypeA,
+    HAL_Handle digitalSourceHandleB, HAL_AnalogTriggerType analogTriggerTypeB,
+    HAL_Bool reverseDirection, HAL_EncoderEncodingType encodingType,
+    int32_t* status);
+
+/**
+ * Frees an encoder.
+ *
+ * @param encoderHandle the encoder handle
+ */
+void HAL_FreeEncoder(HAL_EncoderHandle encoderHandle, int32_t* status);
+
+/**
+ * Gets the current counts of the encoder after encoding type scaling.
+ *
+ * This is scaled by the value passed duing initialization to encodingType.
+ *
+ * @param encoderHandle the encoder handle
+ * @return the current scaled count
+ */
+int32_t HAL_GetEncoder(HAL_EncoderHandle encoderHandle, int32_t* status);
+
+/**
+ * Gets the raw counts of the encoder.
+ *
+ * This is not scaled by any values.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the raw encoder count
+ */
+int32_t HAL_GetEncoderRaw(HAL_EncoderHandle encoderHandle, int32_t* status);
+
+/**
+ * Gets the encoder scale value.
+ *
+ * This is set by the value passed during initialization to encodingType.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the encoder scale value
+ */
+int32_t HAL_GetEncoderEncodingScale(HAL_EncoderHandle encoderHandle,
+                                    int32_t* status);
+
+/**
+ * Reads the current encoder value.
+ *
+ * Read the value at this instant. It may still be running, so it reflects the
+ * current value. Next time it is read, it might have a different value.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the current encoder value
+ */
+void HAL_ResetEncoder(HAL_EncoderHandle encoderHandle, int32_t* status);
+
+/*
+ * Gets the Period of the most recent count.
+ *
+ * Returns the time interval of the most recent count. This can be used for
+ * velocity calculations to determine shaft speed.
+ *
+ * @param encoderHandle the encoder handle
+ * @returns             the period of the last two pulses in units of seconds
+ */
+double HAL_GetEncoderPeriod(HAL_EncoderHandle encoderHandle, int32_t* status);
+
+/**
+ * Sets the maximum period where the device is still considered "moving".
+ *
+ * Sets the maximum period where the device is considered moving. This value is
+ * used to determine the "stopped" state of the encoder using the
+ * HAL_GetEncoderStopped method.
+ *
+ * @param encoderHandle the encoder handle
+ * @param maxPeriod     the maximum period where the counted device is
+ * considered moving in seconds
+ */
+void HAL_SetEncoderMaxPeriod(HAL_EncoderHandle encoderHandle, double maxPeriod,
+                             int32_t* status);
+
+/**
+ * Determines if the clock is stopped.
+ *
+ * Determines if the clocked input is stopped based on the MaxPeriod value set
+ * using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
+ * device (and encoder) are assumed to be stopped and it returns true.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              true if the most recent encoder period exceeds the
+ * MaxPeriod value set by SetMaxPeriod
+ */
+HAL_Bool HAL_GetEncoderStopped(HAL_EncoderHandle encoderHandle,
+                               int32_t* status);
+
+/**
+ * Gets the last direction the encoder value changed.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the last direction the encoder value changed
+ */
+HAL_Bool HAL_GetEncoderDirection(HAL_EncoderHandle encoderHandle,
+                                 int32_t* status);
+
+/**
+ * Gets the current distance traveled by the encoder.
+ *
+ * This is the encoder count scaled by the distance per pulse set for the
+ * encoder.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the encoder distance (units are determined by the units
+ * passed to HAL_SetEncoderDistancePerPulse)
+ */
+double HAL_GetEncoderDistance(HAL_EncoderHandle encoderHandle, int32_t* status);
+
+/**
+ * Gets the current rate of the encoder.
+ *
+ * This is the encoder period scaled by the distance per pulse set for the
+ * encoder.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the encoder rate (units are determined by the units
+ * passed to HAL_SetEncoderDistancePerPulse, time value is seconds)
+ */
+double HAL_GetEncoderRate(HAL_EncoderHandle encoderHandle, int32_t* status);
+
+/**
+ * Sets the minimum rate to be considered moving by the encoder.
+ *
+ * Units need to match what is set by HAL_SetEncoderDistancePerPulse, with time
+ * as seconds.
+ *
+ * @param encoderHandle the encoder handle
+ * @param minRate       the minimum rate to be considered moving (units are
+ * determined by the units passed to HAL_SetEncoderDistancePerPulse, time value
+ * is seconds)
+ */
+void HAL_SetEncoderMinRate(HAL_EncoderHandle encoderHandle, double minRate,
+                           int32_t* status);
+
+/**
+ * Sets the distance traveled per encoder pulse. This is used as a scaling
+ * factor for the rate and distance calls.
+ *
+ * @param encoderHandle    the encoder handle
+ * @param distancePerPulse the distance traveled per encoder pulse (units user
+ * defined)
+ */
+void HAL_SetEncoderDistancePerPulse(HAL_EncoderHandle encoderHandle,
+                                    double distancePerPulse, int32_t* status);
+
+/**
+ * Sets if to reverse the direction of the encoder.
+ *
+ * Note that this is not a toggle. It is an absolute set.
+ *
+ * @param encoderHandle    the encoder handle
+ * @param reverseDirection true to reverse the direction, false to not.
+ */
+void HAL_SetEncoderReverseDirection(HAL_EncoderHandle encoderHandle,
+                                    HAL_Bool reverseDirection, int32_t* status);
+
+/**
+ * Sets the number of encoder samples to average when calculating encoder rate.
+ *
+ * @param encoderHandle    the encoder handle
+ * @param samplesToAverage the number of samples to average
+ */
+void HAL_SetEncoderSamplesToAverage(HAL_EncoderHandle encoderHandle,
+                                    int32_t samplesToAverage, int32_t* status);
+
+/**
+ * Gets the current samples to average value.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the current samples to average value
+ */
+int32_t HAL_GetEncoderSamplesToAverage(HAL_EncoderHandle encoderHandle,
+                                       int32_t* status);
+
+/**
+ * Sets the source for an index pulse on the encoder.
+ *
+ * The index pulse can be used to cause an encoder to reset based on an external
+ * input.
+ *
+ * @param encoderHandle       the encoder handle
+ * @param digitalSourceHandle the index source handle (either a
+ * HAL_AnalogTriggerHandle of a HAL_DigitalHandle)
+ * @param analogTriggerType   the analog trigger type if the source is an analog
+ * trigger
+ * @param type                the index triggering type
+ */
+void HAL_SetEncoderIndexSource(HAL_EncoderHandle encoderHandle,
+                               HAL_Handle digitalSourceHandle,
+                               HAL_AnalogTriggerType analogTriggerType,
+                               HAL_EncoderIndexingType type, int32_t* status);
+
+/**
+ * Gets the FPGA index of the encoder.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the FPGA index of the encoder
+ */
+int32_t HAL_GetEncoderFPGAIndex(HAL_EncoderHandle encoderHandle,
+                                int32_t* status);
+
+/**
+ * Gets the decoding scale factor of the encoder.
+ *
+ * This is used to perform the scaling from raw to type scaled values.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the scale value for the encoder
+ */
+double HAL_GetEncoderDecodingScaleFactor(HAL_EncoderHandle encoderHandle,
+                                         int32_t* status);
+
+/**
+ * Gets the user set distance per pulse of the encoder.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the set distance per pulse
+ */
+double HAL_GetEncoderDistancePerPulse(HAL_EncoderHandle encoderHandle,
+                                      int32_t* status);
+
+/**
+ * Gets the encoding type of the encoder.
+ *
+ * @param encoderHandle the encoder handle
+ * @return              the encoding type
+ */
+HAL_EncoderEncodingType HAL_GetEncoderEncodingType(
+    HAL_EncoderHandle encoderHandle, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Errors.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Errors.h
new file mode 100644
index 0000000..4476ab0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Errors.h
@@ -0,0 +1,132 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/**
+ * @defgroup hal_errors Error Defines
+ * @ingroup hal_capi
+ * @{
+ */
+
+#define CTR_RxTimeout_MESSAGE "CTRE CAN Receive Timeout"
+#define CTR_TxTimeout_MESSAGE "CTRE CAN Transmit Timeout"
+#define CTR_InvalidParamValue_MESSAGE "CTRE CAN Invalid Parameter"
+#define CTR_UnexpectedArbId_MESSAGE \
+  "CTRE Unexpected Arbitration ID (CAN Node ID)"
+#define CTR_TxFailed_MESSAGE "CTRE CAN Transmit Error"
+#define CTR_SigNotUpdated_MESSAGE "CTRE CAN Signal Not Updated"
+
+#define NiFpga_Status_FifoTimeout_MESSAGE "NIFPGA: FIFO timeout error"
+#define NiFpga_Status_TransferAborted_MESSAGE "NIFPGA: Transfer aborted error"
+#define NiFpga_Status_MemoryFull_MESSAGE \
+  "NIFPGA: Memory Allocation failed, memory full"
+#define NiFpga_Status_SoftwareFault_MESSAGE "NIFPGA: Unexpected software error"
+#define NiFpga_Status_InvalidParameter_MESSAGE "NIFPGA: Invalid Parameter"
+#define NiFpga_Status_ResourceNotFound_MESSAGE "NIFPGA: Resource not found"
+#define NiFpga_Status_ResourceNotInitialized_MESSAGE \
+  "NIFPGA: Resource not initialized"
+#define NiFpga_Status_HardwareFault_MESSAGE "NIFPGA: Hardware Fault"
+#define NiFpga_Status_IrqTimeout_MESSAGE "NIFPGA: Interrupt timeout"
+
+#define ERR_CANSessionMux_InvalidBuffer_MESSAGE "CAN: Invalid Buffer"
+#define ERR_CANSessionMux_MessageNotFound_MESSAGE "CAN: Message not found"
+#define WARN_CANSessionMux_NoToken_MESSAGE "CAN: No token"
+#define ERR_CANSessionMux_NotAllowed_MESSAGE "CAN: Not allowed"
+#define ERR_CANSessionMux_NotInitialized_MESSAGE "CAN: Not initialized"
+
+#define ERR_FRCSystem_NetCommNotResponding_MESSAGE \
+  "FRCSystem: NetComm not responding"
+#define ERR_FRCSystem_NoDSConnection_MESSAGE \
+  "FRCSystem: No driver station connected"
+
+#define SAMPLE_RATE_TOO_HIGH 1001
+#define SAMPLE_RATE_TOO_HIGH_MESSAGE \
+  "HAL: Analog module sample rate is too high"
+#define VOLTAGE_OUT_OF_RANGE 1002
+#define VOLTAGE_OUT_OF_RANGE_MESSAGE \
+  "HAL: Voltage to convert to raw value is out of range [0; 5]"
+#define LOOP_TIMING_ERROR 1004
+#define LOOP_TIMING_ERROR_MESSAGE \
+  "HAL: Digital module loop timing is not the expected value"
+#define SPI_WRITE_NO_MOSI 1012
+#define SPI_WRITE_NO_MOSI_MESSAGE \
+  "HAL: Cannot write to SPI port with no MOSI output"
+#define SPI_READ_NO_MISO 1013
+#define SPI_READ_NO_MISO_MESSAGE \
+  "HAL: Cannot read from SPI port with no MISO input"
+#define SPI_READ_NO_DATA 1014
+#define SPI_READ_NO_DATA_MESSAGE "HAL: No data available to read from SPI"
+#define INCOMPATIBLE_STATE 1015
+#define INCOMPATIBLE_STATE_MESSAGE \
+  "HAL: Incompatible State: The operation cannot be completed"
+#define NO_AVAILABLE_RESOURCES -1004
+#define NO_AVAILABLE_RESOURCES_MESSAGE "HAL: No available resources to allocate"
+#define NULL_PARAMETER -1005
+#define NULL_PARAMETER_MESSAGE "HAL: A pointer parameter to a method is NULL"
+#define ANALOG_TRIGGER_LIMIT_ORDER_ERROR -1010
+#define ANALOG_TRIGGER_LIMIT_ORDER_ERROR_MESSAGE \
+  "HAL: AnalogTrigger limits error.  Lower limit > Upper Limit"
+#define ANALOG_TRIGGER_PULSE_OUTPUT_ERROR -1011
+#define ANALOG_TRIGGER_PULSE_OUTPUT_ERROR_MESSAGE \
+  "HAL: Attempted to read AnalogTrigger pulse output."
+#define PARAMETER_OUT_OF_RANGE -1028
+#define PARAMETER_OUT_OF_RANGE_MESSAGE "HAL: A parameter is out of range."
+#define RESOURCE_IS_ALLOCATED -1029
+#define RESOURCE_IS_ALLOCATED_MESSAGE "HAL: Resource already allocated"
+#define RESOURCE_OUT_OF_RANGE -1030
+#define RESOURCE_OUT_OF_RANGE_MESSAGE \
+  "HAL: The requested resource is out of range."
+#define HAL_INVALID_ACCUMULATOR_CHANNEL -1035
+#define HAL_INVALID_ACCUMULATOR_CHANNEL_MESSAGE \
+  "HAL: The requested input is not an accumulator channel"
+#define HAL_COUNTER_NOT_SUPPORTED -1058
+#define HAL_COUNTER_NOT_SUPPORTED_MESSAGE \
+  "HAL: Counter mode not supported for encoder method"
+#define HAL_PWM_SCALE_ERROR -1072
+#define HAL_PWM_SCALE_ERROR_MESSAGE \
+  "HAL: The PWM Scale Factors are out of range"
+#define HAL_HANDLE_ERROR -1098
+#define HAL_HANDLE_ERROR_MESSAGE \
+  "HAL: A handle parameter was passed incorrectly"
+
+#define HAL_SERIAL_PORT_NOT_FOUND -1123
+#define HAL_SERIAL_PORT_NOT_FOUND_MESSAGE \
+  "HAL: The specified serial port device was not found"
+
+#define HAL_SERIAL_PORT_OPEN_ERROR -1124
+#define HAL_SERIAL_PORT_OPEN_ERROR_MESSAGE \
+  "HAL: The serial port could not be opened"
+
+#define HAL_SERIAL_PORT_ERROR -1125
+#define HAL_SERIAL_PORT_ERROR_MESSAGE \
+  "HAL: There was an error on the serial port"
+
+#define HAL_THREAD_PRIORITY_ERROR -1152
+#define HAL_THREAD_PRIORITY_ERROR_MESSAGE \
+  "HAL: Getting or setting the priority of a thread has failed";
+
+#define HAL_THREAD_PRIORITY_RANGE_ERROR -1153
+#define HAL_THREAD_PRIORITY_RANGE_ERROR_MESSAGE \
+  "HAL: The priority requested to be set is invalid"
+
+#define HAL_CAN_TIMEOUT -1154
+#define HAL_CAN_TIMEOUT_MESSAGE "HAL: CAN Receive has Timed Out"
+
+#define VI_ERROR_SYSTEM_ERROR_MESSAGE "HAL - VISA: System Error";
+#define VI_ERROR_INV_OBJECT_MESSAGE "HAL - VISA: Invalid Object"
+#define VI_ERROR_RSRC_LOCKED_MESSAGE "HAL - VISA: Resource Locked"
+#define VI_ERROR_RSRC_NFOUND_MESSAGE "HAL - VISA: Resource Not Found"
+#define VI_ERROR_INV_RSRC_NAME_MESSAGE "HAL - VISA: Invalid Resource Name"
+#define VI_ERROR_QUEUE_OVERFLOW_MESSAGE "HAL - VISA: Queue Overflow"
+#define VI_ERROR_IO_MESSAGE "HAL - VISA: General IO Error"
+#define VI_ERROR_ASRL_PARITY_MESSAGE "HAL - VISA: Parity Error"
+#define VI_ERROR_ASRL_FRAMING_MESSAGE "HAL - VISA: Framing Error"
+#define VI_ERROR_ASRL_OVERRUN_MESSAGE "HAL - VISA: Buffer Overrun Error"
+#define VI_ERROR_RSRC_BUSY_MESSAGE "HAL - VISA: Resource Busy"
+#define VI_ERROR_INV_PARAMETER_MESSAGE "HAL - VISA: Invalid Parameter"
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Extensions.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Extensions.h
new file mode 100644
index 0000000..0fcbcba
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Extensions.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/**
+ * @defgroup hal_extensions Simulator Extensions
+ * @ingroup hal_capi
+ * HAL Simulator Extensions.  These are libraries that provide additional
+ * simulator functionality, such as a Gazebo interface, or a more light weight
+ * simulation.
+ *
+ * An extension must expose the HALSIM_InitExtension entry point which is
+ * invoked after the library is loaded.
+ *
+ * The entry point is expected to return < 0 for errors that should stop
+ * the HAL completely, 0 for success, and > 0 for a non fatal error.
+ * @{
+ */
+typedef int halsim_extension_init_func_t(void);
+
+extern "C" {
+/**
+ * Loads a single extension from a direct path.
+ *
+ * Expected to be called internally, not by users.
+ *
+ * @param library the library path
+ * @return        the succes state of the initialization
+ */
+int HAL_LoadOneExtension(const char* library);
+
+/**
+ * Loads any extra halsim libraries provided in the HALSIM_EXTENSIONS
+ * environment variable.
+ *
+ * @return        the succes state of the initialization
+ */
+int HAL_LoadExtensions(void);
+}  // extern "C"
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/HAL.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/HAL.h
new file mode 100644
index 0000000..f0da13f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/HAL.h
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2013-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#ifndef HAL_USE_LABVIEW
+
+#include "hal/Accelerometer.h"
+#include "hal/AnalogAccumulator.h"
+#include "hal/AnalogGyro.h"
+#include "hal/AnalogInput.h"
+#include "hal/AnalogOutput.h"
+#include "hal/AnalogTrigger.h"
+#include "hal/CAN.h"
+#include "hal/Compressor.h"
+#include "hal/Constants.h"
+#include "hal/Counter.h"
+#include "hal/DIO.h"
+#include "hal/DriverStation.h"
+#include "hal/Errors.h"
+#include "hal/I2C.h"
+#include "hal/Interrupts.h"
+#include "hal/Notifier.h"
+#include "hal/PDP.h"
+#include "hal/PWM.h"
+#include "hal/Ports.h"
+#include "hal/Power.h"
+#include "hal/Relay.h"
+#include "hal/SPI.h"
+#include "hal/SerialPort.h"
+#include "hal/Solenoid.h"
+
+#endif  // HAL_USE_LABVIEW
+
+#include "hal/Types.h"
+#include "hal/HALBase.h"
+
+#ifdef __cplusplus
+#include "hal/FRCUsageReporting.h"
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/HALBase.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/HALBase.h
new file mode 100644
index 0000000..fd22c0c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/HALBase.h
@@ -0,0 +1,182 @@
+/*----------------------------------------------------------------------------*/

+/* Copyright (c) 2008-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.                                                               */

+/*----------------------------------------------------------------------------*/

+

+#pragma once

+

+#include <stdint.h>

+

+#include "hal/Types.h"

+

+/**

+ * @defgroup hal_capi WPILib HAL API

+ * Hardware Abstraction Layer to hardware or simulator

+ * @{

+ */

+

+// clang-format off

+HAL_ENUM(HAL_RuntimeType) { HAL_Athena, HAL_Mock };

+// clang-format on

+

+#ifdef __cplusplus

+extern "C" {

+#endif

+

+/**

+ * Gets the error message for a specific status code.

+ *

+ * @param code the status code

+ * @return     the error message for the code. This does not need to be freed.

+ */

+const char* HAL_GetErrorMessage(int32_t code);

+

+/**

+ * Returns the FPGA Version number.

+ *

+ * For now, expect this to be competition year.

+ *

+ * @return FPGA Version number.

+ */

+int32_t HAL_GetFPGAVersion(int32_t* status);

+

+/**

+ * Returns the FPGA Revision number.

+ *

+ * The format of the revision is 3 numbers.

+ * The 12 most significant bits are the Major Revision.

+ * the next 8 bits are the Minor Revision.

+ * The 12 least significant bits are the Build Number.

+ *

+ * @return FPGA Revision number.

+ */

+int64_t HAL_GetFPGARevision(int32_t* status);

+

+HAL_RuntimeType HAL_GetRuntimeType(void);

+

+/**

+ * Gets the state of the "USER" button on the roboRIO.

+ *

+ * @return true if the button is currently pressed down

+ */

+HAL_Bool HAL_GetFPGAButton(int32_t* status);

+

+/**

+ * Gets if the system outputs are currently active

+ *

+ * @return true if the system outputs are active, false if disabled

+ */

+HAL_Bool HAL_GetSystemActive(int32_t* status);

+

+/**

+ * Gets if the system is in a browned out state.

+ *

+ * @return true if the system is in a low voltage brown out, false otherwise

+ */

+HAL_Bool HAL_GetBrownedOut(int32_t* status);

+

+/**

+ * The base HAL initialize function. Useful if you need to ensure the DS and

+ * base HAL functions (the ones above this declaration in HAL.h) are properly

+ * initialized. For normal programs and executables, please use HAL_Initialize.

+ *

+ * This is mainly expected to be use from libraries that are expected to be used

+ * from LabVIEW, as it handles its own initialization for objects.

+ */

+void HAL_BaseInitialize(int32_t* status);

+

+#ifndef HAL_USE_LABVIEW

+

+/**

+ * Gets a port handle for a specific channel.

+ *

+ * The created handle does not need to be freed.

+ *

+ * @param channel the channel number

+ * @return        the created port

+ */

+HAL_PortHandle HAL_GetPort(int32_t channel);

+

+/**

+ * Gets a port handle for a specific channel and module.

+ *

+ * This is expected to be used for PCMs, as the roboRIO does not work with

+ * modules anymore.

+ *

+ * The created handle does not need to be freed.

+ *

+ * @param module  the module number

+ * @param channel the channel number

+ * @return        the created port

+ */

+HAL_PortHandle HAL_GetPortWithModule(int32_t module, int32_t channel);

+

+/**

+ * Reads the microsecond-resolution timer on the FPGA.

+ *

+ * @return The current time in microseconds according to the FPGA (since FPGA

+ * reset).

+ */

+uint64_t HAL_GetFPGATime(int32_t* status);

+

+/**

+ * Call this to start up HAL. This is required for robot programs.

+ *

+ * This must be called before any other HAL functions. Failure to do so will

+ * result in undefined behavior, and likely segmentation faults. This means that

+ * any statically initialized variables in a program MUST call this function in

+ * their constructors if they want to use other HAL calls.

+ *

+ * The common parameters are 500 for timeout and 0 for mode.

+ *

+ * This function is safe to call from any thread, and as many times as you wish.

+ * It internally guards from any reentrancy.

+ *

+ * The applicable modes are:

+ *   0: Try to kill an existing HAL from another program, if not successful,

+ * error.

+ *   1: Force kill a HAL from another program.

+ *   2: Just warn if another hal exists and cannot be killed. Will likely result

+ * in undefined behavior.

+ *

+ * @param timeout the initialization timeout (ms)

+ * @param mode    the initialization mode (see remarks)

+ * @return        true if initialization was successful, otherwise false.

+ */

+HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode);

+

+// ifdef's definition is to allow for default parameters in C++.

+#ifdef __cplusplus

+/**

+ * Reports a hardware usage to the HAL.

+ *

+ * @param resource       the used resource

+ * @param instanceNumber the instance of the resource

+ * @param context        a user specified context index

+ * @param feature        a user specified feature string

+ * @return               the index of the added value in NetComm

+ */

+int64_t HAL_Report(int32_t resource, int32_t instanceNumber,

+                   int32_t context = 0, const char* feature = nullptr);

+#else

+

+/**

+ * Reports a hardware usage to the HAL.

+ *

+ * @param resource       the used resource

+ * @param instanceNumber the instance of the resource

+ * @param context        a user specified context index

+ * @param feature        a user specified feature string

+ * @return               the index of the added value in NetComm

+ */

+int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context,

+                   const char* feature);

+#endif

+

+#endif  // HAL_USE_LABVIEW

+#ifdef __cplusplus

+}  // extern "C"

+#endif

+/** @} */

diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/I2C.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/I2C.h
new file mode 100644
index 0000000..fc8b5c8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/I2C.h
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/I2CTypes.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_i2c I2C Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes the I2C port.
+ *
+ * Opens the port if necessary and saves the handle.
+ * If opening the MXP port, also sets up the channel functions appropriately.
+ *
+ * @param port The port to open, 0 for the on-board, 1 for the MXP.
+ */
+void HAL_InitializeI2C(HAL_I2CPort port, int32_t* status);
+
+/**
+ * Generic I2C read/write transaction.
+ *
+ * This is a lower-level interface to the I2C hardware giving you more control
+ * over each transaction.
+ *
+ * @param port The I2C port, 0 for the on-board, 1 for the MXP.
+ * @param dataToSend Buffer of data to send as part of the transaction.
+ * @param sendSize Number of bytes to send as part of the transaction.
+ * @param dataReceived Buffer to read data into.
+ * @param receiveSize Number of bytes to read from the device.
+ * @return >= 0 on success or -1 on transfer abort.
+ */
+int32_t HAL_TransactionI2C(HAL_I2CPort port, int32_t deviceAddress,
+                           const uint8_t* dataToSend, int32_t sendSize,
+                           uint8_t* dataReceived, int32_t receiveSize);
+
+/**
+ * Executes a write transaction with the device.
+ *
+ * Writes a single byte to a register on a device and wait until the
+ *   transaction is complete.
+ *
+ * @param port The I2C port, 0 for the on-board, 1 for the MXP.
+ * @param registerAddress The address of the register on the device to be
+ * written.
+ * @param data The byte to write to the register on the device.
+ * @return >= 0 on success or -1 on transfer abort.
+ */
+int32_t HAL_WriteI2C(HAL_I2CPort port, int32_t deviceAddress,
+                     const uint8_t* dataToSend, int32_t sendSize);
+
+/**
+ * Executes a read transaction with the device.
+ *
+ * Reads bytes from a device.
+ * Most I2C devices will auto-increment the register pointer internally allowing
+ *   you to read consecutive registers on a device in a single transaction.
+ *
+ * @param port The I2C port, 0 for the on-board, 1 for the MXP.
+ * @param registerAddress The register to read first in the transaction.
+ * @param count The number of bytes to read in the transaction.
+ * @param buffer A pointer to the array of bytes to store the data read from the
+ * device.
+ * @return >= 0 on success or -1 on transfer abort.
+ */
+int32_t HAL_ReadI2C(HAL_I2CPort port, int32_t deviceAddress, uint8_t* buffer,
+                    int32_t count);
+
+/**
+ * Closes an I2C port
+ *
+ * @param port The I2C port, 0 for the on-board, 1 for the MXP.
+ */
+void HAL_CloseI2C(HAL_I2CPort port);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/I2CTypes.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/I2CTypes.h
new file mode 100644
index 0000000..d0b269f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/I2CTypes.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_i2c I2C Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+// clang-format off
+HAL_ENUM(HAL_I2CPort) { HAL_I2C_kInvalid = -1, HAL_I2C_kOnboard, HAL_I2C_kMXP };
+// clang-format on
+
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Interrupts.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Interrupts.h
new file mode 100644
index 0000000..126b92c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Interrupts.h
@@ -0,0 +1,159 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/AnalogTrigger.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_interrupts Interrupts Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+typedef void (*HAL_InterruptHandlerFunction)(uint32_t interruptAssertedMask,
+                                             void* param);
+
+/**
+ * Initializes an interrupt.
+ *
+ * @param watcher true for synchronous interrupts, false for asynchronous
+ * @return        the created interrupt handle
+ */
+HAL_InterruptHandle HAL_InitializeInterrupts(HAL_Bool watcher, int32_t* status);
+
+/**
+ * Frees an interrupt.
+ *
+ * @param interruptHandle the interrupt handle
+ * @return                the param passed to the interrupt, or nullptr if one
+ * wasn't passed.
+ */
+void* HAL_CleanInterrupts(HAL_InterruptHandle interruptHandle, int32_t* status);
+
+/**
+ * In synchronous mode, waits for the defined interrupt to occur.
+ *
+ * @param interruptHandle the interrupt handle
+ * @param timeout        timeout in seconds
+ * @param ignorePrevious if true, ignore interrupts that happened before
+ * waitForInterrupt was called
+ * @return               the mask of interrupts that fired
+ */
+int64_t HAL_WaitForInterrupt(HAL_InterruptHandle interruptHandle,
+                             double timeout, HAL_Bool ignorePrevious,
+                             int32_t* status);
+
+/**
+ * Enables interrupts to occur on this input.
+ *
+ * Interrupts are disabled when the RequestInterrupt call is made. This gives
+ * time to do the setup of the other options before starting to field
+ * interrupts.
+ *
+ * @param interruptHandle the interrupt handle
+ */
+void HAL_EnableInterrupts(HAL_InterruptHandle interruptHandle, int32_t* status);
+
+/**
+ * Disables interrupts without without deallocating structures.
+ *
+ * @param interruptHandle the interrupt handle
+ */
+void HAL_DisableInterrupts(HAL_InterruptHandle interruptHandle,
+                           int32_t* status);
+
+/**
+ * Returns the timestamp for the rising interrupt that occurred most recently.
+ *
+ * This is in the same time domain as HAL_GetFPGATime().  It only contains the
+ * bottom 32 bits of the timestamp.  If your robot has been running for over 1
+ * hour, you will need to fill in the upper 32 bits yourself.
+ *
+ * @param interruptHandle the interrupt handle
+ * @return                timestamp in microseconds since FPGA Initialization
+ */
+int64_t HAL_ReadInterruptRisingTimestamp(HAL_InterruptHandle interruptHandle,
+                                         int32_t* status);
+
+/**
+ * Returns the timestamp for the falling interrupt that occurred most recently.
+ *
+ * This is in the same time domain as HAL_GetFPGATime().  It only contains the
+ * bottom 32 bits of the timestamp.  If your robot has been running for over 1
+ * hour, you will need to fill in the upper 32 bits yourself.
+ *
+ * @param interruptHandle the interrupt handle
+ * @return                timestamp in microseconds since FPGA Initialization
+ */
+int64_t HAL_ReadInterruptFallingTimestamp(HAL_InterruptHandle interruptHandle,
+                                          int32_t* status);
+
+/**
+ * Requests interrupts on a specific digital source.
+ *
+ * @param interruptHandle     the interrupt handle
+ * @param digitalSourceHandle the digital source handle (either a
+ * HAL_AnalogTriggerHandle of a HAL_DigitalHandle)
+ * @param analogTriggerType   the trigger type if the source is an AnalogTrigger
+ */
+void HAL_RequestInterrupts(HAL_InterruptHandle interruptHandle,
+                           HAL_Handle digitalSourceHandle,
+                           HAL_AnalogTriggerType analogTriggerType,
+                           int32_t* status);
+
+/**
+ * Attaches an asynchronous interrupt handler to the interrupt.
+ *
+ * This interrupt gets called directly on the FPGA interrupt thread, so will
+ * block other interrupts while running.
+ *
+ * @param interruptHandle the interrupt handle
+ * @param handler         the handler function for the interrupt to call
+ * @param param           a parameter to be passed to the handler
+ */
+void HAL_AttachInterruptHandler(HAL_InterruptHandle interruptHandle,
+                                HAL_InterruptHandlerFunction handler,
+                                void* param, int32_t* status);
+
+/**
+ * Attaches an asynchronous interrupt handler to the interrupt.
+ *
+ * This interrupt gets called on a thread specific to the interrupt, so will not
+ * block other interrupts.
+ *
+ * @param interruptHandle the interrupt handle
+ * @param handler         the handler function for the interrupt to call
+ * @param param           a parameter to be passed to the handler
+ */
+void HAL_AttachInterruptHandlerThreaded(HAL_InterruptHandle interruptHandle,
+                                        HAL_InterruptHandlerFunction handler,
+                                        void* param, int32_t* status);
+
+/**
+ * Sets the edges to trigger the interrupt on.
+ *
+ * Note that both edges triggered is a valid configuration.
+ *
+ * @param interruptHandle the interrupt handle
+ * @param risingEdge      true for triggering on rising edge
+ * @param fallingEdge     true for triggering on falling edge
+ */
+void HAL_SetInterruptUpSourceEdge(HAL_InterruptHandle interruptHandle,
+                                  HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                  int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Notifier.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Notifier.h
new file mode 100644
index 0000000..27f20e3
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Notifier.h
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_notifier Notifier Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a notifier.
+ *
+ * A notifier is an FPGA controller timer that triggers at requested intervals
+ * based on the FPGA time. This can be used to make precise control loops.
+ *
+ * @return the created notifier
+ */
+HAL_NotifierHandle HAL_InitializeNotifier(int32_t* status);
+
+/**
+ * Stops a notifier from running.
+ *
+ * This will cause any call into HAL_WaitForNotifierAlarm to return.
+ *
+ * @param notifierHandle the notifier handle
+ */
+void HAL_StopNotifier(HAL_NotifierHandle notifierHandle, int32_t* status);
+
+/**
+ * Cleans a notifier.
+ *
+ * Note this also stops a notifier if it is already running.
+ *
+ * @param notifierHandle the notifier handle
+ */
+void HAL_CleanNotifier(HAL_NotifierHandle notifierHandle, int32_t* status);
+
+/**
+ * Updates the trigger time for a notifier.
+ *
+ * Note that this time is an absolute time relative to HAL_GetFPGATime()
+ *
+ * @param notifierHandle the notifier handle
+ * @param triggerTime    the updated trigger time
+ */
+void HAL_UpdateNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                             uint64_t triggerTime, int32_t* status);
+
+/**
+ * Cancels the next notifier alarm.
+ *
+ * This does not cause HAL_WaitForNotifierAlarm to return.
+ *
+ * @param notifierHandle the notifier handle
+ */
+void HAL_CancelNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                             int32_t* status);
+
+/**
+ * Waits for the next alarm for the specific notifier.
+ *
+ * This is a blocking call until either the time elapses or HAL_StopNotifier
+ * gets called.
+ *
+ * @param notifierHandle the notifier handle
+ * @return               the FPGA time the notifier returned
+ */
+uint64_t HAL_WaitForNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                                  int32_t* status);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/PDP.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/PDP.h
new file mode 100644
index 0000000..50873f8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/PDP.h
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_pdp PDP Functions
+ * @ingroup hal_capi
+ * Functions to control the Power Distribution Panel.
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a Power Distribution Panel.
+ *
+ * @param  module the module number to initialize
+ * @return the created PDP
+ */
+HAL_PDPHandle HAL_InitializePDP(int32_t module, int32_t* status);
+
+/**
+ * Cleans a PDP module.
+ *
+ * @param handle the module handle
+ */
+void HAL_CleanPDP(HAL_PDPHandle handle);
+
+/**
+ * Checks if a PDP channel is valid.
+ *
+ * @param channel the channel to check
+ * @return        true if the channel is valid, otherwise false
+ */
+HAL_Bool HAL_CheckPDPChannel(int32_t channel);
+
+/**
+ * Checks if a PDP module is valid.
+ *
+ * @param channel the module to check
+ * @return        true if the module is valid, otherwise false
+ */
+HAL_Bool HAL_CheckPDPModule(int32_t module);
+
+/**
+ * Gets the temperature of the PDP.
+ *
+ * @param handle the module handle
+ * @return       the module temperature (celsius)
+ */
+double HAL_GetPDPTemperature(HAL_PDPHandle handle, int32_t* status);
+
+/**
+ * Gets the PDP input voltage.
+ *
+ * @param handle the module handle
+ * @return       the input voltage (volts)
+ */
+double HAL_GetPDPVoltage(HAL_PDPHandle handle, int32_t* status);
+
+/**
+ * Gets the current of a specific PDP channel.
+ *
+ * @param module  the module
+ * @param channel the channel
+ * @return        the channel current (amps)
+ */
+double HAL_GetPDPChannelCurrent(HAL_PDPHandle handle, int32_t channel,
+                                int32_t* status);
+
+/**
+ * Gets the total current of the PDP.
+ *
+ * @param handle the module handle
+ * @return       the total current (amps)
+ */
+double HAL_GetPDPTotalCurrent(HAL_PDPHandle handle, int32_t* status);
+
+/**
+ * Gets the total power of the PDP.
+ *
+ * @param handle the module handle
+ * @return       the total power (watts)
+ */
+double HAL_GetPDPTotalPower(HAL_PDPHandle handle, int32_t* status);
+
+/**
+ * Gets the total energy of the PDP.
+ *
+ * @param handle the module handle
+ * @return       the total energy (joules)
+ */
+double HAL_GetPDPTotalEnergy(HAL_PDPHandle handle, int32_t* status);
+
+/**
+ * Resets the PDP accumulated energy.
+ *
+ * @param handle the module handle
+ */
+void HAL_ResetPDPTotalEnergy(HAL_PDPHandle handle, int32_t* status);
+
+/**
+ * Clears any PDP sticky faults.
+ *
+ * @param handle the module handle
+ */
+void HAL_ClearPDPStickyFaults(HAL_PDPHandle handle, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/PWM.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/PWM.h
new file mode 100644
index 0000000..781a423
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/PWM.h
@@ -0,0 +1,233 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_pwm PWM Output Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a PWM port.
+ *
+ * @param portHandle the port to initialize
+ * @return           the created pwm handle
+ */
+HAL_DigitalHandle HAL_InitializePWMPort(HAL_PortHandle portHandle,
+                                        int32_t* status);
+
+/**
+ * Frees a PWM port.
+ *
+ * @param pwmPortHandle the pwm handle
+ */
+void HAL_FreePWMPort(HAL_DigitalHandle pwmPortHandle, int32_t* status);
+
+/**
+ * Checks if a pwm channel is valid.
+ *
+ * @param channel the channel to check
+ * @return        true if the channel is valid, otherwise false
+ */
+HAL_Bool HAL_CheckPWMChannel(int32_t channel);
+
+/**
+ * Sets the configuration settings for the PWM channel.
+ *
+ * All values are in milliseconds.
+ *
+ * @param pwmPortHandle  the PWM handle
+ * @param maxPwm         the maximum PWM value
+ * @param deadbandMaxPwm the high range of the center deadband
+ * @param centerPwm      the center PWM value
+ * @param deadbandMinPwm the low range of the center deadband
+ * @param minPwm         the minimum PWM value
+ */
+void HAL_SetPWMConfig(HAL_DigitalHandle pwmPortHandle, double maxPwm,
+                      double deadbandMaxPwm, double centerPwm,
+                      double deadbandMinPwm, double minPwm, int32_t* status);
+
+/**
+ * Sets the raw configuration settings for the PWM channel.
+ *
+ * We recommend using HAL_SetPWMConfig() instead, as those values are properly
+ * scaled. Usually used for values grabbed by HAL_GetPWMConfigRaw().
+ *
+ * Values are in raw FPGA units.
+ *
+ * @param pwmPortHandle  the PWM handle
+ * @param maxPwm         the maximum PWM value
+ * @param deadbandMaxPwm the high range of the center deadband
+ * @param centerPwm      the center PWM value
+ * @param deadbandMinPwm the low range of the center deadband
+ * @param minPwm         the minimum PWM value
+ */
+void HAL_SetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t maxPwm,
+                         int32_t deadbandMaxPwm, int32_t centerPwm,
+                         int32_t deadbandMinPwm, int32_t minPwm,
+                         int32_t* status);
+
+/**
+ * Gets the raw pwm configuration settings for the PWM channel.
+ *
+ * Values are in raw FPGA units. These units have the potential to change for
+ * any FPGA release.
+ *
+ * @param pwmPortHandle  the PWM handle
+ * @param maxPwm         the maximum PWM value
+ * @param deadbandMaxPwm the high range of the center deadband
+ * @param centerPwm      the center PWM value
+ * @param deadbandMinPwm the low range of the center deadband
+ * @param minPwm         the minimum PWM value
+ */
+void HAL_GetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t* maxPwm,
+                         int32_t* deadbandMaxPwm, int32_t* centerPwm,
+                         int32_t* deadbandMinPwm, int32_t* minPwm,
+                         int32_t* status);
+
+/**
+ * Sets if the FPGA should output the center value if the input value is within
+ * the deadband.
+ *
+ * @param pwmPortHandle     the PWM handle
+ * @param eliminateDeadband true to eliminate deadband, otherwise false
+ */
+void HAL_SetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
+                                 HAL_Bool eliminateDeadband, int32_t* status);
+
+/**
+ * Gets the current eliminate deadband value.
+ *
+ * @param pwmPortHandle the PWM handle
+ * @return              true if set, otherwise false
+ */
+HAL_Bool HAL_GetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
+                                     int32_t* status);
+
+/**
+ * Sets a PWM channel to the desired value.
+ *
+ * The values are in raw FPGA units, and have the potential to change with any
+ * FPGA release.
+ *
+ * @param pwmPortHandle the PWM handle
+ * @param value         the PWM value to set
+ */
+void HAL_SetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t value,
+                   int32_t* status);
+
+/**
+ * Sets a PWM channel to the desired scaled value.
+ *
+ * The values range from -1 to 1 and the period is controlled by the PWM Period
+ * and MinHigh registers.
+ *
+ * @param pwmPortHandle the PWM handle
+ * @param value         the scaled PWM value to set
+ */
+void HAL_SetPWMSpeed(HAL_DigitalHandle pwmPortHandle, double speed,
+                     int32_t* status);
+
+/**
+ * Sets a PWM channel to the desired position value.
+ *
+ * The values range from 0 to 1 and the period is controlled by the PWM Period
+ * and MinHigh registers.
+ *
+ * @param pwmPortHandle the PWM handle
+ * @param value         the positional PWM value to set
+ */
+void HAL_SetPWMPosition(HAL_DigitalHandle pwmPortHandle, double position,
+                        int32_t* status);
+
+/**
+ * Sets a PWM channel to be disabled.
+ *
+ * The channel is disabled until the next time it is set. Note this is different
+ * from just setting a 0 speed, as this will actively stop all signalling on the
+ * channel.
+ *
+ * @param pwmPortHandle the PWM handle.
+ */
+void HAL_SetPWMDisabled(HAL_DigitalHandle pwmPortHandle, int32_t* status);
+
+/**
+ * Gets a value from a PWM channel.
+ *
+ * The values are in raw FPGA units, and have the potential to change with any
+ * FPGA release.
+ *
+ * @param pwmPortHandle the PWM handle
+ * @return              the current raw PWM value
+ */
+int32_t HAL_GetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t* status);
+
+/**
+ * Gets a scaled value from a PWM channel.
+ *
+ * The values range from -1 to 1.
+ *
+ * @param pwmPortHandle the PWM handle
+ * @return              the current speed PWM value
+ */
+double HAL_GetPWMSpeed(HAL_DigitalHandle pwmPortHandle, int32_t* status);
+
+/**
+ * Gets a position value from a PWM channel.
+ *
+ * The values range from 0 to 1.
+ *
+ * @param pwmPortHandle the PWM handle
+ * @return              the current positional PWM value
+ */
+double HAL_GetPWMPosition(HAL_DigitalHandle pwmPortHandle, int32_t* status);
+
+/**
+ * Forces a PWM signal to go to 0 temporarily.
+ *
+ * @param pwmPortHandle the PWM handle.
+ */
+void HAL_LatchPWMZero(HAL_DigitalHandle pwmPortHandle, int32_t* status);
+
+/**
+ * Sets how how often the PWM signal is squelched, thus scaling the period.
+ *
+ * @param pwmPortHandle the PWM handle.
+ * @param squelchMask   the 2-bit mask of outputs to squelch
+ */
+void HAL_SetPWMPeriodScale(HAL_DigitalHandle pwmPortHandle, int32_t squelchMask,
+                           int32_t* status);
+
+/**
+ * Gets the loop timing of the PWM system.
+ *
+ * @return the loop time
+ */
+int32_t HAL_GetPWMLoopTiming(int32_t* status);
+
+/**
+ * Gets the pwm starting cycle time.
+ *
+ * This time is relative to the FPGA time.
+ *
+ * @return the pwm cycle start time
+ */
+uint64_t HAL_GetPWMCycleStartTime(int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Ports.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Ports.h
new file mode 100644
index 0000000..9b29817
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Ports.h
@@ -0,0 +1,150 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+/**
+ * @defgroup hal_ports Ports Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Gets the number of analog accumulators in the current system.
+ *
+ * @return the number of analog accumulators
+ */
+int32_t HAL_GetNumAccumulators(void);
+
+/**
+ * Gets the number of analog triggers in the current system.
+ *
+ * @return the number of analog triggers
+ */
+int32_t HAL_GetNumAnalogTriggers(void);
+
+/**
+ * Gets the number of analog inputs in the current system.
+ *
+ * @return the number of analog inputs
+ */
+int32_t HAL_GetNumAnalogInputs(void);
+
+/**
+ * Gets the number of analog outputs in the current system.
+ *
+ * @return the number of analog outputs
+ */
+int32_t HAL_GetNumAnalogOutputs(void);
+
+/**
+ * Gets the number of analog counters in the current system.
+ *
+ * @return the number of counters
+ */
+int32_t HAL_GetNumCounters(void);
+
+/**
+ * Gets the number of digital headers in the current system.
+ *
+ * @return the number of digital headers
+ */
+int32_t HAL_GetNumDigitalHeaders(void);
+
+/**
+ * Gets the number of PWM headers in the current system.
+ *
+ * @return the number of PWM headers
+ */
+int32_t HAL_GetNumPWMHeaders(void);
+
+/**
+ * Gets the number of digital channels in the current system.
+ *
+ * @return the number of digital channels
+ */
+int32_t HAL_GetNumDigitalChannels(void);
+
+/**
+ * Gets the number of PWM channels in the current system.
+ *
+ * @return the number of PWM channels
+ */
+int32_t HAL_GetNumPWMChannels(void);
+
+/**
+ * Gets the number of digital IO PWM outputs in the current system.
+ *
+ * @return the number of digital IO PWM outputs
+ */
+int32_t HAL_GetNumDigitalPWMOutputs(void);
+
+/**
+ * Gets the number of quadrature encoders in the current system.
+ *
+ * @return the number of quadrature encoders
+ */
+int32_t HAL_GetNumEncoders(void);
+
+/**
+ * Gets the number of interrupts in the current system.
+ *
+ * @return the number of interrupts
+ */
+int32_t HAL_GetNumInterrupts(void);
+
+/**
+ * Gets the number of relay channels in the current system.
+ *
+ * @return the number of relay channels
+ */
+int32_t HAL_GetNumRelayChannels(void);
+
+/**
+ * Gets the number of relay headers in the current system.
+ *
+ * @return the number of relay headers
+ */
+int32_t HAL_GetNumRelayHeaders(void);
+
+/**
+ * Gets the number of PCM modules in the current system.
+ *
+ * @return the number of PCM modules
+ */
+int32_t HAL_GetNumPCMModules(void);
+
+/**
+ * Gets the number of solenoid channels in the current system.
+ *
+ * @return the number of solenoid channels
+ */
+int32_t HAL_GetNumSolenoidChannels(void);
+
+/**
+ * Gets the number of PDP modules in the current system.
+ *
+ * @return the number of PDP modules
+ */
+int32_t HAL_GetNumPDPModules(void);
+
+/**
+ * Gets the number of PDP channels in the current system.
+ *
+ * @return the number of PDP channels
+ */
+int32_t HAL_GetNumPDPChannels(void);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Power.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Power.h
new file mode 100644
index 0000000..7ac7991
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Power.h
@@ -0,0 +1,124 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_power Power Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Gets the roboRIO input voltage.
+ *
+ * @return the input voltage (volts)
+ */
+double HAL_GetVinVoltage(int32_t* status);
+
+/**
+ * Gets the roboRIO input current.
+ *
+ * @return the input current (amps)
+ */
+double HAL_GetVinCurrent(int32_t* status);
+
+/**
+ * Gets the 6V rail voltage.
+ *
+ * @return the 6V rail voltage (volts)
+ */
+double HAL_GetUserVoltage6V(int32_t* status);
+
+/**
+ * Gets the 6V rail current.
+ *
+ * @return the 6V rail current (amps)
+ */
+double HAL_GetUserCurrent6V(int32_t* status);
+
+/**
+ * Gets the active state of the 6V rail.
+ *
+ * @return true if the rail is active, otherwise false
+ */
+HAL_Bool HAL_GetUserActive6V(int32_t* status);
+
+/**
+ * Gets the fault count for the 6V rail.
+ *
+ * @return the number of 6V fault counts
+ */
+int32_t HAL_GetUserCurrentFaults6V(int32_t* status);
+
+/**
+ * Gets the 5V rail voltage.
+ *
+ * @return the 5V rail voltage (volts)
+ */
+double HAL_GetUserVoltage5V(int32_t* status);
+
+/**
+ * Gets the 5V rail current.
+ *
+ * @return the 5V rail current (amps)
+ */
+double HAL_GetUserCurrent5V(int32_t* status);
+
+/**
+ * Gets the active state of the 5V rail.
+ *
+ * @return true if the rail is active, otherwise false
+ */
+HAL_Bool HAL_GetUserActive5V(int32_t* status);
+
+/**
+ * Gets the fault count for the 5V rail.
+ *
+ * @return the number of 5V fault counts
+ */
+int32_t HAL_GetUserCurrentFaults5V(int32_t* status);
+
+/**
+ * Gets the 3V3 rail voltage.
+ *
+ * @return the 3V3 rail voltage (volts)
+ */
+double HAL_GetUserVoltage3V3(int32_t* status);
+
+/**
+ * Gets the 3V3 rail current.
+ *
+ * @return the 3V3 rail current (amps)
+ */
+double HAL_GetUserCurrent3V3(int32_t* status);
+
+/**
+ * Gets the active state of the 3V3 rail.
+ *
+ * @return true if the rail is active, otherwise false
+ */
+HAL_Bool HAL_GetUserActive3V3(int32_t* status);
+
+/**
+ * Gets the fault count for the 3V3 rail.
+ *
+ * @return the number of 3V3 fault counts
+ */
+int32_t HAL_GetUserCurrentFaults3V3(int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Relay.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Relay.h
new file mode 100644
index 0000000..281aad6
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Relay.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_relay Relay Output Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a relay.
+ *
+ * Note this call will only initialize either the forward or reverse port of the
+ * relay. If you need both, you will need to initialize 2 relays.
+ *
+ * @param portHandle the port handle to initialize
+ * @param fwd        true for the forward port, false for the reverse port
+ * @return           the created relay handle
+ */
+HAL_RelayHandle HAL_InitializeRelayPort(HAL_PortHandle portHandle, HAL_Bool fwd,
+                                        int32_t* status);
+
+/**
+ * Frees a relay port.
+ *
+ * @param relayPortHandle the relay handle
+ */
+void HAL_FreeRelayPort(HAL_RelayHandle relayPortHandle);
+
+/**
+ * Checks if a relay channel is valid.
+ *
+ * @param channel the channel to check
+ * @return        true if the channel is valid, otherwise false
+ */
+HAL_Bool HAL_CheckRelayChannel(int32_t channel);
+
+/**
+ * Sets the state of a relay output.
+ *
+ * @param relayPortHandle the relay handle
+ * @param on              true for on, false for off
+ */
+void HAL_SetRelay(HAL_RelayHandle relayPortHandle, HAL_Bool on,
+                  int32_t* status);
+
+/**
+ * Gets the current state of the relay channel.
+ *
+ * @param relayPortHandle the relay handle
+ * @return                true for on, false for off
+ */
+HAL_Bool HAL_GetRelay(HAL_RelayHandle relayPortHandle, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/SPI.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/SPI.h
new file mode 100644
index 0000000..4f1815f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/SPI.h
@@ -0,0 +1,250 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/AnalogTrigger.h"
+#include "hal/SPITypes.h"
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_spi SPI Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes the SPI port. Opens the port if necessary and saves the handle.
+ *
+ * If opening the MXP port, also sets up the channel functions appropriately.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS3, 4 for MXP
+ */
+void HAL_InitializeSPI(HAL_SPIPort port, int32_t* status);
+
+/**
+ * Performs an SPI send/receive transaction.
+ *
+ * This is a lower-level interface to the spi hardware giving you more control
+ * over each transaction.
+ *
+ * @param port         The number of the port to use. 0-3 for Onboard CS0-CS2, 4
+ * for MXP
+ * @param dataToSend   Buffer of data to send as part of the transaction.
+ * @param dataReceived Buffer to read data into.
+ * @param size         Number of bytes to transfer. [0..7]
+ * @return             Number of bytes transferred, -1 for error
+ */
+int32_t HAL_TransactionSPI(HAL_SPIPort port, const uint8_t* dataToSend,
+                           uint8_t* dataReceived, int32_t size);
+
+/**
+ * Executes a write transaction with the device.
+ *
+ * Writes to a device and wait until the transaction is complete.
+ *
+ * @param port      The number of the port to use. 0-3 for Onboard CS0-CS2, 4
+ * for MXP
+ * @param datToSend The data to write to the register on the device.
+ * @param sendSize  The number of bytes to be written
+ * @return          The number of bytes written. -1 for an error
+ */
+int32_t HAL_WriteSPI(HAL_SPIPort port, const uint8_t* dataToSend,
+                     int32_t sendSize);
+
+/**
+ * Executes a read from the device.
+ *
+ * This method does not write any data out to the device.
+ *
+ * Most spi devices will require a register address to be written before they
+ * begin returning data.
+ *
+ * @param port   The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP
+ * @param buffer A pointer to the array of bytes to store the data read from the
+ * device.
+ * @param count  The number of bytes to read in the transaction. [1..7]
+ * @return       Number of bytes read. -1 for error.
+ */
+int32_t HAL_ReadSPI(HAL_SPIPort port, uint8_t* buffer, int32_t count);
+
+/**
+ * Closes the SPI port.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void HAL_CloseSPI(HAL_SPIPort port);
+
+/**
+ * Sets the clock speed for the SPI bus.
+ *
+ * @param port  The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP
+ * @param speed The speed in Hz (0-1MHz)
+ */
+void HAL_SetSPISpeed(HAL_SPIPort port, int32_t speed);
+
+/**
+ * Sets the SPI options.
+ *
+ * @param port             The number of the port to use. 0-3 for Onboard
+ * CS0-CS2, 4 for MXP
+ * @param msbFirst         True to write the MSB first, False for LSB first
+ * @param sampleOnTrailing True to sample on the trailing edge, False to sample
+ * on the leading edge
+ * @param clkIdleHigh      True to set the clock to active low, False to set the
+ * clock active high
+ */
+void HAL_SetSPIOpts(HAL_SPIPort port, HAL_Bool msbFirst,
+                    HAL_Bool sampleOnTrailing, HAL_Bool clkIdleHigh);
+
+/**
+ * Sets the CS Active high for a SPI port.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void HAL_SetSPIChipSelectActiveHigh(HAL_SPIPort port, int32_t* status);
+
+/**
+ * Sets the CS Active low for a SPI port.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ */
+void HAL_SetSPIChipSelectActiveLow(HAL_SPIPort port, int32_t* status);
+
+/**
+ * Gets the stored handle for a SPI port.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for MXP
+ * @return     The stored handle for the SPI port. 0 represents no stored
+ * handle.
+ */
+int32_t HAL_GetSPIHandle(HAL_SPIPort port);
+
+/**
+ * Sets the stored handle for a SPI port.
+ *
+ * @param port   The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP.
+ * @param handle The value of the handle for the port.
+ */
+void HAL_SetSPIHandle(HAL_SPIPort port, int32_t handle);
+
+/**
+ * Initializes the SPI automatic accumulator.
+ *
+ * @param port       The number of the port to use. 0-3 for Onboard CS0-CS2, 4
+ * for MXP.
+ * @param bufferSize The accumulator buffer size.
+ */
+void HAL_InitSPIAuto(HAL_SPIPort port, int32_t bufferSize, int32_t* status);
+
+/**
+ * Frees an SPI automatic accumulator.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP.
+ */
+void HAL_FreeSPIAuto(HAL_SPIPort port, int32_t* status);
+
+/**
+ * Sets the period for automatic SPI accumulation.
+ *
+ * @param port   The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP.
+ * @param period The accumlation period (seconds).
+ */
+void HAL_StartSPIAutoRate(HAL_SPIPort port, double period, int32_t* status);
+
+/**
+ * Starts the auto SPI accumulator on a specific trigger.
+ *
+ * Note that triggering on both rising and falling edges is a valid
+ * configuration.
+ *
+ * @param port                The number of the port to use. 0-3 for Onboard
+ * CS0-CS2, 4 for MXP.
+ * @param digitalSourceHandle The trigger source to use (Either
+ * HAL_AnalogTriggerHandle or HAL_DigitalHandle).
+ * @param analogTriggerType   The analog trigger type, if the source is an
+ * analog trigger.
+ * @param triggerRising       Trigger on the rising edge if true.
+ * @param triggerFalling      Trigger on the falling edge if true.
+ */
+void HAL_StartSPIAutoTrigger(HAL_SPIPort port, HAL_Handle digitalSourceHandle,
+                             HAL_AnalogTriggerType analogTriggerType,
+                             HAL_Bool triggerRising, HAL_Bool triggerFalling,
+                             int32_t* status);
+
+/**
+ * Stops an automatic SPI accumlation.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP.
+ */
+void HAL_StopSPIAuto(HAL_SPIPort port, int32_t* status);
+
+/**
+ * Sets the data to be transmitted to the device to initiate a read.
+ *
+ * @param port       The number of the port to use. 0-3 for Onboard CS0-CS2, 4
+ * for MXP.
+ * @param dataToSend Pointer to the data to send (Gets copied for continue use,
+ * so no need to keep alive).
+ * @param dataSize   The length of the data to send.
+ * @param zeroSize   The number of zeros to send after the data.
+ */
+void HAL_SetSPIAutoTransmitData(HAL_SPIPort port, const uint8_t* dataToSend,
+                                int32_t dataSize, int32_t zeroSize,
+                                int32_t* status);
+
+/**
+ * Immediately forces an SPI read to happen.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP.
+ */
+void HAL_ForceSPIAutoRead(HAL_SPIPort port, int32_t* status);
+
+/**
+ * Reads data received by the SPI accumulator.  Each received data sequence
+ * consists of a timestamp followed by the received data bytes, one byte per
+ * word (in the least significant byte).  The length of each received data
+ * sequence is the same as the combined dataSize + zeroSize set in
+ * HAL_SetSPIAutoTransmitData.
+ *
+ * @param port      The number of the port to use. 0-3 for Onboard CS0-CS2, 4
+ * for MXP.
+ * @param buffer    The buffer to store the data into.
+ * @param numToRead The number of words to read.
+ * @param timeout   The read timeout (in seconds).
+ * @return          The number of words actually read.
+ */
+int32_t HAL_ReadSPIAutoReceivedData(HAL_SPIPort port, uint32_t* buffer,
+                                    int32_t numToRead, double timeout,
+                                    int32_t* status);
+
+/**
+ * Gets the count of how many SPI accumulations have been missed.
+ *
+ * @param port The number of the port to use. 0-3 for Onboard CS0-CS2, 4 for
+ * MXP.
+ * @return     The number of missed accumulations.
+ */
+int32_t HAL_GetSPIAutoDroppedCount(HAL_SPIPort port, int32_t* status);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/SPITypes.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/SPITypes.h
new file mode 100644
index 0000000..907623c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/SPITypes.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_spi SPI Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+// clang-format off
+HAL_ENUM(HAL_SPIPort) {
+  HAL_SPI_kInvalid = -1,
+  HAL_SPI_kOnboardCS0,
+  HAL_SPI_kOnboardCS1,
+  HAL_SPI_kOnboardCS2,
+  HAL_SPI_kOnboardCS3,
+  HAL_SPI_kMXP
+};
+// clang-format on
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/SerialPort.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/SerialPort.h
new file mode 100644
index 0000000..c2fd105
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/SerialPort.h
@@ -0,0 +1,230 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_serialport Serial Port Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+// clang-format off
+HAL_ENUM(HAL_SerialPort) {
+  HAL_SerialPort_Onboard = 0,
+  HAL_SerialPort_MXP = 1,
+  HAL_SerialPort_USB1 = 2,
+  HAL_SerialPort_USB2 = 3
+};
+// clang-format on
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a serial port.
+ *
+ * The channels are either the onboard RS232, the mxp uart, or 2 USB ports. The
+ * top port is USB1, the bottom port is USB2.
+ *
+ * @param port the serial port to initialize
+ */
+void HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status);
+
+/**
+ * Initializes a serial port with a direct name.
+ *
+ * This name is the VISA name for a specific port (find this in the web dash).
+ * Note these are not always consistent between roboRIO reboots.
+ *
+ * @param port     the serial port to initialize
+ * @param portName the VISA port name
+ */
+void HAL_InitializeSerialPortDirect(HAL_SerialPort port, const char* portName,
+                                    int32_t* status);
+
+/**
+ * Sets the baud rate of a serial port.
+ *
+ * Any value between 0 and 0xFFFFFFFF may be used. Default is 9600.
+ *
+ * @param port the serial port
+ * @param baud the baud rate to set
+ */
+void HAL_SetSerialBaudRate(HAL_SerialPort port, int32_t baud, int32_t* status);
+
+/**
+ * Sets the number of data bits on a serial port.
+ *
+ * Defaults to 8.
+ *
+ * @param port the serial port
+ * @param bits the number of data bits (5-8)
+ */
+void HAL_SetSerialDataBits(HAL_SerialPort port, int32_t bits, int32_t* status);
+
+/**
+ * Sets the number of parity bits on a serial port.
+ *
+ * Valid values are:
+ *   0: None (default)
+ *   1: Odd
+ *   2: Even
+ *   3: Mark - Means exists and always 1
+ *   4: Space - Means exists and always 0
+ *
+ * @param port   the serial port
+ * @param parity the parity bit mode (see remarks for valid values)
+ */
+void HAL_SetSerialParity(HAL_SerialPort port, int32_t parity, int32_t* status);
+
+/**
+ * Sets the number of stop bits on a serial port.
+ *
+ * Valid values are:
+ *   10: One stop bit (default)
+ *   15: One and a half stop bits
+ *   20: Two stop bits
+ *
+ * @param port     the serial port
+ * @param stopBits the stop bit value (see remarks for valid values)
+ */
+void HAL_SetSerialStopBits(HAL_SerialPort port, int32_t stopBits,
+                           int32_t* status);
+
+/**
+ * Sets the write mode on a serial port.
+ *
+ * Valid values are:
+ *   1: Flush on access
+ *   2: Flush when full (default)
+ *
+ * @param port the serial port
+ * @param mode the mode to set (see remarks for valid values)
+ */
+void HAL_SetSerialWriteMode(HAL_SerialPort port, int32_t mode, int32_t* status);
+
+/**
+ * Sets the flow control mode of a serial port.
+ *
+ * Valid values are:
+ *   0: None (default)
+ *   1: XON-XOFF
+ *   2: RTS-CTS
+ *   3: DTR-DSR
+ *
+ * @param port the serial port
+ * @param flow the mode to set (see remarks for valid values)
+ */
+void HAL_SetSerialFlowControl(HAL_SerialPort port, int32_t flow,
+                              int32_t* status);
+
+/**
+ * Sets the minimum serial read timeout of a port.
+ *
+ * @param port    the serial port
+ * @param timeout the timeout in milliseconds
+ */
+void HAL_SetSerialTimeout(HAL_SerialPort port, double timeout, int32_t* status);
+
+/**
+ * Sets the termination character that terminates a read.
+ *
+ * By default this is disabled.
+ *
+ * @param port       the serial port
+ * @param terminator the termination character to set
+ */
+void HAL_EnableSerialTermination(HAL_SerialPort port, char terminator,
+                                 int32_t* status);
+
+/**
+ * Disables a termination character for reads.
+ *
+ * @param port the serial port
+ */
+void HAL_DisableSerialTermination(HAL_SerialPort port, int32_t* status);
+
+/**
+ * Sets the size of the read buffer.
+ *
+ * @param port the serial port
+ * @param size the read buffer size
+ */
+void HAL_SetSerialReadBufferSize(HAL_SerialPort port, int32_t size,
+                                 int32_t* status);
+
+/**
+ * Sets the size of the write buffer.
+ *
+ * @param port the serial port
+ * @param size the write buffer size
+ */
+void HAL_SetSerialWriteBufferSize(HAL_SerialPort port, int32_t size,
+                                  int32_t* status);
+
+/**
+ * Gets the number of bytes currently in the read buffer.
+ *
+ * @param port the serial port
+ * @return     the number of bytes in the read buffer
+ */
+int32_t HAL_GetSerialBytesReceived(HAL_SerialPort port, int32_t* status);
+
+/**
+ * Reads data from the serial port.
+ *
+ * Will wait for either timeout (if set), the termination char (if set), or the
+ * count to be full. Whichever one comes first.
+ *
+ * @param port  the serial port
+ * @param count the number of bytes maximum to read
+ * @return      the number of bytes actually read
+ */
+int32_t HAL_ReadSerial(HAL_SerialPort port, char* buffer, int32_t count,
+                       int32_t* status);
+
+/**
+ * Writes data to the serial port.
+ *
+ * @param port   the serial port
+ * @param buffer the buffer to write
+ * @param count  the number of bytes to write from the buffer
+ * @return       the number of bytes actually written
+ */
+int32_t HAL_WriteSerial(HAL_SerialPort port, const char* buffer, int32_t count,
+                        int32_t* status);
+
+/**
+ * Flushes the serial write buffer out to the port.
+ *
+ * @param port the serial port
+ */
+void HAL_FlushSerial(HAL_SerialPort port, int32_t* status);
+
+/**
+ * Clears the receive buffer of the serial port.
+ *
+ * @param port the serial port
+ */
+void HAL_ClearSerial(HAL_SerialPort port, int32_t* status);
+
+/**
+ * Closes a serial port.
+ *
+ * @param port the serial port to close
+ */
+void HAL_CloseSerial(HAL_SerialPort port, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Solenoid.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Solenoid.h
new file mode 100644
index 0000000..53257b2
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Solenoid.h
@@ -0,0 +1,141 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_solenoid Solenoid Output Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * Initializes a solenoid port.
+ *
+ * @param portHandle the port handle of the module and channel to initialize
+ * @return           the created solenoid handle
+ */
+HAL_SolenoidHandle HAL_InitializeSolenoidPort(HAL_PortHandle portHandle,
+                                              int32_t* status);
+
+/**
+ * Frees a solenoid port.
+ *
+ * @param solenoidPortHandle the solenoid handle
+ */
+void HAL_FreeSolenoidPort(HAL_SolenoidHandle solenoidPortHandle);
+
+/**
+ * Checks if a solenoid module is in the valid range.
+ *
+ * @param module the module number to check
+ * @return       true if the module number is valid, otherwise false
+ */
+HAL_Bool HAL_CheckSolenoidModule(int32_t module);
+
+/**
+ * Checks if a solenoid channel is in the valid range.
+ *
+ * @param channel the channel number to check
+ * @return       true if the channel number is valid, otherwise false
+ */
+HAL_Bool HAL_CheckSolenoidChannel(int32_t channel);
+
+/**
+ * Gets the current solenoid output value.
+ *
+ * @param solenoidPortHandle the solenoid handle
+ * @return                   true if the solenoid is on, otherwise false
+ */
+HAL_Bool HAL_GetSolenoid(HAL_SolenoidHandle solenoidPortHandle,
+                         int32_t* status);
+
+/**
+ * Gets the status of all solenoids on a specific module.
+ *
+ * @param module the module to check
+ * @return       bitmask of the channels, 1 for on 0 for off
+ */
+int32_t HAL_GetAllSolenoids(int32_t module, int32_t* status);
+
+/**
+ * Sets a solenoid output value.
+ *
+ * @param solenoidPortHandle the solenoid handle
+ * @param value              true for on, false for off
+ */
+void HAL_SetSolenoid(HAL_SolenoidHandle solenoidPortHandle, HAL_Bool value,
+                     int32_t* status);
+
+/**
+ * Sets all channels on a specific module.
+ *
+ * @param module the module to set the channels on
+ * @param state  bitmask of the channels to set, 1 for on 0 for off
+ */
+void HAL_SetAllSolenoids(int32_t module, int32_t state, int32_t* status);
+
+/**
+ * Gets the channels blacklisted from being enabled on a module.
+ *
+ * @param module the module to check
+ * @retur        bitmask of the blacklisted channels, 1 for true 0 for false
+ */
+int32_t HAL_GetPCMSolenoidBlackList(int32_t module, int32_t* status);
+
+/**
+ * Gets if a specific module has an over or under voltage sticky fault.
+ *
+ * @param module the module to check
+ * @return       true if a stick fault is set, otherwise false
+ */
+HAL_Bool HAL_GetPCMSolenoidVoltageStickyFault(int32_t module, int32_t* status);
+
+/**
+ * Gets if a specific module has an over or under voltage fault.
+ *
+ * @param module the module to check
+ * @return       true if faulted, otherwise false
+ */
+HAL_Bool HAL_GetPCMSolenoidVoltageFault(int32_t module, int32_t* status);
+
+/**
+ * Clears all faults on a module.
+ *
+ * @param module the module to clear
+ */
+void HAL_ClearAllPCMStickyFaults(int32_t module, int32_t* status);
+
+/**
+ * Sets the one shot duration on a solenoid channel.
+ *
+ * @param solenoidPortHandle the solenoid handle
+ * @param durMS              the one shot duration in ms
+ */
+void HAL_SetOneShotDuration(HAL_SolenoidHandle solenoidPortHandle,
+                            int32_t durMS, int32_t* status);
+
+/**
+ * Fires a single pulse on a solenoid channel.
+ *
+ * The pulse is the duration set by HAL_SetOneShotDuration().
+ *
+ * @param solenoidPortHandle the solenoid handle
+ */
+void HAL_FireOneShot(HAL_SolenoidHandle solenoidPortHandle, int32_t* status);
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Threads.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Threads.h
new file mode 100644
index 0000000..4908c9c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Threads.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#define NativeThreadHandle const void*
+
+#include "hal/Types.h"
+
+/**
+ * @defgroup hal_threads Threads Functions
+ * @ingroup hal_capi
+ * @{
+ */
+
+extern "C" {
+/**
+ * Gets the thread priority for the specified thread.
+ *
+ * @param handle     Native handle pointer to the thread to get the priority for
+ * @param isRealTime Set to true if thread is realtime, otherwise false
+ * @param status     Error status variable. 0 on success
+ * @return           The current thread priority. Scaled 1-99, with 1 being
+ * highest.
+ */
+int32_t HAL_GetThreadPriority(NativeThreadHandle handle, HAL_Bool* isRealTime,
+                              int32_t* status);
+
+/**
+ * Gets the thread priority for the current thread.
+ *
+ * @param handle     Native handle pointer to the thread to get the priority for
+ * @param isRealTime Set to true if thread is realtime, otherwise false
+ * @param status     Error status variable. 0 on success
+ * @return           The current thread priority. Scaled 1-99, with 1 being
+ * highest.
+ */
+int32_t HAL_GetCurrentThreadPriority(HAL_Bool* isRealTime, int32_t* status);
+
+/**
+ * Sets the thread priority for the specified thread.
+ *
+ * @param thread   Reference to the thread to set the priority of
+ * @param realTime Set to true to set a realtime priority, false for standard
+ * priority
+ * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+ * highest
+ * @param status   Error status variable. 0 on success
+ * @return         The success state of setting the priority
+ */
+HAL_Bool HAL_SetThreadPriority(NativeThreadHandle handle, HAL_Bool realTime,
+                               int32_t priority, int32_t* status);
+
+/**
+ * Sets the thread priority for the current thread.
+ *
+ * @param thread   Reference to the thread to set the priority of
+ * @param realTime Set to true to set a realtime priority, false for standard
+ * priority
+ * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+ * highest
+ * @param status   Error status variable. 0 on success
+ * @return         The success state of setting the priority
+ */
+HAL_Bool HAL_SetCurrentThreadPriority(HAL_Bool realTime, int32_t priority,
+                                      int32_t* status);
+}  // extern "C"
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/Types.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Types.h
new file mode 100644
index 0000000..6180439
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/Types.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+/**
+ * @defgroup hal_types Type Definitions
+ * @ingroup hal_capi
+ * @{
+ */
+
+#define HAL_kInvalidHandle 0
+
+typedef int32_t HAL_Handle;
+
+typedef HAL_Handle HAL_PortHandle;
+
+typedef HAL_Handle HAL_AnalogInputHandle;
+
+typedef HAL_Handle HAL_AnalogOutputHandle;
+
+typedef HAL_Handle HAL_AnalogTriggerHandle;
+
+typedef HAL_Handle HAL_CompressorHandle;
+
+typedef HAL_Handle HAL_CounterHandle;
+
+typedef HAL_Handle HAL_DigitalHandle;
+
+typedef HAL_Handle HAL_DigitalPWMHandle;
+
+typedef HAL_Handle HAL_EncoderHandle;
+
+typedef HAL_Handle HAL_FPGAEncoderHandle;
+
+typedef HAL_Handle HAL_GyroHandle;
+
+typedef HAL_Handle HAL_InterruptHandle;
+
+typedef HAL_Handle HAL_NotifierHandle;
+
+typedef HAL_Handle HAL_RelayHandle;
+
+typedef HAL_Handle HAL_SolenoidHandle;
+
+typedef HAL_Handle HAL_CANHandle;
+
+typedef HAL_CANHandle HAL_PDPHandle;
+
+typedef int32_t HAL_Bool;
+
+#ifdef __cplusplus
+#define HAL_ENUM(name) enum name : int32_t
+#else
+#define HAL_ENUM(name)  \
+  typedef int32_t name; \
+  enum name
+#endif
+/** @} */
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/Log.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/Log.h
new file mode 100644
index 0000000..bcc3995
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/Log.h
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <chrono>
+#include <string>
+
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+inline std::string NowTime();
+
+enum TLogLevel {
+  logNONE,
+  logERROR,
+  logWARNING,
+  logINFO,
+  logDEBUG,
+  logDEBUG1,
+  logDEBUG2,
+  logDEBUG3,
+  logDEBUG4
+};
+
+class Log {
+ public:
+  Log();
+  virtual ~Log();
+  wpi::raw_ostream& Get(TLogLevel level = logINFO);
+
+ public:
+  static TLogLevel& ReportingLevel();
+  static std::string ToString(TLogLevel level);
+  static TLogLevel FromString(const std::string& level);
+
+ protected:
+  wpi::SmallString<128> buf;
+  wpi::raw_svector_ostream oss{buf};
+
+ private:
+  Log(const Log&);
+  Log& operator=(const Log&);
+};
+
+inline Log::Log() {}
+
+inline wpi::raw_ostream& Log::Get(TLogLevel level) {
+  oss << "- " << NowTime();
+  oss << " " << ToString(level) << ": ";
+  if (level > logDEBUG) {
+    oss << std::string(level - logDEBUG, '\t');
+  }
+  return oss;
+}
+
+inline Log::~Log() {
+  oss << "\n";
+  wpi::errs() << oss.str();
+}
+
+inline TLogLevel& Log::ReportingLevel() {
+  static TLogLevel reportingLevel = logDEBUG4;
+  return reportingLevel;
+}
+
+inline std::string Log::ToString(TLogLevel level) {
+  static const char* const buffer[] = {"NONE",   "ERROR",  "WARNING",
+                                       "INFO",   "DEBUG",  "DEBUG1",
+                                       "DEBUG2", "DEBUG3", "DEBUG4"};
+  return buffer[level];
+}
+
+inline TLogLevel Log::FromString(const std::string& level) {
+  if (level == "DEBUG4") return logDEBUG4;
+  if (level == "DEBUG3") return logDEBUG3;
+  if (level == "DEBUG2") return logDEBUG2;
+  if (level == "DEBUG1") return logDEBUG1;
+  if (level == "DEBUG") return logDEBUG;
+  if (level == "INFO") return logINFO;
+  if (level == "WARNING") return logWARNING;
+  if (level == "ERROR") return logERROR;
+  if (level == "NONE") return logNONE;
+  Log().Get(logWARNING) << "Unknown logging level '" << level
+                        << "'. Using INFO level as default.";
+  return logINFO;
+}
+
+using FILELog = Log;  // NOLINT
+
+#define FILE_LOG(level)                  \
+  if (level > FILELog::ReportingLevel()) \
+    ;                                    \
+  else                                   \
+    Log().Get(level)
+
+inline std::string NowTime() {
+  wpi::SmallString<128> buf;
+  wpi::raw_svector_ostream oss(buf);
+
+  using std::chrono::duration_cast;
+
+  auto now = std::chrono::system_clock::now().time_since_epoch();
+
+  // Hours
+  auto count = duration_cast<std::chrono::hours>(now).count() % 24;
+  if (count < 10) oss << "0";
+  oss << count << ":";
+
+  // Minutes
+  count = duration_cast<std::chrono::minutes>(now).count() % 60;
+  if (count < 10) oss << "0";
+  oss << count << ":";
+
+  // Seconds
+  count = duration_cast<std::chrono::seconds>(now).count() % 60;
+  if (count < 10) oss << "0";
+  oss << count << ".";
+
+  // Milliseconds
+  oss << duration_cast<std::chrono::milliseconds>(now).count() % 1000;
+
+  return oss.str();
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/SerialHelper.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/SerialHelper.h
new file mode 100644
index 0000000..9f4d6a0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/SerialHelper.h
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <string>
+#include <vector>
+
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+#include "hal/SerialPort.h"
+
+namespace hal {
+/**
+ * A class for deterministically getting information about Serial Ports.
+ */
+class SerialHelper {
+ public:
+  SerialHelper();
+
+  /**
+   * Get the VISA name of a serial port.
+   *
+   * @param port   the serial port index
+   * @param status status check
+   * @return       the VISA name
+   */
+  std::string GetVISASerialPortName(HAL_SerialPort port, int32_t* status);
+
+  /**
+   * Get the OS name of a serial port.
+   *
+   * @param port   the serial port index
+   * @param status status check
+   * @return       the OS name
+   */
+  std::string GetOSSerialPortName(HAL_SerialPort port, int32_t* status);
+
+  /**
+   * Get a vector of all serial port VISA names.
+   *
+   * @param status status check
+   * @return       vector of serial port VISA names
+   */
+  std::vector<std::string> GetVISASerialPortList(int32_t* status);
+
+  /**
+   * Get a vector of all serial port OS names.
+   *
+   * @param status status check
+   * @return       vector of serial port OS names
+   */
+  std::vector<std::string> GetOSSerialPortList(int32_t* status);
+
+ private:
+  void SortHubPathVector();
+  void CoiteratedSort(wpi::SmallVectorImpl<wpi::SmallString<16>>& vec);
+  void QueryHubPaths(int32_t* status);
+
+  int32_t GetIndexForPort(HAL_SerialPort port, int32_t* status);
+
+  // Vectors to hold data before sorting.
+  // Note we will most likely have at max 2 instances, and the longest string
+  // is around 12, so these should never touch the heap;
+  wpi::SmallVector<wpi::SmallString<16>, 4> m_visaResource;
+  wpi::SmallVector<wpi::SmallString<16>, 4> m_osResource;
+  wpi::SmallVector<wpi::SmallString<16>, 4> m_unsortedHubPath;
+  wpi::SmallVector<wpi::SmallString<16>, 4> m_sortedHubPath;
+
+  int32_t m_resourceHandle;
+
+  static wpi::mutex m_nameMutex;
+  static std::string m_usbNames[2];
+};
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/UnsafeDIO.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/UnsafeDIO.h
new file mode 100644
index 0000000..ceb41c3
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/UnsafeDIO.h
@@ -0,0 +1,95 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/mutex.h>
+
+#include "hal/ChipObject.h"
+#include "hal/Types.h"
+
+namespace hal {
+
+/**
+ * Proxy class for directly manipulating the DIO pins.
+ *
+ * This class is not copyable or movable, and should never be used
+ * outside of the UnsafeManipulateDIO callback.
+ */
+struct DIOSetProxy {
+  DIOSetProxy(const DIOSetProxy&) = delete;
+  DIOSetProxy(DIOSetProxy&&) = delete;
+  DIOSetProxy& operator=(const DIOSetProxy&) = delete;
+  DIOSetProxy& operator=(DIOSetProxy&&) = delete;
+
+  void SetOutputMode(int32_t* status) {
+    m_dio->writeOutputEnable(m_setOutputDirReg, status);
+  }
+
+  void SetInputMode(int32_t* status) {
+    m_dio->writeOutputEnable(m_unsetOutputDirReg, status);
+  }
+
+  void SetOutputTrue(int32_t* status) {
+    m_dio->writeDO(m_setOutputStateReg, status);
+  }
+
+  void SetOutputFalse(int32_t* status) {
+    m_dio->writeDO(m_unsetOutputStateReg, status);
+  }
+
+  tDIO::tOutputEnable m_setOutputDirReg;
+  tDIO::tOutputEnable m_unsetOutputDirReg;
+  tDIO::tDO m_setOutputStateReg;
+  tDIO::tDO m_unsetOutputStateReg;
+  tDIO* m_dio;
+};
+namespace detail {
+wpi::mutex& UnsafeGetDIOMutex();
+tDIO* UnsafeGetDigialSystem();
+int32_t ComputeDigitalMask(HAL_DigitalHandle handle, int32_t* status);
+}  // namespace detail
+
+/**
+ * Unsafe digital output set function
+ * This function can be used to perform fast and determinstically set digital
+ * outputs. This function holds the DIO lock, so calling anyting other then
+ * functions on the Proxy object passed as a parameter can deadlock your
+ * program.
+ *
+ * @param handle the HAL digital handle of the pin to toggle.
+ * @param status status check
+ * @param func   A functor taking a ref to a DIOSetProxy object.
+ */
+template <typename Functor>
+void UnsafeManipulateDIO(HAL_DigitalHandle handle, int32_t* status,
+                         Functor func) {
+  auto port = digitalChannelHandles->Get(handle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  wpi::mutex& dioMutex = detail::UnsafeGetDIOMutex();
+  tDIO* dSys = detail::UnsafeGetDigialSystem();
+  auto mask = detail::ComputeDigitalMask(handle, status);
+  if (status != 0) return;
+  std::lock_guard<wpi::mutex> lock(dioMutex);
+
+  tDIO::tOutputEnable enableOE = dSys->readOutputEnable(status);
+  enableOE.value |= mask;
+  auto disableOE = enableOE;
+  disableOE.value &= ~mask;
+  tDIO::tDO enableDO = dSys->readDO(status);
+  enableDO.value |= mask;
+  auto disableDO = enableDO;
+  disableDO.value &= ~mask;
+
+  DIOSetProxy dioData{enableOE, disableOE, enableDO, disableDO, dSys};
+  func(dioData);
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/fpga_clock.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/fpga_clock.h
new file mode 100644
index 0000000..94031b1
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/cpp/fpga_clock.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <chrono>
+#include <limits>
+
+/** WPILib Hardware Abstraction Layer (HAL) namespace */
+namespace hal {
+
+/**
+ * A std::chrono compatible wrapper around the FPGA Timer.
+ */
+class fpga_clock {
+ public:
+  using rep = std::chrono::microseconds::rep;
+  using period = std::chrono::microseconds::period;
+  using duration = std::chrono::microseconds;
+  using time_point = std::chrono::time_point<fpga_clock>;
+
+  static fpga_clock::time_point now() noexcept;
+  static constexpr bool is_steady = true;
+
+  static fpga_clock::time_point epoch() noexcept { return time_point(zero()); }
+
+  static fpga_clock::duration zero() noexcept { return duration(0); }
+
+  static const time_point min_time;
+};
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/DigitalHandleResource.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/DigitalHandleResource.h
new file mode 100644
index 0000000..23fb676
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/DigitalHandleResource.h
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <array>
+#include <memory>
+
+#include <wpi/mutex.h>
+
+#include "hal/Errors.h"
+#include "hal/Types.h"
+#include "hal/handles/HandlesInternal.h"
+
+namespace hal {
+
+/**
+ * The DigitalHandleResource class is a way to track handles. This version
+ * allows a limited number of handles that are allocated by index.
+ * The enum value is seperate, as 2 enum values are allowed per handle
+ * Because they are allocated by index, each individual index holds its own
+ * mutex, which reduces contention heavily.]
+ *
+ * @tparam THandle The Handle Type (Must be typedefed from HAL_Handle)
+ * @tparam TStruct The struct type held by this resource
+ * @tparam size The number of resources allowed to be allocated
+ *
+ */
+template <typename THandle, typename TStruct, int16_t size>
+class DigitalHandleResource : public HandleBase {
+  friend class DigitalHandleResourceTest;
+
+ public:
+  DigitalHandleResource() = default;
+  DigitalHandleResource(const DigitalHandleResource&) = delete;
+  DigitalHandleResource& operator=(const DigitalHandleResource&) = delete;
+
+  THandle Allocate(int16_t index, HAL_HandleEnum enumValue, int32_t* status);
+  std::shared_ptr<TStruct> Get(THandle handle, HAL_HandleEnum enumValue);
+  void Free(THandle handle, HAL_HandleEnum enumValue);
+  void ResetHandles() override;
+
+ private:
+  std::array<std::shared_ptr<TStruct>, size> m_structures;
+  std::array<wpi::mutex, size> m_handleMutexes;
+};
+
+template <typename THandle, typename TStruct, int16_t size>
+THandle DigitalHandleResource<THandle, TStruct, size>::Allocate(
+    int16_t index, HAL_HandleEnum enumValue, int32_t* status) {
+  // don't aquire the lock if we can fail early.
+  if (index < 0 || index >= size) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  // check for allocation, otherwise allocate and return a valid handle
+  if (m_structures[index] != nullptr) {
+    *status = RESOURCE_IS_ALLOCATED;
+    return HAL_kInvalidHandle;
+  }
+  m_structures[index] = std::make_shared<TStruct>();
+  return static_cast<THandle>(hal::createHandle(index, enumValue, m_version));
+}
+
+template <typename THandle, typename TStruct, int16_t size>
+std::shared_ptr<TStruct> DigitalHandleResource<THandle, TStruct, size>::Get(
+    THandle handle, HAL_HandleEnum enumValue) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) {
+    return nullptr;
+  }
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  // return structure. Null will propogate correctly, so no need to manually
+  // check.
+  return m_structures[index];
+}
+
+template <typename THandle, typename TStruct, int16_t size>
+void DigitalHandleResource<THandle, TStruct, size>::Free(
+    THandle handle, HAL_HandleEnum enumValue) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) return;
+  // lock and deallocated handle
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  m_structures[index].reset();
+}
+
+template <typename THandle, typename TStruct, int16_t size>
+void DigitalHandleResource<THandle, TStruct, size>::ResetHandles() {
+  for (int i = 0; i < size; i++) {
+    std::lock_guard<wpi::mutex> lock(m_handleMutexes[i]);
+    m_structures[i].reset();
+  }
+  HandleBase::ResetHandles();
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/HandlesInternal.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/HandlesInternal.h
new file mode 100644
index 0000000..85b3493
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/HandlesInternal.h
@@ -0,0 +1,211 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "hal/Types.h"
+
+/* General Handle Data Layout
+ * Bits 0-15:  Handle Index
+ * Bits 16-23: 8 bit rolling reset detection
+ * Bits 24-30: Handle Type
+ * Bit 31:     1 if handle error, 0 if no error
+ *
+ * Other specialized handles will use different formats, however Bits 24-31 are
+ * always reserved for type and error handling.
+ */
+
+namespace hal {
+
+/**
+ * Base for all HAL Handles.
+ */
+class HandleBase {
+ public:
+  HandleBase();
+  ~HandleBase();
+  HandleBase(const HandleBase&) = delete;
+  HandleBase& operator=(const HandleBase&) = delete;
+  virtual void ResetHandles();
+  static void ResetGlobalHandles();
+
+ protected:
+  int16_t m_version;
+};
+
+constexpr int16_t InvalidHandleIndex = -1;
+
+/**
+ * Enum of HAL handle types. Vendors/Teams should use Vendor (17).
+ */
+enum class HAL_HandleEnum {
+  Undefined = 0,
+  DIO = 1,
+  Port = 2,
+  Notifier = 3,
+  Interrupt = 4,
+  AnalogOutput = 5,
+  AnalogInput = 6,
+  AnalogTrigger = 7,
+  Relay = 8,
+  PWM = 9,
+  DigitalPWM = 10,
+  Counter = 11,
+  FPGAEncoder = 12,
+  Encoder = 13,
+  Compressor = 14,
+  Solenoid = 15,
+  AnalogGyro = 16,
+  Vendor = 17,
+  SimulationJni = 18,
+  CAN = 19,
+};
+
+/**
+ * Get the handle index from a handle.
+ *
+ * @param handle the handle
+ * @return       the index
+ */
+static inline int16_t getHandleIndex(HAL_Handle handle) {
+  // mask and return last 16 bits
+  return static_cast<int16_t>(handle & 0xffff);
+}
+
+/**
+ * Get the handle type from a handle.
+ *
+ * @param handle the handle
+ * @return       the type
+ */
+static inline HAL_HandleEnum getHandleType(HAL_Handle handle) {
+  // mask first 8 bits and cast to enum
+  return static_cast<HAL_HandleEnum>((handle >> 24) & 0xff);
+}
+
+/**
+ * Get if the handle is a specific type.
+ *
+ * @param handle     the handle
+ * @param handleType the type to check
+ * @return           true if the type is correct, otherwise false
+ */
+static inline bool isHandleType(HAL_Handle handle, HAL_HandleEnum handleType) {
+  return handleType == getHandleType(handle);
+}
+
+/**
+ * Get if the version of the handle is correct.
+ *
+ * Do not use on the roboRIO, used specifically for the sim to handle resets.
+ *
+ * @param handle  the handle
+ * @param version the handle version to check
+ * @return        true if the handle is the right version, otherwise false
+ */
+static inline bool isHandleCorrectVersion(HAL_Handle handle, int16_t version) {
+  return (((handle & 0xFF0000) >> 16) & version) == version;
+}
+
+/**
+ * Get if the handle is a correct type and version.
+ *
+ * Note the version is not checked on the roboRIO.
+ *
+ * @param handle     the handle
+ * @param handleType the type to check
+ * @param version    the handle version to check
+ * @return           true if the handle is proper version and type, otherwise
+ * false.
+ */
+static inline int16_t getHandleTypedIndex(HAL_Handle handle,
+                                          HAL_HandleEnum enumType,
+                                          int16_t version) {
+  if (!isHandleType(handle, enumType)) return InvalidHandleIndex;
+#if !defined(__FRC_ROBORIO__)
+  if (!isHandleCorrectVersion(handle, version)) return InvalidHandleIndex;
+#endif
+  return getHandleIndex(handle);
+}
+
+/* specialized functions for Port handle
+ * Port Handle Data Layout
+ * Bits 0-7:   Channel Number
+ * Bits 8-15:  Module Number
+ * Bits 16-23: Unused
+ * Bits 24-30: Handle Type
+ * Bit 31:     1 if handle error, 0 if no error
+ */
+
+// using a 16 bit value so we can store 0-255 and still report error
+/**
+ * Gets the port channel of a port handle.
+ *
+ * @param handle the port handle
+ * @return       the port channel
+ */
+static inline int16_t getPortHandleChannel(HAL_PortHandle handle) {
+  if (!isHandleType(handle, HAL_HandleEnum::Port)) return InvalidHandleIndex;
+  return static_cast<uint8_t>(handle & 0xff);
+}
+
+// using a 16 bit value so we can store 0-255 and still report error
+/**
+ * Gets the port module of a port handle.
+ *
+ * @param handle the port handle
+ * @return       the port module
+ */
+static inline int16_t getPortHandleModule(HAL_PortHandle handle) {
+  if (!isHandleType(handle, HAL_HandleEnum::Port)) return InvalidHandleIndex;
+  return static_cast<uint8_t>((handle >> 8) & 0xff);
+}
+
+// using a 16 bit value so we can store 0-255 and still report error
+/**
+ * Gets the SPI channel of a port handle.
+ *
+ * @param handle the port handle
+ * @return       the port SPI channel
+ */
+static inline int16_t getPortHandleSPIEnable(HAL_PortHandle handle) {
+  if (!isHandleType(handle, HAL_HandleEnum::Port)) return InvalidHandleIndex;
+  return static_cast<uint8_t>((handle >> 16) & 0xff);
+}
+
+/**
+ * Create a port handle.
+ *
+ * @param channel the channel
+ * @param module  the module
+ * @return        port handle for the module and channel
+ */
+HAL_PortHandle createPortHandle(uint8_t channel, uint8_t module);
+
+/**
+ * Create a port handle for SPI.
+ *
+ * @param channel the SPI channel
+ * @return        port handle for the channel
+ */
+HAL_PortHandle createPortHandleForSPI(uint8_t channel);
+
+/**
+ * Create a handle for a specific index, type and version.
+ *
+ * Note the version is not checked on the roboRIO.
+ *
+ * @param index      the index
+ * @param handleType the handle type
+ * @param version    the handle version
+ * @return           the created handle
+ */
+HAL_Handle createHandle(int16_t index, HAL_HandleEnum handleType,
+                        int16_t version);
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/IndexedClassedHandleResource.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/IndexedClassedHandleResource.h
new file mode 100644
index 0000000..a038e04
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/IndexedClassedHandleResource.h
@@ -0,0 +1,117 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <array>
+#include <memory>
+#include <vector>
+
+#include <wpi/mutex.h>
+
+#include "hal/Errors.h"
+#include "hal/Types.h"
+#include "hal/handles/HandlesInternal.h"
+
+namespace hal {
+
+/**
+ * The IndexedClassedHandleResource class is a way to track handles. This
+ * version
+ * allows a limited number of handles that are allocated by index.
+ * Because they are allocated by index, each individual index holds its own
+ * mutex, which reduces contention heavily.]
+ *
+ * @tparam THandle The Handle Type (Must be typedefed from HAL_Handle)
+ * @tparam TStruct The struct type held by this resource
+ * @tparam size The number of resources allowed to be allocated
+ * @tparam enumValue The type value stored in the handle
+ *
+ */
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+class IndexedClassedHandleResource : public HandleBase {
+  friend class IndexedClassedHandleResourceTest;
+
+ public:
+  IndexedClassedHandleResource() = default;
+  IndexedClassedHandleResource(const IndexedClassedHandleResource&) = delete;
+  IndexedClassedHandleResource& operator=(const IndexedClassedHandleResource&) =
+      delete;
+
+  THandle Allocate(int16_t index, std::shared_ptr<TStruct> toSet,
+                   int32_t* status);
+  std::shared_ptr<TStruct> Get(THandle handle);
+  void Free(THandle handle);
+  void ResetHandles();
+
+ private:
+  std::array<std::shared_ptr<TStruct>, size> m_structures;
+  std::array<wpi::mutex, size> m_handleMutexes;
+};
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+THandle
+IndexedClassedHandleResource<THandle, TStruct, size, enumValue>::Allocate(
+    int16_t index, std::shared_ptr<TStruct> toSet, int32_t* status) {
+  // don't aquire the lock if we can fail early.
+  if (index < 0 || index >= size) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  // check for allocation, otherwise allocate and return a valid handle
+  if (m_structures[index] != nullptr) {
+    *status = RESOURCE_IS_ALLOCATED;
+    return HAL_kInvalidHandle;
+  }
+  m_structures[index] = toSet;
+  return static_cast<THandle>(hal::createHandle(index, enumValue, m_version));
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+std::shared_ptr<TStruct>
+IndexedClassedHandleResource<THandle, TStruct, size, enumValue>::Get(
+    THandle handle) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) {
+    return nullptr;
+  }
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  // return structure. Null will propogate correctly, so no need to manually
+  // check.
+  return m_structures[index];
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+void IndexedClassedHandleResource<THandle, TStruct, size, enumValue>::Free(
+    THandle handle) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) return;
+  // lock and deallocated handle
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  m_structures[index].reset();
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+void IndexedClassedHandleResource<THandle, TStruct, size,
+                                  enumValue>::ResetHandles() {
+  for (int i = 0; i < size; i++) {
+    std::lock_guard<wpi::mutex> lock(m_handleMutexes[i]);
+    m_structures[i].reset();
+  }
+  HandleBase::ResetHandles();
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/IndexedHandleResource.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/IndexedHandleResource.h
new file mode 100644
index 0000000..39abf58
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/IndexedHandleResource.h
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <array>
+#include <memory>
+
+#include <wpi/mutex.h>
+
+#include "hal/Errors.h"
+#include "hal/Types.h"
+#include "hal/handles/HandlesInternal.h"
+
+namespace hal {
+
+/**
+ * The IndexedHandleResource class is a way to track handles. This version
+ * allows a limited number of handles that are allocated by index.
+ * Because they are allocated by index, each individual index holds its own
+ * mutex, which reduces contention heavily.]
+ *
+ * @tparam THandle The Handle Type (Must be typedefed from HAL_Handle)
+ * @tparam TStruct The struct type held by this resource
+ * @tparam size The number of resources allowed to be allocated
+ * @tparam enumValue The type value stored in the handle
+ *
+ */
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+class IndexedHandleResource : public HandleBase {
+  friend class IndexedHandleResourceTest;
+
+ public:
+  IndexedHandleResource() = default;
+  IndexedHandleResource(const IndexedHandleResource&) = delete;
+  IndexedHandleResource& operator=(const IndexedHandleResource&) = delete;
+
+  THandle Allocate(int16_t index, int32_t* status);
+  std::shared_ptr<TStruct> Get(THandle handle);
+  void Free(THandle handle);
+  void ResetHandles() override;
+
+ private:
+  std::array<std::shared_ptr<TStruct>, size> m_structures;
+  std::array<wpi::mutex, size> m_handleMutexes;
+};
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+THandle IndexedHandleResource<THandle, TStruct, size, enumValue>::Allocate(
+    int16_t index, int32_t* status) {
+  // don't aquire the lock if we can fail early.
+  if (index < 0 || index >= size) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  // check for allocation, otherwise allocate and return a valid handle
+  if (m_structures[index] != nullptr) {
+    *status = RESOURCE_IS_ALLOCATED;
+    return HAL_kInvalidHandle;
+  }
+  m_structures[index] = std::make_shared<TStruct>();
+  return static_cast<THandle>(hal::createHandle(index, enumValue, m_version));
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+std::shared_ptr<TStruct>
+IndexedHandleResource<THandle, TStruct, size, enumValue>::Get(THandle handle) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) {
+    return nullptr;
+  }
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  // return structure. Null will propogate correctly, so no need to manually
+  // check.
+  return m_structures[index];
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+void IndexedHandleResource<THandle, TStruct, size, enumValue>::Free(
+    THandle handle) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) return;
+  // lock and deallocated handle
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  m_structures[index].reset();
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+void IndexedHandleResource<THandle, TStruct, size, enumValue>::ResetHandles() {
+  for (int i = 0; i < size; i++) {
+    std::lock_guard<wpi::mutex> lock(m_handleMutexes[i]);
+    m_structures[i].reset();
+  }
+  HandleBase::ResetHandles();
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/LimitedClassedHandleResource.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/LimitedClassedHandleResource.h
new file mode 100644
index 0000000..2723129
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/LimitedClassedHandleResource.h
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <array>
+#include <memory>
+
+#include <wpi/mutex.h>
+
+#include "hal/Types.h"
+#include "hal/handles/HandlesInternal.h"
+
+namespace hal {
+
+/**
+ * The LimitedClassedHandleResource class is a way to track handles. This
+ * version
+ * allows a limited number of handles that are allocated sequentially.
+ *
+ * @tparam THandle The Handle Type (Must be typedefed from HAL_Handle)
+ * @tparam TStruct The struct type held by this resource
+ * @tparam size The number of resources allowed to be allocated
+ * @tparam enumValue The type value stored in the handle
+ *
+ */
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+class LimitedClassedHandleResource : public HandleBase {
+  friend class LimitedClassedHandleResourceTest;
+
+ public:
+  LimitedClassedHandleResource() = default;
+  LimitedClassedHandleResource(const LimitedClassedHandleResource&) = delete;
+  LimitedClassedHandleResource& operator=(const LimitedClassedHandleResource&) =
+      delete;
+
+  THandle Allocate(std::shared_ptr<TStruct> toSet);
+  std::shared_ptr<TStruct> Get(THandle handle);
+  void Free(THandle handle);
+  void ResetHandles() override;
+
+ private:
+  std::array<std::shared_ptr<TStruct>, size> m_structures;
+  std::array<wpi::mutex, size> m_handleMutexes;
+  wpi::mutex m_allocateMutex;
+};
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+THandle
+LimitedClassedHandleResource<THandle, TStruct, size, enumValue>::Allocate(
+    std::shared_ptr<TStruct> toSet) {
+  // globally lock to loop through indices
+  std::lock_guard<wpi::mutex> lock(m_allocateMutex);
+  for (int16_t i = 0; i < size; i++) {
+    if (m_structures[i] == nullptr) {
+      // if a false index is found, grab its specific mutex
+      // and allocate it.
+      std::lock_guard<wpi::mutex> lock(m_handleMutexes[i]);
+      m_structures[i] = toSet;
+      return static_cast<THandle>(createHandle(i, enumValue, m_version));
+    }
+  }
+  return HAL_kInvalidHandle;
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+std::shared_ptr<TStruct>
+LimitedClassedHandleResource<THandle, TStruct, size, enumValue>::Get(
+    THandle handle) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) {
+    return nullptr;
+  }
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  // return structure. Null will propogate correctly, so no need to manually
+  // check.
+  return m_structures[index];
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+void LimitedClassedHandleResource<THandle, TStruct, size, enumValue>::Free(
+    THandle handle) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) return;
+  // lock and deallocated handle
+  std::lock_guard<wpi::mutex> allocateLock(m_allocateMutex);
+  std::lock_guard<wpi::mutex> handleLock(m_handleMutexes[index]);
+  m_structures[index].reset();
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+void LimitedClassedHandleResource<THandle, TStruct, size,
+                                  enumValue>::ResetHandles() {
+  {
+    std::lock_guard<wpi::mutex> allocateLock(m_allocateMutex);
+    for (int i = 0; i < size; i++) {
+      std::lock_guard<wpi::mutex> handleLock(m_handleMutexes[i]);
+      m_structures[i].reset();
+    }
+  }
+  HandleBase::ResetHandles();
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/LimitedHandleResource.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/LimitedHandleResource.h
new file mode 100644
index 0000000..a535829
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/LimitedHandleResource.h
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <array>
+#include <memory>
+
+#include <wpi/mutex.h>
+
+#include "HandlesInternal.h"
+#include "hal/Types.h"
+
+namespace hal {
+
+/**
+ * The LimitedHandleResource class is a way to track handles. This version
+ * allows a limited number of handles that are allocated sequentially.
+ *
+ * @tparam THandle The Handle Type (Must be typedefed from HAL_Handle)
+ * @tparam TStruct The struct type held by this resource
+ * @tparam size The number of resources allowed to be allocated
+ * @tparam enumValue The type value stored in the handle
+ *
+ */
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+class LimitedHandleResource : public HandleBase {
+  friend class LimitedHandleResourceTest;
+
+ public:
+  LimitedHandleResource() = default;
+  LimitedHandleResource(const LimitedHandleResource&) = delete;
+  LimitedHandleResource& operator=(const LimitedHandleResource&) = delete;
+
+  THandle Allocate();
+  std::shared_ptr<TStruct> Get(THandle handle);
+  void Free(THandle handle);
+  void ResetHandles() override;
+
+ private:
+  std::array<std::shared_ptr<TStruct>, size> m_structures;
+  std::array<wpi::mutex, size> m_handleMutexes;
+  wpi::mutex m_allocateMutex;
+};
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+THandle LimitedHandleResource<THandle, TStruct, size, enumValue>::Allocate() {
+  // globally lock to loop through indices
+  std::lock_guard<wpi::mutex> lock(m_allocateMutex);
+  for (int16_t i = 0; i < size; i++) {
+    if (m_structures[i] == nullptr) {
+      // if a false index is found, grab its specific mutex
+      // and allocate it.
+      std::lock_guard<wpi::mutex> lock(m_handleMutexes[i]);
+      m_structures[i] = std::make_shared<TStruct>();
+      return static_cast<THandle>(createHandle(i, enumValue, m_version));
+    }
+  }
+  return HAL_kInvalidHandle;
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+std::shared_ptr<TStruct>
+LimitedHandleResource<THandle, TStruct, size, enumValue>::Get(THandle handle) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) {
+    return nullptr;
+  }
+  std::lock_guard<wpi::mutex> lock(m_handleMutexes[index]);
+  // return structure. Null will propogate correctly, so no need to manually
+  // check.
+  return m_structures[index];
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+void LimitedHandleResource<THandle, TStruct, size, enumValue>::Free(
+    THandle handle) {
+  // get handle index, and fail early if index out of range or wrong handle
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  if (index < 0 || index >= size) return;
+  // lock and deallocated handle
+  std::lock_guard<wpi::mutex> allocateLock(m_allocateMutex);
+  std::lock_guard<wpi::mutex> handleLock(m_handleMutexes[index]);
+  m_structures[index].reset();
+}
+
+template <typename THandle, typename TStruct, int16_t size,
+          HAL_HandleEnum enumValue>
+void LimitedHandleResource<THandle, TStruct, size, enumValue>::ResetHandles() {
+  {
+    std::lock_guard<wpi::mutex> allocateLock(m_allocateMutex);
+    for (int i = 0; i < size; i++) {
+      std::lock_guard<wpi::mutex> handleLock(m_handleMutexes[i]);
+      m_structures[i].reset();
+    }
+  }
+  HandleBase::ResetHandles();
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/UnlimitedHandleResource.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/UnlimitedHandleResource.h
new file mode 100644
index 0000000..7df8061
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/handles/UnlimitedHandleResource.h
@@ -0,0 +1,126 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <utility>
+#include <vector>
+
+#include <wpi/mutex.h>
+
+#include "hal/Types.h"
+#include "hal/handles/HandlesInternal.h"
+
+namespace hal {
+
+/**
+ * The UnlimitedHandleResource class is a way to track handles. This version
+ * allows an unlimted number of handles that are allocated sequentially. When
+ * possible, indices are reused to save memory usage and keep the array length
+ * down.
+ * However, automatic array management has not been implemented, but might be in
+ * the future.
+ * Because we have to loop through the allocator, we must use a global mutex.
+
+ * @tparam THandle The Handle Type (Must be typedefed from HAL_Handle)
+ * @tparam TStruct The struct type held by this resource
+ * @tparam enumValue The type value stored in the handle
+ *
+ */
+template <typename THandle, typename TStruct, HAL_HandleEnum enumValue>
+class UnlimitedHandleResource : public HandleBase {
+  friend class UnlimitedHandleResourceTest;
+
+ public:
+  UnlimitedHandleResource() = default;
+  UnlimitedHandleResource(const UnlimitedHandleResource&) = delete;
+  UnlimitedHandleResource& operator=(const UnlimitedHandleResource&) = delete;
+
+  THandle Allocate(std::shared_ptr<TStruct> structure);
+  std::shared_ptr<TStruct> Get(THandle handle);
+  /* Returns structure previously at that handle (or nullptr if none) */
+  std::shared_ptr<TStruct> Free(THandle handle);
+  void ResetHandles() override;
+
+  /* Calls func(THandle, TStruct*) for each handle.  Note this holds the
+   * global lock for the entirety of execution.
+   */
+  template <typename Functor>
+  void ForEach(Functor func);
+
+ private:
+  std::vector<std::shared_ptr<TStruct>> m_structures;
+  wpi::mutex m_handleMutex;
+};
+
+template <typename THandle, typename TStruct, HAL_HandleEnum enumValue>
+THandle UnlimitedHandleResource<THandle, TStruct, enumValue>::Allocate(
+    std::shared_ptr<TStruct> structure) {
+  std::lock_guard<wpi::mutex> lock(m_handleMutex);
+  size_t i;
+  for (i = 0; i < m_structures.size(); i++) {
+    if (m_structures[i] == nullptr) {
+      m_structures[i] = structure;
+      return static_cast<THandle>(createHandle(i, enumValue, m_version));
+    }
+  }
+  if (i >= INT16_MAX) return HAL_kInvalidHandle;
+
+  m_structures.push_back(structure);
+  return static_cast<THandle>(
+      createHandle(static_cast<int16_t>(i), enumValue, m_version));
+}
+
+template <typename THandle, typename TStruct, HAL_HandleEnum enumValue>
+std::shared_ptr<TStruct>
+UnlimitedHandleResource<THandle, TStruct, enumValue>::Get(THandle handle) {
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  std::lock_guard<wpi::mutex> lock(m_handleMutex);
+  if (index < 0 || index >= static_cast<int16_t>(m_structures.size()))
+    return nullptr;
+  return m_structures[index];
+}
+
+template <typename THandle, typename TStruct, HAL_HandleEnum enumValue>
+std::shared_ptr<TStruct>
+UnlimitedHandleResource<THandle, TStruct, enumValue>::Free(THandle handle) {
+  int16_t index = getHandleTypedIndex(handle, enumValue, m_version);
+  std::lock_guard<wpi::mutex> lock(m_handleMutex);
+  if (index < 0 || index >= static_cast<int16_t>(m_structures.size()))
+    return nullptr;
+  return std::move(m_structures[index]);
+}
+
+template <typename THandle, typename TStruct, HAL_HandleEnum enumValue>
+void UnlimitedHandleResource<THandle, TStruct, enumValue>::ResetHandles() {
+  {
+    std::lock_guard<wpi::mutex> lock(m_handleMutex);
+    for (size_t i = 0; i < m_structures.size(); i++) {
+      m_structures[i].reset();
+    }
+  }
+  HandleBase::ResetHandles();
+}
+
+template <typename THandle, typename TStruct, HAL_HandleEnum enumValue>
+template <typename Functor>
+void UnlimitedHandleResource<THandle, TStruct, enumValue>::ForEach(
+    Functor func) {
+  std::lock_guard<wpi::mutex> lock(m_handleMutex);
+  size_t i;
+  for (i = 0; i < m_structures.size(); i++) {
+    if (m_structures[i] != nullptr) {
+      func(static_cast<THandle>(createHandle(i, enumValue, m_version)),
+           m_structures[i].get());
+    }
+  }
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/hal/labview/HAL.h b/third_party/allwpilib_2019/hal/src/main/native/include/hal/labview/HAL.h
new file mode 100644
index 0000000..db9f20f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/hal/labview/HAL.h
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#define HAL_USE_LABVIEW
+
+#include "hal/DriverStation.h"
+#include "hal/HAL.h"
+#include "hal/Types.h"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AccelerometerData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AccelerometerData.h
new file mode 100644
index 0000000..79f151d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AccelerometerData.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Accelerometer.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetAccelerometerData(int32_t index);
+int32_t HALSIM_RegisterAccelerometerActiveCallback(int32_t index,
+                                                   HAL_NotifyCallback callback,
+                                                   void* param,
+                                                   HAL_Bool initialNotify);
+void HALSIM_CancelAccelerometerActiveCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetAccelerometerActive(int32_t index);
+void HALSIM_SetAccelerometerActive(int32_t index, HAL_Bool active);
+
+int32_t HALSIM_RegisterAccelerometerRangeCallback(int32_t index,
+                                                  HAL_NotifyCallback callback,
+                                                  void* param,
+                                                  HAL_Bool initialNotify);
+void HALSIM_CancelAccelerometerRangeCallback(int32_t index, int32_t uid);
+HAL_AccelerometerRange HALSIM_GetAccelerometerRange(int32_t index);
+void HALSIM_SetAccelerometerRange(int32_t index, HAL_AccelerometerRange range);
+
+int32_t HALSIM_RegisterAccelerometerXCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelAccelerometerXCallback(int32_t index, int32_t uid);
+double HALSIM_GetAccelerometerX(int32_t index);
+void HALSIM_SetAccelerometerX(int32_t index, double x);
+
+int32_t HALSIM_RegisterAccelerometerYCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelAccelerometerYCallback(int32_t index, int32_t uid);
+double HALSIM_GetAccelerometerY(int32_t index);
+void HALSIM_SetAccelerometerY(int32_t index, double y);
+
+int32_t HALSIM_RegisterAccelerometerZCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelAccelerometerZCallback(int32_t index, int32_t uid);
+double HALSIM_GetAccelerometerZ(int32_t index);
+void HALSIM_SetAccelerometerZ(int32_t index, double z);
+
+void HALSIM_RegisterAccelerometerAllCallbacks(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogGyroData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogGyroData.h
new file mode 100644
index 0000000..5b648ee
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogGyroData.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetAnalogGyroData(int32_t index);
+int32_t HALSIM_RegisterAnalogGyroAngleCallback(int32_t index,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify);
+void HALSIM_CancelAnalogGyroAngleCallback(int32_t index, int32_t uid);
+double HALSIM_GetAnalogGyroAngle(int32_t index);
+void HALSIM_SetAnalogGyroAngle(int32_t index, double angle);
+
+int32_t HALSIM_RegisterAnalogGyroRateCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelAnalogGyroRateCallback(int32_t index, int32_t uid);
+double HALSIM_GetAnalogGyroRate(int32_t index);
+void HALSIM_SetAnalogGyroRate(int32_t index, double rate);
+
+int32_t HALSIM_RegisterAnalogGyroInitializedCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogGyroInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetAnalogGyroInitialized(int32_t index);
+void HALSIM_SetAnalogGyroInitialized(int32_t index, HAL_Bool initialized);
+
+void HALSIM_RegisterAnalogGyroAllCallbacks(int32_t index,
+                                           HAL_NotifyCallback callback,
+                                           void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogInData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogInData.h
new file mode 100644
index 0000000..7a95164
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogInData.h
@@ -0,0 +1,101 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetAnalogInData(int32_t index);
+int32_t HALSIM_RegisterAnalogInInitializedCallback(int32_t index,
+                                                   HAL_NotifyCallback callback,
+                                                   void* param,
+                                                   HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetAnalogInInitialized(int32_t index);
+void HALSIM_SetAnalogInInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterAnalogInAverageBitsCallback(int32_t index,
+                                                   HAL_NotifyCallback callback,
+                                                   void* param,
+                                                   HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInAverageBitsCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetAnalogInAverageBits(int32_t index);
+void HALSIM_SetAnalogInAverageBits(int32_t index, int32_t averageBits);
+
+int32_t HALSIM_RegisterAnalogInOversampleBitsCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInOversampleBitsCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetAnalogInOversampleBits(int32_t index);
+void HALSIM_SetAnalogInOversampleBits(int32_t index, int32_t oversampleBits);
+
+int32_t HALSIM_RegisterAnalogInVoltageCallback(int32_t index,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInVoltageCallback(int32_t index, int32_t uid);
+double HALSIM_GetAnalogInVoltage(int32_t index);
+void HALSIM_SetAnalogInVoltage(int32_t index, double voltage);
+
+int32_t HALSIM_RegisterAnalogInAccumulatorInitializedCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInAccumulatorInitializedCallback(int32_t index,
+                                                         int32_t uid);
+HAL_Bool HALSIM_GetAnalogInAccumulatorInitialized(int32_t index);
+void HALSIM_SetAnalogInAccumulatorInitialized(int32_t index,
+                                              HAL_Bool accumulatorInitialized);
+
+int32_t HALSIM_RegisterAnalogInAccumulatorValueCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInAccumulatorValueCallback(int32_t index, int32_t uid);
+int64_t HALSIM_GetAnalogInAccumulatorValue(int32_t index);
+void HALSIM_SetAnalogInAccumulatorValue(int32_t index,
+                                        int64_t accumulatorValue);
+
+int32_t HALSIM_RegisterAnalogInAccumulatorCountCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInAccumulatorCountCallback(int32_t index, int32_t uid);
+int64_t HALSIM_GetAnalogInAccumulatorCount(int32_t index);
+void HALSIM_SetAnalogInAccumulatorCount(int32_t index,
+                                        int64_t accumulatorCount);
+
+int32_t HALSIM_RegisterAnalogInAccumulatorCenterCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInAccumulatorCenterCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetAnalogInAccumulatorCenter(int32_t index);
+void HALSIM_SetAnalogInAccumulatorCenter(int32_t index,
+                                         int32_t accumulatorCenter);
+
+int32_t HALSIM_RegisterAnalogInAccumulatorDeadbandCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogInAccumulatorDeadbandCallback(int32_t index,
+                                                      int32_t uid);
+int32_t HALSIM_GetAnalogInAccumulatorDeadband(int32_t index);
+void HALSIM_SetAnalogInAccumulatorDeadband(int32_t index,
+                                           int32_t accumulatorDeadband);
+
+void HALSIM_RegisterAnalogInAllCallbacks(int32_t index,
+                                         HAL_NotifyCallback callback,
+                                         void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogOutData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogOutData.h
new file mode 100644
index 0000000..48046ec
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogOutData.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetAnalogOutData(int32_t index);
+int32_t HALSIM_RegisterAnalogOutVoltageCallback(int32_t index,
+                                                HAL_NotifyCallback callback,
+                                                void* param,
+                                                HAL_Bool initialNotify);
+void HALSIM_CancelAnalogOutVoltageCallback(int32_t index, int32_t uid);
+double HALSIM_GetAnalogOutVoltage(int32_t index);
+void HALSIM_SetAnalogOutVoltage(int32_t index, double voltage);
+
+int32_t HALSIM_RegisterAnalogOutInitializedCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogOutInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetAnalogOutInitialized(int32_t index);
+void HALSIM_SetAnalogOutInitialized(int32_t index, HAL_Bool initialized);
+
+void HALSIM_RegisterAnalogOutAllCallbacks(int32_t index,
+                                          HAL_NotifyCallback callback,
+                                          void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogTriggerData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogTriggerData.h
new file mode 100644
index 0000000..8146b8f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/AnalogTriggerData.h
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+enum HALSIM_AnalogTriggerMode : int32_t {
+  HALSIM_AnalogTriggerUnassigned,
+  HALSIM_AnalogTriggerFiltered,
+  HALSIM_AnalogTriggerAveraged
+};
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetAnalogTriggerData(int32_t index);
+int32_t HALSIM_RegisterAnalogTriggerInitializedCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogTriggerInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetAnalogTriggerInitialized(int32_t index);
+void HALSIM_SetAnalogTriggerInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterAnalogTriggerTriggerLowerBoundCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogTriggerTriggerLowerBoundCallback(int32_t index,
+                                                         int32_t uid);
+double HALSIM_GetAnalogTriggerTriggerLowerBound(int32_t index);
+void HALSIM_SetAnalogTriggerTriggerLowerBound(int32_t index,
+                                              double triggerLowerBound);
+
+int32_t HALSIM_RegisterAnalogTriggerTriggerUpperBoundCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogTriggerTriggerUpperBoundCallback(int32_t index,
+                                                         int32_t uid);
+double HALSIM_GetAnalogTriggerTriggerUpperBound(int32_t index);
+void HALSIM_SetAnalogTriggerTriggerUpperBound(int32_t index,
+                                              double triggerUpperBound);
+
+int32_t HALSIM_RegisterAnalogTriggerTriggerModeCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelAnalogTriggerTriggerModeCallback(int32_t index, int32_t uid);
+HALSIM_AnalogTriggerMode HALSIM_GetAnalogTriggerTriggerMode(int32_t index);
+void HALSIM_SetAnalogTriggerTriggerMode(int32_t index,
+                                        HALSIM_AnalogTriggerMode triggerMode);
+
+void HALSIM_RegisterAnalogTriggerAllCallbacks(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/CanData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/CanData.h
new file mode 100644
index 0000000..4d76dca
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/CanData.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "HAL_Value.h"
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+typedef void (*HAL_CAN_SendMessageCallback)(const char* name, void* param,
+                                            uint32_t messageID,
+                                            const uint8_t* data,
+                                            uint8_t dataSize, int32_t periodMs,
+                                            int32_t* status);
+
+typedef void (*HAL_CAN_ReceiveMessageCallback)(
+    const char* name, void* param, uint32_t* messageID, uint32_t messageIDMask,
+    uint8_t* data, uint8_t* dataSize, uint32_t* timeStamp, int32_t* status);
+
+typedef void (*HAL_CAN_OpenStreamSessionCallback)(
+    const char* name, void* param, uint32_t* sessionHandle, uint32_t messageID,
+    uint32_t messageIDMask, uint32_t maxMessages, int32_t* status);
+
+typedef void (*HAL_CAN_CloseStreamSessionCallback)(const char* name,
+                                                   void* param,
+                                                   uint32_t sessionHandle);
+
+typedef void (*HAL_CAN_ReadStreamSessionCallback)(
+    const char* name, void* param, uint32_t sessionHandle,
+    struct HAL_CANStreamMessage* messages, uint32_t messagesToRead,
+    uint32_t* messagesRead, int32_t* status);
+
+typedef void (*HAL_CAN_GetCANStatusCallback)(
+    const char* name, void* param, float* percentBusUtilization,
+    uint32_t* busOffCount, uint32_t* txFullCount, uint32_t* receiveErrorCount,
+    uint32_t* transmitErrorCount, int32_t* status);
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetCanData(void);
+
+int32_t HALSIM_RegisterCanSendMessageCallback(
+    HAL_CAN_SendMessageCallback callback, void* param);
+void HALSIM_CancelCanSendMessageCallback(int32_t uid);
+
+int32_t HALSIM_RegisterCanReceiveMessageCallback(
+    HAL_CAN_ReceiveMessageCallback callback, void* param);
+void HALSIM_CancelCanReceiveMessageCallback(int32_t uid);
+
+int32_t HALSIM_RegisterCanOpenStreamCallback(
+    HAL_CAN_OpenStreamSessionCallback callback, void* param);
+void HALSIM_CancelCanOpenStreamCallback(int32_t uid);
+
+int32_t HALSIM_RegisterCanCloseStreamCallback(
+    HAL_CAN_CloseStreamSessionCallback callback, void* param);
+void HALSIM_CancelCanCloseStreamCallback(int32_t uid);
+
+int32_t HALSIM_RegisterCanReadStreamCallback(
+    HAL_CAN_ReadStreamSessionCallback callback, void* param);
+void HALSIM_CancelCanReadStreamCallback(int32_t uid);
+
+int32_t HALSIM_RegisterCanGetCANStatusCallback(
+    HAL_CAN_GetCANStatusCallback callback, void* param);
+void HALSIM_CancelCanGetCANStatusCallback(int32_t uid);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DIOData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DIOData.h
new file mode 100644
index 0000000..b3bd9f2
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DIOData.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetDIOData(int32_t index);
+int32_t HALSIM_RegisterDIOInitializedCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelDIOInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetDIOInitialized(int32_t index);
+void HALSIM_SetDIOInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterDIOValueCallback(int32_t index,
+                                        HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify);
+void HALSIM_CancelDIOValueCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetDIOValue(int32_t index);
+void HALSIM_SetDIOValue(int32_t index, HAL_Bool value);
+
+int32_t HALSIM_RegisterDIOPulseLengthCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelDIOPulseLengthCallback(int32_t index, int32_t uid);
+double HALSIM_GetDIOPulseLength(int32_t index);
+void HALSIM_SetDIOPulseLength(int32_t index, double pulseLength);
+
+int32_t HALSIM_RegisterDIOIsInputCallback(int32_t index,
+                                          HAL_NotifyCallback callback,
+                                          void* param, HAL_Bool initialNotify);
+void HALSIM_CancelDIOIsInputCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetDIOIsInput(int32_t index);
+void HALSIM_SetDIOIsInput(int32_t index, HAL_Bool isInput);
+
+int32_t HALSIM_RegisterDIOFilterIndexCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelDIOFilterIndexCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetDIOFilterIndex(int32_t index);
+void HALSIM_SetDIOFilterIndex(int32_t index, int32_t filterIndex);
+
+void HALSIM_RegisterDIOAllCallbacks(int32_t index, HAL_NotifyCallback callback,
+                                    void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DigitalPWMData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DigitalPWMData.h
new file mode 100644
index 0000000..d35e313
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DigitalPWMData.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetDigitalPWMData(int32_t index);
+int32_t HALSIM_RegisterDigitalPWMInitializedCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelDigitalPWMInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetDigitalPWMInitialized(int32_t index);
+void HALSIM_SetDigitalPWMInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterDigitalPWMDutyCycleCallback(int32_t index,
+                                                   HAL_NotifyCallback callback,
+                                                   void* param,
+                                                   HAL_Bool initialNotify);
+void HALSIM_CancelDigitalPWMDutyCycleCallback(int32_t index, int32_t uid);
+double HALSIM_GetDigitalPWMDutyCycle(int32_t index);
+void HALSIM_SetDigitalPWMDutyCycle(int32_t index, double dutyCycle);
+
+int32_t HALSIM_RegisterDigitalPWMPinCallback(int32_t index,
+                                             HAL_NotifyCallback callback,
+                                             void* param,
+                                             HAL_Bool initialNotify);
+void HALSIM_CancelDigitalPWMPinCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetDigitalPWMPin(int32_t index);
+void HALSIM_SetDigitalPWMPin(int32_t index, int32_t pin);
+
+void HALSIM_RegisterDigitalPWMAllCallbacks(int32_t index,
+                                           HAL_NotifyCallback callback,
+                                           void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DriverStationData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DriverStationData.h
new file mode 100644
index 0000000..57ca4e0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/DriverStationData.h
@@ -0,0 +1,95 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/DriverStationTypes.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetDriverStationData(void);
+int32_t HALSIM_RegisterDriverStationEnabledCallback(HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelDriverStationEnabledCallback(int32_t uid);
+HAL_Bool HALSIM_GetDriverStationEnabled(void);
+void HALSIM_SetDriverStationEnabled(HAL_Bool enabled);
+
+int32_t HALSIM_RegisterDriverStationAutonomousCallback(
+    HAL_NotifyCallback callback, void* param, HAL_Bool initialNotify);
+void HALSIM_CancelDriverStationAutonomousCallback(int32_t uid);
+HAL_Bool HALSIM_GetDriverStationAutonomous(void);
+void HALSIM_SetDriverStationAutonomous(HAL_Bool autonomous);
+
+int32_t HALSIM_RegisterDriverStationTestCallback(HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelDriverStationTestCallback(int32_t uid);
+HAL_Bool HALSIM_GetDriverStationTest(void);
+void HALSIM_SetDriverStationTest(HAL_Bool test);
+
+int32_t HALSIM_RegisterDriverStationEStopCallback(HAL_NotifyCallback callback,
+                                                  void* param,
+                                                  HAL_Bool initialNotify);
+void HALSIM_CancelDriverStationEStopCallback(int32_t uid);
+HAL_Bool HALSIM_GetDriverStationEStop(void);
+void HALSIM_SetDriverStationEStop(HAL_Bool eStop);
+
+int32_t HALSIM_RegisterDriverStationFmsAttachedCallback(
+    HAL_NotifyCallback callback, void* param, HAL_Bool initialNotify);
+void HALSIM_CancelDriverStationFmsAttachedCallback(int32_t uid);
+HAL_Bool HALSIM_GetDriverStationFmsAttached(void);
+void HALSIM_SetDriverStationFmsAttached(HAL_Bool fmsAttached);
+
+int32_t HALSIM_RegisterDriverStationDsAttachedCallback(
+    HAL_NotifyCallback callback, void* param, HAL_Bool initialNotify);
+void HALSIM_CancelDriverStationDsAttachedCallback(int32_t uid);
+HAL_Bool HALSIM_GetDriverStationDsAttached(void);
+void HALSIM_SetDriverStationDsAttached(HAL_Bool dsAttached);
+
+int32_t HALSIM_RegisterDriverStationAllianceStationIdCallback(
+    HAL_NotifyCallback callback, void* param, HAL_Bool initialNotify);
+void HALSIM_CancelDriverStationAllianceStationIdCallback(int32_t uid);
+HAL_AllianceStationID HALSIM_GetDriverStationAllianceStationId(void);
+void HALSIM_SetDriverStationAllianceStationId(
+    HAL_AllianceStationID allianceStationId);
+
+int32_t HALSIM_RegisterDriverStationMatchTimeCallback(
+    HAL_NotifyCallback callback, void* param, HAL_Bool initialNotify);
+void HALSIM_CancelDriverStationMatchTimeCallback(int32_t uid);
+double HALSIM_GetDriverStationMatchTime(void);
+void HALSIM_SetDriverStationMatchTime(double matchTime);
+
+void HALSIM_SetJoystickAxes(int32_t joystickNum, const HAL_JoystickAxes* axes);
+void HALSIM_SetJoystickPOVs(int32_t joystickNum, const HAL_JoystickPOVs* povs);
+void HALSIM_SetJoystickButtons(int32_t joystickNum,
+                               const HAL_JoystickButtons* buttons);
+void HALSIM_SetJoystickDescriptor(int32_t joystickNum,
+                                  const HAL_JoystickDescriptor* descriptor);
+
+void HALSIM_GetJoystickOutputs(int32_t joystickNum, int64_t* outputs,
+                               int32_t* leftRumble, int32_t* rightRumble);
+
+void HALSIM_SetMatchInfo(const HAL_MatchInfo* info);
+
+void HALSIM_RegisterDriverStationAllCallbacks(HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+
+void HALSIM_NotifyDriverStationNewData(void);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/EncoderData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/EncoderData.h
new file mode 100644
index 0000000..bcd00a7
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/EncoderData.h
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetEncoderData(int32_t index);
+int16_t HALSIM_GetDigitalChannelA(int32_t index);
+int32_t HALSIM_RegisterEncoderInitializedCallback(int32_t index,
+                                                  HAL_NotifyCallback callback,
+                                                  void* param,
+                                                  HAL_Bool initialNotify);
+void HALSIM_CancelEncoderInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetEncoderInitialized(int32_t index);
+void HALSIM_SetEncoderInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterEncoderCountCallback(int32_t index,
+                                            HAL_NotifyCallback callback,
+                                            void* param,
+                                            HAL_Bool initialNotify);
+void HALSIM_CancelEncoderCountCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetEncoderCount(int32_t index);
+void HALSIM_SetEncoderCount(int32_t index, int32_t count);
+
+int32_t HALSIM_RegisterEncoderPeriodCallback(int32_t index,
+                                             HAL_NotifyCallback callback,
+                                             void* param,
+                                             HAL_Bool initialNotify);
+void HALSIM_CancelEncoderPeriodCallback(int32_t index, int32_t uid);
+double HALSIM_GetEncoderPeriod(int32_t index);
+void HALSIM_SetEncoderPeriod(int32_t index, double period);
+
+int32_t HALSIM_RegisterEncoderResetCallback(int32_t index,
+                                            HAL_NotifyCallback callback,
+                                            void* param,
+                                            HAL_Bool initialNotify);
+void HALSIM_CancelEncoderResetCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetEncoderReset(int32_t index);
+void HALSIM_SetEncoderReset(int32_t index, HAL_Bool reset);
+
+int32_t HALSIM_RegisterEncoderMaxPeriodCallback(int32_t index,
+                                                HAL_NotifyCallback callback,
+                                                void* param,
+                                                HAL_Bool initialNotify);
+void HALSIM_CancelEncoderMaxPeriodCallback(int32_t index, int32_t uid);
+double HALSIM_GetEncoderMaxPeriod(int32_t index);
+void HALSIM_SetEncoderMaxPeriod(int32_t index, double maxPeriod);
+
+int32_t HALSIM_RegisterEncoderDirectionCallback(int32_t index,
+                                                HAL_NotifyCallback callback,
+                                                void* param,
+                                                HAL_Bool initialNotify);
+void HALSIM_CancelEncoderDirectionCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetEncoderDirection(int32_t index);
+void HALSIM_SetEncoderDirection(int32_t index, HAL_Bool direction);
+
+int32_t HALSIM_RegisterEncoderReverseDirectionCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelEncoderReverseDirectionCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetEncoderReverseDirection(int32_t index);
+void HALSIM_SetEncoderReverseDirection(int32_t index,
+                                       HAL_Bool reverseDirection);
+
+int32_t HALSIM_RegisterEncoderSamplesToAverageCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelEncoderSamplesToAverageCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetEncoderSamplesToAverage(int32_t index);
+void HALSIM_SetEncoderSamplesToAverage(int32_t index, int32_t samplesToAverage);
+
+int32_t HALSIM_RegisterEncoderDistancePerPulseCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelEncoderDistancePerPulseCallback(int32_t index, int32_t uid);
+double HALSIM_GetEncoderDistancePerPulse(int32_t index);
+void HALSIM_SetEncoderDistancePerPulse(int32_t index, double distancePerPulse);
+
+void HALSIM_RegisterEncoderAllCallbacks(int32_t index,
+                                        HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/HAL_Value.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/HAL_Value.h
new file mode 100644
index 0000000..ee348b9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/HAL_Value.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "hal/Types.h"
+
+/** HAL data types. */
+enum HAL_Type {
+  HAL_UNASSIGNED = 0,
+  HAL_BOOLEAN = 0x01,
+  HAL_DOUBLE = 0x02,
+  HAL_ENUM = 0x16,
+  HAL_INT = 0x32,
+  HAL_LONG = 0x64,
+};
+
+/** HAL Entry Value.  Note this is a typed union. */
+struct HAL_Value {
+  union {
+    HAL_Bool v_boolean;
+    int32_t v_enum;
+    int32_t v_int;
+    int64_t v_long;
+    double v_double;
+  } data;
+  enum HAL_Type type;
+};
+
+inline HAL_Value MakeBoolean(HAL_Bool v) {
+  HAL_Value value;
+  value.type = HAL_BOOLEAN;
+  value.data.v_boolean = v;
+  return value;
+}
+
+inline HAL_Value MakeEnum(int v) {
+  HAL_Value value;
+  value.type = HAL_ENUM;
+  value.data.v_enum = v;
+  return value;
+}
+
+inline HAL_Value MakeInt(int v) {
+  HAL_Value value;
+  value.type = HAL_INT;
+  value.data.v_int = v;
+  return value;
+}
+
+inline HAL_Value MakeLong(int64_t v) {
+  HAL_Value value;
+  value.type = HAL_LONG;
+  value.data.v_long = v;
+  return value;
+}
+
+inline HAL_Value MakeDouble(double v) {
+  HAL_Value value;
+  value.type = HAL_DOUBLE;
+  value.data.v_double = v;
+  return value;
+}
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/I2CData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/I2CData.h
new file mode 100644
index 0000000..8565fdb
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/I2CData.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetI2CData(int32_t index);
+
+int32_t HALSIM_RegisterI2CInitializedCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelI2CInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetI2CInitialized(int32_t index);
+void HALSIM_SetI2CInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterI2CReadCallback(int32_t index,
+                                       HAL_BufferCallback callback,
+                                       void* param);
+void HALSIM_CancelI2CReadCallback(int32_t index, int32_t uid);
+
+int32_t HALSIM_RegisterI2CWriteCallback(int32_t index,
+                                        HAL_ConstBufferCallback callback,
+                                        void* param);
+void HALSIM_CancelI2CWriteCallback(int32_t index, int32_t uid);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/MockHooks.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/MockHooks.h
new file mode 100644
index 0000000..37eb0e7
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/MockHooks.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "hal/Types.h"
+
+extern "C" {
+void HALSIM_WaitForProgramStart(void);
+void HALSIM_SetProgramStarted(void);
+HAL_Bool HALSIM_GetProgramStarted(void);
+void HALSIM_RestartTiming(void);
+}  // extern "C"
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/NotifyListener.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/NotifyListener.h
new file mode 100644
index 0000000..8d7e199
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/NotifyListener.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "HAL_Value.h"
+
+typedef void (*HAL_NotifyCallback)(const char* name, void* param,
+                                   const struct HAL_Value* value);
+
+typedef void (*HAL_BufferCallback)(const char* name, void* param,
+                                   unsigned char* buffer, unsigned int count);
+
+typedef void (*HAL_ConstBufferCallback)(const char* name, void* param,
+                                        const unsigned char* buffer,
+                                        unsigned int count);
+
+namespace hal {
+
+template <typename CallbackFunction>
+struct HalCallbackListener {
+  HalCallbackListener() = default;
+  HalCallbackListener(void* param_, CallbackFunction callback_)
+      : callback(callback_), param(param_) {}
+
+  explicit operator bool() const { return callback != nullptr; }
+
+  CallbackFunction callback;
+  void* param;
+};
+
+}  // namespace hal
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PCMData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PCMData.h
new file mode 100644
index 0000000..d919cc9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PCMData.h
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetPCMData(int32_t index);
+int32_t HALSIM_RegisterPCMSolenoidInitializedCallback(
+    int32_t index, int32_t channel, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelPCMSolenoidInitializedCallback(int32_t index, int32_t channel,
+                                                 int32_t uid);
+HAL_Bool HALSIM_GetPCMSolenoidInitialized(int32_t index, int32_t channel);
+void HALSIM_SetPCMSolenoidInitialized(int32_t index, int32_t channel,
+                                      HAL_Bool solenoidInitialized);
+
+int32_t HALSIM_RegisterPCMSolenoidOutputCallback(int32_t index, int32_t channel,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelPCMSolenoidOutputCallback(int32_t index, int32_t channel,
+                                            int32_t uid);
+HAL_Bool HALSIM_GetPCMSolenoidOutput(int32_t index, int32_t channel);
+void HALSIM_SetPCMSolenoidOutput(int32_t index, int32_t channel,
+                                 HAL_Bool solenoidOutput);
+
+int32_t HALSIM_RegisterPCMCompressorInitializedCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelPCMCompressorInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetPCMCompressorInitialized(int32_t index);
+void HALSIM_SetPCMCompressorInitialized(int32_t index,
+                                        HAL_Bool compressorInitialized);
+
+int32_t HALSIM_RegisterPCMCompressorOnCallback(int32_t index,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify);
+void HALSIM_CancelPCMCompressorOnCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetPCMCompressorOn(int32_t index);
+void HALSIM_SetPCMCompressorOn(int32_t index, HAL_Bool compressorOn);
+
+int32_t HALSIM_RegisterPCMClosedLoopEnabledCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelPCMClosedLoopEnabledCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetPCMClosedLoopEnabled(int32_t index);
+void HALSIM_SetPCMClosedLoopEnabled(int32_t index, HAL_Bool closedLoopEnabled);
+
+int32_t HALSIM_RegisterPCMPressureSwitchCallback(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelPCMPressureSwitchCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetPCMPressureSwitch(int32_t index);
+void HALSIM_SetPCMPressureSwitch(int32_t index, HAL_Bool pressureSwitch);
+
+int32_t HALSIM_RegisterPCMCompressorCurrentCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelPCMCompressorCurrentCallback(int32_t index, int32_t uid);
+double HALSIM_GetPCMCompressorCurrent(int32_t index);
+void HALSIM_SetPCMCompressorCurrent(int32_t index, double compressorCurrent);
+
+void HALSIM_RegisterPCMAllNonSolenoidCallbacks(int32_t index,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify);
+
+void HALSIM_RegisterPCMAllSolenoidCallbacks(int32_t index, int32_t channel,
+                                            HAL_NotifyCallback callback,
+                                            void* param,
+                                            HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PDPData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PDPData.h
new file mode 100644
index 0000000..be24da8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PDPData.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetPDPData(int32_t index);
+int32_t HALSIM_RegisterPDPInitializedCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelPDPInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetPDPInitialized(int32_t index);
+void HALSIM_SetPDPInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterPDPTemperatureCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelPDPTemperatureCallback(int32_t index, int32_t uid);
+double HALSIM_GetPDPTemperature(int32_t index);
+void HALSIM_SetPDPTemperature(int32_t index, double temperature);
+
+int32_t HALSIM_RegisterPDPVoltageCallback(int32_t index,
+                                          HAL_NotifyCallback callback,
+                                          void* param, HAL_Bool initialNotify);
+void HALSIM_CancelPDPVoltageCallback(int32_t index, int32_t uid);
+double HALSIM_GetPDPVoltage(int32_t index);
+void HALSIM_SetPDPVoltage(int32_t index, double voltage);
+
+int32_t HALSIM_RegisterPDPCurrentCallback(int32_t index, int32_t channel,
+                                          HAL_NotifyCallback callback,
+                                          void* param, HAL_Bool initialNotify);
+void HALSIM_CancelPDPCurrentCallback(int32_t index, int32_t channel,
+                                     int32_t uid);
+double HALSIM_GetPDPCurrent(int32_t index, int32_t channel);
+void HALSIM_SetPDPCurrent(int32_t index, int32_t channel, double current);
+
+void HALSIM_RegisterPDPAllNonCurrentCallbacks(int32_t index, int32_t channel,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PWMData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PWMData.h
new file mode 100644
index 0000000..08ba357
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/PWMData.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetPWMData(int32_t index);
+int32_t HALSIM_RegisterPWMInitializedCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelPWMInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetPWMInitialized(int32_t index);
+void HALSIM_SetPWMInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterPWMRawValueCallback(int32_t index,
+                                           HAL_NotifyCallback callback,
+                                           void* param, HAL_Bool initialNotify);
+void HALSIM_CancelPWMRawValueCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetPWMRawValue(int32_t index);
+void HALSIM_SetPWMRawValue(int32_t index, int32_t rawValue);
+
+int32_t HALSIM_RegisterPWMSpeedCallback(int32_t index,
+                                        HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify);
+void HALSIM_CancelPWMSpeedCallback(int32_t index, int32_t uid);
+double HALSIM_GetPWMSpeed(int32_t index);
+void HALSIM_SetPWMSpeed(int32_t index, double speed);
+
+int32_t HALSIM_RegisterPWMPositionCallback(int32_t index,
+                                           HAL_NotifyCallback callback,
+                                           void* param, HAL_Bool initialNotify);
+void HALSIM_CancelPWMPositionCallback(int32_t index, int32_t uid);
+double HALSIM_GetPWMPosition(int32_t index);
+void HALSIM_SetPWMPosition(int32_t index, double position);
+
+int32_t HALSIM_RegisterPWMPeriodScaleCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelPWMPeriodScaleCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetPWMPeriodScale(int32_t index);
+void HALSIM_SetPWMPeriodScale(int32_t index, int32_t periodScale);
+
+int32_t HALSIM_RegisterPWMZeroLatchCallback(int32_t index,
+                                            HAL_NotifyCallback callback,
+                                            void* param,
+                                            HAL_Bool initialNotify);
+void HALSIM_CancelPWMZeroLatchCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetPWMZeroLatch(int32_t index);
+void HALSIM_SetPWMZeroLatch(int32_t index, HAL_Bool zeroLatch);
+
+void HALSIM_RegisterPWMAllCallbacks(int32_t index, HAL_NotifyCallback callback,
+                                    void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/RelayData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/RelayData.h
new file mode 100644
index 0000000..6fdac7f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/RelayData.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetRelayData(int32_t index);
+int32_t HALSIM_RegisterRelayInitializedForwardCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelRelayInitializedForwardCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetRelayInitializedForward(int32_t index);
+void HALSIM_SetRelayInitializedForward(int32_t index,
+                                       HAL_Bool initializedForward);
+
+int32_t HALSIM_RegisterRelayInitializedReverseCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelRelayInitializedReverseCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetRelayInitializedReverse(int32_t index);
+void HALSIM_SetRelayInitializedReverse(int32_t index,
+                                       HAL_Bool initializedReverse);
+
+int32_t HALSIM_RegisterRelayForwardCallback(int32_t index,
+                                            HAL_NotifyCallback callback,
+                                            void* param,
+                                            HAL_Bool initialNotify);
+void HALSIM_CancelRelayForwardCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetRelayForward(int32_t index);
+void HALSIM_SetRelayForward(int32_t index, HAL_Bool forward);
+
+int32_t HALSIM_RegisterRelayReverseCallback(int32_t index,
+                                            HAL_NotifyCallback callback,
+                                            void* param,
+                                            HAL_Bool initialNotify);
+void HALSIM_CancelRelayReverseCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetRelayReverse(int32_t index);
+void HALSIM_SetRelayReverse(int32_t index, HAL_Bool reverse);
+
+void HALSIM_RegisterRelayAllCallbacks(int32_t index,
+                                      HAL_NotifyCallback callback, void* param,
+                                      HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/RoboRioData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/RoboRioData.h
new file mode 100644
index 0000000..88b6ece
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/RoboRioData.h
@@ -0,0 +1,146 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetRoboRioData(int32_t index);
+int32_t HALSIM_RegisterRoboRioFPGAButtonCallback(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioFPGAButtonCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetRoboRioFPGAButton(int32_t index);
+void HALSIM_SetRoboRioFPGAButton(int32_t index, HAL_Bool fPGAButton);
+
+int32_t HALSIM_RegisterRoboRioVInVoltageCallback(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioVInVoltageCallback(int32_t index, int32_t uid);
+double HALSIM_GetRoboRioVInVoltage(int32_t index);
+void HALSIM_SetRoboRioVInVoltage(int32_t index, double vInVoltage);
+
+int32_t HALSIM_RegisterRoboRioVInCurrentCallback(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioVInCurrentCallback(int32_t index, int32_t uid);
+double HALSIM_GetRoboRioVInCurrent(int32_t index);
+void HALSIM_SetRoboRioVInCurrent(int32_t index, double vInCurrent);
+
+int32_t HALSIM_RegisterRoboRioUserVoltage6VCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserVoltage6VCallback(int32_t index, int32_t uid);
+double HALSIM_GetRoboRioUserVoltage6V(int32_t index);
+void HALSIM_SetRoboRioUserVoltage6V(int32_t index, double userVoltage6V);
+
+int32_t HALSIM_RegisterRoboRioUserCurrent6VCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserCurrent6VCallback(int32_t index, int32_t uid);
+double HALSIM_GetRoboRioUserCurrent6V(int32_t index);
+void HALSIM_SetRoboRioUserCurrent6V(int32_t index, double userCurrent6V);
+
+int32_t HALSIM_RegisterRoboRioUserActive6VCallback(int32_t index,
+                                                   HAL_NotifyCallback callback,
+                                                   void* param,
+                                                   HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserActive6VCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetRoboRioUserActive6V(int32_t index);
+void HALSIM_SetRoboRioUserActive6V(int32_t index, HAL_Bool userActive6V);
+
+int32_t HALSIM_RegisterRoboRioUserVoltage5VCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserVoltage5VCallback(int32_t index, int32_t uid);
+double HALSIM_GetRoboRioUserVoltage5V(int32_t index);
+void HALSIM_SetRoboRioUserVoltage5V(int32_t index, double userVoltage5V);
+
+int32_t HALSIM_RegisterRoboRioUserCurrent5VCallback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserCurrent5VCallback(int32_t index, int32_t uid);
+double HALSIM_GetRoboRioUserCurrent5V(int32_t index);
+void HALSIM_SetRoboRioUserCurrent5V(int32_t index, double userCurrent5V);
+
+int32_t HALSIM_RegisterRoboRioUserActive5VCallback(int32_t index,
+                                                   HAL_NotifyCallback callback,
+                                                   void* param,
+                                                   HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserActive5VCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetRoboRioUserActive5V(int32_t index);
+void HALSIM_SetRoboRioUserActive5V(int32_t index, HAL_Bool userActive5V);
+
+int32_t HALSIM_RegisterRoboRioUserVoltage3V3Callback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserVoltage3V3Callback(int32_t index, int32_t uid);
+double HALSIM_GetRoboRioUserVoltage3V3(int32_t index);
+void HALSIM_SetRoboRioUserVoltage3V3(int32_t index, double userVoltage3V3);
+
+int32_t HALSIM_RegisterRoboRioUserCurrent3V3Callback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserCurrent3V3Callback(int32_t index, int32_t uid);
+double HALSIM_GetRoboRioUserCurrent3V3(int32_t index);
+void HALSIM_SetRoboRioUserCurrent3V3(int32_t index, double userCurrent3V3);
+
+int32_t HALSIM_RegisterRoboRioUserActive3V3Callback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserActive3V3Callback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetRoboRioUserActive3V3(int32_t index);
+void HALSIM_SetRoboRioUserActive3V3(int32_t index, HAL_Bool userActive3V3);
+
+int32_t HALSIM_RegisterRoboRioUserFaults6VCallback(int32_t index,
+                                                   HAL_NotifyCallback callback,
+                                                   void* param,
+                                                   HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserFaults6VCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetRoboRioUserFaults6V(int32_t index);
+void HALSIM_SetRoboRioUserFaults6V(int32_t index, int32_t userFaults6V);
+
+int32_t HALSIM_RegisterRoboRioUserFaults5VCallback(int32_t index,
+                                                   HAL_NotifyCallback callback,
+                                                   void* param,
+                                                   HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserFaults5VCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetRoboRioUserFaults5V(int32_t index);
+void HALSIM_SetRoboRioUserFaults5V(int32_t index, int32_t userFaults5V);
+
+int32_t HALSIM_RegisterRoboRioUserFaults3V3Callback(int32_t index,
+                                                    HAL_NotifyCallback callback,
+                                                    void* param,
+                                                    HAL_Bool initialNotify);
+void HALSIM_CancelRoboRioUserFaults3V3Callback(int32_t index, int32_t uid);
+int32_t HALSIM_GetRoboRioUserFaults3V3(int32_t index);
+void HALSIM_SetRoboRioUserFaults3V3(int32_t index, int32_t userFaults3V3);
+
+void HALSIM_RegisterRoboRioAllCallbacks(int32_t index,
+                                        HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SPIAccelerometerData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SPIAccelerometerData.h
new file mode 100644
index 0000000..6e37f40
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SPIAccelerometerData.h
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetSPIAccelerometerData(int32_t index);
+int32_t HALSIM_RegisterSPIAccelerometerActiveCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelSPIAccelerometerActiveCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetSPIAccelerometerActive(int32_t index);
+void HALSIM_SetSPIAccelerometerActive(int32_t index, HAL_Bool active);
+
+int32_t HALSIM_RegisterSPIAccelerometerRangeCallback(
+    int32_t index, HAL_NotifyCallback callback, void* param,
+    HAL_Bool initialNotify);
+void HALSIM_CancelSPIAccelerometerRangeCallback(int32_t index, int32_t uid);
+int32_t HALSIM_GetSPIAccelerometerRange(int32_t index);
+void HALSIM_SetSPIAccelerometerRange(int32_t index, int32_t range);
+
+int32_t HALSIM_RegisterSPIAccelerometerXCallback(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelSPIAccelerometerXCallback(int32_t index, int32_t uid);
+double HALSIM_GetSPIAccelerometerX(int32_t index);
+void HALSIM_SetSPIAccelerometerX(int32_t index, double x);
+
+int32_t HALSIM_RegisterSPIAccelerometerYCallback(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelSPIAccelerometerYCallback(int32_t index, int32_t uid);
+double HALSIM_GetSPIAccelerometerY(int32_t index);
+void HALSIM_SetSPIAccelerometerY(int32_t index, double y);
+
+int32_t HALSIM_RegisterSPIAccelerometerZCallback(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+void HALSIM_CancelSPIAccelerometerZCallback(int32_t index, int32_t uid);
+double HALSIM_GetSPIAccelerometerZ(int32_t index);
+void HALSIM_SetSPIAccelerometerZ(int32_t index, double z);
+
+void HALSIM_RegisterSPIAccelerometerAllCallbcaks(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SPIData.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SPIData.h
new file mode 100644
index 0000000..54a2ec9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SPIData.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "NotifyListener.h"
+#include "hal/Types.h"
+
+typedef void (*HAL_SpiReadAutoReceiveBufferCallback)(const char* name,
+                                                     void* param,
+                                                     uint32_t* buffer,
+                                                     int32_t numToRead,
+                                                     int32_t* outputCount);
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+void HALSIM_ResetSPIData(int32_t index);
+
+int32_t HALSIM_RegisterSPIInitializedCallback(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify);
+void HALSIM_CancelSPIInitializedCallback(int32_t index, int32_t uid);
+HAL_Bool HALSIM_GetSPIInitialized(int32_t index);
+void HALSIM_SetSPIInitialized(int32_t index, HAL_Bool initialized);
+
+int32_t HALSIM_RegisterSPIReadCallback(int32_t index,
+                                       HAL_BufferCallback callback,
+                                       void* param);
+void HALSIM_CancelSPIReadCallback(int32_t index, int32_t uid);
+
+int32_t HALSIM_RegisterSPIWriteCallback(int32_t index,
+                                        HAL_ConstBufferCallback callback,
+                                        void* param);
+void HALSIM_CancelSPIWriteCallback(int32_t index, int32_t uid);
+
+int32_t HALSIM_RegisterSPIReadAutoReceivedDataCallback(
+    int32_t index, HAL_SpiReadAutoReceiveBufferCallback callback, void* param);
+void HALSIM_CancelSPIReadAutoReceivedDataCallback(int32_t index, int32_t uid);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SimCallbackRegistry.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SimCallbackRegistry.h
new file mode 100644
index 0000000..da3f0f9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SimCallbackRegistry.h
@@ -0,0 +1,151 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <utility>
+
+#include <wpi/Compiler.h>
+#include <wpi/UidVector.h>
+#include <wpi/spinlock.h>
+
+#include "mockdata/NotifyListener.h"
+
+namespace hal {
+
+namespace impl {
+
+class SimCallbackRegistryBase {
+ public:
+  using RawFunctor = void (*)();
+
+ protected:
+  using CallbackVector = wpi::UidVector<HalCallbackListener<RawFunctor>, 4>;
+
+ public:
+  void Cancel(int32_t uid) {
+    std::lock_guard<wpi::recursive_spinlock> lock(m_mutex);
+    if (m_callbacks) m_callbacks->erase(uid - 1);
+  }
+
+  void Reset() {
+    std::lock_guard<wpi::recursive_spinlock> lock(m_mutex);
+    DoReset();
+  }
+
+  wpi::recursive_spinlock& GetMutex() { return m_mutex; }
+
+ protected:
+  int32_t DoRegister(RawFunctor callback, void* param) {
+    // Must return -1 on a null callback for error handling
+    if (callback == nullptr) return -1;
+    if (!m_callbacks) m_callbacks = std::make_unique<CallbackVector>();
+    return m_callbacks->emplace_back(param, callback) + 1;
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE void DoReset() {
+    if (m_callbacks) m_callbacks->clear();
+  }
+
+  mutable wpi::recursive_spinlock m_mutex;
+  std::unique_ptr<CallbackVector> m_callbacks;
+};
+
+}  // namespace impl
+
+/**
+ * Simulation callback registry.  Provides callback functionality.
+ *
+ * @tparam CallbackFunction callback function type (e.g. HAL_BufferCallback)
+ * @tparam GetName function that returns a const char* for the name
+ */
+template <typename CallbackFunction, const char* (*GetName)()>
+class SimCallbackRegistry : public impl::SimCallbackRegistryBase {
+ public:
+  int32_t Register(CallbackFunction callback, void* param) {
+    std::lock_guard<wpi::recursive_spinlock> lock(m_mutex);
+    return DoRegister(reinterpret_cast<RawFunctor>(callback), param);
+  }
+
+  template <typename... U>
+  void Invoke(U&&... u) const {
+    std::lock_guard<wpi::recursive_spinlock> lock(m_mutex);
+    if (m_callbacks) {
+      const char* name = GetName();
+      for (auto&& cb : *m_callbacks)
+        reinterpret_cast<CallbackFunction>(cb.callback)(name, cb.param,
+                                                        std::forward<U>(u)...);
+    }
+  }
+
+  template <typename... U>
+  LLVM_ATTRIBUTE_ALWAYS_INLINE void operator()(U&&... u) const {
+    return Invoke(std::forward<U>(u)...);
+  }
+};
+
+/**
+ * Define a name functor for use with SimCallbackRegistry.
+ * This creates a function named GetNAMEName() that returns "NAME".
+ * @param NAME the name to return
+ */
+#define HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(NAME)           \
+  static LLVM_ATTRIBUTE_ALWAYS_INLINE constexpr const char* \
+      Get##NAME##Name() {                                   \
+    return #NAME;                                           \
+  }
+
+/**
+ * Define a standard C API for SimCallbackRegistry.
+ *
+ * Functions defined:
+ * - int32 NS_RegisterCAPINAMECallback(
+ *      int32_t index, TYPE callback, void* param)
+ * - void NS_CancelCAPINAMECallback(int32_t index, int32_t uid)
+ *
+ * @param TYPE the underlying callback type (e.g. HAL_BufferCallback)
+ * @param NS the "namespace" (e.g. HALSIM)
+ * @param CAPINAME the C API name (usually first letter capitalized)
+ * @param DATA the backing data array
+ * @param LOWERNAME the lowercase name of the backing data registry
+ */
+#define HAL_SIMCALLBACKREGISTRY_DEFINE_CAPI(TYPE, NS, CAPINAME, DATA,     \
+                                            LOWERNAME)                    \
+  int32_t NS##_Register##CAPINAME##Callback(int32_t index, TYPE callback, \
+                                            void* param) {                \
+    return DATA[index].LOWERNAME.Register(callback, param);               \
+  }                                                                       \
+                                                                          \
+  void NS##_Cancel##CAPINAME##Callback(int32_t index, int32_t uid) {      \
+    DATA[index].LOWERNAME.Cancel(uid);                                    \
+  }
+
+/**
+ * Define a standard C API for SimCallbackRegistry (no index variant).
+ *
+ * Functions defined:
+ * - int32 NS_RegisterCAPINAMECallback(TYPE callback, void* param)
+ * - void NS_CancelCAPINAMECallback(int32_t uid)
+ *
+ * @param TYPE the underlying callback type (e.g. HAL_BufferCallback)
+ * @param NS the "namespace" (e.g. HALSIM)
+ * @param CAPINAME the C API name (usually first letter capitalized)
+ * @param DATA the backing data pointer
+ * @param LOWERNAME the lowercase name of the backing data registry
+ */
+#define HAL_SIMCALLBACKREGISTRY_DEFINE_CAPI_NOINDEX(TYPE, NS, CAPINAME, DATA, \
+                                                    LOWERNAME)                \
+  int32_t NS##_Register##CAPINAME##Callback(TYPE callback, void* param) {     \
+    return DATA->LOWERNAME.Register(callback, param);                         \
+  }                                                                           \
+                                                                              \
+  void NS##_Cancel##CAPINAME##Callback(int32_t uid) {                         \
+    DATA->LOWERNAME.Cancel(uid);                                              \
+  }
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SimDataValue.h b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SimDataValue.h
new file mode 100644
index 0000000..3b518b9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/mockdata/SimDataValue.h
@@ -0,0 +1,227 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/Compiler.h>
+#include <wpi/UidVector.h>
+#include <wpi/spinlock.h>
+
+#include "mockdata/NotifyListener.h"
+#include "mockdata/SimCallbackRegistry.h"
+
+namespace hal {
+
+namespace impl {
+template <typename T, HAL_Value (*MakeValue)(T)>
+class SimDataValueBase : protected SimCallbackRegistryBase {
+ public:
+  explicit SimDataValueBase(T value) : m_value(value) {}
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE void CancelCallback(int32_t uid) { Cancel(uid); }
+
+  T Get() const {
+    std::lock_guard<wpi::recursive_spinlock> lock(m_mutex);
+    return m_value;
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE operator T() const { return Get(); }
+
+  void Reset(T value) {
+    std::lock_guard<wpi::recursive_spinlock> lock(m_mutex);
+    DoReset();
+    m_value = value;
+  }
+
+  wpi::recursive_spinlock& GetMutex() { return m_mutex; }
+
+ protected:
+  int32_t DoRegisterCallback(HAL_NotifyCallback callback, void* param,
+                             HAL_Bool initialNotify, const char* name) {
+    std::unique_lock<wpi::recursive_spinlock> lock(m_mutex);
+    int32_t newUid = DoRegister(reinterpret_cast<RawFunctor>(callback), param);
+    if (newUid == -1) return -1;
+    if (initialNotify) {
+      // We know that the callback is not null because of earlier null check
+      HAL_Value value = MakeValue(m_value);
+      lock.unlock();
+      callback(name, param, &value);
+    }
+    return newUid + 1;
+  }
+
+  void DoSet(T value, const char* name) {
+    std::lock_guard<wpi::recursive_spinlock> lock(this->m_mutex);
+    if (m_value != value) {
+      m_value = value;
+      if (m_callbacks) {
+        HAL_Value halValue = MakeValue(value);
+        for (auto&& cb : *m_callbacks)
+          reinterpret_cast<HAL_NotifyCallback>(cb.callback)(name, cb.param,
+                                                            &halValue);
+      }
+    }
+  }
+
+  T m_value;
+};
+}  // namespace impl
+
+/**
+ * Simulation data value wrapper.  Provides callback functionality when the
+ * data value is changed.
+ *
+ * @tparam T value type (e.g. double)
+ * @tparam MakeValue function that takes a T and returns a HAL_Value
+ * @tparam GetName function that returns a const char* for the name
+ * @tparam GetDefault function that returns the default T (used only for
+ *                    default constructor)
+ */
+template <typename T, HAL_Value (*MakeValue)(T), const char* (*GetName)(),
+          T (*GetDefault)() = nullptr>
+class SimDataValue final : public impl::SimDataValueBase<T, MakeValue> {
+ public:
+  SimDataValue()
+      : impl::SimDataValueBase<T, MakeValue>(
+            GetDefault != nullptr ? GetDefault() : T()) {}
+  explicit SimDataValue(T value)
+      : impl::SimDataValueBase<T, MakeValue>(value) {}
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE int32_t RegisterCallback(
+      HAL_NotifyCallback callback, void* param, HAL_Bool initialNotify) {
+    return this->DoRegisterCallback(callback, param, initialNotify, GetName());
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE void Set(T value) {
+    this->DoSet(value, GetName());
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE SimDataValue& operator=(T value) {
+    Set(value);
+    return *this;
+  }
+};
+
+/**
+ * Define a name functor for use with SimDataValue.
+ * This creates a function named GetNAMEName() that returns "NAME".
+ * @param NAME the name to return
+ */
+#define HAL_SIMDATAVALUE_DEFINE_NAME(NAME)                  \
+  static LLVM_ATTRIBUTE_ALWAYS_INLINE constexpr const char* \
+      Get##NAME##Name() {                                   \
+    return #NAME;                                           \
+  }
+
+/**
+ * Define a standard C API for simulation data.
+ *
+ * Functions defined:
+ * - int32 NS_RegisterCAPINAMECallback(
+ *      int32_t index, HAL_NotifyCallback callback, void* param,
+ *      HAL_Bool initialNotify)
+ * - void NS_CancelCAPINAMECallback(int32_t index, int32_t uid)
+ * - TYPE NS_GetCAPINAME(int32_t index)
+ * - void NS_SetCAPINAME(int32_t index, TYPE value)
+ *
+ * @param TYPE the underlying value type (e.g. double)
+ * @param NS the "namespace" (e.g. HALSIM)
+ * @param CAPINAME the C API name (usually first letter capitalized)
+ * @param DATA the backing data array
+ * @param LOWERNAME the lowercase name of the backing data variable
+ */
+#define HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, NS, CAPINAME, DATA, LOWERNAME)  \
+  int32_t NS##_Register##CAPINAME##Callback(                               \
+      int32_t index, HAL_NotifyCallback callback, void* param,             \
+      HAL_Bool initialNotify) {                                            \
+    return DATA[index].LOWERNAME.RegisterCallback(callback, param,         \
+                                                  initialNotify);          \
+  }                                                                        \
+                                                                           \
+  void NS##_Cancel##CAPINAME##Callback(int32_t index, int32_t uid) {       \
+    DATA[index].LOWERNAME.CancelCallback(uid);                             \
+  }                                                                        \
+                                                                           \
+  TYPE NS##_Get##CAPINAME(int32_t index) { return DATA[index].LOWERNAME; } \
+                                                                           \
+  void NS##_Set##CAPINAME(int32_t index, TYPE LOWERNAME) {                 \
+    DATA[index].LOWERNAME = LOWERNAME;                                     \
+  }
+
+/**
+ * Define a standard C API for simulation data (channel variant).
+ *
+ * Functions defined:
+ * - int32 NS_RegisterCAPINAMECallback(
+ *      int32_t index, int32_t channel, HAL_NotifyCallback callback,
+ *      void* param, HAL_Bool initialNotify)
+ * - void NS_CancelCAPINAMECallback(int32_t index, int32_t channel, int32_t uid)
+ * - TYPE NS_GetCAPINAME(int32_t index, int32_t channel)
+ * - void NS_SetCAPINAME(int32_t index, int32_t channel, TYPE value)
+ *
+ * @param TYPE the underlying value type (e.g. double)
+ * @param NS the "namespace" (e.g. HALSIM)
+ * @param CAPINAME the C API name (usually first letter capitalized)
+ * @param DATA the backing data array
+ * @param LOWERNAME the lowercase name of the backing data variable array
+ */
+#define HAL_SIMDATAVALUE_DEFINE_CAPI_CHANNEL(TYPE, NS, CAPINAME, DATA,      \
+                                             LOWERNAME)                     \
+  int32_t NS##_Register##CAPINAME##Callback(                                \
+      int32_t index, int32_t channel, HAL_NotifyCallback callback,          \
+      void* param, HAL_Bool initialNotify) {                                \
+    return DATA[index].LOWERNAME[channel].RegisterCallback(callback, param, \
+                                                           initialNotify);  \
+  }                                                                         \
+                                                                            \
+  void NS##_Cancel##CAPINAME##Callback(int32_t index, int32_t channel,      \
+                                       int32_t uid) {                       \
+    DATA[index].LOWERNAME[channel].CancelCallback(uid);                     \
+  }                                                                         \
+                                                                            \
+  TYPE NS##_Get##CAPINAME(int32_t index, int32_t channel) {                 \
+    return DATA[index].LOWERNAME[channel];                                  \
+  }                                                                         \
+                                                                            \
+  void NS##_Set##CAPINAME(int32_t index, int32_t channel, TYPE LOWERNAME) { \
+    DATA[index].LOWERNAME[channel] = LOWERNAME;                             \
+  }
+
+/**
+ * Define a standard C API for simulation data (no index variant).
+ *
+ * Functions defined:
+ * - int32 NS_RegisterCAPINAMECallback(
+ *      HAL_NotifyCallback callback, void* param, HAL_Bool initialNotify)
+ * - void NS_CancelCAPINAMECallback(int32_t uid)
+ * - TYPE NS_GetCAPINAME(void)
+ * - void NS_SetCAPINAME(TYPE value)
+ *
+ * @param TYPE the underlying value type (e.g. double)
+ * @param NS the "namespace" (e.g. HALSIM)
+ * @param CAPINAME the C API name (usually first letter capitalized)
+ * @param DATA the backing data pointer
+ * @param LOWERNAME the lowercase name of the backing data variable
+ */
+#define HAL_SIMDATAVALUE_DEFINE_CAPI_NOINDEX(TYPE, NS, CAPINAME, DATA,       \
+                                             LOWERNAME)                      \
+  int32_t NS##_Register##CAPINAME##Callback(                                 \
+      HAL_NotifyCallback callback, void* param, HAL_Bool initialNotify) {    \
+    return DATA->LOWERNAME.RegisterCallback(callback, param, initialNotify); \
+  }                                                                          \
+                                                                             \
+  void NS##_Cancel##CAPINAME##Callback(int32_t uid) {                        \
+    DATA->LOWERNAME.CancelCallback(uid);                                     \
+  }                                                                          \
+                                                                             \
+  TYPE NS##_Get##CAPINAME(void) { return DATA->LOWERNAME; }                  \
+                                                                             \
+  void NS##_Set##CAPINAME(TYPE LOWERNAME) { DATA->LOWERNAME = LOWERNAME; }
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AccelerometerSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AccelerometerSim.h
new file mode 100644
index 0000000..ea873c7
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AccelerometerSim.h
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/AccelerometerData.h"
+
+namespace frc {
+namespace sim {
+class AccelerometerSim {
+ public:
+  explicit AccelerometerSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterActiveCallback(NotifyCallback callback,
+                                                        bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAccelerometerActiveCallback);
+    store->SetUid(HALSIM_RegisterAccelerometerActiveCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetActive() const { return HALSIM_GetAccelerometerActive(m_index); }
+
+  void SetActive(bool active) {
+    HALSIM_SetAccelerometerActive(m_index, active);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterRangeCallback(NotifyCallback callback,
+                                                       bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAccelerometerRangeCallback);
+    store->SetUid(HALSIM_RegisterAccelerometerRangeCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  HAL_AccelerometerRange GetRange() const {
+    return HALSIM_GetAccelerometerRange(m_index);
+  }
+
+  void SetRange(HAL_AccelerometerRange range) {
+    HALSIM_SetAccelerometerRange(m_index, range);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterXCallback(NotifyCallback callback,
+                                                   bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAccelerometerXCallback);
+    store->SetUid(HALSIM_RegisterAccelerometerXCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetX() const { return HALSIM_GetAccelerometerX(m_index); }
+
+  void SetX(double x) { HALSIM_SetAccelerometerX(m_index, x); }
+
+  std::unique_ptr<CallbackStore> RegisterYCallback(NotifyCallback callback,
+                                                   bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAccelerometerYCallback);
+    store->SetUid(HALSIM_RegisterAccelerometerYCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetY() const { return HALSIM_GetAccelerometerY(m_index); }
+
+  void SetY(double y) { HALSIM_SetAccelerometerY(m_index, y); }
+
+  std::unique_ptr<CallbackStore> RegisterZCallback(NotifyCallback callback,
+                                                   bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAccelerometerZCallback);
+    store->SetUid(HALSIM_RegisterAccelerometerZCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetZ() const { return HALSIM_GetAccelerometerZ(m_index); }
+
+  void SetZ(double z) { HALSIM_SetAccelerometerZ(m_index, z); }
+
+  void ResetData() { HALSIM_ResetAccelerometerData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogGyroSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogGyroSim.h
new file mode 100644
index 0000000..b4c48ca
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogGyroSim.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/AnalogGyroData.h"
+
+namespace frc {
+namespace sim {
+class AnalogGyroSim {
+ public:
+  explicit AnalogGyroSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterAngleCallback(NotifyCallback callback,
+                                                       bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogGyroAngleCallback);
+    store->SetUid(HALSIM_RegisterAnalogGyroAngleCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetAngle() const { return HALSIM_GetAnalogGyroAngle(m_index); }
+
+  void SetAngle(double angle) { HALSIM_SetAnalogGyroAngle(m_index, angle); }
+
+  std::unique_ptr<CallbackStore> RegisterRateCallback(NotifyCallback callback,
+                                                      bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogGyroRateCallback);
+    store->SetUid(HALSIM_RegisterAnalogGyroRateCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetRate() const { return HALSIM_GetAnalogGyroRate(m_index); }
+
+  void SetRate(double rate) { HALSIM_SetAnalogGyroRate(m_index, rate); }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogGyroInitializedCallback);
+    store->SetUid(HALSIM_RegisterAnalogGyroInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const {
+    return HALSIM_GetAnalogGyroInitialized(m_index);
+  }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetAnalogGyroInitialized(m_index, initialized);
+  }
+
+  void ResetData() { HALSIM_ResetAnalogGyroData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogInSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogInSim.h
new file mode 100644
index 0000000..a513c33
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogInSim.h
@@ -0,0 +1,180 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/AnalogInData.h"
+
+namespace frc {
+namespace sim {
+class AnalogInSim {
+ public:
+  explicit AnalogInSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogInInitializedCallback);
+    store->SetUid(HALSIM_RegisterAnalogInInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const { return HALSIM_GetAnalogInInitialized(m_index); }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetAnalogInInitialized(m_index, initialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterAverageBitsCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogInAverageBitsCallback);
+    store->SetUid(HALSIM_RegisterAnalogInAverageBitsCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetAverageBits() const { return HALSIM_GetAnalogInAverageBits(m_index); }
+
+  void SetAverageBits(int averageBits) {
+    HALSIM_SetAnalogInAverageBits(m_index, averageBits);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterOversampleBitsCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogInOversampleBitsCallback);
+    store->SetUid(HALSIM_RegisterAnalogInOversampleBitsCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetOversampleBits() const {
+    return HALSIM_GetAnalogInOversampleBits(m_index);
+  }
+
+  void SetOversampleBits(int oversampleBits) {
+    HALSIM_SetAnalogInOversampleBits(m_index, oversampleBits);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterVoltageCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogInVoltageCallback);
+    store->SetUid(HALSIM_RegisterAnalogInVoltageCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetVoltage() const { return HALSIM_GetAnalogInVoltage(m_index); }
+
+  void SetVoltage(double voltage) {
+    HALSIM_SetAnalogInVoltage(m_index, voltage);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterAccumulatorInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback,
+        &HALSIM_CancelAnalogInAccumulatorInitializedCallback);
+    store->SetUid(HALSIM_RegisterAnalogInAccumulatorInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetAccumulatorInitialized() const {
+    return HALSIM_GetAnalogInAccumulatorInitialized(m_index);
+  }
+
+  void SetAccumulatorInitialized(bool accumulatorInitialized) {
+    HALSIM_SetAnalogInAccumulatorInitialized(m_index, accumulatorInitialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterAccumulatorValueCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogInAccumulatorValueCallback);
+    store->SetUid(HALSIM_RegisterAnalogInAccumulatorValueCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int64_t GetAccumulatorValue() const {
+    return HALSIM_GetAnalogInAccumulatorValue(m_index);
+  }
+
+  void SetAccumulatorValue(int64_t accumulatorValue) {
+    HALSIM_SetAnalogInAccumulatorValue(m_index, accumulatorValue);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterAccumulatorCountCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogInAccumulatorCountCallback);
+    store->SetUid(HALSIM_RegisterAnalogInAccumulatorCountCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int64_t GetAccumulatorCount() const {
+    return HALSIM_GetAnalogInAccumulatorCount(m_index);
+  }
+
+  void SetAccumulatorCount(int64_t accumulatorCount) {
+    HALSIM_SetAnalogInAccumulatorCount(m_index, accumulatorCount);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterAccumulatorCenterCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogInAccumulatorCenterCallback);
+    store->SetUid(HALSIM_RegisterAnalogInAccumulatorCenterCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetAccumulatorCenter() const {
+    return HALSIM_GetAnalogInAccumulatorCenter(m_index);
+  }
+
+  void SetAccumulatorCenter(int accumulatorCenter) {
+    HALSIM_SetAnalogInAccumulatorCenter(m_index, accumulatorCenter);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterAccumulatorDeadbandCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback,
+        &HALSIM_CancelAnalogInAccumulatorDeadbandCallback);
+    store->SetUid(HALSIM_RegisterAnalogInAccumulatorDeadbandCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetAccumulatorDeadband() const {
+    return HALSIM_GetAnalogInAccumulatorDeadband(m_index);
+  }
+
+  void SetAccumulatorDeadband(int accumulatorDeadband) {
+    HALSIM_SetAnalogInAccumulatorDeadband(m_index, accumulatorDeadband);
+  }
+
+  void ResetData() { HALSIM_ResetAnalogInData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogOutSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogOutSim.h
new file mode 100644
index 0000000..3617a66
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogOutSim.h
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/AnalogOutData.h"
+
+namespace frc {
+namespace sim {
+class AnalogOutSim {
+ public:
+  explicit AnalogOutSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterVoltageCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogOutVoltageCallback);
+    store->SetUid(HALSIM_RegisterAnalogOutVoltageCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetVoltage() const { return HALSIM_GetAnalogOutVoltage(m_index); }
+
+  void SetVoltage(double voltage) {
+    HALSIM_SetAnalogOutVoltage(m_index, voltage);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogOutInitializedCallback);
+    store->SetUid(HALSIM_RegisterAnalogOutInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const {
+    return HALSIM_GetAnalogOutInitialized(m_index);
+  }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetAnalogOutInitialized(m_index, initialized);
+  }
+
+  void ResetData() { HALSIM_ResetAnalogOutData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogTriggerSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogTriggerSim.h
new file mode 100644
index 0000000..04faf05
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/AnalogTriggerSim.h
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/AnalogTriggerData.h"
+
+namespace frc {
+namespace sim {
+class AnalogTriggerSim {
+ public:
+  explicit AnalogTriggerSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelAnalogTriggerInitializedCallback);
+    store->SetUid(HALSIM_RegisterAnalogTriggerInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const {
+    return HALSIM_GetAnalogTriggerInitialized(m_index);
+  }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetAnalogTriggerInitialized(m_index, initialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterTriggerLowerBoundCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback,
+        &HALSIM_CancelAnalogTriggerTriggerLowerBoundCallback);
+    store->SetUid(HALSIM_RegisterAnalogTriggerTriggerLowerBoundCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetTriggerLowerBound() const {
+    return HALSIM_GetAnalogTriggerTriggerLowerBound(m_index);
+  }
+
+  void SetTriggerLowerBound(double triggerLowerBound) {
+    HALSIM_SetAnalogTriggerTriggerLowerBound(m_index, triggerLowerBound);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterTriggerUpperBoundCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback,
+        &HALSIM_CancelAnalogTriggerTriggerUpperBoundCallback);
+    store->SetUid(HALSIM_RegisterAnalogTriggerTriggerUpperBoundCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetTriggerUpperBound() const {
+    return HALSIM_GetAnalogTriggerTriggerUpperBound(m_index);
+  }
+
+  void SetTriggerUpperBound(double triggerUpperBound) {
+    HALSIM_SetAnalogTriggerTriggerUpperBound(m_index, triggerUpperBound);
+  }
+
+  void ResetData() { HALSIM_ResetAnalogTriggerData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/CallbackStore.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/CallbackStore.h
new file mode 100644
index 0000000..967e963
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/CallbackStore.h
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <functional>
+
+#include <wpi/StringRef.h>
+
+#include "mockdata/HAL_Value.h"
+
+namespace frc {
+namespace sim {
+
+using NotifyCallback = std::function<void(wpi::StringRef, const HAL_Value*)>;
+typedef void (*CancelCallbackFunc)(int32_t index, int32_t uid);
+typedef void (*CancelCallbackNoIndexFunc)(int32_t uid);
+typedef void (*CancelCallbackChannelFunc)(int32_t index, int32_t channel,
+                                          int32_t uid);
+
+void CallbackStoreThunk(const char* name, void* param, const HAL_Value* value);
+
+class CallbackStore {
+ public:
+  CallbackStore(int32_t i, NotifyCallback cb, CancelCallbackNoIndexFunc ccf) {
+    index = i;
+    callback = cb;
+    this->ccnif = ccf;
+    cancelType = NoIndex;
+  }
+
+  CallbackStore(int32_t i, int32_t u, NotifyCallback cb,
+                CancelCallbackFunc ccf) {
+    index = i;
+    uid = u;
+    callback = cb;
+    this->ccf = ccf;
+    cancelType = Normal;
+  }
+
+  CallbackStore(int32_t i, int32_t c, int32_t u, NotifyCallback cb,
+                CancelCallbackChannelFunc ccf) {
+    index = i;
+    channel = c;
+    uid = u;
+    callback = cb;
+    this->cccf = ccf;
+    cancelType = Channel;
+  }
+
+  ~CallbackStore() {
+    switch (cancelType) {
+      case Normal:
+        ccf(index, uid);
+        break;
+      case Channel:
+        cccf(index, channel, uid);
+        break;
+      case NoIndex:
+        ccnif(uid);
+        break;
+    }
+  }
+
+  void SetUid(int32_t uid) { this->uid = uid; }
+
+  friend void CallbackStoreThunk(const char* name, void* param,
+                                 const HAL_Value* value);
+
+ private:
+  int32_t index;
+  int32_t channel;
+  int32_t uid;
+
+  NotifyCallback callback;
+  union {
+    CancelCallbackFunc ccf;
+    CancelCallbackChannelFunc cccf;
+    CancelCallbackNoIndexFunc ccnif;
+  };
+  enum CancelType { Normal, Channel, NoIndex };
+  CancelType cancelType;
+};
+}  // namespace sim
+}  // namespace frc
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DIOSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DIOSim.h
new file mode 100644
index 0000000..b4fe947
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DIOSim.h
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/DIOData.h"
+
+namespace frc {
+namespace sim {
+class DIOSim {
+ public:
+  explicit DIOSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDIOInitializedCallback);
+    store->SetUid(HALSIM_RegisterDIOInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const { return HALSIM_GetDIOInitialized(m_index); }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetDIOInitialized(m_index, initialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterValueCallback(NotifyCallback callback,
+                                                       bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDIOValueCallback);
+    store->SetUid(HALSIM_RegisterDIOValueCallback(m_index, &CallbackStoreThunk,
+                                                  store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetValue() const { return HALSIM_GetDIOValue(m_index); }
+
+  void SetValue(bool value) { HALSIM_SetDIOValue(m_index, value); }
+
+  std::unique_ptr<CallbackStore> RegisterPulseLengthCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDIOPulseLengthCallback);
+    store->SetUid(HALSIM_RegisterDIOPulseLengthCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetPulseLength() const { return HALSIM_GetDIOPulseLength(m_index); }
+
+  void SetPulseLength(double pulseLength) {
+    HALSIM_SetDIOPulseLength(m_index, pulseLength);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterIsInputCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDIOIsInputCallback);
+    store->SetUid(HALSIM_RegisterDIOIsInputCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetIsInput() const { return HALSIM_GetDIOIsInput(m_index); }
+
+  void SetIsInput(bool isInput) { HALSIM_SetDIOIsInput(m_index, isInput); }
+
+  std::unique_ptr<CallbackStore> RegisterFilterIndexCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDIOFilterIndexCallback);
+    store->SetUid(HALSIM_RegisterDIOFilterIndexCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetFilterIndex() const { return HALSIM_GetDIOFilterIndex(m_index); }
+
+  void SetFilterIndex(int filterIndex) {
+    HALSIM_SetDIOFilterIndex(m_index, filterIndex);
+  }
+
+  void ResetData() { HALSIM_ResetDIOData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DigitalPWMSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DigitalPWMSim.h
new file mode 100644
index 0000000..ecfc56d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DigitalPWMSim.h
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/DigitalPWMData.h"
+
+namespace frc {
+namespace sim {
+class DigitalPWMSim {
+ public:
+  explicit DigitalPWMSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDigitalPWMInitializedCallback);
+    store->SetUid(HALSIM_RegisterDigitalPWMInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const {
+    return HALSIM_GetDigitalPWMInitialized(m_index);
+  }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetDigitalPWMInitialized(m_index, initialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterDutyCycleCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDigitalPWMDutyCycleCallback);
+    store->SetUid(HALSIM_RegisterDigitalPWMDutyCycleCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetDutyCycle() const { return HALSIM_GetDigitalPWMDutyCycle(m_index); }
+
+  void SetDutyCycle(double dutyCycle) {
+    HALSIM_SetDigitalPWMDutyCycle(m_index, dutyCycle);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterPinCallback(NotifyCallback callback,
+                                                     bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelDigitalPWMPinCallback);
+    store->SetUid(HALSIM_RegisterDigitalPWMPinCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetPin() const { return HALSIM_GetDigitalPWMPin(m_index); }
+
+  void SetPin(int pin) { HALSIM_SetDigitalPWMPin(m_index, pin); }
+
+  void ResetData() { HALSIM_ResetDigitalPWMData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DriverStationSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DriverStationSim.h
new file mode 100644
index 0000000..55c38a9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/DriverStationSim.h
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/DriverStationData.h"
+
+namespace frc {
+namespace sim {
+class DriverStationSim {
+ public:
+  std::unique_ptr<CallbackStore> RegisterEnabledCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        -1, callback, &HALSIM_CancelDriverStationEnabledCallback);
+    store->SetUid(HALSIM_RegisterDriverStationEnabledCallback(
+        &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetEnabled() const { return HALSIM_GetDriverStationEnabled(); }
+
+  void SetEnabled(bool enabled) { HALSIM_SetDriverStationEnabled(enabled); }
+
+  std::unique_ptr<CallbackStore> RegisterAutonomousCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        -1, callback, &HALSIM_CancelDriverStationAutonomousCallback);
+    store->SetUid(HALSIM_RegisterDriverStationAutonomousCallback(
+        &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetAutonomous() const { return HALSIM_GetDriverStationAutonomous(); }
+
+  void SetAutonomous(bool autonomous) {
+    HALSIM_SetDriverStationAutonomous(autonomous);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterTestCallback(NotifyCallback callback,
+                                                      bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        -1, callback, &HALSIM_CancelDriverStationTestCallback);
+    store->SetUid(HALSIM_RegisterDriverStationTestCallback(
+        &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetTest() const { return HALSIM_GetDriverStationTest(); }
+
+  void SetTest(bool test) { HALSIM_SetDriverStationTest(test); }
+
+  std::unique_ptr<CallbackStore> RegisterEStopCallback(NotifyCallback callback,
+                                                       bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        -1, callback, &HALSIM_CancelDriverStationEStopCallback);
+    store->SetUid(HALSIM_RegisterDriverStationEStopCallback(
+        &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetEStop() const { return HALSIM_GetDriverStationEStop(); }
+
+  void SetEStop(bool eStop) { HALSIM_SetDriverStationEStop(eStop); }
+
+  std::unique_ptr<CallbackStore> RegisterFmsAttachedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        -1, callback, &HALSIM_CancelDriverStationFmsAttachedCallback);
+    store->SetUid(HALSIM_RegisterDriverStationFmsAttachedCallback(
+        &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetFmsAttached() const { return HALSIM_GetDriverStationFmsAttached(); }
+
+  void SetFmsAttached(bool fmsAttached) {
+    HALSIM_SetDriverStationFmsAttached(fmsAttached);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterDsAttachedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        -1, callback, &HALSIM_CancelDriverStationDsAttachedCallback);
+    store->SetUid(HALSIM_RegisterDriverStationDsAttachedCallback(
+        &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetDsAttached() const { return HALSIM_GetDriverStationDsAttached(); }
+
+  void SetDsAttached(bool dsAttached) {
+    HALSIM_SetDriverStationDsAttached(dsAttached);
+  }
+
+  void NotifyNewData() { HALSIM_NotifyDriverStationNewData(); }
+
+  void ResetData() { HALSIM_ResetDriverStationData(); }
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/EncoderSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/EncoderSim.h
new file mode 100644
index 0000000..493f338
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/EncoderSim.h
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/EncoderData.h"
+
+namespace frc {
+namespace sim {
+class EncoderSim {
+ public:
+  explicit EncoderSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderInitializedCallback);
+    store->SetUid(HALSIM_RegisterEncoderInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const { return HALSIM_GetEncoderInitialized(m_index); }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetEncoderInitialized(m_index, initialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterCountCallback(NotifyCallback callback,
+                                                       bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderCountCallback);
+    store->SetUid(HALSIM_RegisterEncoderCountCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetCount() const { return HALSIM_GetEncoderCount(m_index); }
+
+  void SetCount(int count) { HALSIM_SetEncoderCount(m_index, count); }
+
+  std::unique_ptr<CallbackStore> RegisterPeriodCallback(NotifyCallback callback,
+                                                        bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderPeriodCallback);
+    store->SetUid(HALSIM_RegisterEncoderPeriodCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetPeriod() const { return HALSIM_GetEncoderPeriod(m_index); }
+
+  void SetPeriod(double period) { HALSIM_SetEncoderPeriod(m_index, period); }
+
+  std::unique_ptr<CallbackStore> RegisterResetCallback(NotifyCallback callback,
+                                                       bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderResetCallback);
+    store->SetUid(HALSIM_RegisterEncoderResetCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetReset() const { return HALSIM_GetEncoderReset(m_index); }
+
+  void SetReset(bool reset) { HALSIM_SetEncoderReset(m_index, reset); }
+
+  std::unique_ptr<CallbackStore> RegisterMaxPeriodCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderMaxPeriodCallback);
+    store->SetUid(HALSIM_RegisterEncoderMaxPeriodCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetMaxPeriod() const { return HALSIM_GetEncoderMaxPeriod(m_index); }
+
+  void SetMaxPeriod(double maxPeriod) {
+    HALSIM_SetEncoderMaxPeriod(m_index, maxPeriod);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterDirectionCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderDirectionCallback);
+    store->SetUid(HALSIM_RegisterEncoderDirectionCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetDirection() const { return HALSIM_GetEncoderDirection(m_index); }
+
+  void SetDirection(bool direction) {
+    HALSIM_SetEncoderDirection(m_index, direction);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterReverseDirectionCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderReverseDirectionCallback);
+    store->SetUid(HALSIM_RegisterEncoderReverseDirectionCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetReverseDirection() const {
+    return HALSIM_GetEncoderReverseDirection(m_index);
+  }
+
+  void SetReverseDirection(bool reverseDirection) {
+    HALSIM_SetEncoderReverseDirection(m_index, reverseDirection);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterSamplesToAverageCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderSamplesToAverageCallback);
+    store->SetUid(HALSIM_RegisterEncoderSamplesToAverageCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetSamplesToAverage() const {
+    return HALSIM_GetEncoderSamplesToAverage(m_index);
+  }
+
+  void SetSamplesToAverage(int samplesToAverage) {
+    HALSIM_SetEncoderSamplesToAverage(m_index, samplesToAverage);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterDistancePerPulseCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelEncoderDistancePerPulseCallback);
+    store->SetUid(HALSIM_RegisterEncoderDistancePerPulseCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetDistancePerPulse() const {
+    return HALSIM_GetEncoderDistancePerPulse(m_index);
+  }
+
+  void SetDistancePerPulse(double distancePerPulse) {
+    HALSIM_SetEncoderDistancePerPulse(m_index, distancePerPulse);
+  }
+
+  void ResetData() { HALSIM_ResetEncoderData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PCMSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PCMSim.h
new file mode 100644
index 0000000..bfefa6e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PCMSim.h
@@ -0,0 +1,150 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/PCMData.h"
+
+namespace frc {
+namespace sim {
+class PCMSim {
+ public:
+  explicit PCMSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterSolenoidInitializedCallback(
+      int channel, NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, channel, -1, callback,
+        &HALSIM_CancelPCMSolenoidInitializedCallback);
+    store->SetUid(HALSIM_RegisterPCMSolenoidInitializedCallback(
+        m_index, channel, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetSolenoidInitialized(int channel) const {
+    return HALSIM_GetPCMSolenoidInitialized(m_index, channel);
+  }
+
+  void SetSolenoidInitialized(int channel, bool solenoidInitialized) {
+    HALSIM_SetPCMSolenoidInitialized(m_index, channel, solenoidInitialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterSolenoidOutputCallback(
+      int channel, NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, channel, -1, callback,
+        &HALSIM_CancelPCMSolenoidOutputCallback);
+    store->SetUid(HALSIM_RegisterPCMSolenoidOutputCallback(
+        m_index, channel, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetSolenoidOutput(int channel) const {
+    return HALSIM_GetPCMSolenoidOutput(m_index, channel);
+  }
+
+  void SetSolenoidOutput(int channel, bool solenoidOutput) {
+    HALSIM_SetPCMSolenoidOutput(m_index, channel, solenoidOutput);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterCompressorInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPCMCompressorInitializedCallback);
+    store->SetUid(HALSIM_RegisterPCMCompressorInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetCompressorInitialized() const {
+    return HALSIM_GetPCMCompressorInitialized(m_index);
+  }
+
+  void SetCompressorInitialized(bool compressorInitialized) {
+    HALSIM_SetPCMCompressorInitialized(m_index, compressorInitialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterCompressorOnCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPCMCompressorOnCallback);
+    store->SetUid(HALSIM_RegisterPCMCompressorOnCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetCompressorOn() const { return HALSIM_GetPCMCompressorOn(m_index); }
+
+  void SetCompressorOn(bool compressorOn) {
+    HALSIM_SetPCMCompressorOn(m_index, compressorOn);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterClosedLoopEnabledCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPCMClosedLoopEnabledCallback);
+    store->SetUid(HALSIM_RegisterPCMClosedLoopEnabledCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetClosedLoopEnabled() const {
+    return HALSIM_GetPCMClosedLoopEnabled(m_index);
+  }
+
+  void SetClosedLoopEnabled(bool closedLoopEnabled) {
+    HALSIM_SetPCMClosedLoopEnabled(m_index, closedLoopEnabled);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterPressureSwitchCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPCMPressureSwitchCallback);
+    store->SetUid(HALSIM_RegisterPCMPressureSwitchCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetPressureSwitch() const {
+    return HALSIM_GetPCMPressureSwitch(m_index);
+  }
+
+  void SetPressureSwitch(bool pressureSwitch) {
+    HALSIM_SetPCMPressureSwitch(m_index, pressureSwitch);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterCompressorCurrentCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPCMCompressorCurrentCallback);
+    store->SetUid(HALSIM_RegisterPCMCompressorCurrentCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetCompressorCurrent() const {
+    return HALSIM_GetPCMCompressorCurrent(m_index);
+  }
+
+  void SetCompressorCurrent(double compressorCurrent) {
+    HALSIM_SetPCMCompressorCurrent(m_index, compressorCurrent);
+  }
+
+  void ResetData() { HALSIM_ResetPCMData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PDPSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PDPSim.h
new file mode 100644
index 0000000..7677ec2
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PDPSim.h
@@ -0,0 +1,91 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/PDPData.h"
+
+namespace frc {
+namespace sim {
+class PDPSim {
+ public:
+  explicit PDPSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPDPInitializedCallback);
+    store->SetUid(HALSIM_RegisterPDPInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const { return HALSIM_GetPDPInitialized(m_index); }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetPDPInitialized(m_index, initialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterTemperatureCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPDPTemperatureCallback);
+    store->SetUid(HALSIM_RegisterPDPTemperatureCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetTemperature() const { return HALSIM_GetPDPTemperature(m_index); }
+
+  void SetTemperature(double temperature) {
+    HALSIM_SetPDPTemperature(m_index, temperature);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterVoltageCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPDPVoltageCallback);
+    store->SetUid(HALSIM_RegisterPDPVoltageCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetVoltage() const { return HALSIM_GetPDPVoltage(m_index); }
+
+  void SetVoltage(double voltage) { HALSIM_SetPDPVoltage(m_index, voltage); }
+
+  std::unique_ptr<CallbackStore> RegisterCurrentCallback(
+      int channel, NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, channel, -1, callback, &HALSIM_CancelPDPCurrentCallback);
+    store->SetUid(HALSIM_RegisterPDPCurrentCallback(
+        m_index, channel, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetCurrent(int channel) const {
+    return HALSIM_GetPDPCurrent(m_index, channel);
+  }
+
+  void SetCurrent(int channel, double current) {
+    HALSIM_SetPDPCurrent(m_index, channel, current);
+  }
+
+  void ResetData() { HALSIM_ResetPDPData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PWMSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PWMSim.h
new file mode 100644
index 0000000..b90b76f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/PWMSim.h
@@ -0,0 +1,117 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/PWMData.h"
+
+namespace frc {
+namespace sim {
+class PWMSim {
+ public:
+  explicit PWMSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPWMInitializedCallback);
+    store->SetUid(HALSIM_RegisterPWMInitializedCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitialized() const { return HALSIM_GetPWMInitialized(m_index); }
+
+  void SetInitialized(bool initialized) {
+    HALSIM_SetPWMInitialized(m_index, initialized);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterRawValueCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPWMRawValueCallback);
+    store->SetUid(HALSIM_RegisterPWMRawValueCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetRawValue() const { return HALSIM_GetPWMRawValue(m_index); }
+
+  void SetRawValue(int rawValue) { HALSIM_SetPWMRawValue(m_index, rawValue); }
+
+  std::unique_ptr<CallbackStore> RegisterSpeedCallback(NotifyCallback callback,
+                                                       bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPWMSpeedCallback);
+    store->SetUid(HALSIM_RegisterPWMSpeedCallback(m_index, &CallbackStoreThunk,
+                                                  store.get(), initialNotify));
+    return store;
+  }
+
+  double GetSpeed() const { return HALSIM_GetPWMSpeed(m_index); }
+
+  void SetSpeed(double speed) { HALSIM_SetPWMSpeed(m_index, speed); }
+
+  std::unique_ptr<CallbackStore> RegisterPositionCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPWMPositionCallback);
+    store->SetUid(HALSIM_RegisterPWMPositionCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetPosition() const { return HALSIM_GetPWMPosition(m_index); }
+
+  void SetPosition(double position) {
+    HALSIM_SetPWMPosition(m_index, position);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterPeriodScaleCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPWMPeriodScaleCallback);
+    store->SetUid(HALSIM_RegisterPWMPeriodScaleCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetPeriodScale() const { return HALSIM_GetPWMPeriodScale(m_index); }
+
+  void SetPeriodScale(int periodScale) {
+    HALSIM_SetPWMPeriodScale(m_index, periodScale);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterZeroLatchCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelPWMZeroLatchCallback);
+    store->SetUid(HALSIM_RegisterPWMZeroLatchCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetZeroLatch() const { return HALSIM_GetPWMZeroLatch(m_index); }
+
+  void SetZeroLatch(bool zeroLatch) {
+    HALSIM_SetPWMZeroLatch(m_index, zeroLatch);
+  }
+
+  void ResetData() { HALSIM_ResetPWMData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/RelaySim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/RelaySim.h
new file mode 100644
index 0000000..b21a047
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/RelaySim.h
@@ -0,0 +1,91 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/RelayData.h"
+
+namespace frc {
+namespace sim {
+class RelaySim {
+ public:
+  explicit RelaySim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedForwardCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRelayInitializedForwardCallback);
+    store->SetUid(HALSIM_RegisterRelayInitializedForwardCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitializedForward() const {
+    return HALSIM_GetRelayInitializedForward(m_index);
+  }
+
+  void SetInitializedForward(bool initializedForward) {
+    HALSIM_SetRelayInitializedForward(m_index, initializedForward);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterInitializedReverseCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRelayInitializedReverseCallback);
+    store->SetUid(HALSIM_RegisterRelayInitializedReverseCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetInitializedReverse() const {
+    return HALSIM_GetRelayInitializedReverse(m_index);
+  }
+
+  void SetInitializedReverse(bool initializedReverse) {
+    HALSIM_SetRelayInitializedReverse(m_index, initializedReverse);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterForwardCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRelayForwardCallback);
+    store->SetUid(HALSIM_RegisterRelayForwardCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetForward() const { return HALSIM_GetRelayForward(m_index); }
+
+  void SetForward(bool forward) { HALSIM_SetRelayForward(m_index, forward); }
+
+  std::unique_ptr<CallbackStore> RegisterReverseCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRelayReverseCallback);
+    store->SetUid(HALSIM_RegisterRelayReverseCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetReverse() const { return HALSIM_GetRelayReverse(m_index); }
+
+  void SetReverse(bool reverse) { HALSIM_SetRelayReverse(m_index, reverse); }
+
+  void ResetData() { HALSIM_ResetRelayData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/RoboRioSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/RoboRioSim.h
new file mode 100644
index 0000000..0d7c31c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/RoboRioSim.h
@@ -0,0 +1,276 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/RoboRioData.h"
+
+namespace frc {
+namespace sim {
+class RoboRioSim {
+ public:
+  explicit RoboRioSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterFPGAButtonCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioFPGAButtonCallback);
+    store->SetUid(HALSIM_RegisterRoboRioFPGAButtonCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetFPGAButton() const { return HALSIM_GetRoboRioFPGAButton(m_index); }
+
+  void SetFPGAButton(bool fPGAButton) {
+    HALSIM_SetRoboRioFPGAButton(m_index, fPGAButton);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterVInVoltageCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioVInVoltageCallback);
+    store->SetUid(HALSIM_RegisterRoboRioVInVoltageCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetVInVoltage() const { return HALSIM_GetRoboRioVInVoltage(m_index); }
+
+  void SetVInVoltage(double vInVoltage) {
+    HALSIM_SetRoboRioVInVoltage(m_index, vInVoltage);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterVInCurrentCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioVInCurrentCallback);
+    store->SetUid(HALSIM_RegisterRoboRioVInCurrentCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetVInCurrent() const { return HALSIM_GetRoboRioVInCurrent(m_index); }
+
+  void SetVInCurrent(double vInCurrent) {
+    HALSIM_SetRoboRioVInCurrent(m_index, vInCurrent);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserVoltage6VCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserVoltage6VCallback);
+    store->SetUid(HALSIM_RegisterRoboRioUserVoltage6VCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetUserVoltage6V() const {
+    return HALSIM_GetRoboRioUserVoltage6V(m_index);
+  }
+
+  void SetUserVoltage6V(double userVoltage6V) {
+    HALSIM_SetRoboRioUserVoltage6V(m_index, userVoltage6V);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserCurrent6VCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserCurrent6VCallback);
+    store->SetUid(HALSIM_RegisterRoboRioUserCurrent6VCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetUserCurrent6V() const {
+    return HALSIM_GetRoboRioUserCurrent6V(m_index);
+  }
+
+  void SetUserCurrent6V(double userCurrent6V) {
+    HALSIM_SetRoboRioUserCurrent6V(m_index, userCurrent6V);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserActive6VCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserActive6VCallback);
+    store->SetUid(HALSIM_RegisterRoboRioUserActive6VCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetUserActive6V() const {
+    return HALSIM_GetRoboRioUserActive6V(m_index);
+  }
+
+  void SetUserActive6V(bool userActive6V) {
+    HALSIM_SetRoboRioUserActive6V(m_index, userActive6V);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserVoltage5VCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserVoltage5VCallback);
+    store->SetUid(HALSIM_RegisterRoboRioUserVoltage5VCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetUserVoltage5V() const {
+    return HALSIM_GetRoboRioUserVoltage5V(m_index);
+  }
+
+  void SetUserVoltage5V(double userVoltage5V) {
+    HALSIM_SetRoboRioUserVoltage5V(m_index, userVoltage5V);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserCurrent5VCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserCurrent5VCallback);
+    store->SetUid(HALSIM_RegisterRoboRioUserCurrent5VCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetUserCurrent5V() const {
+    return HALSIM_GetRoboRioUserCurrent5V(m_index);
+  }
+
+  void SetUserCurrent5V(double userCurrent5V) {
+    HALSIM_SetRoboRioUserCurrent5V(m_index, userCurrent5V);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserActive5VCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserActive5VCallback);
+    store->SetUid(HALSIM_RegisterRoboRioUserActive5VCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetUserActive5V() const {
+    return HALSIM_GetRoboRioUserActive5V(m_index);
+  }
+
+  void SetUserActive5V(bool userActive5V) {
+    HALSIM_SetRoboRioUserActive5V(m_index, userActive5V);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserVoltage3V3Callback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserVoltage3V3Callback);
+    store->SetUid(HALSIM_RegisterRoboRioUserVoltage3V3Callback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetUserVoltage3V3() const {
+    return HALSIM_GetRoboRioUserVoltage3V3(m_index);
+  }
+
+  void SetUserVoltage3V3(double userVoltage3V3) {
+    HALSIM_SetRoboRioUserVoltage3V3(m_index, userVoltage3V3);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserCurrent3V3Callback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserCurrent3V3Callback);
+    store->SetUid(HALSIM_RegisterRoboRioUserCurrent3V3Callback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetUserCurrent3V3() const {
+    return HALSIM_GetRoboRioUserCurrent3V3(m_index);
+  }
+
+  void SetUserCurrent3V3(double userCurrent3V3) {
+    HALSIM_SetRoboRioUserCurrent3V3(m_index, userCurrent3V3);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserActive3V3Callback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserActive3V3Callback);
+    store->SetUid(HALSIM_RegisterRoboRioUserActive3V3Callback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetUserActive3V3() const {
+    return HALSIM_GetRoboRioUserActive3V3(m_index);
+  }
+
+  void SetUserActive3V3(bool userActive3V3) {
+    HALSIM_SetRoboRioUserActive3V3(m_index, userActive3V3);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserFaults6VCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserFaults6VCallback);
+    store->SetUid(HALSIM_RegisterRoboRioUserFaults6VCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetUserFaults6V() const { return HALSIM_GetRoboRioUserFaults6V(m_index); }
+
+  void SetUserFaults6V(int userFaults6V) {
+    HALSIM_SetRoboRioUserFaults6V(m_index, userFaults6V);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserFaults5VCallback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserFaults5VCallback);
+    store->SetUid(HALSIM_RegisterRoboRioUserFaults5VCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetUserFaults5V() const { return HALSIM_GetRoboRioUserFaults5V(m_index); }
+
+  void SetUserFaults5V(int userFaults5V) {
+    HALSIM_SetRoboRioUserFaults5V(m_index, userFaults5V);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterUserFaults3V3Callback(
+      NotifyCallback callback, bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelRoboRioUserFaults3V3Callback);
+    store->SetUid(HALSIM_RegisterRoboRioUserFaults3V3Callback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetUserFaults3V3() const {
+    return HALSIM_GetRoboRioUserFaults3V3(m_index);
+  }
+
+  void SetUserFaults3V3(int userFaults3V3) {
+    HALSIM_SetRoboRioUserFaults3V3(m_index, userFaults3V3);
+  }
+
+  void ResetData() { HALSIM_ResetRoboRioData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/SPIAccelerometerSim.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/SPIAccelerometerSim.h
new file mode 100644
index 0000000..4369938
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/SPIAccelerometerSim.h
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include <memory>
+#include <utility>
+
+#include "CallbackStore.h"
+#include "mockdata/SPIAccelerometerData.h"
+
+namespace frc {
+namespace sim {
+class SPIAccelerometerSim {
+ public:
+  explicit SPIAccelerometerSim(int index) { m_index = index; }
+
+  std::unique_ptr<CallbackStore> RegisterActiveCallback(NotifyCallback callback,
+                                                        bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelSPIAccelerometerActiveCallback);
+    store->SetUid(HALSIM_RegisterSPIAccelerometerActiveCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  bool GetActive() const { return HALSIM_GetSPIAccelerometerActive(m_index); }
+
+  void SetActive(bool active) {
+    HALSIM_SetSPIAccelerometerActive(m_index, active);
+  }
+
+  std::unique_ptr<CallbackStore> RegisterRangeCallback(NotifyCallback callback,
+                                                       bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelSPIAccelerometerRangeCallback);
+    store->SetUid(HALSIM_RegisterSPIAccelerometerRangeCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  int GetRange() const { return HALSIM_GetSPIAccelerometerRange(m_index); }
+
+  void SetRange(int range) { HALSIM_SetSPIAccelerometerRange(m_index, range); }
+
+  std::unique_ptr<CallbackStore> RegisterXCallback(NotifyCallback callback,
+                                                   bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelSPIAccelerometerXCallback);
+    store->SetUid(HALSIM_RegisterSPIAccelerometerXCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetX() const { return HALSIM_GetSPIAccelerometerX(m_index); }
+
+  void SetX(double x) { HALSIM_SetSPIAccelerometerX(m_index, x); }
+
+  std::unique_ptr<CallbackStore> RegisterYCallback(NotifyCallback callback,
+                                                   bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelSPIAccelerometerYCallback);
+    store->SetUid(HALSIM_RegisterSPIAccelerometerYCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetY() const { return HALSIM_GetSPIAccelerometerY(m_index); }
+
+  void SetY(double y) { HALSIM_SetSPIAccelerometerY(m_index, y); }
+
+  std::unique_ptr<CallbackStore> RegisterZCallback(NotifyCallback callback,
+                                                   bool initialNotify) {
+    auto store = std::make_unique<CallbackStore>(
+        m_index, -1, callback, &HALSIM_CancelSPIAccelerometerZCallback);
+    store->SetUid(HALSIM_RegisterSPIAccelerometerZCallback(
+        m_index, &CallbackStoreThunk, store.get(), initialNotify));
+    return store;
+  }
+
+  double GetZ() const { return HALSIM_GetSPIAccelerometerZ(m_index); }
+
+  void SetZ(double z) { HALSIM_SetSPIAccelerometerZ(m_index, z); }
+
+  void ResetData() { HALSIM_ResetSPIAccelerometerData(m_index); }
+
+ private:
+  int m_index;
+};
+}  // namespace sim
+}  // namespace frc
+#endif  // __FRC_ROBORIO__
diff --git a/third_party/allwpilib_2019/hal/src/main/native/include/simulation/SimHooks.h b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/SimHooks.h
new file mode 100644
index 0000000..6f03952
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/include/simulation/SimHooks.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#ifndef __FRC_ROBORIO__
+
+#include "mockdata/MockHooks.h"
+
+namespace frc {
+namespace sim {
+
+void WaitForProgramStart() { HALSIM_WaitForProgramStart(); }
+
+void SetProgramStarted() { HALSIM_SetProgramStarted(); }
+
+bool GetProgramStarted() { return HALSIM_GetProgramStarted(); }
+
+void RestartTiming() { HALSIM_RestartTiming(); }
+
+}  // namespace sim
+}  // namespace frc
+
+#endif
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Accelerometer.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Accelerometer.cpp
new file mode 100644
index 0000000..1435fd5
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Accelerometer.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/Accelerometer.h"
+
+#include "mockdata/AccelerometerDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAccelerometer() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+void HAL_SetAccelerometerActive(HAL_Bool active) {
+  SimAccelerometerData[0].active = active;
+}
+
+void HAL_SetAccelerometerRange(HAL_AccelerometerRange range) {
+  SimAccelerometerData[0].range = range;
+}
+double HAL_GetAccelerometerX(void) { return SimAccelerometerData[0].x; }
+double HAL_GetAccelerometerY(void) { return SimAccelerometerData[0].y; }
+double HAL_GetAccelerometerZ(void) { return SimAccelerometerData[0].z; }
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogAccumulator.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogAccumulator.cpp
new file mode 100644
index 0000000..537aa15
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogAccumulator.cpp
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/AnalogAccumulator.h"
+
+#include "AnalogInternal.h"
+#include "mockdata/AnalogInDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAnalogAccumulator() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_Bool HAL_IsAccumulatorChannel(HAL_AnalogInputHandle analogPortHandle,
+                                  int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  for (int32_t i = 0; i < kNumAccumulators; i++) {
+    if (port->channel == kAccumulatorChannels[i]) return true;
+  }
+  return false;
+}
+void HAL_InitAccumulator(HAL_AnalogInputHandle analogPortHandle,
+                         int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (!HAL_IsAccumulatorChannel(analogPortHandle, status)) {
+    *status = HAL_INVALID_ACCUMULATOR_CHANNEL;
+    return;
+  }
+
+  SimAnalogInData[port->channel].accumulatorInitialized = true;
+}
+void HAL_ResetAccumulator(HAL_AnalogInputHandle analogPortHandle,
+                          int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimAnalogInData[port->channel].accumulatorCenter = 0;
+  SimAnalogInData[port->channel].accumulatorCount = 0;
+  SimAnalogInData[port->channel].accumulatorValue = 0;
+}
+void HAL_SetAccumulatorCenter(HAL_AnalogInputHandle analogPortHandle,
+                              int32_t center, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimAnalogInData[port->channel].accumulatorCenter = center;
+}
+void HAL_SetAccumulatorDeadband(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t deadband, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimAnalogInData[port->channel].accumulatorDeadband = deadband;
+}
+int64_t HAL_GetAccumulatorValue(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimAnalogInData[port->channel].accumulatorValue;
+}
+int64_t HAL_GetAccumulatorCount(HAL_AnalogInputHandle analogPortHandle,
+                                int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimAnalogInData[port->channel].accumulatorCount;
+}
+void HAL_GetAccumulatorOutput(HAL_AnalogInputHandle analogPortHandle,
+                              int64_t* value, int64_t* count, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  *count = SimAnalogInData[port->channel].accumulatorCount;
+  *value = SimAnalogInData[port->channel].accumulatorValue;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogGyro.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogGyro.cpp
new file mode 100644
index 0000000..b7d84d9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogGyro.cpp
@@ -0,0 +1,147 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/AnalogGyro.h"
+
+#include <chrono>
+#include <thread>
+
+#include "AnalogInternal.h"
+#include "HALInitializer.h"
+#include "hal/AnalogAccumulator.h"
+#include "hal/AnalogInput.h"
+#include "hal/handles/IndexedHandleResource.h"
+#include "mockdata/AnalogGyroDataInternal.h"
+
+namespace {
+struct AnalogGyro {
+  HAL_AnalogInputHandle handle;
+  uint8_t index;
+};
+}  // namespace
+
+using namespace hal;
+
+static IndexedHandleResource<HAL_GyroHandle, AnalogGyro, kNumAccumulators,
+                             HAL_HandleEnum::AnalogGyro>* analogGyroHandles;
+
+namespace hal {
+namespace init {
+void InitializeAnalogGyro() {
+  static IndexedHandleResource<HAL_GyroHandle, AnalogGyro, kNumAccumulators,
+                               HAL_HandleEnum::AnalogGyro>
+      agH;
+  analogGyroHandles = &agH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_GyroHandle HAL_InitializeAnalogGyro(HAL_AnalogInputHandle analogHandle,
+                                        int32_t* status) {
+  hal::init::CheckInit();
+  if (!HAL_IsAccumulatorChannel(analogHandle, status)) {
+    if (*status == 0) {
+      *status = HAL_INVALID_ACCUMULATOR_CHANNEL;
+    }
+    return HAL_kInvalidHandle;
+  }
+
+  // handle known to be correct, so no need to type check
+  int16_t channel = getHandleIndex(analogHandle);
+
+  auto handle = analogGyroHandles->Allocate(channel, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  // Initialize port structure
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {  // would only error on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  gyro->handle = analogHandle;
+  gyro->index = channel;
+
+  SimAnalogGyroData[channel].initialized = true;
+
+  return handle;
+}
+
+void HAL_SetupAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
+  // No op
+}
+
+void HAL_FreeAnalogGyro(HAL_GyroHandle handle) {
+  auto gyro = analogGyroHandles->Get(handle);
+  analogGyroHandles->Free(handle);
+  if (gyro == nullptr) return;
+  SimAnalogGyroData[gyro->index].initialized = false;
+}
+
+void HAL_SetAnalogGyroParameters(HAL_GyroHandle handle,
+                                 double voltsPerDegreePerSecond, double offset,
+                                 int32_t center, int32_t* status) {
+  // No op
+}
+
+void HAL_SetAnalogGyroVoltsPerDegreePerSecond(HAL_GyroHandle handle,
+                                              double voltsPerDegreePerSecond,
+                                              int32_t* status) {
+  // No op
+}
+
+void HAL_ResetAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimAnalogGyroData[gyro->index].angle = 0.0;
+}
+
+void HAL_CalibrateAnalogGyro(HAL_GyroHandle handle, int32_t* status) {
+  // Just do a reset
+  HAL_ResetAnalogGyro(handle, status);
+}
+
+void HAL_SetAnalogGyroDeadband(HAL_GyroHandle handle, double volts,
+                               int32_t* status) {
+  // No op
+}
+
+double HAL_GetAnalogGyroAngle(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimAnalogGyroData[gyro->index].angle;
+}
+
+double HAL_GetAnalogGyroRate(HAL_GyroHandle handle, int32_t* status) {
+  auto gyro = analogGyroHandles->Get(handle);
+  if (gyro == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimAnalogGyroData[gyro->index].rate;
+}
+
+double HAL_GetAnalogGyroOffset(HAL_GyroHandle handle, int32_t* status) {
+  return 0.0;
+}
+
+int32_t HAL_GetAnalogGyroCenter(HAL_GyroHandle handle, int32_t* status) {
+  return 0;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInput.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInput.cpp
new file mode 100644
index 0000000..a0f44a7
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInput.cpp
@@ -0,0 +1,179 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/AnalogInput.h"
+
+#include "AnalogInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/AnalogAccumulator.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/AnalogInDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAnalogInput() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_AnalogInputHandle HAL_InitializeAnalogInputPort(HAL_PortHandle portHandle,
+                                                    int32_t* status) {
+  hal::init::CheckInit();
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  HAL_AnalogInputHandle handle = analogInputHandles->Allocate(channel, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  // Initialize port structure
+  auto analog_port = analogInputHandles->Get(handle);
+  if (analog_port == nullptr) {  // would only error on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  analog_port->channel = static_cast<uint8_t>(channel);
+  if (HAL_IsAccumulatorChannel(handle, status)) {
+    analog_port->isAccumulator = true;
+  } else {
+    analog_port->isAccumulator = false;
+  }
+
+  SimAnalogInData[channel].initialized = true;
+  SimAnalogInData[channel].accumulatorInitialized = false;
+
+  return handle;
+}
+void HAL_FreeAnalogInputPort(HAL_AnalogInputHandle analogPortHandle) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  // no status, so no need to check for a proper free.
+  analogInputHandles->Free(analogPortHandle);
+  if (port == nullptr) return;
+  SimAnalogInData[port->channel].initialized = false;
+  SimAnalogInData[port->channel].accumulatorInitialized = false;
+}
+
+HAL_Bool HAL_CheckAnalogModule(int32_t module) { return module == 1; }
+
+HAL_Bool HAL_CheckAnalogInputChannel(int32_t channel) {
+  return channel < kNumAnalogInputs && channel >= 0;
+}
+
+void HAL_SetAnalogSampleRate(double samplesPerSecond, int32_t* status) {
+  // No op
+}
+double HAL_GetAnalogSampleRate(int32_t* status) { return kDefaultSampleRate; }
+void HAL_SetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
+                              int32_t bits, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimAnalogInData[port->channel].averageBits = bits;
+}
+int32_t HAL_GetAnalogAverageBits(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimAnalogInData[port->channel].averageBits;
+}
+void HAL_SetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
+                                 int32_t bits, int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimAnalogInData[port->channel].oversampleBits = bits;
+}
+int32_t HAL_GetAnalogOversampleBits(HAL_AnalogInputHandle analogPortHandle,
+                                    int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimAnalogInData[port->channel].oversampleBits;
+}
+int32_t HAL_GetAnalogValue(HAL_AnalogInputHandle analogPortHandle,
+                           int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  double voltage = SimAnalogInData[port->channel].voltage;
+  return HAL_GetAnalogVoltsToValue(analogPortHandle, voltage, status);
+}
+int32_t HAL_GetAnalogAverageValue(HAL_AnalogInputHandle analogPortHandle,
+                                  int32_t* status) {
+  // No averaging supported
+  return HAL_GetAnalogValue(analogPortHandle, status);
+}
+int32_t HAL_GetAnalogVoltsToValue(HAL_AnalogInputHandle analogPortHandle,
+                                  double voltage, int32_t* status) {
+  if (voltage > 5.0) {
+    voltage = 5.0;
+    *status = VOLTAGE_OUT_OF_RANGE;
+  }
+  if (voltage < 0.0) {
+    voltage = 0.0;
+    *status = VOLTAGE_OUT_OF_RANGE;
+  }
+  int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogPortHandle, status);
+  int32_t offset = HAL_GetAnalogOffset(analogPortHandle, status);
+  int32_t value =
+      static_cast<int32_t>((voltage + offset * 1.0e-9) / (LSBWeight * 1.0e-9));
+  return value;
+}
+double HAL_GetAnalogVoltage(HAL_AnalogInputHandle analogPortHandle,
+                            int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+
+  return SimAnalogInData[port->channel].voltage;
+}
+double HAL_GetAnalogAverageVoltage(HAL_AnalogInputHandle analogPortHandle,
+                                   int32_t* status) {
+  auto port = analogInputHandles->Get(analogPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+
+  // No averaging supported
+  return SimAnalogInData[port->channel].voltage;
+}
+int32_t HAL_GetAnalogLSBWeight(HAL_AnalogInputHandle analogPortHandle,
+                               int32_t* status) {
+  return 1220703;
+}
+int32_t HAL_GetAnalogOffset(HAL_AnalogInputHandle analogPortHandle,
+                            int32_t* status) {
+  return 0;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInternal.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInternal.cpp
new file mode 100644
index 0000000..1e6a755
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInternal.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "AnalogInternal.h"
+
+#include "PortsInternal.h"
+#include "hal/AnalogInput.h"
+
+namespace hal {
+IndexedHandleResource<HAL_AnalogInputHandle, hal::AnalogPort, kNumAnalogInputs,
+                      HAL_HandleEnum::AnalogInput>* analogInputHandles;
+}  // namespace hal
+
+namespace hal {
+namespace init {
+void InitializeAnalogInternal() {
+  static IndexedHandleResource<HAL_AnalogInputHandle, hal::AnalogPort,
+                               kNumAnalogInputs, HAL_HandleEnum::AnalogInput>
+      aiH;
+  analogInputHandles = &aiH;
+}
+}  // namespace init
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInternal.h
new file mode 100644
index 0000000..bcc5c95
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogInternal.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+
+#include "PortsInternal.h"
+#include "hal/Ports.h"
+#include "hal/handles/IndexedHandleResource.h"
+
+namespace hal {
+constexpr int32_t kTimebase = 40000000;  ///< 40 MHz clock
+constexpr int32_t kDefaultOversampleBits = 0;
+constexpr int32_t kDefaultAverageBits = 7;
+constexpr double kDefaultSampleRate = 50000.0;
+static constexpr uint32_t kAccumulatorChannels[] = {0, 1};
+
+struct AnalogPort {
+  uint8_t channel;
+  bool isAccumulator;
+};
+
+extern IndexedHandleResource<HAL_AnalogInputHandle, hal::AnalogPort,
+                             kNumAnalogInputs, HAL_HandleEnum::AnalogInput>*
+    analogInputHandles;
+
+int32_t GetAnalogTriggerInputIndex(HAL_AnalogTriggerHandle handle,
+                                   int32_t* status);
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogOutput.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogOutput.cpp
new file mode 100644
index 0000000..2e3a348
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogOutput.cpp
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/AnalogOutput.h"
+
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/IndexedHandleResource.h"
+#include "mockdata/AnalogOutDataInternal.h"
+
+using namespace hal;
+
+namespace {
+struct AnalogOutput {
+  uint8_t channel;
+};
+}  // namespace
+
+static IndexedHandleResource<HAL_AnalogOutputHandle, AnalogOutput,
+                             kNumAnalogOutputs, HAL_HandleEnum::AnalogOutput>*
+    analogOutputHandles;
+
+namespace hal {
+namespace init {
+void InitializeAnalogOutput() {
+  static IndexedHandleResource<HAL_AnalogOutputHandle, AnalogOutput,
+                               kNumAnalogOutputs, HAL_HandleEnum::AnalogOutput>
+      aoH;
+  analogOutputHandles = &aoH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_AnalogOutputHandle HAL_InitializeAnalogOutputPort(HAL_PortHandle portHandle,
+                                                      int32_t* status) {
+  hal::init::CheckInit();
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  HAL_AnalogOutputHandle handle =
+      analogOutputHandles->Allocate(channel, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  auto port = analogOutputHandles->Get(handle);
+  if (port == nullptr) {  // would only error on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  port->channel = static_cast<uint8_t>(channel);
+
+  // Initialize sim analog input
+  SimAnalogOutData[channel].initialized = true;
+  return handle;
+}
+
+void HAL_FreeAnalogOutputPort(HAL_AnalogOutputHandle analogOutputHandle) {
+  // no status, so no need to check for a proper free.
+  auto port = analogOutputHandles->Get(analogOutputHandle);
+  if (port == nullptr) return;
+  analogOutputHandles->Free(analogOutputHandle);
+  SimAnalogOutData[port->channel].initialized = false;
+}
+
+HAL_Bool HAL_CheckAnalogOutputChannel(int32_t channel) {
+  return channel < kNumAnalogOutputs && channel >= 0;
+}
+
+void HAL_SetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle,
+                         double voltage, int32_t* status) {
+  auto port = analogOutputHandles->Get(analogOutputHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimAnalogOutData[port->channel].voltage = voltage;
+}
+
+double HAL_GetAnalogOutput(HAL_AnalogOutputHandle analogOutputHandle,
+                           int32_t* status) {
+  auto port = analogOutputHandles->Get(analogOutputHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+
+  return SimAnalogOutData[port->channel].voltage;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogTrigger.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogTrigger.cpp
new file mode 100644
index 0000000..53b165c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/AnalogTrigger.cpp
@@ -0,0 +1,261 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/AnalogTrigger.h"
+
+#include "AnalogInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/AnalogInput.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+#include "mockdata/AnalogInDataInternal.h"
+#include "mockdata/AnalogTriggerDataInternal.h"
+
+namespace {
+struct AnalogTrigger {
+  HAL_AnalogInputHandle analogHandle;
+  uint8_t index;
+  HAL_Bool trigState;
+};
+}  // namespace
+
+using namespace hal;
+
+static LimitedHandleResource<HAL_AnalogTriggerHandle, AnalogTrigger,
+                             kNumAnalogTriggers, HAL_HandleEnum::AnalogTrigger>*
+    analogTriggerHandles;
+
+namespace hal {
+namespace init {
+void InitializeAnalogTrigger() {
+  static LimitedHandleResource<HAL_AnalogTriggerHandle, AnalogTrigger,
+                               kNumAnalogTriggers,
+                               HAL_HandleEnum::AnalogTrigger>
+      atH;
+  analogTriggerHandles = &atH;
+}
+}  // namespace init
+}  // namespace hal
+
+int32_t hal::GetAnalogTriggerInputIndex(HAL_AnalogTriggerHandle handle,
+                                        int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(handle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  auto analog_port = analogInputHandles->Get(trigger->analogHandle);
+  if (analog_port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  return analog_port->channel;
+}
+
+extern "C" {
+
+HAL_AnalogTriggerHandle HAL_InitializeAnalogTrigger(
+    HAL_AnalogInputHandle portHandle, int32_t* index, int32_t* status) {
+  hal::init::CheckInit();
+  // ensure we are given a valid and active AnalogInput handle
+  auto analog_port = analogInputHandles->Get(portHandle);
+  if (analog_port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  HAL_AnalogTriggerHandle handle = analogTriggerHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto trigger = analogTriggerHandles->Get(handle);
+  if (trigger == nullptr) {  // would only occur on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  trigger->analogHandle = portHandle;
+  trigger->index = static_cast<uint8_t>(getHandleIndex(handle));
+  *index = trigger->index;
+
+  SimAnalogTriggerData[trigger->index].initialized = true;
+
+  trigger->trigState = false;
+
+  return handle;
+}
+
+void HAL_CleanAnalogTrigger(HAL_AnalogTriggerHandle analogTriggerHandle,
+                            int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  analogTriggerHandles->Free(analogTriggerHandle);
+  if (trigger == nullptr) return;
+  SimAnalogTriggerData[trigger->index].initialized = false;
+  // caller owns the analog input handle.
+}
+
+static double GetAnalogValueToVoltage(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t value,
+    int32_t* status) {
+  int32_t LSBWeight = HAL_GetAnalogLSBWeight(analogTriggerHandle, status);
+  int32_t offset = HAL_GetAnalogOffset(analogTriggerHandle, status);
+
+  double voltage = LSBWeight * 1.0e-9 * value - offset * 1.0e-9;
+  return voltage;
+}
+
+void HAL_SetAnalogTriggerLimitsRaw(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                   int32_t lower, int32_t upper,
+                                   int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (lower > upper) {
+    *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+  }
+
+  double trigLower =
+      GetAnalogValueToVoltage(trigger->analogHandle, lower, status);
+  if (status != 0) return;
+  double trigUpper =
+      GetAnalogValueToVoltage(trigger->analogHandle, upper, status);
+  if (status != 0) return;
+
+  SimAnalogTriggerData[trigger->index].triggerUpperBound = trigUpper;
+  SimAnalogTriggerData[trigger->index].triggerLowerBound = trigLower;
+}
+void HAL_SetAnalogTriggerLimitsVoltage(
+    HAL_AnalogTriggerHandle analogTriggerHandle, double lower, double upper,
+    int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (lower > upper) {
+    *status = ANALOG_TRIGGER_LIMIT_ORDER_ERROR;
+  }
+
+  SimAnalogTriggerData[trigger->index].triggerUpperBound = upper;
+  SimAnalogTriggerData[trigger->index].triggerLowerBound = lower;
+}
+void HAL_SetAnalogTriggerAveraged(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                  HAL_Bool useAveragedValue, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  AnalogTriggerData* triggerData = &SimAnalogTriggerData[trigger->index];
+
+  if (triggerData->triggerMode.Get() == HALSIM_AnalogTriggerFiltered) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  auto setVal = useAveragedValue ? HALSIM_AnalogTriggerAveraged
+                                 : HALSIM_AnalogTriggerUnassigned;
+  triggerData->triggerMode = setVal;
+}
+void HAL_SetAnalogTriggerFiltered(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                  HAL_Bool useFilteredValue, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  AnalogTriggerData* triggerData = &SimAnalogTriggerData[trigger->index];
+
+  if (triggerData->triggerMode.Get() == HALSIM_AnalogTriggerAveraged) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  auto setVal = useFilteredValue ? HALSIM_AnalogTriggerAveraged
+                                 : HALSIM_AnalogTriggerUnassigned;
+  triggerData->triggerMode = setVal;
+}
+
+static double GetTriggerValue(AnalogTrigger* trigger, int32_t* status) {
+  auto analogIn = analogInputHandles->Get(trigger->analogHandle);
+  if (analogIn == nullptr) {
+    // Returning HAL Handle Error, but going to ignore lower down
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+
+  return SimAnalogInData[analogIn->channel].voltage;
+}
+
+HAL_Bool HAL_GetAnalogTriggerInWindow(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+
+  double voltage = GetTriggerValue(trigger.get(), status);
+  if (*status == HAL_HANDLE_ERROR) {
+    // Don't error if analog has been destroyed
+    *status = 0;
+    return false;
+  }
+
+  double trigUpper = SimAnalogTriggerData[trigger->index].triggerUpperBound;
+  double trigLower = SimAnalogTriggerData[trigger->index].triggerLowerBound;
+
+  return voltage >= trigLower && voltage <= trigUpper;
+}
+HAL_Bool HAL_GetAnalogTriggerTriggerState(
+    HAL_AnalogTriggerHandle analogTriggerHandle, int32_t* status) {
+  auto trigger = analogTriggerHandles->Get(analogTriggerHandle);
+  if (trigger == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+
+  double voltage = GetTriggerValue(trigger.get(), status);
+  if (*status == HAL_HANDLE_ERROR) {
+    // Don't error if analog has been destroyed
+    *status = 0;
+    return false;
+  }
+
+  double trigUpper = SimAnalogTriggerData[trigger->index].triggerUpperBound;
+  double trigLower = SimAnalogTriggerData[trigger->index].triggerLowerBound;
+
+  if (voltage < trigLower) {
+    trigger->trigState = false;
+    return false;
+  }
+  if (voltage > trigUpper) {
+    trigger->trigState = true;
+    return true;
+  }
+  return trigger->trigState;
+}
+HAL_Bool HAL_GetAnalogTriggerOutput(HAL_AnalogTriggerHandle analogTriggerHandle,
+                                    HAL_AnalogTriggerType type,
+                                    int32_t* status) {
+  if (type == HAL_Trigger_kInWindow) {
+    return HAL_GetAnalogTriggerInWindow(analogTriggerHandle, status);
+  } else if (type == HAL_Trigger_kState) {
+    return HAL_GetAnalogTriggerTriggerState(analogTriggerHandle, status);
+  } else {
+    *status = ANALOG_TRIGGER_PULSE_OUTPUT_ERROR;
+    return false;
+  }
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/CAN.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/CAN.cpp
new file mode 100644
index 0000000..d55eafd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/CAN.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/CAN.h"
+
+#include "mockdata/CanDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeCAN() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+void HAL_CAN_SendMessage(uint32_t messageID, const uint8_t* data,
+                         uint8_t dataSize, int32_t periodMs, int32_t* status) {
+  SimCanData->sendMessage(messageID, data, dataSize, periodMs, status);
+}
+void HAL_CAN_ReceiveMessage(uint32_t* messageID, uint32_t messageIDMask,
+                            uint8_t* data, uint8_t* dataSize,
+                            uint32_t* timeStamp, int32_t* status) {
+  SimCanData->receiveMessage(messageID, messageIDMask, data, dataSize,
+                             timeStamp, status);
+}
+void HAL_CAN_OpenStreamSession(uint32_t* sessionHandle, uint32_t messageID,
+                               uint32_t messageIDMask, uint32_t maxMessages,
+                               int32_t* status) {
+  SimCanData->openStreamSession(sessionHandle, messageID, messageIDMask,
+                                maxMessages, status);
+}
+void HAL_CAN_CloseStreamSession(uint32_t sessionHandle) {
+  SimCanData->closeStreamSession(sessionHandle);
+}
+void HAL_CAN_ReadStreamSession(uint32_t sessionHandle,
+                               struct HAL_CANStreamMessage* messages,
+                               uint32_t messagesToRead, uint32_t* messagesRead,
+                               int32_t* status) {
+  SimCanData->readStreamSession(sessionHandle, messages, messagesToRead,
+                                messagesRead, status);
+}
+void HAL_CAN_GetCANStatus(float* percentBusUtilization, uint32_t* busOffCount,
+                          uint32_t* txFullCount, uint32_t* receiveErrorCount,
+                          uint32_t* transmitErrorCount, int32_t* status) {
+  SimCanData->getCANStatus(percentBusUtilization, busOffCount, txFullCount,
+                           receiveErrorCount, transmitErrorCount, status);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/CANAPI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/CANAPI.cpp
new file mode 100644
index 0000000..a54f06f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/CANAPI.cpp
@@ -0,0 +1,335 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "hal/CANAPI.h"
+
+#include <atomic>
+#include <ctime>
+
+#include <wpi/DenseMap.h>
+
+#include "CANAPIInternal.h"
+#include "HALInitializer.h"
+#include "hal/CAN.h"
+#include "hal/Errors.h"
+#include "hal/HAL.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+
+using namespace hal;
+
+namespace {
+struct Receives {
+  uint64_t lastTimeStamp;
+  uint8_t data[8];
+  uint8_t length;
+};
+
+struct CANStorage {
+  HAL_CANManufacturer manufacturer;
+  HAL_CANDeviceType deviceType;
+  uint8_t deviceId;
+  wpi::mutex mapMutex;
+  wpi::SmallDenseMap<int32_t, int32_t> periodicSends;
+  wpi::SmallDenseMap<int32_t, Receives> receives;
+};
+}  // namespace
+
+static UnlimitedHandleResource<HAL_CANHandle, CANStorage, HAL_HandleEnum::CAN>*
+    canHandles;
+
+static uint32_t GetPacketBaseTime() {
+  int status = 0;
+  auto basetime = HAL_GetFPGATime(&status);
+  // us to ms
+  return (basetime / 1000ull) & 0xFFFFFFFF;
+}
+
+namespace hal {
+namespace init {
+void InitializeCANAPI() {
+  static UnlimitedHandleResource<HAL_CANHandle, CANStorage, HAL_HandleEnum::CAN>
+      cH;
+  canHandles = &cH;
+}
+}  // namespace init
+namespace can {
+int32_t GetCANModuleFromHandle(HAL_CANHandle handle, int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+  return can->deviceId;
+}
+}  // namespace can
+}  // namespace hal
+
+static int32_t CreateCANId(CANStorage* storage, int32_t apiId) {
+  int32_t createdId = 0;
+  createdId |= (static_cast<int32_t>(storage->deviceType) & 0x1F) << 24;
+  createdId |= (static_cast<int32_t>(storage->manufacturer) & 0xFF) << 16;
+  createdId |= (apiId & 0x3FF) << 6;
+  createdId |= (storage->deviceId & 0x3F);
+  return createdId;
+}
+
+HAL_CANHandle HAL_InitializeCAN(HAL_CANManufacturer manufacturer,
+                                int32_t deviceId, HAL_CANDeviceType deviceType,
+                                int32_t* status) {
+  hal::init::CheckInit();
+  auto can = std::make_shared<CANStorage>();
+
+  auto handle = canHandles->Allocate(can);
+
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  can->deviceId = deviceId;
+  can->deviceType = deviceType;
+  can->manufacturer = manufacturer;
+
+  return handle;
+}
+
+void HAL_CleanCAN(HAL_CANHandle handle) {
+  auto data = canHandles->Free(handle);
+
+  std::lock_guard<wpi::mutex> lock(data->mapMutex);
+
+  for (auto&& i : data->periodicSends) {
+    int32_t s = 0;
+    HAL_CAN_SendMessage(i.first, nullptr, 0, HAL_CAN_SEND_PERIOD_STOP_REPEATING,
+                        &s);
+    i.second = -1;
+  }
+}
+
+void HAL_WriteCANPacket(HAL_CANHandle handle, const uint8_t* data,
+                        int32_t length, int32_t apiId, int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  auto id = CreateCANId(can.get(), apiId);
+
+  HAL_CAN_SendMessage(id, data, length, HAL_CAN_SEND_PERIOD_NO_REPEAT, status);
+
+  if (*status != 0) {
+    return;
+  }
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  can->periodicSends[apiId] = -1;
+}
+
+void HAL_WriteCANPacketRepeating(HAL_CANHandle handle, const uint8_t* data,
+                                 int32_t length, int32_t apiId,
+                                 int32_t repeatMs, int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  auto id = CreateCANId(can.get(), apiId);
+
+  HAL_CAN_SendMessage(id, data, length, repeatMs, status);
+
+  if (*status != 0) {
+    return;
+  }
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  can->periodicSends[apiId] = repeatMs;
+}
+
+void HAL_StopCANPacketRepeating(HAL_CANHandle handle, int32_t apiId,
+                                int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  auto id = CreateCANId(can.get(), apiId);
+
+  HAL_CAN_SendMessage(id, nullptr, 0, HAL_CAN_SEND_PERIOD_STOP_REPEATING,
+                      status);
+
+  if (*status != 0) {
+    return;
+  }
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  can->periodicSends[apiId] = -1;
+}
+
+void HAL_ReadCANPacketNew(HAL_CANHandle handle, int32_t apiId, uint8_t* data,
+                          int32_t* length, uint64_t* receivedTimestamp,
+                          int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+  uint8_t dataSize = 0;
+  uint32_t ts = 0;
+  HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
+
+  if (*status == 0) {
+    std::lock_guard<wpi::mutex> lock(can->mapMutex);
+    auto& msg = can->receives[messageId];
+    msg.length = dataSize;
+    msg.lastTimeStamp = ts;
+    // The NetComm call placed in data, copy into the msg
+    std::memcpy(msg.data, data, dataSize);
+  }
+  *length = dataSize;
+  *receivedTimestamp = ts;
+}
+
+void HAL_ReadCANPacketLatest(HAL_CANHandle handle, int32_t apiId, uint8_t* data,
+                             int32_t* length, uint64_t* receivedTimestamp,
+                             int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+  uint8_t dataSize = 0;
+  uint32_t ts = 0;
+  HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
+
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  if (*status == 0) {
+    // fresh update
+    auto& msg = can->receives[messageId];
+    msg.length = dataSize;
+    *length = dataSize;
+    msg.lastTimeStamp = ts;
+    *receivedTimestamp = ts;
+    // The NetComm call placed in data, copy into the msg
+    std::memcpy(msg.data, data, dataSize);
+  } else {
+    auto i = can->receives.find(messageId);
+    if (i != can->receives.end()) {
+      // Read the data from the stored message into the output
+      std::memcpy(data, i->second.data, i->second.length);
+      *length = i->second.length;
+      *receivedTimestamp = i->second.lastTimeStamp;
+      *status = 0;
+    }
+  }
+}
+
+void HAL_ReadCANPacketTimeout(HAL_CANHandle handle, int32_t apiId,
+                              uint8_t* data, int32_t* length,
+                              uint64_t* receivedTimestamp, int32_t timeoutMs,
+                              int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+  uint8_t dataSize = 0;
+  uint32_t ts = 0;
+  HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
+
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  if (*status == 0) {
+    // fresh update
+    auto& msg = can->receives[messageId];
+    msg.length = dataSize;
+    *length = dataSize;
+    msg.lastTimeStamp = ts;
+    *receivedTimestamp = ts;
+    // The NetComm call placed in data, copy into the msg
+    std::memcpy(msg.data, data, dataSize);
+  } else {
+    auto i = can->receives.find(messageId);
+    if (i != can->receives.end()) {
+      // Found, check if new enough
+      uint32_t now = GetPacketBaseTime();
+      if (now - i->second.lastTimeStamp > static_cast<uint32_t>(timeoutMs)) {
+        // Timeout, return bad status
+        *status = HAL_CAN_TIMEOUT;
+        return;
+      }
+      // Read the data from the stored message into the output
+      std::memcpy(data, i->second.data, i->second.length);
+      *length = i->second.length;
+      *receivedTimestamp = i->second.lastTimeStamp;
+      *status = 0;
+    }
+  }
+}
+
+void HAL_ReadCANPeriodicPacket(HAL_CANHandle handle, int32_t apiId,
+                               uint8_t* data, int32_t* length,
+                               uint64_t* receivedTimestamp, int32_t timeoutMs,
+                               int32_t periodMs, int32_t* status) {
+  auto can = canHandles->Get(handle);
+  if (!can) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  uint32_t messageId = CreateCANId(can.get(), apiId);
+
+  {
+    std::lock_guard<wpi::mutex> lock(can->mapMutex);
+    auto i = can->receives.find(messageId);
+    if (i != can->receives.end()) {
+      // Found, check if new enough
+      uint32_t now = GetPacketBaseTime();
+      if (now - i->second.lastTimeStamp < static_cast<uint32_t>(periodMs)) {
+        *status = 0;
+        // Read the data from the stored message into the output
+        std::memcpy(data, i->second.data, i->second.length);
+        *length = i->second.length;
+        *receivedTimestamp = i->second.lastTimeStamp;
+        return;
+      }
+    }
+  }
+
+  uint8_t dataSize = 0;
+  uint32_t ts = 0;
+  HAL_CAN_ReceiveMessage(&messageId, 0x1FFFFFFF, data, &dataSize, &ts, status);
+
+  std::lock_guard<wpi::mutex> lock(can->mapMutex);
+  if (*status == 0) {
+    // fresh update
+    auto& msg = can->receives[messageId];
+    msg.length = dataSize;
+    *length = dataSize;
+    msg.lastTimeStamp = ts;
+    *receivedTimestamp = ts;
+    // The NetComm call placed in data, copy into the msg
+    std::memcpy(msg.data, data, dataSize);
+  } else {
+    auto i = can->receives.find(messageId);
+    if (i != can->receives.end()) {
+      // Found, check if new enough
+      uint32_t now = GetPacketBaseTime();
+      if (now - i->second.lastTimeStamp > static_cast<uint32_t>(timeoutMs)) {
+        // Timeout, return bad status
+        *status = HAL_CAN_TIMEOUT;
+        return;
+      }
+      // Read the data from the stored message into the output
+      std::memcpy(data, i->second.data, i->second.length);
+      *length = i->second.length;
+      *receivedTimestamp = i->second.lastTimeStamp;
+      *status = 0;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/CANAPIInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/CANAPIInternal.h
new file mode 100644
index 0000000..074f682
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/CANAPIInternal.h
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "hal/Types.h"
+
+namespace hal {
+namespace can {
+int32_t GetCANModuleFromHandle(HAL_CANHandle handle, int32_t* status);
+}  // namespace can
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/CallbackStore.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/CallbackStore.cpp
new file mode 100644
index 0000000..d278b93
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/CallbackStore.cpp
@@ -0,0 +1,13 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "simulation/CallbackStore.h"
+
+void frc::sim::CallbackStoreThunk(const char* name, void* param,
+                                  const HAL_Value* value) {
+  reinterpret_cast<CallbackStore*>(param)->callback(name, value);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Compressor.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Compressor.cpp
new file mode 100644
index 0000000..b5c5867
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Compressor.cpp
@@ -0,0 +1,123 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Compressor.h"
+
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/PCMDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeCompressor() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_CompressorHandle HAL_InitializeCompressor(int32_t module, int32_t* status) {
+  hal::init::CheckInit();
+  // As compressors can have unlimited objects, just create a
+  // handle with the module number as the index.
+
+  SimPCMData[module].compressorInitialized = true;
+  return (HAL_CompressorHandle)createHandle(static_cast<int16_t>(module),
+                                            HAL_HandleEnum::Compressor, 0);
+}
+
+HAL_Bool HAL_CheckCompressorModule(int32_t module) {
+  return module < kNumPCMModules && module >= 0;
+}
+
+HAL_Bool HAL_GetCompressor(HAL_CompressorHandle compressorHandle,
+                           int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+
+  return SimPCMData[index].compressorOn;
+}
+
+void HAL_SetCompressorClosedLoopControl(HAL_CompressorHandle compressorHandle,
+                                        HAL_Bool value, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimPCMData[index].closedLoopEnabled = value;
+}
+
+HAL_Bool HAL_GetCompressorClosedLoopControl(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+
+  return SimPCMData[index].closedLoopEnabled;
+}
+
+HAL_Bool HAL_GetCompressorPressureSwitch(HAL_CompressorHandle compressorHandle,
+                                         int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+
+  return SimPCMData[index].pressureSwitch;
+}
+
+double HAL_GetCompressorCurrent(HAL_CompressorHandle compressorHandle,
+                                int32_t* status) {
+  int16_t index =
+      getHandleTypedIndex(compressorHandle, HAL_HandleEnum::Compressor, 0);
+  if (index == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimPCMData[index].compressorCurrent;
+}
+HAL_Bool HAL_GetCompressorCurrentTooHighFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  return false;
+}
+HAL_Bool HAL_GetCompressorCurrentTooHighStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  return false;
+}
+HAL_Bool HAL_GetCompressorShortedStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  return false;
+}
+HAL_Bool HAL_GetCompressorShortedFault(HAL_CompressorHandle compressorHandle,
+                                       int32_t* status) {
+  return false;
+}
+HAL_Bool HAL_GetCompressorNotConnectedStickyFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  return false;
+}
+HAL_Bool HAL_GetCompressorNotConnectedFault(
+    HAL_CompressorHandle compressorHandle, int32_t* status) {
+  return false;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Constants.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Constants.cpp
new file mode 100644
index 0000000..64cb52b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Constants.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Constants.h"
+
+#include "ConstantsInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeConstants() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+int32_t HAL_GetSystemClockTicksPerMicrosecond(void) {
+  return kSystemClockTicksPerMicrosecond;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/ConstantsInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/ConstantsInternal.h
new file mode 100644
index 0000000..c3a6e8f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/ConstantsInternal.h
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+namespace hal {
+constexpr int32_t kSystemClockTicksPerMicrosecond = 40;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Counter.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Counter.cpp
new file mode 100644
index 0000000..37454d0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Counter.cpp
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/Counter.h"
+
+#include "CounterInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+namespace hal {
+
+LimitedHandleResource<HAL_CounterHandle, Counter, kNumCounters,
+                      HAL_HandleEnum::Counter>* counterHandles;
+}  // namespace hal
+
+namespace hal {
+namespace init {
+void InitializeCounter() {
+  static LimitedHandleResource<HAL_CounterHandle, Counter, kNumCounters,
+                               HAL_HandleEnum::Counter>
+      cH;
+  counterHandles = &cH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_CounterHandle HAL_InitializeCounter(HAL_Counter_Mode mode, int32_t* index,
+                                        int32_t* status) {
+  hal::init::CheckInit();
+  return 0;
+}
+void HAL_FreeCounter(HAL_CounterHandle counterHandle, int32_t* status) {}
+void HAL_SetCounterAverageSize(HAL_CounterHandle counterHandle, int32_t size,
+                               int32_t* status) {}
+void HAL_SetCounterUpSource(HAL_CounterHandle counterHandle,
+                            HAL_Handle digitalSourceHandle,
+                            HAL_AnalogTriggerType analogTriggerType,
+                            int32_t* status) {}
+void HAL_SetCounterUpSourceEdge(HAL_CounterHandle counterHandle,
+                                HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                int32_t* status) {}
+void HAL_ClearCounterUpSource(HAL_CounterHandle counterHandle,
+                              int32_t* status) {}
+void HAL_SetCounterDownSource(HAL_CounterHandle counterHandle,
+                              HAL_Handle digitalSourceHandle,
+                              HAL_AnalogTriggerType analogTriggerType,
+                              int32_t* status) {}
+void HAL_SetCounterDownSourceEdge(HAL_CounterHandle counterHandle,
+                                  HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                  int32_t* status) {}
+void HAL_ClearCounterDownSource(HAL_CounterHandle counterHandle,
+                                int32_t* status) {}
+void HAL_SetCounterUpDownMode(HAL_CounterHandle counterHandle,
+                              int32_t* status) {}
+void HAL_SetCounterExternalDirectionMode(HAL_CounterHandle counterHandle,
+                                         int32_t* status) {}
+void HAL_SetCounterSemiPeriodMode(HAL_CounterHandle counterHandle,
+                                  HAL_Bool highSemiPeriod, int32_t* status) {}
+void HAL_SetCounterPulseLengthMode(HAL_CounterHandle counterHandle,
+                                   double threshold, int32_t* status) {}
+int32_t HAL_GetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
+                                       int32_t* status) {
+  return 0;
+}
+void HAL_SetCounterSamplesToAverage(HAL_CounterHandle counterHandle,
+                                    int32_t samplesToAverage, int32_t* status) {
+}
+void HAL_ResetCounter(HAL_CounterHandle counterHandle, int32_t* status) {}
+int32_t HAL_GetCounter(HAL_CounterHandle counterHandle, int32_t* status) {
+  return 0;
+}
+double HAL_GetCounterPeriod(HAL_CounterHandle counterHandle, int32_t* status) {
+  return 0.0;
+}
+void HAL_SetCounterMaxPeriod(HAL_CounterHandle counterHandle, double maxPeriod,
+                             int32_t* status) {}
+void HAL_SetCounterUpdateWhenEmpty(HAL_CounterHandle counterHandle,
+                                   HAL_Bool enabled, int32_t* status) {}
+HAL_Bool HAL_GetCounterStopped(HAL_CounterHandle counterHandle,
+                               int32_t* status) {
+  return false;
+}
+HAL_Bool HAL_GetCounterDirection(HAL_CounterHandle counterHandle,
+                                 int32_t* status) {
+  return false;
+}
+void HAL_SetCounterReverseDirection(HAL_CounterHandle counterHandle,
+                                    HAL_Bool reverseDirection,
+                                    int32_t* status) {}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/CounterInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/CounterInternal.h
new file mode 100644
index 0000000..70fbe54
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/CounterInternal.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "PortsInternal.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+
+namespace hal {
+
+struct Counter {
+  uint8_t index;
+};
+
+extern LimitedHandleResource<HAL_CounterHandle, Counter, kNumCounters,
+                             HAL_HandleEnum::Counter>* counterHandles;
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/DIO.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/DIO.cpp
new file mode 100644
index 0000000..e67b756
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/DIO.cpp
@@ -0,0 +1,247 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/DIO.h"
+
+#include <cmath>
+
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+#include "mockdata/DIODataInternal.h"
+#include "mockdata/DigitalPWMDataInternal.h"
+
+using namespace hal;
+
+static LimitedHandleResource<HAL_DigitalPWMHandle, uint8_t,
+                             kNumDigitalPWMOutputs, HAL_HandleEnum::DigitalPWM>*
+    digitalPWMHandles;
+
+namespace hal {
+namespace init {
+void InitializeDIO() {
+  static LimitedHandleResource<HAL_DigitalPWMHandle, uint8_t,
+                               kNumDigitalPWMOutputs,
+                               HAL_HandleEnum::DigitalPWM>
+      dpH;
+  digitalPWMHandles = &dpH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_DigitalHandle HAL_InitializeDIOPort(HAL_PortHandle portHandle,
+                                        HAL_Bool input, int32_t* status) {
+  hal::init::CheckInit();
+  if (*status != 0) return HAL_kInvalidHandle;
+
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  auto handle =
+      digitalChannelHandles->Allocate(channel, HAL_HandleEnum::DIO, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  auto port = digitalChannelHandles->Get(handle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  port->channel = static_cast<uint8_t>(channel);
+
+  SimDIOData[channel].initialized = true;
+
+  SimDIOData[channel].isInput = input;
+
+  return handle;
+}
+
+HAL_Bool HAL_CheckDIOChannel(int32_t channel) {
+  return channel < kNumDigitalChannels && channel >= 0;
+}
+
+void HAL_FreeDIOPort(HAL_DigitalHandle dioPortHandle) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  // no status, so no need to check for a proper free.
+  digitalChannelHandles->Free(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) return;
+  SimDIOData[port->channel].initialized = true;
+}
+
+HAL_DigitalPWMHandle HAL_AllocateDigitalPWM(int32_t* status) {
+  auto handle = digitalPWMHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+
+  auto id = digitalPWMHandles->Get(handle);
+  if (id == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  *id = static_cast<uint8_t>(getHandleIndex(handle));
+
+  SimDigitalPWMData[*id].initialized = true;
+
+  return handle;
+}
+
+void HAL_FreeDigitalPWM(HAL_DigitalPWMHandle pwmGenerator, int32_t* status) {
+  auto port = digitalPWMHandles->Get(pwmGenerator);
+  digitalPWMHandles->Free(pwmGenerator);
+  if (port == nullptr) return;
+  int32_t id = *port;
+  SimDigitalPWMData[id].initialized = false;
+}
+
+void HAL_SetDigitalPWMRate(double rate, int32_t* status) {
+  // Currently rounding in the log rate domain... heavy weight toward picking a
+  // higher freq.
+  // TODO: Round in the linear rate domain.
+  // uint8_t pwmPeriodPower = static_cast<uint8_t>(
+  //    std::log(1.0 / (kExpectedLoopTiming * 0.25E-6 * rate)) /
+  //        std::log(2.0) +
+  //    0.5);
+  // TODO(THAD) : Add a case to set this in the simulator
+  // digitalSystem->writePWMPeriodPower(pwmPeriodPower, status);
+}
+
+void HAL_SetDigitalPWMDutyCycle(HAL_DigitalPWMHandle pwmGenerator,
+                                double dutyCycle, int32_t* status) {
+  auto port = digitalPWMHandles->Get(pwmGenerator);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  int32_t id = *port;
+  if (dutyCycle > 1.0) dutyCycle = 1.0;
+  if (dutyCycle < 0.0) dutyCycle = 0.0;
+  SimDigitalPWMData[id].dutyCycle = dutyCycle;
+}
+
+void HAL_SetDigitalPWMOutputChannel(HAL_DigitalPWMHandle pwmGenerator,
+                                    int32_t channel, int32_t* status) {
+  auto port = digitalPWMHandles->Get(pwmGenerator);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  int32_t id = *port;
+  SimDigitalPWMData[id].pin = channel;
+}
+
+void HAL_SetDIO(HAL_DigitalHandle dioPortHandle, HAL_Bool value,
+                int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (value != 0 && value != 1) {
+    if (value != 0) value = 1;
+  }
+  SimDIOData[port->channel].value = value;
+}
+
+void HAL_SetDIODirection(HAL_DigitalHandle dioPortHandle, HAL_Bool input,
+                         int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimDIOData[port->channel].isInput = input;
+}
+
+HAL_Bool HAL_GetDIO(HAL_DigitalHandle dioPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  HAL_Bool value = SimDIOData[port->channel].value;
+  if (value > 1) value = 1;
+  if (value < 0) value = 0;
+  return value;
+}
+
+HAL_Bool HAL_GetDIODirection(HAL_DigitalHandle dioPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  HAL_Bool value = SimDIOData[port->channel].isInput;
+  if (value > 1) value = 1;
+  if (value < 0) value = 0;
+  return value;
+}
+
+void HAL_Pulse(HAL_DigitalHandle dioPortHandle, double pulseLength,
+               int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  // TODO (Thad) Add this
+}
+
+HAL_Bool HAL_IsPulsing(HAL_DigitalHandle dioPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  return false;
+  // TODO (Thad) Add this
+}
+
+HAL_Bool HAL_IsAnyPulsing(int32_t* status) {
+  return false;  // TODO(Thad) Figure this out
+}
+
+void HAL_SetFilterSelect(HAL_DigitalHandle dioPortHandle, int32_t filterIndex,
+                         int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  // TODO(Thad) Figure this out
+}
+
+int32_t HAL_GetFilterSelect(HAL_DigitalHandle dioPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(dioPortHandle, HAL_HandleEnum::DIO);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  return 0;
+  // TODO(Thad) Figure this out
+}
+
+void HAL_SetFilterPeriod(int32_t filterIndex, int64_t value, int32_t* status) {
+  // TODO(Thad) figure this out
+}
+
+int64_t HAL_GetFilterPeriod(int32_t filterIndex, int32_t* status) {
+  return 0;  // TODO(Thad) figure this out
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/DigitalInternal.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/DigitalInternal.cpp
new file mode 100644
index 0000000..070754a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/DigitalInternal.cpp
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "DigitalInternal.h"
+
+#include "ConstantsInternal.h"
+#include "PortsInternal.h"
+#include "hal/AnalogTrigger.h"
+#include "hal/HAL.h"
+#include "hal/Ports.h"
+
+namespace hal {
+
+DigitalHandleResource<HAL_DigitalHandle, DigitalPort,
+                      kNumDigitalChannels + kNumPWMHeaders>*
+    digitalChannelHandles;
+
+namespace init {
+void InitializeDigitalInternal() {
+  static DigitalHandleResource<HAL_DigitalHandle, DigitalPort,
+                               kNumDigitalChannels + kNumPWMHeaders>
+      dcH;
+  digitalChannelHandles = &dcH;
+}
+}  // namespace init
+
+bool remapDigitalSource(HAL_Handle digitalSourceHandle,
+                        HAL_AnalogTriggerType analogTriggerType,
+                        uint8_t& channel, uint8_t& module,
+                        bool& analogTrigger) {
+  if (isHandleType(digitalSourceHandle, HAL_HandleEnum::AnalogTrigger)) {
+    // If handle passed, index is not negative
+    int32_t index = getHandleIndex(digitalSourceHandle);
+    channel = (index << 2) + analogTriggerType;
+    module = channel >> 4;
+    analogTrigger = true;
+    return true;
+  } else if (isHandleType(digitalSourceHandle, HAL_HandleEnum::DIO)) {
+    int32_t index = getHandleIndex(digitalSourceHandle);
+    if (index >= kNumDigitalHeaders) {
+      channel = remapMXPChannel(index);
+      module = 1;
+    } else {
+      channel = index;
+      module = 0;
+    }
+    analogTrigger = false;
+    return true;
+  } else {
+    return false;
+  }
+}
+
+int32_t remapMXPChannel(int32_t channel) { return channel - 10; }
+
+int32_t remapMXPPWMChannel(int32_t channel) {
+  if (channel < 14) {
+    return channel - 10;  // first block of 4 pwms (MXP 0-3)
+  } else {
+    return channel - 6;  // block of PWMs after SPI
+  }
+}
+
+int32_t GetDigitalInputChannel(HAL_DigitalHandle handle, int32_t* status) {
+  auto digital = digitalChannelHandles->Get(handle, HAL_HandleEnum::DIO);
+  if (digital == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return -1;
+  }
+
+  return digital->channel;
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/DigitalInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/DigitalInternal.h
new file mode 100644
index 0000000..89644a1
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/DigitalInternal.h
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+
+#include "PortsInternal.h"
+#include "hal/AnalogTrigger.h"
+#include "hal/Ports.h"
+#include "hal/Types.h"
+#include "hal/handles/DigitalHandleResource.h"
+#include "hal/handles/HandlesInternal.h"
+
+namespace hal {
+/**
+ * MXP channels when used as digital output PWM are offset from actual value
+ */
+constexpr int32_t kMXPDigitalPWMOffset = 6;
+
+constexpr int32_t kExpectedLoopTiming = 40;
+
+/**
+ * kDefaultPwmPeriod is in ms
+ *
+ * - 20ms periods (50 Hz) are the "safest" setting in that this works for all
+ *   devices
+ * - 20ms periods seem to be desirable for Vex Motors
+ * - 20ms periods are the specified period for HS-322HD servos, but work
+ *   reliably down to 10.0 ms; starting at about 8.5ms, the servo sometimes hums
+ *   and get hot; by 5.0ms the hum is nearly continuous
+ * - 10ms periods work well for Victor 884
+ * - 5ms periods allows higher update rates for Luminary Micro Jaguar speed
+ *   controllers. Due to the shipping firmware on the Jaguar, we can't run the
+ *   update period less than 5.05 ms.
+ *
+ * kDefaultPwmPeriod is the 1x period (5.05 ms).  In hardware, the period
+ * scaling is implemented as an output squelch to get longer periods for old
+ * devices.
+ */
+constexpr float kDefaultPwmPeriod = 5.05;
+/**
+ * kDefaultPwmCenter is the PWM range center in ms
+ */
+constexpr float kDefaultPwmCenter = 1.5;
+/**
+ * kDefaultPWMStepsDown is the number of PWM steps below the centerpoint
+ */
+constexpr int32_t kDefaultPwmStepsDown = 1000;
+constexpr int32_t kPwmDisabled = 0;
+
+struct DigitalPort {
+  uint8_t channel;
+  bool configSet = false;
+  bool eliminateDeadband = false;
+  int32_t maxPwm = 0;
+  int32_t deadbandMaxPwm = 0;
+  int32_t centerPwm = 0;
+  int32_t deadbandMinPwm = 0;
+  int32_t minPwm = 0;
+};
+
+extern DigitalHandleResource<HAL_DigitalHandle, DigitalPort,
+                             kNumDigitalChannels + kNumPWMHeaders>*
+    digitalChannelHandles;
+
+/**
+ * Remap the digital source channel and set the module.
+ *
+ * If it's an analog trigger, determine the module from the high order routing
+ * channel else do normal digital input remapping based on channel number
+ * (MXP).
+ */
+bool remapDigitalSource(HAL_Handle digitalSourceHandle,
+                        HAL_AnalogTriggerType analogTriggerType,
+                        uint8_t& channel, uint8_t& module, bool& analogTrigger);
+
+/**
+ * Map DIO channel numbers from their physical number (10 to 26) to their
+ * position in the bit field.
+ */
+int32_t remapMXPChannel(int32_t channel);
+
+int32_t remapMXPPWMChannel(int32_t channel);
+
+int32_t GetDigitalInputChannel(HAL_DigitalHandle handle, int32_t* status);
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/DriverStation.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/DriverStation.cpp
new file mode 100644
index 0000000..0c9c028
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/DriverStation.cpp
@@ -0,0 +1,291 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/DriverStation.h"
+
+#ifdef __APPLE__
+#include <pthread.h>
+#endif
+
+#include <cstdio>
+#include <cstdlib>
+#include <cstring>
+#include <string>
+
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "HALInitializer.h"
+#include "mockdata/DriverStationDataInternal.h"
+#include "mockdata/MockHooks.h"
+
+static wpi::mutex msgMutex;
+static wpi::condition_variable* newDSDataAvailableCond;
+static wpi::mutex newDSDataAvailableMutex;
+static int newDSDataAvailableCounter{0};
+static std::atomic_bool isFinalized{false};
+
+namespace hal {
+namespace init {
+void InitializeDriverStation() {
+  static wpi::condition_variable nddaC;
+  newDSDataAvailableCond = &nddaC;
+}
+}  // namespace init
+}  // namespace hal
+
+using namespace hal;
+
+extern "C" {
+int32_t HAL_SendError(HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode,
+                      const char* details, const char* location,
+                      const char* callStack, HAL_Bool printMsg) {
+  // Avoid flooding console by keeping track of previous 5 error
+  // messages and only printing again if they're longer than 1 second old.
+  static constexpr int KEEP_MSGS = 5;
+  std::lock_guard<wpi::mutex> lock(msgMutex);
+  static std::string prevMsg[KEEP_MSGS];
+  static std::chrono::time_point<std::chrono::steady_clock>
+      prevMsgTime[KEEP_MSGS];
+  static bool initialized = false;
+  if (!initialized) {
+    for (int i = 0; i < KEEP_MSGS; i++) {
+      prevMsgTime[i] =
+          std::chrono::steady_clock::now() - std::chrono::seconds(2);
+    }
+    initialized = true;
+  }
+
+  auto curTime = std::chrono::steady_clock::now();
+  int i;
+  for (i = 0; i < KEEP_MSGS; ++i) {
+    if (prevMsg[i] == details) break;
+  }
+  int retval = 0;
+  if (i == KEEP_MSGS || (curTime - prevMsgTime[i]) >= std::chrono::seconds(1)) {
+    printMsg = true;
+    if (printMsg) {
+      if (location && location[0] != '\0') {
+        std::fprintf(stderr, "%s at %s: ", isError ? "Error" : "Warning",
+                     location);
+      }
+      std::fprintf(stderr, "%s\n", details);
+      if (callStack && callStack[0] != '\0') {
+        std::fprintf(stderr, "%s\n", callStack);
+      }
+    }
+    if (i == KEEP_MSGS) {
+      // replace the oldest one
+      i = 0;
+      auto first = prevMsgTime[0];
+      for (int j = 1; j < KEEP_MSGS; ++j) {
+        if (prevMsgTime[j] < first) {
+          first = prevMsgTime[j];
+          i = j;
+        }
+      }
+      prevMsg[i] = details;
+    }
+    prevMsgTime[i] = curTime;
+  }
+  return retval;
+}
+
+int32_t HAL_GetControlWord(HAL_ControlWord* controlWord) {
+  controlWord->enabled = SimDriverStationData->enabled;
+  controlWord->autonomous = SimDriverStationData->autonomous;
+  controlWord->test = SimDriverStationData->test;
+  controlWord->eStop = SimDriverStationData->eStop;
+  controlWord->fmsAttached = SimDriverStationData->fmsAttached;
+  controlWord->dsAttached = SimDriverStationData->dsAttached;
+  return 0;
+}
+
+HAL_AllianceStationID HAL_GetAllianceStation(int32_t* status) {
+  *status = 0;
+  return SimDriverStationData->allianceStationId;
+}
+
+int32_t HAL_GetJoystickAxes(int32_t joystickNum, HAL_JoystickAxes* axes) {
+  SimDriverStationData->GetJoystickAxes(joystickNum, axes);
+  return 0;
+}
+
+int32_t HAL_GetJoystickPOVs(int32_t joystickNum, HAL_JoystickPOVs* povs) {
+  SimDriverStationData->GetJoystickPOVs(joystickNum, povs);
+  return 0;
+}
+
+int32_t HAL_GetJoystickButtons(int32_t joystickNum,
+                               HAL_JoystickButtons* buttons) {
+  SimDriverStationData->GetJoystickButtons(joystickNum, buttons);
+  return 0;
+}
+
+int32_t HAL_GetJoystickDescriptor(int32_t joystickNum,
+                                  HAL_JoystickDescriptor* desc) {
+  SimDriverStationData->GetJoystickDescriptor(joystickNum, desc);
+  return 0;
+}
+
+HAL_Bool HAL_GetJoystickIsXbox(int32_t joystickNum) {
+  HAL_JoystickDescriptor desc;
+  SimDriverStationData->GetJoystickDescriptor(joystickNum, &desc);
+  return desc.isXbox;
+}
+
+int32_t HAL_GetJoystickType(int32_t joystickNum) {
+  HAL_JoystickDescriptor desc;
+  SimDriverStationData->GetJoystickDescriptor(joystickNum, &desc);
+  return desc.type;
+}
+
+char* HAL_GetJoystickName(int32_t joystickNum) {
+  HAL_JoystickDescriptor desc;
+  SimDriverStationData->GetJoystickDescriptor(joystickNum, &desc);
+  size_t len = std::strlen(desc.name);
+  char* name = static_cast<char*>(std::malloc(len + 1));
+  std::memcpy(name, desc.name, len + 1);
+  return name;
+}
+
+void HAL_FreeJoystickName(char* name) { std::free(name); }
+
+int32_t HAL_GetJoystickAxisType(int32_t joystickNum, int32_t axis) { return 0; }
+
+int32_t HAL_SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
+                               int32_t leftRumble, int32_t rightRumble) {
+  SimDriverStationData->SetJoystickOutputs(joystickNum, outputs, leftRumble,
+                                           rightRumble);
+  return 0;
+}
+
+double HAL_GetMatchTime(int32_t* status) {
+  return SimDriverStationData->matchTime;
+}
+
+int32_t HAL_GetMatchInfo(HAL_MatchInfo* info) {
+  SimDriverStationData->GetMatchInfo(info);
+  return 0;
+}
+
+void HAL_ObserveUserProgramStarting(void) { HALSIM_SetProgramStarted(); }
+
+void HAL_ObserveUserProgramDisabled(void) {
+  // TODO
+}
+
+void HAL_ObserveUserProgramAutonomous(void) {
+  // TODO
+}
+
+void HAL_ObserveUserProgramTeleop(void) {
+  // TODO
+}
+
+void HAL_ObserveUserProgramTest(void) {
+  // TODO
+}
+
+#ifdef __APPLE__
+static pthread_key_t lastCountKey;
+static pthread_once_t lastCountKeyOnce = PTHREAD_ONCE_INIT;
+
+static void InitLastCountKey(void) {
+  pthread_key_create(&lastCountKey, std::free);
+}
+#endif
+
+HAL_Bool HAL_IsNewControlData(void) {
+#ifdef __APPLE__
+  pthread_once(&lastCountKeyOnce, InitLastCountKey);
+  int* lastCountPtr = static_cast<int*>(pthread_getspecific(lastCountKey));
+  if (!lastCountPtr) {
+    lastCountPtr = static_cast<int*>(std::malloc(sizeof(int)));
+    *lastCountPtr = -1;
+    pthread_setspecific(lastCountKey, lastCountPtr);
+  }
+  int& lastCount = *lastCountPtr;
+#else
+  thread_local int lastCount{-1};
+#endif
+  // 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
+  // 20ms rate occurs once every 2.7 years of DS connected runtime, so not
+  // worth the cycles to check.
+  int currentCount = 0;
+  {
+    std::unique_lock<wpi::mutex> lock(newDSDataAvailableMutex);
+    currentCount = newDSDataAvailableCounter;
+  }
+  if (lastCount == currentCount) return false;
+  lastCount = currentCount;
+  return true;
+}
+
+void HAL_WaitForDSData(void) { HAL_WaitForDSDataTimeout(0); }
+
+HAL_Bool HAL_WaitForDSDataTimeout(double timeout) {
+  if (isFinalized.load()) {
+    return false;
+  }
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+
+  std::unique_lock<wpi::mutex> lock(newDSDataAvailableMutex);
+  int currentCount = newDSDataAvailableCounter;
+  while (newDSDataAvailableCounter == currentCount) {
+    if (timeout > 0) {
+      auto timedOut = newDSDataAvailableCond->wait_until(lock, timeoutTime);
+      if (timedOut == std::cv_status::timeout) {
+        return false;
+      }
+    } else {
+      newDSDataAvailableCond->wait(lock);
+    }
+  }
+  return true;
+}
+
+// Constant number to be used for our occur handle
+constexpr int32_t refNumber = 42;
+
+static int32_t newDataOccur(uint32_t refNum) {
+  // Since we could get other values, require our specific handle
+  // to signal our threads
+  if (refNum != refNumber) return 0;
+  std::lock_guard<wpi::mutex> lock(newDSDataAvailableMutex);
+  // Nofify all threads
+  newDSDataAvailableCounter++;
+  newDSDataAvailableCond->notify_all();
+  return 0;
+}
+
+void HAL_InitializeDriverStation(void) {
+  hal::init::CheckInit();
+  static std::atomic_bool initialized{false};
+  static wpi::mutex initializeMutex;
+  // Initial check, as if it's true initialization has finished
+  if (initialized) return;
+
+  std::lock_guard<wpi::mutex> lock(initializeMutex);
+  // Second check in case another thread was waiting
+  if (initialized) return;
+
+  SimDriverStationData->ResetData();
+
+  std::atexit([]() {
+    isFinalized.store(true);
+    HAL_ReleaseDSMutex();
+  });
+
+  initialized = true;
+}
+
+void HAL_ReleaseDSMutex(void) { newDataOccur(refNumber); }
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Encoder.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Encoder.cpp
new file mode 100644
index 0000000..3f197a2
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Encoder.cpp
@@ -0,0 +1,345 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/Encoder.h"
+
+#include "CounterInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Counter.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+#include "mockdata/EncoderDataInternal.h"
+
+using namespace hal;
+
+namespace {
+struct Encoder {
+  HAL_Handle nativeHandle;
+  HAL_EncoderEncodingType encodingType;
+  double distancePerPulse;
+  uint8_t index;
+};
+struct Empty {};
+}  // namespace
+
+static LimitedHandleResource<HAL_EncoderHandle, Encoder,
+                             kNumEncoders + kNumCounters,
+                             HAL_HandleEnum::Encoder>* encoderHandles;
+
+static LimitedHandleResource<HAL_FPGAEncoderHandle, Empty, kNumEncoders,
+                             HAL_HandleEnum::FPGAEncoder>* fpgaEncoderHandles;
+
+namespace hal {
+namespace init {
+void InitializeEncoder() {
+  static LimitedHandleResource<HAL_FPGAEncoderHandle, Empty, kNumEncoders,
+                               HAL_HandleEnum::FPGAEncoder>
+      feH;
+  fpgaEncoderHandles = &feH;
+  static LimitedHandleResource<HAL_EncoderHandle, Encoder,
+                               kNumEncoders + kNumCounters,
+                               HAL_HandleEnum::Encoder>
+      eH;
+  encoderHandles = &eH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_EncoderHandle HAL_InitializeEncoder(
+    HAL_Handle digitalSourceHandleA, HAL_AnalogTriggerType analogTriggerTypeA,
+    HAL_Handle digitalSourceHandleB, HAL_AnalogTriggerType analogTriggerTypeB,
+    HAL_Bool reverseDirection, HAL_EncoderEncodingType encodingType,
+    int32_t* status) {
+  hal::init::CheckInit();
+  HAL_Handle nativeHandle = HAL_kInvalidHandle;
+  if (encodingType == HAL_EncoderEncodingType::HAL_Encoder_k4X) {
+    // k4x, allocate encoder
+    nativeHandle = fpgaEncoderHandles->Allocate();
+  } else {
+    // k2x or k1x, allocate counter
+    nativeHandle = counterHandles->Allocate();
+  }
+  if (nativeHandle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto handle = encoderHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto encoder = encoderHandles->Get(handle);
+  if (encoder == nullptr) {  // would only occur on thread issue
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  int16_t index = getHandleIndex(handle);
+  SimEncoderData[index].digitalChannelA = getHandleIndex(digitalSourceHandleA);
+  SimEncoderData[index].initialized = true;
+  SimEncoderData[index].reverseDirection = reverseDirection;
+  // TODO: Add encoding type to Sim data
+  encoder->index = index;
+  encoder->nativeHandle = nativeHandle;
+  encoder->encodingType = encodingType;
+  encoder->distancePerPulse = 1.0;
+  return handle;
+}
+
+void HAL_FreeEncoder(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  encoderHandles->Free(encoderHandle);
+  if (encoder == nullptr) return;
+  if (isHandleType(encoder->nativeHandle, HAL_HandleEnum::FPGAEncoder)) {
+    fpgaEncoderHandles->Free(encoder->nativeHandle);
+  } else if (isHandleType(encoder->nativeHandle, HAL_HandleEnum::Counter)) {
+    counterHandles->Free(encoder->nativeHandle);
+  }
+  SimEncoderData[encoder->index].initialized = false;
+}
+
+static inline int EncodingScaleFactor(Encoder* encoder) {
+  switch (encoder->encodingType) {
+    case HAL_Encoder_k1X:
+      return 1;
+    case HAL_Encoder_k2X:
+      return 2;
+    case HAL_Encoder_k4X:
+      return 4;
+    default:
+      return 0;
+  }
+}
+
+static inline double DecodingScaleFactor(Encoder* encoder) {
+  switch (encoder->encodingType) {
+    case HAL_Encoder_k1X:
+      return 1.0;
+    case HAL_Encoder_k2X:
+      return 0.5;
+    case HAL_Encoder_k4X:
+      return 0.25;
+    default:
+      return 0.0;
+  }
+}
+
+int32_t HAL_GetEncoder(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimEncoderData[encoder->index].count;
+}
+int32_t HAL_GetEncoderRaw(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimEncoderData[encoder->index].count /
+         DecodingScaleFactor(encoder.get());
+}
+int32_t HAL_GetEncoderEncodingScale(HAL_EncoderHandle encoderHandle,
+                                    int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return EncodingScaleFactor(encoder.get());
+}
+void HAL_ResetEncoder(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimEncoderData[encoder->index].count = 0;
+  SimEncoderData[encoder->index].period = std::numeric_limits<double>::max();
+  SimEncoderData[encoder->index].reset = true;
+}
+double HAL_GetEncoderPeriod(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimEncoderData[encoder->index].period;
+}
+void HAL_SetEncoderMaxPeriod(HAL_EncoderHandle encoderHandle, double maxPeriod,
+                             int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimEncoderData[encoder->index].maxPeriod = maxPeriod;
+}
+HAL_Bool HAL_GetEncoderStopped(HAL_EncoderHandle encoderHandle,
+                               int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimEncoderData[encoder->index].period >
+         SimEncoderData[encoder->index].maxPeriod;
+}
+HAL_Bool HAL_GetEncoderDirection(HAL_EncoderHandle encoderHandle,
+                                 int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimEncoderData[encoder->index].direction;
+}
+double HAL_GetEncoderDistance(HAL_EncoderHandle encoderHandle,
+                              int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimEncoderData[encoder->index].count * encoder->distancePerPulse;
+}
+double HAL_GetEncoderRate(HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return encoder->distancePerPulse / SimEncoderData[encoder->index].period;
+}
+void HAL_SetEncoderMinRate(HAL_EncoderHandle encoderHandle, double minRate,
+                           int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (minRate == 0.0) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+
+  SimEncoderData[encoder->index].maxPeriod =
+      encoder->distancePerPulse / minRate;
+}
+void HAL_SetEncoderDistancePerPulse(HAL_EncoderHandle encoderHandle,
+                                    double distancePerPulse, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  if (distancePerPulse == 0.0) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return;
+  }
+  encoder->distancePerPulse = distancePerPulse;
+  SimEncoderData[encoder->index].distancePerPulse = distancePerPulse;
+}
+void HAL_SetEncoderReverseDirection(HAL_EncoderHandle encoderHandle,
+                                    HAL_Bool reverseDirection,
+                                    int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimEncoderData[encoder->index].reverseDirection = reverseDirection;
+}
+void HAL_SetEncoderSamplesToAverage(HAL_EncoderHandle encoderHandle,
+                                    int32_t samplesToAverage, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimEncoderData[encoder->index].samplesToAverage = samplesToAverage;
+}
+int32_t HAL_GetEncoderSamplesToAverage(HAL_EncoderHandle encoderHandle,
+                                       int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimEncoderData[encoder->index].samplesToAverage;
+}
+
+void HAL_SetEncoderIndexSource(HAL_EncoderHandle encoderHandle,
+                               HAL_Handle digitalSourceHandle,
+                               HAL_AnalogTriggerType analogTriggerType,
+                               HAL_EncoderIndexingType type, int32_t* status) {
+  // Not implemented yet
+}
+
+int32_t HAL_GetEncoderFPGAIndex(HAL_EncoderHandle encoderHandle,
+                                int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return encoder->index;
+}
+
+double HAL_GetEncoderDecodingScaleFactor(HAL_EncoderHandle encoderHandle,
+                                         int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+
+  return DecodingScaleFactor(encoder.get());
+}
+
+double HAL_GetEncoderDistancePerPulse(HAL_EncoderHandle encoderHandle,
+                                      int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0.0;
+  }
+
+  return encoder->distancePerPulse;
+}
+
+HAL_EncoderEncodingType HAL_GetEncoderEncodingType(
+    HAL_EncoderHandle encoderHandle, int32_t* status) {
+  auto encoder = encoderHandles->Get(encoderHandle);
+  if (encoder == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_Encoder_k4X;  // default to k4x
+  }
+
+  return encoder->encodingType;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/ErrorsInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/ErrorsInternal.h
new file mode 100644
index 0000000..55372d8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/ErrorsInternal.h
@@ -0,0 +1,448 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+typedef enum {
+  CTR_OKAY,       // No Error - Function executed as expected
+  CTR_RxTimeout,  // CAN frame has not been received within specified period of
+                  // time.
+  CTR_TxTimeout,  // Not used.
+  CTR_InvalidParamValue,  // Caller passed an invalid param
+  CTR_UnexpectedArbId,    // Specified CAN Id is invalid.
+  CTR_TxFailed,           // Could not transmit the CAN frame.
+  CTR_SigNotUpdated,      // Have not received an value response for signal.
+  CTR_BufferFull,  // Caller attempted to insert data into a buffer that is
+                   // full.
+} CTR_Code;
+
+// VISA Error
+#define _VI_ERROR (-2147483647L - 1)
+#define VI_ERROR_SYSTEM_ERROR (_VI_ERROR + 0x3FFF0000L)
+#define VI_ERROR_INV_OBJECT (_VI_ERROR + 0x3FFF000EL)
+#define VI_ERROR_RSRC_LOCKED (_VI_ERROR + 0x3FFF000FL)
+#define VI_ERROR_INV_EXPR (_VI_ERROR + 0x3FFF0010L)
+#define VI_ERROR_RSRC_NFOUND (_VI_ERROR + 0x3FFF0011L)
+#define VI_ERROR_INV_RSRC_NAME (_VI_ERROR + 0x3FFF0012L)
+#define VI_ERROR_INV_ACC_MODE (_VI_ERROR + 0x3FFF0013L)
+#define VI_ERROR_TMO (_VI_ERROR + 0x3FFF0015L)
+#define VI_ERROR_CLOSING_FAILED (_VI_ERROR + 0x3FFF0016L)
+#define VI_ERROR_INV_DEGREE (_VI_ERROR + 0x3FFF001BL)
+#define VI_ERROR_INV_JOB_ID (_VI_ERROR + 0x3FFF001CL)
+#define VI_ERROR_NSUP_ATTR (_VI_ERROR + 0x3FFF001DL)
+#define VI_ERROR_NSUP_ATTR_STATE (_VI_ERROR + 0x3FFF001EL)
+#define VI_ERROR_ATTR_READONLY (_VI_ERROR + 0x3FFF001FL)
+#define VI_ERROR_INV_LOCK_TYPE (_VI_ERROR + 0x3FFF0020L)
+#define VI_ERROR_INV_ACCESS_KEY (_VI_ERROR + 0x3FFF0021L)
+#define VI_ERROR_INV_EVENT (_VI_ERROR + 0x3FFF0026L)
+#define VI_ERROR_INV_MECH (_VI_ERROR + 0x3FFF0027L)
+#define VI_ERROR_HNDLR_NINSTALLED (_VI_ERROR + 0x3FFF0028L)
+#define VI_ERROR_INV_HNDLR_REF (_VI_ERROR + 0x3FFF0029L)
+#define VI_ERROR_INV_CONTEXT (_VI_ERROR + 0x3FFF002AL)
+#define VI_ERROR_QUEUE_OVERFLOW (_VI_ERROR + 0x3FFF002DL)
+#define VI_ERROR_NENABLED (_VI_ERROR + 0x3FFF002FL)
+#define VI_ERROR_ABORT (_VI_ERROR + 0x3FFF0030L)
+#define VI_ERROR_RAW_WR_PROT_VIOL (_VI_ERROR + 0x3FFF0034L)
+#define VI_ERROR_RAW_RD_PROT_VIOL (_VI_ERROR + 0x3FFF0035L)
+#define VI_ERROR_OUTP_PROT_VIOL (_VI_ERROR + 0x3FFF0036L)
+#define VI_ERROR_INP_PROT_VIOL (_VI_ERROR + 0x3FFF0037L)
+#define VI_ERROR_BERR (_VI_ERROR + 0x3FFF0038L)
+#define VI_ERROR_IN_PROGRESS (_VI_ERROR + 0x3FFF0039L)
+#define VI_ERROR_INV_SETUP (_VI_ERROR + 0x3FFF003AL)
+#define VI_ERROR_QUEUE_ERROR (_VI_ERROR + 0x3FFF003BL)
+#define VI_ERROR_ALLOC (_VI_ERROR + 0x3FFF003CL)
+#define VI_ERROR_INV_MASK (_VI_ERROR + 0x3FFF003DL)
+#define VI_ERROR_IO (_VI_ERROR + 0x3FFF003EL)
+#define VI_ERROR_INV_FMT (_VI_ERROR + 0x3FFF003FL)
+#define VI_ERROR_NSUP_FMT (_VI_ERROR + 0x3FFF0041L)
+#define VI_ERROR_LINE_IN_USE (_VI_ERROR + 0x3FFF0042L)
+#define VI_ERROR_NSUP_MODE (_VI_ERROR + 0x3FFF0046L)
+#define VI_ERROR_SRQ_NOCCURRED (_VI_ERROR + 0x3FFF004AL)
+#define VI_ERROR_INV_SPACE (_VI_ERROR + 0x3FFF004EL)
+#define VI_ERROR_INV_OFFSET (_VI_ERROR + 0x3FFF0051L)
+#define VI_ERROR_INV_WIDTH (_VI_ERROR + 0x3FFF0052L)
+#define VI_ERROR_NSUP_OFFSET (_VI_ERROR + 0x3FFF0054L)
+#define VI_ERROR_NSUP_VAR_WIDTH (_VI_ERROR + 0x3FFF0055L)
+#define VI_ERROR_WINDOW_NMAPPED (_VI_ERROR + 0x3FFF0057L)
+#define VI_ERROR_RESP_PENDING (_VI_ERROR + 0x3FFF0059L)
+#define VI_ERROR_NLISTENERS (_VI_ERROR + 0x3FFF005FL)
+#define VI_ERROR_NCIC (_VI_ERROR + 0x3FFF0060L)
+#define VI_ERROR_NSYS_CNTLR (_VI_ERROR + 0x3FFF0061L)
+#define VI_ERROR_NSUP_OPER (_VI_ERROR + 0x3FFF0067L)
+#define VI_ERROR_INTR_PENDING (_VI_ERROR + 0x3FFF0068L)
+#define VI_ERROR_ASRL_PARITY (_VI_ERROR + 0x3FFF006AL)
+#define VI_ERROR_ASRL_FRAMING (_VI_ERROR + 0x3FFF006BL)
+#define VI_ERROR_ASRL_OVERRUN (_VI_ERROR + 0x3FFF006CL)
+#define VI_ERROR_TRIG_NMAPPED (_VI_ERROR + 0x3FFF006EL)
+#define VI_ERROR_NSUP_ALIGN_OFFSET (_VI_ERROR + 0x3FFF0070L)
+#define VI_ERROR_USER_BUF (_VI_ERROR + 0x3FFF0071L)
+#define VI_ERROR_RSRC_BUSY (_VI_ERROR + 0x3FFF0072L)
+#define VI_ERROR_NSUP_WIDTH (_VI_ERROR + 0x3FFF0076L)
+#define VI_ERROR_INV_PARAMETER (_VI_ERROR + 0x3FFF0078L)
+#define VI_ERROR_INV_PROT (_VI_ERROR + 0x3FFF0079L)
+#define VI_ERROR_INV_SIZE (_VI_ERROR + 0x3FFF007BL)
+#define VI_ERROR_WINDOW_MAPPED (_VI_ERROR + 0x3FFF0080L)
+#define VI_ERROR_NIMPL_OPER (_VI_ERROR + 0x3FFF0081L)
+#define VI_ERROR_INV_LENGTH (_VI_ERROR + 0x3FFF0083L)
+#define VI_ERROR_INV_MODE (_VI_ERROR + 0x3FFF0091L)
+#define VI_ERROR_SESN_NLOCKED (_VI_ERROR + 0x3FFF009CL)
+#define VI_ERROR_MEM_NSHARED (_VI_ERROR + 0x3FFF009DL)
+#define VI_ERROR_LIBRARY_NFOUND (_VI_ERROR + 0x3FFF009EL)
+#define VI_ERROR_NSUP_INTR (_VI_ERROR + 0x3FFF009FL)
+#define VI_ERROR_INV_LINE (_VI_ERROR + 0x3FFF00A0L)
+#define VI_ERROR_FILE_ACCESS (_VI_ERROR + 0x3FFF00A1L)
+#define VI_ERROR_FILE_IO (_VI_ERROR + 0x3FFF00A2L)
+#define VI_ERROR_NSUP_LINE (_VI_ERROR + 0x3FFF00A3L)
+#define VI_ERROR_NSUP_MECH (_VI_ERROR + 0x3FFF00A4L)
+#define VI_ERROR_INTF_NUM_NCONFIG (_VI_ERROR + 0x3FFF00A5L)
+#define VI_ERROR_CONN_LOST (_VI_ERROR + 0x3FFF00A6L)
+#define VI_ERROR_MACHINE_NAVAIL (_VI_ERROR + 0x3FFF00A7L)
+#define VI_ERROR_NPERMISSION (_VI_ERROR + 0x3FFF00A8L)
+
+// FPGA Errors
+
+/**
+ * Represents the resulting status of a function call through its return value.
+ * 0 is success, negative values are errors, and positive values are warnings.
+ */
+typedef int32_t NiFpga_Status;
+
+/**
+ * No errors or warnings.
+ */
+static const NiFpga_Status NiFpga_Status_Success = 0;
+
+/**
+ * The timeout expired before the FIFO operation could complete.
+ */
+static const NiFpga_Status NiFpga_Status_FifoTimeout = -50400;
+
+/**
+ * No transfer is in progress because the transfer was aborted by the client.
+ * The operation could not be completed as specified.
+ */
+static const NiFpga_Status NiFpga_Status_TransferAborted = -50405;
+
+/**
+ * A memory allocation failed. Try again after rebooting.
+ */
+static const NiFpga_Status NiFpga_Status_MemoryFull = -52000;
+
+/**
+ * An unexpected software error occurred.
+ */
+static const NiFpga_Status NiFpga_Status_SoftwareFault = -52003;
+
+/**
+ * A parameter to a function was not valid. This could be a NULL pointer, a bad
+ * value, etc.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidParameter = -52005;
+
+/**
+ * A required resource was not found. The NiFpga.* library, the RIO resource, or
+ * some other resource may be missing.
+ */
+static const NiFpga_Status NiFpga_Status_ResourceNotFound = -52006;
+
+/**
+ * A required resource was not properly initialized. This could occur if
+ * NiFpga_Initialize was not called or a required NiFpga_IrqContext was not
+ * reserved.
+ */
+static const NiFpga_Status NiFpga_Status_ResourceNotInitialized = -52010;
+
+/**
+ * A hardware failure has occurred. The operation could not be completed as
+ * specified.
+ */
+static const NiFpga_Status NiFpga_Status_HardwareFault = -52018;
+
+/**
+ * The FPGA is already running.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaAlreadyRunning = -61003;
+
+/**
+ * An error occurred downloading the VI to the FPGA device. Verify that
+ * the target is connected and powered and that the resource of the target
+ * is properly configured.
+ */
+static const NiFpga_Status NiFpga_Status_DownloadError = -61018;
+
+/**
+ * The bitfile was not compiled for the specified resource's device type.
+ */
+static const NiFpga_Status NiFpga_Status_DeviceTypeMismatch = -61024;
+
+/**
+ * An error was detected in the communication between the host computer and the
+ * FPGA target.
+ */
+static const NiFpga_Status NiFpga_Status_CommunicationTimeout = -61046;
+
+/**
+ * The timeout expired before any of the IRQs were asserted.
+ */
+static const NiFpga_Status NiFpga_Status_IrqTimeout = -61060;
+
+/**
+ * The specified bitfile is invalid or corrupt.
+ */
+static const NiFpga_Status NiFpga_Status_CorruptBitfile = -61070;
+
+/**
+ * The requested FIFO depth is invalid. It is either 0 or an amount not
+ * supported by the hardware.
+ */
+static const NiFpga_Status NiFpga_Status_BadDepth = -61072;
+
+/**
+ * The number of FIFO elements is invalid. Either the number is greater than the
+ * depth of the host memory DMA FIFO, or more elements were requested for
+ * release than had been acquired.
+ */
+static const NiFpga_Status NiFpga_Status_BadReadWriteCount = -61073;
+
+/**
+ * A hardware clocking error occurred. A derived clock lost lock with its base
+ * clock during the execution of the LabVIEW FPGA VI. If any base clocks with
+ * derived clocks are referencing an external source, make sure that the
+ * external source is connected and within the supported frequency, jitter,
+ * accuracy, duty cycle, and voltage specifications. Also verify that the
+ * characteristics of the base clock match the configuration specified in the
+ * FPGA Base Clock Properties. If all base clocks with derived clocks are
+ * generated from free-running, on-board sources, please contact National
+ * Instruments technical support at ni.com/support.
+ */
+static const NiFpga_Status NiFpga_Status_ClockLostLock = -61083;
+
+/**
+ * The operation could not be performed because the FPGA is busy. Stop all
+ * activities on the FPGA before requesting this operation. If the target is in
+ * Scan Interface programming mode, put it in FPGA Interface programming mode.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusy = -61141;
+
+/**
+ * The operation could not be performed because the FPGA is busy operating in
+ * FPGA Interface C API mode. Stop all activities on the FPGA before requesting
+ * this operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyFpgaInterfaceCApi = -61200;
+
+/**
+ * The chassis is in Scan Interface programming mode. In order to run FPGA VIs,
+ * you must go to the chassis properties page, select FPGA programming mode, and
+ * deploy settings.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyScanInterface = -61201;
+
+/**
+ * The operation could not be performed because the FPGA is busy operating in
+ * FPGA Interface mode. Stop all activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyFpgaInterface = -61202;
+
+/**
+ * The operation could not be performed because the FPGA is busy operating in
+ * Interactive mode. Stop all activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyInteractive = -61203;
+
+/**
+ * The operation could not be performed because the FPGA is busy operating in
+ * Emulation mode. Stop all activities on the FPGA before requesting this
+ * operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyEmulation = -61204;
+
+/**
+ * LabVIEW FPGA does not support the Reset method for bitfiles that allow
+ * removal of implicit enable signals in single-cycle Timed Loops.
+ */
+static const NiFpga_Status NiFpga_Status_ResetCalledWithImplicitEnableRemoval =
+    -61211;
+
+/**
+ * LabVIEW FPGA does not support the Abort method for bitfiles that allow
+ * removal of implicit enable signals in single-cycle Timed Loops.
+ */
+static const NiFpga_Status NiFpga_Status_AbortCalledWithImplicitEnableRemoval =
+    -61212;
+
+/**
+ * LabVIEW FPGA does not support Close and Reset if Last Reference for bitfiles
+ * that allow removal of implicit enable signals in single-cycle Timed Loops.
+ * Pass the NiFpga_CloseAttribute_NoResetIfLastSession attribute to NiFpga_Close
+ * instead of 0.
+ */
+static const NiFpga_Status
+    NiFpga_Status_CloseAndResetCalledWithImplicitEnableRemoval = -61213;
+
+/**
+ * For bitfiles that allow removal of implicit enable signals in single-cycle
+ * Timed Loops, LabVIEW FPGA does not support this method prior to running the
+ * bitfile.
+ */
+static const NiFpga_Status NiFpga_Status_ImplicitEnableRemovalButNotYetRun =
+    -61214;
+
+/**
+ * Bitfiles that allow removal of implicit enable signals in single-cycle Timed
+ * Loops can run only once. Download the bitfile again before re-running the VI.
+ */
+static const NiFpga_Status
+    NiFpga_Status_RunAfterStoppedCalledWithImplicitEnableRemoval = -61215;
+
+/**
+ * A gated clock has violated the handshaking protocol. If you are using
+ * external gated clocks, ensure that they follow the required clock gating
+ * protocol. If you are generating your clocks internally, please contact
+ * National Instruments Technical Support.
+ */
+static const NiFpga_Status NiFpga_Status_GatedClockHandshakingViolation =
+    -61216;
+
+/**
+ * The number of elements requested must be less than or equal to the number of
+ * unacquired elements left in the host memory DMA FIFO. There are currently
+ * fewer unacquired elements left in the FIFO than are being requested. Release
+ * some acquired elements before acquiring more elements.
+ */
+static const NiFpga_Status NiFpga_Status_ElementsNotPermissibleToBeAcquired =
+    -61219;
+
+/**
+ * The operation could not be performed because the FPGA is in configuration or
+ * discovery mode. Wait for configuration or discovery to complete and retry
+ * your operation.
+ */
+static const NiFpga_Status NiFpga_Status_FpgaBusyConfiguration = -61252;
+
+/**
+ * An unexpected internal error occurred.
+ */
+static const NiFpga_Status NiFpga_Status_InternalError = -61499;
+
+/**
+ * The NI-RIO driver was unable to allocate memory for a FIFO. This can happen
+ * when the combined depth of all DMA FIFOs exceeds the maximum depth for the
+ * controller, or when the controller runs out of system memory. You may be able
+ * to reconfigure the controller with a greater maximum FIFO depth. For more
+ * information, refer to the NI KnowledgeBase article 65OF2ERQ.
+ */
+static const NiFpga_Status NiFpga_Status_TotalDmaFifoDepthExceeded = -63003;
+
+/**
+ * Access to the remote system was denied. Use MAX to check the Remote Device
+ * Access settings under Software>>NI-RIO>>NI-RIO Settings on the remote system.
+ */
+static const NiFpga_Status NiFpga_Status_AccessDenied = -63033;
+
+/**
+ * The NI-RIO software on the host is not compatible with the software on the
+ * target. Upgrade the NI-RIO software on the host in order to connect to this
+ * target.
+ */
+static const NiFpga_Status NiFpga_Status_HostVersionMismatch = -63038;
+
+/**
+ * A connection could not be established to the specified remote device. Ensure
+ * that the device is on and accessible over the network, that NI-RIO software
+ * is installed, and that the RIO server is running and properly configured.
+ */
+static const NiFpga_Status NiFpga_Status_RpcConnectionError = -63040;
+
+/**
+ * The RPC session is invalid. The target may have reset or been rebooted. Check
+ * the network connection and retry the operation.
+ */
+static const NiFpga_Status NiFpga_Status_RpcSessionError = -63043;
+
+/**
+ * The operation could not complete because another session is accessing the
+ * FIFO. Close the other session and retry.
+ */
+static const NiFpga_Status NiFpga_Status_FifoReserved = -63082;
+
+/**
+ * A Configure FIFO, Stop FIFO, Read FIFO, or Write FIFO function was called
+ * while the host had acquired elements of the FIFO. Release all acquired
+ * elements before configuring, stopping, reading, or writing.
+ */
+static const NiFpga_Status NiFpga_Status_FifoElementsCurrentlyAcquired = -63083;
+
+/**
+ * A function was called using a misaligned address. The address must be a
+ * multiple of the size of the datatype.
+ */
+static const NiFpga_Status NiFpga_Status_MisalignedAccess = -63084;
+
+/**
+ * The FPGA Read/Write Control Function is accessing a control or indicator
+ * with data that exceeds the maximum size supported on the current target.
+ * Refer to the hardware documentation for the limitations on data types for
+ * this target.
+ */
+static const NiFpga_Status NiFpga_Status_ControlOrIndicatorTooLarge = -63085;
+
+/**
+ * A valid .lvbitx bitfile is required. If you are using a valid .lvbitx
+ * bitfile, the bitfile may not be compatible with the software you are using.
+ * Determine which version of LabVIEW was used to make the bitfile, update your
+ * software to that version or later, and try again.
+ */
+static const NiFpga_Status NiFpga_Status_BitfileReadError = -63101;
+
+/**
+ * The specified signature does not match the signature of the bitfile. If the
+ * bitfile has been recompiled, regenerate the C API and rebuild the
+ * application.
+ */
+static const NiFpga_Status NiFpga_Status_SignatureMismatch = -63106;
+
+/**
+ * The bitfile you are trying to use is incompatible with the version
+ * of NI-RIO installed on the target and/or host. Update the version
+ * of NI-RIO on the target and/or host to the same version (or later)
+ * used to compile the bitfile. Alternatively, recompile the bitfile
+ * with the same version of NI-RIO that is currently installed on the
+ * target and/or host.
+ */
+static const NiFpga_Status NiFpga_Status_IncompatibleBitfile = -63107;
+
+/**
+ * Either the supplied resource name is invalid as a RIO resource name, or the
+ * device was not found. Use MAX to find the proper resource name for the
+ * intended device.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidResourceName = -63192;
+
+/**
+ * The requested feature is not supported.
+ */
+static const NiFpga_Status NiFpga_Status_FeatureNotSupported = -63193;
+
+/**
+ * The NI-RIO software on the target system is not compatible with this
+ * software. Upgrade the NI-RIO software on the target system.
+ */
+static const NiFpga_Status NiFpga_Status_VersionMismatch = -63194;
+
+/**
+ * The session is invalid or has been closed.
+ */
+static const NiFpga_Status NiFpga_Status_InvalidSession = -63195;
+
+/**
+ * The maximum number of open FPGA sessions has been reached. Close some open
+ * sessions.
+ */
+static const NiFpga_Status NiFpga_Status_OutOfHandles = -63198;
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Extensions.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Extensions.cpp
new file mode 100644
index 0000000..6ef7903
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Extensions.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/Extensions.h"
+
+#include <wpi/SmallString.h>
+#include <wpi/StringRef.h>
+
+#include "hal/HAL.h"
+
+#if defined(WIN32) || defined(_WIN32)
+#include <windows.h>
+#else
+#include <dlfcn.h>
+#endif
+
+#if defined(WIN32) || defined(_WIN32)
+#define DELIM ';'
+#define HTYPE HMODULE
+#define DLOPEN(a) LoadLibrary(a)
+#define DLSYM GetProcAddress
+#define DLCLOSE FreeLibrary
+#else
+#define DELIM ':'
+#define HTYPE void*
+#define PREFIX "lib"
+#define DLOPEN(a) dlopen(a, RTLD_LAZY)
+#define DLSYM dlsym
+#define DLCLOSE dlclose
+#endif
+
+namespace hal {
+namespace init {
+void InitializeExtensions() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+int HAL_LoadOneExtension(const char* library) {
+  int rc = 1;  // It is expected and reasonable not to find an extra simulation
+  HTYPE handle = DLOPEN(library);
+#if !defined(WIN32) && !defined(_WIN32)
+  if (!handle) {
+    wpi::SmallString<128> libraryName("lib");
+    libraryName += library;
+#if defined(__APPLE__)
+    libraryName += ".dylib";
+#else
+    libraryName += ".so";
+#endif
+    handle = DLOPEN(libraryName.c_str());
+  }
+#endif
+  if (!handle) return rc;
+
+  auto init = reinterpret_cast<halsim_extension_init_func_t*>(
+      DLSYM(handle, "HALSIM_InitExtension"));
+
+  if (init) rc = (*init)();
+
+  if (rc != 0) DLCLOSE(handle);
+  return rc;
+}
+
+int HAL_LoadExtensions(void) {
+  int rc = 1;
+  wpi::SmallVector<wpi::StringRef, 2> libraries;
+  const char* e = std::getenv("HALSIM_EXTENSIONS");
+  if (!e) return rc;
+  wpi::StringRef env{e};
+  env.split(libraries, DELIM, -1, false);
+  for (auto& libref : libraries) {
+    wpi::SmallString<128> library(libref);
+    rc = HAL_LoadOneExtension(library.c_str());
+    if (rc < 0) break;
+  }
+  return rc;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/HAL.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/HAL.cpp
new file mode 100644
index 0000000..d058c1a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/HAL.cpp
@@ -0,0 +1,256 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/HAL.h"
+
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "ErrorsInternal.h"
+#include "HALInitializer.h"
+#include "MockHooksInternal.h"
+#include "hal/DriverStation.h"
+#include "hal/Errors.h"
+#include "hal/Extensions.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/RoboRioDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeHAL() {
+  InitializeAccelerometerData();
+  InitializeAnalogGyroData();
+  InitializeAnalogInData();
+  InitializeAnalogOutData();
+  InitializeAnalogTriggerData();
+  InitializeCanData();
+  InitializeCANAPI();
+  InitializeDigitalPWMData();
+  InitializeDIOData();
+  InitializeDriverStationData();
+  InitializeEncoderData();
+  InitializeI2CData();
+  InitializePCMData();
+  InitializePDPData();
+  InitializePWMData();
+  InitializeRelayData();
+  InitializeRoboRioData();
+  InitializeSPIAccelerometerData();
+  InitializeSPIData();
+  InitializeAccelerometer();
+  InitializeAnalogAccumulator();
+  InitializeAnalogGyro();
+  InitializeAnalogInput();
+  InitializeAnalogInternal();
+  InitializeAnalogOutput();
+  InitializeCAN();
+  InitializeCompressor();
+  InitializeConstants();
+  InitializeCounter();
+  InitializeDigitalInternal();
+  InitializeDIO();
+  InitializeDriverStation();
+  InitializeEncoder();
+  InitializeExtensions();
+  InitializeI2C();
+  InitializeInterrupts();
+  InitializeMockHooks();
+  InitializeNotifier();
+  InitializePDP();
+  InitializePorts();
+  InitializePower();
+  InitializePWM();
+  InitializeRelay();
+  InitializeSerialPort();
+  InitializeSolenoid();
+  InitializeSPI();
+  InitializeThreads();
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_PortHandle HAL_GetPort(int32_t channel) {
+  // Dont allow a number that wouldn't fit in a uint8_t
+  if (channel < 0 || channel >= 255) return HAL_kInvalidHandle;
+  return createPortHandle(channel, 1);
+}
+
+HAL_PortHandle HAL_GetPortWithModule(int32_t module, int32_t channel) {
+  // Dont allow a number that wouldn't fit in a uint8_t
+  if (channel < 0 || channel >= 255) return HAL_kInvalidHandle;
+  if (module < 0 || module >= 255) return HAL_kInvalidHandle;
+  return createPortHandle(channel, module);
+}
+
+const char* HAL_GetErrorMessage(int32_t code) {
+  switch (code) {
+    case 0:
+      return "";
+    case CTR_RxTimeout:
+      return CTR_RxTimeout_MESSAGE;
+    case CTR_TxTimeout:
+      return CTR_TxTimeout_MESSAGE;
+    case CTR_InvalidParamValue:
+      return CTR_InvalidParamValue_MESSAGE;
+    case CTR_UnexpectedArbId:
+      return CTR_UnexpectedArbId_MESSAGE;
+    case CTR_TxFailed:
+      return CTR_TxFailed_MESSAGE;
+    case CTR_SigNotUpdated:
+      return CTR_SigNotUpdated_MESSAGE;
+    case NiFpga_Status_FifoTimeout:
+      return NiFpga_Status_FifoTimeout_MESSAGE;
+    case NiFpga_Status_TransferAborted:
+      return NiFpga_Status_TransferAborted_MESSAGE;
+    case NiFpga_Status_MemoryFull:
+      return NiFpga_Status_MemoryFull_MESSAGE;
+    case NiFpga_Status_SoftwareFault:
+      return NiFpga_Status_SoftwareFault_MESSAGE;
+    case NiFpga_Status_InvalidParameter:
+      return NiFpga_Status_InvalidParameter_MESSAGE;
+    case NiFpga_Status_ResourceNotFound:
+      return NiFpga_Status_ResourceNotFound_MESSAGE;
+    case NiFpga_Status_ResourceNotInitialized:
+      return NiFpga_Status_ResourceNotInitialized_MESSAGE;
+    case NiFpga_Status_HardwareFault:
+      return NiFpga_Status_HardwareFault_MESSAGE;
+    case NiFpga_Status_IrqTimeout:
+      return NiFpga_Status_IrqTimeout_MESSAGE;
+    case SAMPLE_RATE_TOO_HIGH:
+      return SAMPLE_RATE_TOO_HIGH_MESSAGE;
+    case VOLTAGE_OUT_OF_RANGE:
+      return VOLTAGE_OUT_OF_RANGE_MESSAGE;
+    case LOOP_TIMING_ERROR:
+      return LOOP_TIMING_ERROR_MESSAGE;
+    case SPI_WRITE_NO_MOSI:
+      return SPI_WRITE_NO_MOSI_MESSAGE;
+    case SPI_READ_NO_MISO:
+      return SPI_READ_NO_MISO_MESSAGE;
+    case SPI_READ_NO_DATA:
+      return SPI_READ_NO_DATA_MESSAGE;
+    case INCOMPATIBLE_STATE:
+      return INCOMPATIBLE_STATE_MESSAGE;
+    case NO_AVAILABLE_RESOURCES:
+      return NO_AVAILABLE_RESOURCES_MESSAGE;
+    case RESOURCE_IS_ALLOCATED:
+      return RESOURCE_IS_ALLOCATED_MESSAGE;
+    case RESOURCE_OUT_OF_RANGE:
+      return RESOURCE_OUT_OF_RANGE_MESSAGE;
+    case HAL_INVALID_ACCUMULATOR_CHANNEL:
+      return HAL_INVALID_ACCUMULATOR_CHANNEL_MESSAGE;
+    case HAL_HANDLE_ERROR:
+      return HAL_HANDLE_ERROR_MESSAGE;
+    case NULL_PARAMETER:
+      return NULL_PARAMETER_MESSAGE;
+    case ANALOG_TRIGGER_LIMIT_ORDER_ERROR:
+      return ANALOG_TRIGGER_LIMIT_ORDER_ERROR_MESSAGE;
+    case ANALOG_TRIGGER_PULSE_OUTPUT_ERROR:
+      return ANALOG_TRIGGER_PULSE_OUTPUT_ERROR_MESSAGE;
+    case PARAMETER_OUT_OF_RANGE:
+      return PARAMETER_OUT_OF_RANGE_MESSAGE;
+    case HAL_COUNTER_NOT_SUPPORTED:
+      return HAL_COUNTER_NOT_SUPPORTED_MESSAGE;
+    case HAL_ERR_CANSessionMux_InvalidBuffer:
+      return ERR_CANSessionMux_InvalidBuffer_MESSAGE;
+    case HAL_ERR_CANSessionMux_MessageNotFound:
+      return ERR_CANSessionMux_MessageNotFound_MESSAGE;
+    case HAL_WARN_CANSessionMux_NoToken:
+      return WARN_CANSessionMux_NoToken_MESSAGE;
+    case HAL_ERR_CANSessionMux_NotAllowed:
+      return ERR_CANSessionMux_NotAllowed_MESSAGE;
+    case HAL_ERR_CANSessionMux_NotInitialized:
+      return ERR_CANSessionMux_NotInitialized_MESSAGE;
+    case VI_ERROR_SYSTEM_ERROR:
+      return VI_ERROR_SYSTEM_ERROR_MESSAGE;
+    case VI_ERROR_INV_OBJECT:
+      return VI_ERROR_INV_OBJECT_MESSAGE;
+    case VI_ERROR_RSRC_LOCKED:
+      return VI_ERROR_RSRC_LOCKED_MESSAGE;
+    case VI_ERROR_RSRC_NFOUND:
+      return VI_ERROR_RSRC_NFOUND_MESSAGE;
+    case VI_ERROR_INV_RSRC_NAME:
+      return VI_ERROR_INV_RSRC_NAME_MESSAGE;
+    case VI_ERROR_QUEUE_OVERFLOW:
+      return VI_ERROR_QUEUE_OVERFLOW_MESSAGE;
+    case VI_ERROR_IO:
+      return VI_ERROR_IO_MESSAGE;
+    case VI_ERROR_ASRL_PARITY:
+      return VI_ERROR_ASRL_PARITY_MESSAGE;
+    case VI_ERROR_ASRL_FRAMING:
+      return VI_ERROR_ASRL_FRAMING_MESSAGE;
+    case VI_ERROR_ASRL_OVERRUN:
+      return VI_ERROR_ASRL_OVERRUN_MESSAGE;
+    case VI_ERROR_RSRC_BUSY:
+      return VI_ERROR_RSRC_BUSY_MESSAGE;
+    case VI_ERROR_INV_PARAMETER:
+      return VI_ERROR_INV_PARAMETER_MESSAGE;
+    case HAL_PWM_SCALE_ERROR:
+      return HAL_PWM_SCALE_ERROR_MESSAGE;
+    case HAL_CAN_TIMEOUT:
+      return HAL_CAN_TIMEOUT_MESSAGE;
+    default:
+      return "Unknown error status";
+  }
+}
+
+HAL_RuntimeType HAL_GetRuntimeType(void) { return HAL_Mock; }
+
+int32_t HAL_GetFPGAVersion(int32_t* status) {
+  return 2018;  // Automatically script this at some point
+}
+
+int64_t HAL_GetFPGARevision(int32_t* status) {
+  return 0;  // TODO: Find a better number to return;
+}
+
+uint64_t HAL_GetFPGATime(int32_t* status) { return hal::GetFPGATime(); }
+
+HAL_Bool HAL_GetFPGAButton(int32_t* status) {
+  return SimRoboRioData[0].fpgaButton;
+}
+
+HAL_Bool HAL_GetSystemActive(int32_t* status) {
+  return true;  // Figure out if we need to handle this
+}
+
+HAL_Bool HAL_GetBrownedOut(int32_t* status) {
+  return false;  // Figure out if we need to detect a brownout condition
+}
+
+HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) {
+  static std::atomic_bool initialized{false};
+  static wpi::mutex initializeMutex;
+  // Initial check, as if it's true initialization has finished
+  if (initialized) return true;
+
+  std::lock_guard<wpi::mutex> lock(initializeMutex);
+  // Second check in case another thread was waiting
+  if (initialized) return true;
+
+  hal::init::InitializeHAL();
+
+  hal::init::HAL_IsInitialized.store(true);
+
+  wpi::outs().SetUnbuffered();
+  if (HAL_LoadExtensions() < 0) return false;
+  hal::RestartTiming();
+  HAL_InitializeDriverStation();
+
+  initialized = true;
+  return true;  // Add initialization if we need to at a later point
+}
+
+int64_t HAL_Report(int32_t resource, int32_t instanceNumber, int32_t context,
+                   const char* feature) {
+  return 0;  // Do nothing for now
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/HALInitializer.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/HALInitializer.cpp
new file mode 100644
index 0000000..a0456d4
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/HALInitializer.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "HALInitializer.h"
+
+#include "hal/HAL.h"
+
+namespace hal {
+namespace init {
+std::atomic_bool HAL_IsInitialized{false};
+void RunInitialize() { HAL_Initialize(500, 0); }
+}  // namespace init
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/HALInitializer.h b/third_party/allwpilib_2019/hal/src/main/native/sim/HALInitializer.h
new file mode 100644
index 0000000..d369a3b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/HALInitializer.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+
+namespace hal {
+namespace init {
+extern std::atomic_bool HAL_IsInitialized;
+extern void RunInitialize();
+static inline void CheckInit() {
+  if (HAL_IsInitialized.load(std::memory_order_relaxed)) return;
+  RunInitialize();
+}
+
+extern void InitializeAccelerometerData();
+extern void InitializeAnalogGyroData();
+extern void InitializeAnalogInData();
+extern void InitializeAnalogOutData();
+extern void InitializeAnalogTriggerData();
+extern void InitializeCanData();
+extern void InitializeCANAPI();
+extern void InitializeDigitalPWMData();
+extern void InitializeDIOData();
+extern void InitializeDriverStationData();
+extern void InitializeEncoderData();
+extern void InitializeI2CData();
+extern void InitializePCMData();
+extern void InitializePDPData();
+extern void InitializePWMData();
+extern void InitializeRelayData();
+extern void InitializeRoboRioData();
+extern void InitializeSPIAccelerometerData();
+extern void InitializeSPIData();
+extern void InitializeAccelerometer();
+extern void InitializeAnalogAccumulator();
+extern void InitializeAnalogGyro();
+extern void InitializeAnalogInput();
+extern void InitializeAnalogInternal();
+extern void InitializeAnalogOutput();
+extern void InitializeCAN();
+extern void InitializeCompressor();
+extern void InitializeConstants();
+extern void InitializeCounter();
+extern void InitializeDigitalInternal();
+extern void InitializeDIO();
+extern void InitializeDriverStation();
+extern void InitializeEncoder();
+extern void InitializeExtensions();
+extern void InitializeHAL();
+extern void InitializeI2C();
+extern void InitializeInterrupts();
+extern void InitializeMockHooks();
+extern void InitializeNotifier();
+extern void InitializePDP();
+extern void InitializePorts();
+extern void InitializePower();
+extern void InitializePWM();
+extern void InitializeRelay();
+extern void InitializeSerialPort();
+extern void InitializeSolenoid();
+extern void InitializeSPI();
+extern void InitializeThreads();
+
+}  // namespace init
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/I2C.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/I2C.cpp
new file mode 100644
index 0000000..fe4952f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/I2C.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/I2C.h"
+
+#include "HALInitializer.h"
+#include "mockdata/I2CDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeI2C() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+void HAL_InitializeI2C(HAL_I2CPort port, int32_t* status) {
+  hal::init::CheckInit();
+  SimI2CData[port].initialized = true;
+}
+int32_t HAL_TransactionI2C(HAL_I2CPort port, int32_t deviceAddress,
+                           const uint8_t* dataToSend, int32_t sendSize,
+                           uint8_t* dataReceived, int32_t receiveSize) {
+  SimI2CData[port].Write(deviceAddress, dataToSend, sendSize);
+  SimI2CData[port].Read(deviceAddress, dataReceived, receiveSize);
+  return 0;
+}
+int32_t HAL_WriteI2C(HAL_I2CPort port, int32_t deviceAddress,
+                     const uint8_t* dataToSend, int32_t sendSize) {
+  SimI2CData[port].Write(deviceAddress, dataToSend, sendSize);
+  return 0;
+}
+int32_t HAL_ReadI2C(HAL_I2CPort port, int32_t deviceAddress, uint8_t* buffer,
+                    int32_t count) {
+  SimI2CData[port].Read(deviceAddress, buffer, count);
+  return 0;
+}
+void HAL_CloseI2C(HAL_I2CPort port) { SimI2CData[port].initialized = false; }
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Interrupts.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Interrupts.cpp
new file mode 100644
index 0000000..75247ca
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Interrupts.cpp
@@ -0,0 +1,565 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/Interrupts.h"
+
+#include <memory>
+
+#include <wpi/condition_variable.h>
+
+#include "AnalogInternal.h"
+#include "DigitalInternal.h"
+#include "ErrorsInternal.h"
+#include "HALInitializer.h"
+#include "MockHooksInternal.h"
+#include "PortsInternal.h"
+#include "hal/AnalogTrigger.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/LimitedHandleResource.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/AnalogInDataInternal.h"
+#include "mockdata/DIODataInternal.h"
+#include "mockdata/HAL_Value.h"
+
+using namespace hal;
+
+enum WaitResult {
+  Timeout = 0x0,
+  RisingEdge = 0x1,
+  FallingEdge = 0x100,
+  Both = 0x101,
+};
+
+namespace {
+struct Interrupt {
+  bool isAnalog;
+  HAL_Handle portHandle;
+  uint8_t index;
+  HAL_AnalogTriggerType trigType;
+  bool watcher;
+  int64_t risingTimestamp;
+  int64_t fallingTimestamp;
+  bool previousState;
+  bool fireOnUp;
+  bool fireOnDown;
+  int32_t callbackId;
+
+  void* callbackParam;
+  HAL_InterruptHandlerFunction callbackFunction;
+};
+
+struct SynchronousWaitData {
+  HAL_InterruptHandle interruptHandle;
+  wpi::condition_variable waitCond;
+  HAL_Bool waitPredicate;
+};
+}  // namespace
+
+static LimitedHandleResource<HAL_InterruptHandle, Interrupt, kNumInterrupts,
+                             HAL_HandleEnum::Interrupt>* interruptHandles;
+
+typedef HAL_Handle SynchronousWaitDataHandle;
+static UnlimitedHandleResource<SynchronousWaitDataHandle, SynchronousWaitData,
+                               HAL_HandleEnum::Vendor>*
+    synchronousInterruptHandles;
+
+namespace hal {
+namespace init {
+void InitializeInterrupts() {
+  static LimitedHandleResource<HAL_InterruptHandle, Interrupt, kNumInterrupts,
+                               HAL_HandleEnum::Interrupt>
+      iH;
+  interruptHandles = &iH;
+  static UnlimitedHandleResource<SynchronousWaitDataHandle, SynchronousWaitData,
+                                 HAL_HandleEnum::Vendor>
+      siH;
+  synchronousInterruptHandles = &siH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_InterruptHandle HAL_InitializeInterrupts(HAL_Bool watcher,
+                                             int32_t* status) {
+  hal::init::CheckInit();
+  HAL_InterruptHandle handle = interruptHandles->Allocate();
+  if (handle == HAL_kInvalidHandle) {
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto anInterrupt = interruptHandles->Get(handle);
+  if (anInterrupt == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  anInterrupt->index = getHandleIndex(handle);
+  anInterrupt->callbackId = -1;
+
+  anInterrupt->watcher = watcher;
+
+  return handle;
+}
+void* HAL_CleanInterrupts(HAL_InterruptHandle interruptHandle,
+                          int32_t* status) {
+  HAL_DisableInterrupts(interruptHandle, status);
+  auto anInterrupt = interruptHandles->Get(interruptHandle);
+  interruptHandles->Free(interruptHandle);
+  if (anInterrupt == nullptr) {
+    return nullptr;
+  }
+  return anInterrupt->callbackParam;
+}
+
+static void ProcessInterruptDigitalSynchronous(const char* name, void* param,
+                                               const struct HAL_Value* value) {
+  // void* is a SynchronousWaitDataHandle.
+  // convert to uintptr_t first, then to handle
+  uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+  SynchronousWaitDataHandle handle =
+      static_cast<SynchronousWaitDataHandle>(handleTmp);
+  auto interruptData = synchronousInterruptHandles->Get(handle);
+  if (interruptData == nullptr) return;
+  auto interrupt = interruptHandles->Get(interruptData->interruptHandle);
+  if (interrupt == nullptr) return;
+  // Have a valid interrupt
+  if (value->type != HAL_Type::HAL_BOOLEAN) return;
+  bool retVal = value->data.v_boolean;
+  // If no change in interrupt, return;
+  if (retVal == interrupt->previousState) return;
+  // If its a falling change, and we dont fire on falling return
+  if (interrupt->previousState && !interrupt->fireOnDown) return;
+  // If its a rising change, and we dont fire on rising return.
+  if (!interrupt->previousState && !interrupt->fireOnUp) return;
+
+  interruptData->waitPredicate = true;
+
+  // Pulse interrupt
+  interruptData->waitCond.notify_all();
+}
+
+static double GetAnalogTriggerValue(HAL_Handle triggerHandle,
+                                    HAL_AnalogTriggerType type,
+                                    int32_t* status) {
+  return HAL_GetAnalogTriggerOutput(triggerHandle, type, status);
+}
+
+static void ProcessInterruptAnalogSynchronous(const char* name, void* param,
+                                              const struct HAL_Value* value) {
+  // void* is a SynchronousWaitDataHandle.
+  // convert to uintptr_t first, then to handle
+  uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+  SynchronousWaitDataHandle handle =
+      static_cast<SynchronousWaitDataHandle>(handleTmp);
+  auto interruptData = synchronousInterruptHandles->Get(handle);
+  if (interruptData == nullptr) return;
+  auto interrupt = interruptHandles->Get(interruptData->interruptHandle);
+  if (interrupt == nullptr) return;
+  // Have a valid interrupt
+  if (value->type != HAL_Type::HAL_DOUBLE) return;
+  int32_t status = 0;
+  bool retVal = GetAnalogTriggerValue(interrupt->portHandle,
+                                      interrupt->trigType, &status);
+  if (status != 0) {
+    // Interrupt and Cancel
+    interruptData->waitPredicate = true;
+    // Pulse interrupt
+    interruptData->waitCond.notify_all();
+  }
+  // If no change in interrupt, return;
+  if (retVal == interrupt->previousState) return;
+  // If its a falling change, and we dont fire on falling return
+  if (interrupt->previousState && !interrupt->fireOnDown) return;
+  // If its a rising change, and we dont fire on rising return.
+  if (!interrupt->previousState && !interrupt->fireOnUp) return;
+
+  interruptData->waitPredicate = true;
+
+  // Pulse interrupt
+  interruptData->waitCond.notify_all();
+}
+
+static int64_t WaitForInterruptDigital(HAL_InterruptHandle handle,
+                                       Interrupt* interrupt, double timeout,
+                                       bool ignorePrevious) {
+  auto data = std::make_shared<SynchronousWaitData>();
+
+  auto dataHandle = synchronousInterruptHandles->Allocate(data);
+  if (dataHandle == HAL_kInvalidHandle) {
+    // Error allocating data
+    return WaitResult::Timeout;
+  }
+
+  // auto data = synchronousInterruptHandles->Get(dataHandle);
+  data->waitPredicate = false;
+  data->interruptHandle = handle;
+
+  int32_t status = 0;
+
+  int32_t digitalIndex = GetDigitalInputChannel(interrupt->portHandle, &status);
+
+  if (status != 0) return WaitResult::Timeout;
+
+  interrupt->previousState = SimDIOData[digitalIndex].value;
+
+  int32_t uid = SimDIOData[digitalIndex].value.RegisterCallback(
+      &ProcessInterruptDigitalSynchronous,
+      reinterpret_cast<void*>(static_cast<uintptr_t>(dataHandle)), false);
+
+  bool timedOut = false;
+
+  wpi::mutex waitMutex;
+
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+
+  {
+    std::unique_lock<wpi::mutex> lock(waitMutex);
+    while (!data->waitPredicate) {
+      if (data->waitCond.wait_until(lock, timeoutTime) ==
+          std::cv_status::timeout) {
+        timedOut = true;
+        break;
+      }
+    }
+  }
+
+  // Cancel our callback
+  SimDIOData[digitalIndex].value.CancelCallback(uid);
+  synchronousInterruptHandles->Free(dataHandle);
+
+  // Check for what to return
+  if (timedOut) return WaitResult::Timeout;
+  // True => false, Falling
+  if (interrupt->previousState) {
+    // Set our return value and our timestamps
+    interrupt->fallingTimestamp = hal::GetFPGATime();
+    return 1 << (8 + interrupt->index);
+  } else {
+    interrupt->risingTimestamp = hal::GetFPGATime();
+    return 1 << (interrupt->index);
+  }
+}
+
+static int64_t WaitForInterruptAnalog(HAL_InterruptHandle handle,
+                                      Interrupt* interrupt, double timeout,
+                                      bool ignorePrevious) {
+  auto data = std::make_shared<SynchronousWaitData>();
+
+  auto dataHandle = synchronousInterruptHandles->Allocate(data);
+  if (dataHandle == HAL_kInvalidHandle) {
+    // Error allocating data
+    return WaitResult::Timeout;
+  }
+
+  data->waitPredicate = false;
+  data->interruptHandle = handle;
+
+  int32_t status = 0;
+  interrupt->previousState = GetAnalogTriggerValue(
+      interrupt->portHandle, interrupt->trigType, &status);
+
+  if (status != 0) return WaitResult::Timeout;
+
+  int32_t analogIndex =
+      GetAnalogTriggerInputIndex(interrupt->portHandle, &status);
+
+  if (status != 0) return WaitResult::Timeout;
+
+  int32_t uid = SimAnalogInData[analogIndex].voltage.RegisterCallback(
+      &ProcessInterruptAnalogSynchronous,
+      reinterpret_cast<void*>(static_cast<uintptr_t>(dataHandle)), false);
+
+  bool timedOut = false;
+
+  wpi::mutex waitMutex;
+
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+
+  {
+    std::unique_lock<wpi::mutex> lock(waitMutex);
+    while (!data->waitPredicate) {
+      if (data->waitCond.wait_until(lock, timeoutTime) ==
+          std::cv_status::timeout) {
+        timedOut = true;
+        break;
+      }
+    }
+  }
+
+  // Cancel our callback
+  SimAnalogInData[analogIndex].voltage.CancelCallback(uid);
+  synchronousInterruptHandles->Free(dataHandle);
+
+  // Check for what to return
+  if (timedOut) return WaitResult::Timeout;
+  // True => false, Falling
+  if (interrupt->previousState) {
+    // Set our return value and our timestamps
+    interrupt->fallingTimestamp = hal::GetFPGATime();
+    return 1 << (8 + interrupt->index);
+  } else {
+    interrupt->risingTimestamp = hal::GetFPGATime();
+    return 1 << (interrupt->index);
+  }
+}
+
+int64_t HAL_WaitForInterrupt(HAL_InterruptHandle interruptHandle,
+                             double timeout, HAL_Bool ignorePrevious,
+                             int32_t* status) {
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return WaitResult::Timeout;
+  }
+
+  // Check to make sure we are actually an interrupt in synchronous mode
+  if (!interrupt->watcher) {
+    *status = NiFpga_Status_InvalidParameter;
+    return WaitResult::Timeout;
+  }
+
+  if (interrupt->isAnalog) {
+    return WaitForInterruptAnalog(interruptHandle, interrupt.get(), timeout,
+                                  ignorePrevious);
+  } else {
+    return WaitForInterruptDigital(interruptHandle, interrupt.get(), timeout,
+                                   ignorePrevious);
+  }
+}
+
+static void ProcessInterruptDigitalAsynchronous(const char* name, void* param,
+                                                const struct HAL_Value* value) {
+  // void* is a HAL handle
+  // convert to uintptr_t first, then to handle
+  uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+  HAL_InterruptHandle handle = static_cast<HAL_InterruptHandle>(handleTmp);
+  auto interrupt = interruptHandles->Get(handle);
+  if (interrupt == nullptr) return;
+  // Have a valid interrupt
+  if (value->type != HAL_Type::HAL_BOOLEAN) return;
+  bool retVal = value->data.v_boolean;
+  // If no change in interrupt, return;
+  if (retVal == interrupt->previousState) return;
+  int32_t mask = 0;
+  if (interrupt->previousState) {
+    interrupt->previousState = retVal;
+    interrupt->fallingTimestamp = hal::GetFPGATime();
+    mask = 1 << (8 + interrupt->index);
+    if (!interrupt->fireOnDown) return;
+  } else {
+    interrupt->previousState = retVal;
+    interrupt->risingTimestamp = hal::GetFPGATime();
+    mask = 1 << (interrupt->index);
+    if (!interrupt->fireOnUp) return;
+  }
+
+  // run callback
+  auto callback = interrupt->callbackFunction;
+  if (callback == nullptr) return;
+  callback(mask, interrupt->callbackParam);
+}
+
+static void ProcessInterruptAnalogAsynchronous(const char* name, void* param,
+                                               const struct HAL_Value* value) {
+  // void* is a HAL handle
+  // convert to intptr_t first, then to handle
+  uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+  HAL_InterruptHandle handle = static_cast<HAL_InterruptHandle>(handleTmp);
+  auto interrupt = interruptHandles->Get(handle);
+  if (interrupt == nullptr) return;
+  // Have a valid interrupt
+  if (value->type != HAL_Type::HAL_DOUBLE) return;
+  int32_t status = 0;
+  bool retVal = GetAnalogTriggerValue(interrupt->portHandle,
+                                      interrupt->trigType, &status);
+  if (status != 0) return;
+  // If no change in interrupt, return;
+  if (retVal == interrupt->previousState) return;
+  int mask = 0;
+  if (interrupt->previousState) {
+    interrupt->previousState = retVal;
+    interrupt->fallingTimestamp = hal::GetFPGATime();
+    if (!interrupt->fireOnDown) return;
+    mask = 1 << (8 + interrupt->index);
+  } else {
+    interrupt->previousState = retVal;
+    interrupt->risingTimestamp = hal::GetFPGATime();
+    if (!interrupt->fireOnUp) return;
+    mask = 1 << (interrupt->index);
+  }
+
+  // run callback
+  auto callback = interrupt->callbackFunction;
+  if (callback == nullptr) return;
+  callback(mask, interrupt->callbackParam);
+}
+
+static void EnableInterruptsDigital(HAL_InterruptHandle handle,
+                                    Interrupt* interrupt) {
+  int32_t status = 0;
+  int32_t digitalIndex = GetDigitalInputChannel(interrupt->portHandle, &status);
+  if (status != 0) return;
+
+  interrupt->previousState = SimDIOData[digitalIndex].value;
+
+  int32_t uid = SimDIOData[digitalIndex].value.RegisterCallback(
+      &ProcessInterruptDigitalAsynchronous,
+      reinterpret_cast<void*>(static_cast<uintptr_t>(handle)), false);
+  interrupt->callbackId = uid;
+}
+
+static void EnableInterruptsAnalog(HAL_InterruptHandle handle,
+                                   Interrupt* interrupt) {
+  int32_t status = 0;
+  int32_t analogIndex =
+      GetAnalogTriggerInputIndex(interrupt->portHandle, &status);
+  if (status != 0) return;
+
+  status = 0;
+  interrupt->previousState = GetAnalogTriggerValue(
+      interrupt->portHandle, interrupt->trigType, &status);
+  if (status != 0) return;
+
+  int32_t uid = SimAnalogInData[analogIndex].voltage.RegisterCallback(
+      &ProcessInterruptAnalogAsynchronous,
+      reinterpret_cast<void*>(static_cast<uintptr_t>(handle)), false);
+  interrupt->callbackId = uid;
+}
+
+void HAL_EnableInterrupts(HAL_InterruptHandle interruptHandle,
+                          int32_t* status) {
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  // If we have not had a callback set, error out
+  if (interrupt->callbackFunction == nullptr) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  // EnableInterrupts has already been called
+  if (interrupt->callbackId >= 0) {
+    // We can double enable safely.
+    return;
+  }
+
+  if (interrupt->isAnalog) {
+    EnableInterruptsAnalog(interruptHandle, interrupt.get());
+  } else {
+    EnableInterruptsDigital(interruptHandle, interrupt.get());
+  }
+}
+void HAL_DisableInterrupts(HAL_InterruptHandle interruptHandle,
+                           int32_t* status) {
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  // No need to disable if we are already disabled
+  if (interrupt->callbackId < 0) return;
+
+  if (interrupt->isAnalog) {
+    // Do analog
+    int32_t status = 0;
+    int32_t analogIndex =
+        GetAnalogTriggerInputIndex(interrupt->portHandle, &status);
+    if (status != 0) return;
+    SimAnalogInData[analogIndex].voltage.CancelCallback(interrupt->callbackId);
+  } else {
+    int32_t status = 0;
+    int32_t digitalIndex =
+        GetDigitalInputChannel(interrupt->portHandle, &status);
+    if (status != 0) return;
+    SimDIOData[digitalIndex].value.CancelCallback(interrupt->callbackId);
+  }
+  interrupt->callbackId = -1;
+}
+int64_t HAL_ReadInterruptRisingTimestamp(HAL_InterruptHandle interruptHandle,
+                                         int32_t* status) {
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return interrupt->risingTimestamp;
+}
+int64_t HAL_ReadInterruptFallingTimestamp(HAL_InterruptHandle interruptHandle,
+                                          int32_t* status) {
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return interrupt->fallingTimestamp;
+}
+void HAL_RequestInterrupts(HAL_InterruptHandle interruptHandle,
+                           HAL_Handle digitalSourceHandle,
+                           HAL_AnalogTriggerType analogTriggerType,
+                           int32_t* status) {
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  bool routingAnalogTrigger = false;
+  uint8_t routingChannel = 0;
+  uint8_t routingModule = 0;
+  bool success =
+      remapDigitalSource(digitalSourceHandle, analogTriggerType, routingChannel,
+                         routingModule, routingAnalogTrigger);
+  if (!success) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  interrupt->isAnalog = routingAnalogTrigger;
+  interrupt->trigType = analogTriggerType;
+  interrupt->portHandle = digitalSourceHandle;
+}
+void HAL_AttachInterruptHandler(HAL_InterruptHandle interruptHandle,
+                                HAL_InterruptHandlerFunction handler,
+                                void* param, int32_t* status) {
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  interrupt->callbackFunction = handler;
+  interrupt->callbackParam = param;
+}
+
+void HAL_AttachInterruptHandlerThreaded(HAL_InterruptHandle interruptHandle,
+                                        HAL_InterruptHandlerFunction handler,
+                                        void* param, int32_t* status) {
+  HAL_AttachInterruptHandler(interruptHandle, handler, param, status);
+}
+
+void HAL_SetInterruptUpSourceEdge(HAL_InterruptHandle interruptHandle,
+                                  HAL_Bool risingEdge, HAL_Bool fallingEdge,
+                                  int32_t* status) {
+  auto interrupt = interruptHandles->Get(interruptHandle);
+  if (interrupt == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  interrupt->fireOnDown = fallingEdge;
+  interrupt->fireOnUp = risingEdge;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/MockHooks.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/MockHooks.cpp
new file mode 100644
index 0000000..25c1d9f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/MockHooks.cpp
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <atomic>
+#include <chrono>
+#include <cstdio>
+#include <thread>
+
+#include <wpi/timestamp.h>
+
+#include "MockHooksInternal.h"
+
+static std::atomic<bool> programStarted{false};
+
+static std::atomic<uint64_t> programStartTime{0};
+
+namespace hal {
+namespace init {
+void InitializeMockHooks() {}
+}  // namespace init
+}  // namespace hal
+
+namespace hal {
+void RestartTiming() { programStartTime = wpi::Now(); }
+
+int64_t GetFPGATime() {
+  auto now = wpi::Now();
+  auto currentTime = now - programStartTime;
+  return currentTime;
+}
+
+double GetFPGATimestamp() { return GetFPGATime() * 1.0e-6; }
+
+void SetProgramStarted() { programStarted = true; }
+bool GetProgramStarted() { return programStarted; }
+}  // namespace hal
+
+using namespace hal;
+
+extern "C" {
+void HALSIM_WaitForProgramStart(void) {
+  int count = 0;
+  while (!programStarted) {
+    count++;
+    std::printf("Waiting for program start signal: %d\n", count);
+    std::this_thread::sleep_for(std::chrono::milliseconds(500));
+  }
+}
+
+void HALSIM_SetProgramStarted(void) { SetProgramStarted(); }
+
+HAL_Bool HALSIM_GetProgramStarted(void) { return GetProgramStarted(); }
+
+void HALSIM_RestartTiming(void) { RestartTiming(); }
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/MockHooksInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/MockHooksInternal.h
new file mode 100644
index 0000000..e8c09a9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/MockHooksInternal.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "mockdata/MockHooks.h"
+
+namespace hal {
+void RestartTiming();
+
+int64_t GetFPGATime();
+
+double GetFPGATimestamp();
+
+void SetProgramStarted();
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Notifier.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Notifier.cpp
new file mode 100644
index 0000000..9f549d5
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Notifier.cpp
@@ -0,0 +1,159 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Notifier.h"
+
+#include <chrono>
+
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+#include <wpi/timestamp.h>
+
+#include "HALInitializer.h"
+#include "hal/HAL.h"
+#include "hal/cpp/fpga_clock.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+
+namespace {
+struct Notifier {
+  uint64_t waitTime;
+  bool updatedAlarm = false;
+  bool active = true;
+  bool running = false;
+  wpi::mutex mutex;
+  wpi::condition_variable cond;
+};
+}  // namespace
+
+using namespace hal;
+
+class NotifierHandleContainer
+    : public UnlimitedHandleResource<HAL_NotifierHandle, Notifier,
+                                     HAL_HandleEnum::Notifier> {
+ public:
+  ~NotifierHandleContainer() {
+    ForEach([](HAL_NotifierHandle handle, Notifier* notifier) {
+      {
+        std::lock_guard<wpi::mutex> lock(notifier->mutex);
+        notifier->active = false;
+        notifier->running = false;
+      }
+      notifier->cond.notify_all();  // wake up any waiting threads
+    });
+  }
+};
+
+static NotifierHandleContainer* notifierHandles;
+
+namespace hal {
+namespace init {
+void InitializeNotifier() {
+  static NotifierHandleContainer nH;
+  notifierHandles = &nH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_NotifierHandle HAL_InitializeNotifier(int32_t* status) {
+  hal::init::CheckInit();
+  std::shared_ptr<Notifier> notifier = std::make_shared<Notifier>();
+  HAL_NotifierHandle handle = notifierHandles->Allocate(notifier);
+  if (handle == HAL_kInvalidHandle) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  return handle;
+}
+
+void HAL_StopNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return;
+
+  {
+    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    notifier->active = false;
+    notifier->running = false;
+  }
+  notifier->cond.notify_all();
+}
+
+void HAL_CleanNotifier(HAL_NotifierHandle notifierHandle, int32_t* status) {
+  auto notifier = notifierHandles->Free(notifierHandle);
+  if (!notifier) return;
+
+  // Just in case HAL_StopNotifier() wasn't called...
+  {
+    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    notifier->active = false;
+    notifier->running = false;
+  }
+  notifier->cond.notify_all();
+}
+
+void HAL_UpdateNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                             uint64_t triggerTime, int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return;
+
+  {
+    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    notifier->waitTime = triggerTime;
+    notifier->running = true;
+    notifier->updatedAlarm = true;
+  }
+
+  // We wake up any waiters to change how long they're sleeping for
+  notifier->cond.notify_all();
+}
+
+void HAL_CancelNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                             int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return;
+
+  {
+    std::lock_guard<wpi::mutex> lock(notifier->mutex);
+    notifier->running = false;
+  }
+}
+
+uint64_t HAL_WaitForNotifierAlarm(HAL_NotifierHandle notifierHandle,
+                                  int32_t* status) {
+  auto notifier = notifierHandles->Get(notifierHandle);
+  if (!notifier) return 0;
+
+  std::unique_lock<wpi::mutex> lock(notifier->mutex);
+  while (notifier->active) {
+    double waitTime;
+    if (!notifier->running) {
+      waitTime = (HAL_GetFPGATime(status) * 1e-6) + 1000.0;
+      // If not running, wait 1000 seconds
+    } else {
+      waitTime = notifier->waitTime * 1e-6;
+    }
+
+    // Don't wait twice
+    notifier->updatedAlarm = false;
+
+    auto timeoutTime =
+        hal::fpga_clock::epoch() + std::chrono::duration<double>(waitTime);
+    notifier->cond.wait_until(lock, timeoutTime);
+    if (notifier->updatedAlarm) {
+      notifier->updatedAlarm = false;
+      continue;
+    }
+    if (!notifier->running) continue;
+    if (!notifier->active) break;
+    notifier->running = false;
+    return HAL_GetFPGATime(status);
+  }
+  return 0;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/PDP.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/PDP.cpp
new file mode 100644
index 0000000..07f4dcd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/PDP.cpp
@@ -0,0 +1,92 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/PDP.h"
+
+#include "CANAPIInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/CANAPI.h"
+#include "hal/handles/IndexedHandleResource.h"
+#include "mockdata/PDPDataInternal.h"
+
+using namespace hal;
+
+static constexpr HAL_CANManufacturer manufacturer =
+    HAL_CANManufacturer::HAL_CAN_Man_kCTRE;
+
+static constexpr HAL_CANDeviceType deviceType =
+    HAL_CANDeviceType::HAL_CAN_Dev_kPowerDistribution;
+
+namespace hal {
+namespace init {
+void InitializePDP() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_PDPHandle HAL_InitializePDP(int32_t module, int32_t* status) {
+  if (!HAL_CheckPDPModule(module)) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+  hal::init::CheckInit();
+  SimPDPData[module].initialized = true;
+  auto handle = HAL_InitializeCAN(manufacturer, module, deviceType, status);
+
+  if (*status != 0) {
+    HAL_CleanCAN(handle);
+    return HAL_kInvalidHandle;
+  }
+
+  return handle;
+}
+
+HAL_Bool HAL_CheckPDPModule(int32_t module) {
+  return module < kNumPDPModules && module >= 0;
+}
+
+HAL_Bool HAL_CheckPDPChannel(int32_t channel) {
+  return channel < kNumPDPChannels && channel >= 0;
+}
+
+void HAL_CleanPDP(HAL_PDPHandle handle) { HAL_CleanCAN(handle); }
+
+double HAL_GetPDPTemperature(HAL_PDPHandle handle, int32_t* status) {
+  auto module = hal::can::GetCANModuleFromHandle(handle, status);
+  if (*status != 0) {
+    return 0.0;
+  }
+  return SimPDPData[module].temperature;
+}
+double HAL_GetPDPVoltage(HAL_PDPHandle handle, int32_t* status) {
+  auto module = hal::can::GetCANModuleFromHandle(handle, status);
+  if (*status != 0) {
+    return 0.0;
+  }
+  return SimPDPData[module].voltage;
+}
+double HAL_GetPDPChannelCurrent(HAL_PDPHandle handle, int32_t channel,
+                                int32_t* status) {
+  auto module = hal::can::GetCANModuleFromHandle(handle, status);
+  if (*status != 0) {
+    return 0.0;
+  }
+  return SimPDPData[module].current[channel];
+}
+double HAL_GetPDPTotalCurrent(HAL_PDPHandle handle, int32_t* status) {
+  return 0.0;
+}
+double HAL_GetPDPTotalPower(HAL_PDPHandle handle, int32_t* status) {
+  return 0.0;
+}
+double HAL_GetPDPTotalEnergy(HAL_PDPHandle handle, int32_t* status) {
+  return 0.0;
+}
+void HAL_ResetPDPTotalEnergy(HAL_PDPHandle handle, int32_t* status) {}
+void HAL_ClearPDPStickyFaults(HAL_PDPHandle handle, int32_t* status) {}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/PWM.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/PWM.cpp
new file mode 100644
index 0000000..228b540
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/PWM.cpp
@@ -0,0 +1,302 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/PWM.h"
+
+#include "ConstantsInternal.h"
+#include "DigitalInternal.h"
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/PWMDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializePWM() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+
+HAL_DigitalHandle HAL_InitializePWMPort(HAL_PortHandle portHandle,
+                                        int32_t* status) {
+  hal::init::CheckInit();
+  if (*status != 0) return HAL_kInvalidHandle;
+
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  uint8_t origChannel = static_cast<uint8_t>(channel);
+
+  if (origChannel < kNumPWMHeaders) {
+    channel += kNumDigitalChannels;  // remap Headers to end of allocations
+  } else {
+    channel = remapMXPPWMChannel(channel) + 10;  // remap MXP to proper channel
+  }
+
+  auto handle =
+      digitalChannelHandles->Allocate(channel, HAL_HandleEnum::PWM, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  auto port = digitalChannelHandles->Get(handle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  port->channel = origChannel;
+
+  SimPWMData[origChannel].initialized = true;
+
+  // Defaults to allow an always valid config.
+  HAL_SetPWMConfig(handle, 2.0, 1.501, 1.5, 1.499, 1.0, status);
+
+  return handle;
+}
+void HAL_FreePWMPort(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimPWMData[port->channel].initialized = false;
+
+  digitalChannelHandles->Free(pwmPortHandle, HAL_HandleEnum::PWM);
+}
+
+HAL_Bool HAL_CheckPWMChannel(int32_t channel) {
+  return channel < kNumPWMChannels && channel >= 0;
+}
+
+void HAL_SetPWMConfig(HAL_DigitalHandle pwmPortHandle, double max,
+                      double deadbandMax, double center, double deadbandMin,
+                      double min, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  // calculate the loop time in milliseconds
+  double loopTime =
+      HAL_GetPWMLoopTiming(status) / (kSystemClockTicksPerMicrosecond * 1e3);
+  if (*status != 0) return;
+
+  int32_t maxPwm = static_cast<int32_t>((max - kDefaultPwmCenter) / loopTime +
+                                        kDefaultPwmStepsDown - 1);
+  int32_t deadbandMaxPwm = static_cast<int32_t>(
+      (deadbandMax - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
+  int32_t centerPwm = static_cast<int32_t>(
+      (center - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
+  int32_t deadbandMinPwm = static_cast<int32_t>(
+      (deadbandMin - kDefaultPwmCenter) / loopTime + kDefaultPwmStepsDown - 1);
+  int32_t minPwm = static_cast<int32_t>((min - kDefaultPwmCenter) / loopTime +
+                                        kDefaultPwmStepsDown - 1);
+
+  port->maxPwm = maxPwm;
+  port->deadbandMaxPwm = deadbandMaxPwm;
+  port->deadbandMinPwm = deadbandMinPwm;
+  port->centerPwm = centerPwm;
+  port->minPwm = minPwm;
+  port->configSet = true;
+}
+
+void HAL_SetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t maxPwm,
+                         int32_t deadbandMaxPwm, int32_t centerPwm,
+                         int32_t deadbandMinPwm, int32_t minPwm,
+                         int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  port->maxPwm = maxPwm;
+  port->deadbandMaxPwm = deadbandMaxPwm;
+  port->deadbandMinPwm = deadbandMinPwm;
+  port->centerPwm = centerPwm;
+  port->minPwm = minPwm;
+}
+
+void HAL_GetPWMConfigRaw(HAL_DigitalHandle pwmPortHandle, int32_t* maxPwm,
+                         int32_t* deadbandMaxPwm, int32_t* centerPwm,
+                         int32_t* deadbandMinPwm, int32_t* minPwm,
+                         int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  *maxPwm = port->maxPwm;
+  *deadbandMaxPwm = port->deadbandMaxPwm;
+  *deadbandMinPwm = port->deadbandMinPwm;
+  *centerPwm = port->centerPwm;
+  *minPwm = port->minPwm;
+}
+
+void HAL_SetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
+                                 HAL_Bool eliminateDeadband, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  port->eliminateDeadband = eliminateDeadband;
+}
+
+HAL_Bool HAL_GetPWMEliminateDeadband(HAL_DigitalHandle pwmPortHandle,
+                                     int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  return port->eliminateDeadband;
+}
+
+void HAL_SetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t value,
+                   int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimPWMData[port->channel].rawValue = value;
+}
+
+void HAL_SetPWMSpeed(HAL_DigitalHandle pwmPortHandle, double speed,
+                     int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (!port->configSet) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  if (speed < -1.0) {
+    speed = -1.0;
+  } else if (speed > 1.0) {
+    speed = 1.0;
+  }
+
+  SimPWMData[port->channel].speed = speed;
+}
+
+void HAL_SetPWMPosition(HAL_DigitalHandle pwmPortHandle, double pos,
+                        int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (!port->configSet) {
+    *status = INCOMPATIBLE_STATE;
+    return;
+  }
+
+  if (pos < 0.0) {
+    pos = 0.0;
+  } else if (pos > 1.0) {
+    pos = 1.0;
+  }
+
+  SimPWMData[port->channel].position = pos;
+}
+
+void HAL_SetPWMDisabled(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  SimPWMData[port->channel].rawValue = 0;
+  SimPWMData[port->channel].position = 0;
+  SimPWMData[port->channel].speed = 0;
+}
+
+int32_t HAL_GetPWMRaw(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+
+  return SimPWMData[port->channel].rawValue;
+}
+
+double HAL_GetPWMSpeed(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  if (!port->configSet) {
+    *status = INCOMPATIBLE_STATE;
+    return 0;
+  }
+
+  double speed = SimPWMData[port->channel].speed;
+  if (speed > 1) speed = 1;
+  if (speed < -1) speed = -1;
+  return speed;
+}
+
+double HAL_GetPWMPosition(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return 0;
+  }
+  if (!port->configSet) {
+    *status = INCOMPATIBLE_STATE;
+    return 0;
+  }
+
+  double position = SimPWMData[port->channel].position;
+  if (position > 1) position = 1;
+  if (position < 0) position = 0;
+  return position;
+}
+
+void HAL_LatchPWMZero(HAL_DigitalHandle pwmPortHandle, int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimPWMData[port->channel].zeroLatch = true;
+  SimPWMData[port->channel].zeroLatch = false;
+}
+
+void HAL_SetPWMPeriodScale(HAL_DigitalHandle pwmPortHandle, int32_t squelchMask,
+                           int32_t* status) {
+  auto port = digitalChannelHandles->Get(pwmPortHandle, HAL_HandleEnum::PWM);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  SimPWMData[port->channel].periodScale = squelchMask;
+}
+
+int32_t HAL_GetPWMLoopTiming(int32_t* status) { return kExpectedLoopTiming; }
+
+uint64_t HAL_GetPWMCycleStartTime(int32_t* status) { return 0; }
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Ports.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Ports.cpp
new file mode 100644
index 0000000..f50304f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Ports.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Ports.h"
+
+#include "PortsInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializePorts() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+int32_t HAL_GetNumAccumulators(void) { return kNumAccumulators; }
+int32_t HAL_GetNumAnalogTriggers(void) { return kNumAnalogTriggers; }
+int32_t HAL_GetNumAnalogInputs(void) { return kNumAnalogInputs; }
+int32_t HAL_GetNumAnalogOutputs(void) { return kNumAnalogOutputs; }
+int32_t HAL_GetNumCounters(void) { return kNumCounters; }
+int32_t HAL_GetNumDigitalHeaders(void) { return kNumDigitalHeaders; }
+int32_t HAL_GetNumPWMHeaders(void) { return kNumPWMHeaders; }
+int32_t HAL_GetNumDigitalChannels(void) { return kNumDigitalChannels; }
+int32_t HAL_GetNumPWMChannels(void) { return kNumPWMChannels; }
+int32_t HAL_GetNumDigitalPWMOutputs(void) { return kNumDigitalPWMOutputs; }
+int32_t HAL_GetNumEncoders(void) { return kNumEncoders; }
+int32_t HAL_GetNumInterrupts(void) { return kNumInterrupts; }
+int32_t HAL_GetNumRelayChannels(void) { return kNumRelayChannels; }
+int32_t HAL_GetNumRelayHeaders(void) { return kNumRelayHeaders; }
+int32_t HAL_GetNumPCMModules(void) { return kNumPCMModules; }
+int32_t HAL_GetNumSolenoidChannels(void) { return kNumSolenoidChannels; }
+int32_t HAL_GetNumPDPModules(void) { return kNumPDPModules; }
+int32_t HAL_GetNumPDPChannels(void) { return kNumPDPChannels; }
+int32_t HAL_GetNumCanTalons(void) { return kNumCanTalons; }
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/PortsInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/PortsInternal.h
new file mode 100644
index 0000000..0b899f7
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/PortsInternal.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+namespace hal {
+constexpr int32_t kNumAccumulators = 2;
+constexpr int32_t kNumAnalogTriggers = 8;
+constexpr int32_t kNumAnalogInputs = 8;
+constexpr int32_t kNumAnalogOutputs = 2;
+constexpr int32_t kNumCounters = 8;
+constexpr int32_t kNumDigitalHeaders = 10;
+constexpr int32_t kNumPWMHeaders = 10;
+constexpr int32_t kNumDigitalChannels = 26;
+constexpr int32_t kNumPWMChannels = 20;
+constexpr int32_t kNumDigitalPWMOutputs = 6;
+constexpr int32_t kNumEncoders = 8;
+constexpr int32_t kNumInterrupts = 8;
+constexpr int32_t kNumRelayChannels = 8;
+constexpr int32_t kNumRelayHeaders = kNumRelayChannels / 2;
+constexpr int32_t kNumPCMModules = 63;
+constexpr int32_t kNumSolenoidChannels = 8;
+constexpr int32_t kNumPDPModules = 63;
+constexpr int32_t kNumPDPChannels = 16;
+constexpr int32_t kNumCanTalons = 63;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Power.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Power.cpp
new file mode 100644
index 0000000..95bb3dd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Power.cpp
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/Power.h"
+
+#include "mockdata/RoboRioDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializePower() {}
+}  // namespace init
+}  // namespace hal
+
+// TODO: Fix the naming in here
+extern "C" {
+double HAL_GetVinVoltage(int32_t* status) {
+  return SimRoboRioData[0].vInVoltage;
+}
+double HAL_GetVinCurrent(int32_t* status) {
+  return SimRoboRioData[0].vInCurrent;
+}
+double HAL_GetUserVoltage6V(int32_t* status) {
+  return SimRoboRioData[0].userVoltage6V;
+}
+double HAL_GetUserCurrent6V(int32_t* status) {
+  return SimRoboRioData[0].userCurrent6V;
+}
+HAL_Bool HAL_GetUserActive6V(int32_t* status) {
+  return SimRoboRioData[0].userActive6V;
+}
+int32_t HAL_GetUserCurrentFaults6V(int32_t* status) {
+  return SimRoboRioData[0].userFaults6V;
+}
+double HAL_GetUserVoltage5V(int32_t* status) {
+  return SimRoboRioData[0].userVoltage5V;
+}
+double HAL_GetUserCurrent5V(int32_t* status) {
+  return SimRoboRioData[0].userCurrent5V;
+}
+HAL_Bool HAL_GetUserActive5V(int32_t* status) {
+  return SimRoboRioData[0].userActive5V;
+}
+int32_t HAL_GetUserCurrentFaults5V(int32_t* status) {
+  return SimRoboRioData[0].userFaults5V;
+}
+double HAL_GetUserVoltage3V3(int32_t* status) {
+  return SimRoboRioData[0].userVoltage3V3;
+}
+double HAL_GetUserCurrent3V3(int32_t* status) {
+  return SimRoboRioData[0].userCurrent3V3;
+}
+HAL_Bool HAL_GetUserActive3V3(int32_t* status) {
+  return SimRoboRioData[0].userActive3V3;
+}
+int32_t HAL_GetUserCurrentFaults3V3(int32_t* status) {
+  return SimRoboRioData[0].userFaults3V3;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Relay.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Relay.cpp
new file mode 100644
index 0000000..bd1c8a8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Relay.cpp
@@ -0,0 +1,121 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Relay.h"
+
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/handles/IndexedHandleResource.h"
+#include "mockdata/RelayDataInternal.h"
+
+using namespace hal;
+
+namespace {
+struct Relay {
+  uint8_t channel;
+  bool fwd;
+};
+}  // namespace
+
+static IndexedHandleResource<HAL_RelayHandle, Relay, kNumRelayChannels,
+                             HAL_HandleEnum::Relay>* relayHandles;
+
+namespace hal {
+namespace init {
+void InitializeRelay() {
+  static IndexedHandleResource<HAL_RelayHandle, Relay, kNumRelayChannels,
+                               HAL_HandleEnum::Relay>
+      rH;
+  relayHandles = &rH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_RelayHandle HAL_InitializeRelayPort(HAL_PortHandle portHandle, HAL_Bool fwd,
+                                        int32_t* status) {
+  hal::init::CheckInit();
+  if (*status != 0) return HAL_kInvalidHandle;
+
+  int16_t channel = getPortHandleChannel(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = PARAMETER_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  if (!fwd) channel += kNumRelayHeaders;  // add 4 to reverse channels
+
+  auto handle = relayHandles->Allocate(channel, status);
+
+  if (*status != 0)
+    return HAL_kInvalidHandle;  // failed to allocate. Pass error back.
+
+  auto port = relayHandles->Get(handle);
+  if (port == nullptr) {  // would only occur on thread issue.
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  if (!fwd) {
+    // Subtract number of headers to put channel in range
+    channel -= kNumRelayHeaders;
+
+    port->fwd = false;  // set to reverse
+
+    SimRelayData[channel].initializedReverse = true;
+  } else {
+    port->fwd = true;  // set to forward
+    SimRelayData[channel].initializedForward = true;
+  }
+
+  port->channel = static_cast<uint8_t>(channel);
+
+  return handle;
+}
+
+void HAL_FreeRelayPort(HAL_RelayHandle relayPortHandle) {
+  auto port = relayHandles->Get(relayPortHandle);
+  relayHandles->Free(relayPortHandle);
+  if (port == nullptr) return;
+  if (port->fwd)
+    SimRelayData[port->channel].initializedForward = false;
+  else
+    SimRelayData[port->channel].initializedReverse = false;
+}
+
+HAL_Bool HAL_CheckRelayChannel(int32_t channel) {
+  // roboRIO only has 4 headers, and the FPGA has
+  // seperate functions for forward and reverse,
+  // instead of seperate channel IDs
+  return channel < kNumRelayHeaders && channel >= 0;
+}
+
+void HAL_SetRelay(HAL_RelayHandle relayPortHandle, HAL_Bool on,
+                  int32_t* status) {
+  auto port = relayHandles->Get(relayPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+  if (port->fwd)
+    SimRelayData[port->channel].forward = on;
+  else
+    SimRelayData[port->channel].reverse = on;
+}
+
+HAL_Bool HAL_GetRelay(HAL_RelayHandle relayPortHandle, int32_t* status) {
+  auto port = relayHandles->Get(relayPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+  if (port->fwd)
+    return SimRelayData[port->channel].forward;
+  else
+    return SimRelayData[port->channel].reverse;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/SPI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/SPI.cpp
new file mode 100644
index 0000000..8c539d3
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/SPI.cpp
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/SPI.h"
+
+#include "HALInitializer.h"
+#include "mockdata/SPIDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeSPI() {}
+}  // namespace init
+}  // namespace hal
+
+void HAL_InitializeSPI(HAL_SPIPort port, int32_t* status) {
+  hal::init::CheckInit();
+  SimSPIData[port].initialized = true;
+}
+int32_t HAL_TransactionSPI(HAL_SPIPort port, const uint8_t* dataToSend,
+                           uint8_t* dataReceived, int32_t size) {
+  return SimSPIData[port].Transaction(dataToSend, dataReceived, size);
+}
+int32_t HAL_WriteSPI(HAL_SPIPort port, const uint8_t* dataToSend,
+                     int32_t sendSize) {
+  return SimSPIData[port].Write(dataToSend, sendSize);
+}
+int32_t HAL_ReadSPI(HAL_SPIPort port, uint8_t* buffer, int32_t count) {
+  return SimSPIData[port].Read(buffer, count);
+}
+void HAL_CloseSPI(HAL_SPIPort port) { SimSPIData[port].initialized = false; }
+void HAL_SetSPISpeed(HAL_SPIPort port, int32_t speed) {}
+void HAL_SetSPIOpts(HAL_SPIPort port, HAL_Bool msbFirst,
+                    HAL_Bool sampleOnTrailing, HAL_Bool clkIdleHigh) {}
+void HAL_SetSPIChipSelectActiveHigh(HAL_SPIPort port, int32_t* status) {}
+void HAL_SetSPIChipSelectActiveLow(HAL_SPIPort port, int32_t* status) {}
+int32_t HAL_GetSPIHandle(HAL_SPIPort port) { return 0; }
+void HAL_SetSPIHandle(HAL_SPIPort port, int32_t handle) {}
+
+void HAL_InitSPIAuto(HAL_SPIPort port, int32_t bufferSize, int32_t* status) {}
+void HAL_FreeSPIAuto(HAL_SPIPort port, int32_t* status) {}
+void HAL_StartSPIAutoRate(HAL_SPIPort port, double period, int32_t* status) {}
+void HAL_StartSPIAutoTrigger(HAL_SPIPort port, HAL_Handle digitalSourceHandle,
+                             HAL_AnalogTriggerType analogTriggerType,
+                             HAL_Bool triggerRising, HAL_Bool triggerFalling,
+                             int32_t* status) {}
+void HAL_StopSPIAuto(HAL_SPIPort port, int32_t* status) {}
+void HAL_SetSPIAutoTransmitData(HAL_SPIPort port, const uint8_t* dataToSend,
+                                int32_t dataSize, int32_t zeroSize,
+                                int32_t* status) {}
+void HAL_ForceSPIAutoRead(HAL_SPIPort port, int32_t* status) {}
+int32_t HAL_ReadSPIAutoReceivedData(HAL_SPIPort port, uint32_t* buffer,
+                                    int32_t numToRead, double timeout,
+                                    int32_t* status) {
+  return SimSPIData[port].ReadAutoReceivedData(buffer, numToRead, timeout,
+                                               status);
+}
+int32_t HAL_GetSPIAutoDroppedCount(HAL_SPIPort port, int32_t* status) {
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/SerialPort.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/SerialPort.cpp
new file mode 100644
index 0000000..bc08566
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/SerialPort.cpp
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/SerialPort.h"
+
+#include "HALInitializer.h"
+
+namespace hal {
+namespace init {
+void InitializeSerialPort() {}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+void HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status) {
+  hal::init::CheckInit();
+}
+
+void HAL_InitializeSerialPortDirect(HAL_SerialPort port, const char* portName,
+                                    int32_t* status) {}
+
+void HAL_SetSerialBaudRate(HAL_SerialPort port, int32_t baud, int32_t* status) {
+}
+
+void HAL_SetSerialDataBits(HAL_SerialPort port, int32_t bits, int32_t* status) {
+}
+
+void HAL_SetSerialParity(HAL_SerialPort port, int32_t parity, int32_t* status) {
+}
+
+void HAL_SetSerialStopBits(HAL_SerialPort port, int32_t stopBits,
+                           int32_t* status) {}
+
+void HAL_SetSerialWriteMode(HAL_SerialPort port, int32_t mode,
+                            int32_t* status) {}
+
+void HAL_SetSerialFlowControl(HAL_SerialPort port, int32_t flow,
+                              int32_t* status) {}
+
+void HAL_SetSerialTimeout(HAL_SerialPort port, double timeout,
+                          int32_t* status) {}
+
+void HAL_EnableSerialTermination(HAL_SerialPort port, char terminator,
+                                 int32_t* status) {}
+
+void HAL_DisableSerialTermination(HAL_SerialPort port, int32_t* status) {}
+
+void HAL_SetSerialReadBufferSize(HAL_SerialPort port, int32_t size,
+                                 int32_t* status) {}
+
+void HAL_SetSerialWriteBufferSize(HAL_SerialPort port, int32_t size,
+                                  int32_t* status) {}
+
+int32_t HAL_GetSerialBytesReceived(HAL_SerialPort port, int32_t* status) {
+  return 0;
+}
+
+int32_t HAL_ReadSerial(HAL_SerialPort port, char* buffer, int32_t count,
+                       int32_t* status) {
+  return 0;
+}
+
+int32_t HAL_WriteSerial(HAL_SerialPort port, const char* buffer, int32_t count,
+                        int32_t* status) {
+  return 0;
+}
+
+void HAL_FlushSerial(HAL_SerialPort port, int32_t* status) {}
+
+void HAL_ClearSerial(HAL_SerialPort port, int32_t* status) {}
+
+void HAL_CloseSerial(HAL_SerialPort port, int32_t* status) {}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Solenoid.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Solenoid.cpp
new file mode 100644
index 0000000..d3f0c5d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Solenoid.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "hal/Solenoid.h"
+
+#include "HALInitializer.h"
+#include "PortsInternal.h"
+#include "hal/Errors.h"
+#include "hal/handles/HandlesInternal.h"
+#include "hal/handles/IndexedHandleResource.h"
+#include "mockdata/PCMDataInternal.h"
+
+namespace {
+struct Solenoid {
+  uint8_t module;
+  uint8_t channel;
+};
+}  // namespace
+
+using namespace hal;
+
+static IndexedHandleResource<HAL_SolenoidHandle, Solenoid,
+                             kNumPCMModules * kNumSolenoidChannels,
+                             HAL_HandleEnum::Solenoid>* solenoidHandles;
+
+namespace hal {
+namespace init {
+void InitializeSolenoid() {
+  static IndexedHandleResource<HAL_SolenoidHandle, Solenoid,
+                               kNumPCMModules * kNumSolenoidChannels,
+                               HAL_HandleEnum::Solenoid>
+      sH;
+  solenoidHandles = &sH;
+}
+}  // namespace init
+}  // namespace hal
+
+extern "C" {
+HAL_SolenoidHandle HAL_InitializeSolenoidPort(HAL_PortHandle portHandle,
+                                              int32_t* status) {
+  hal::init::CheckInit();
+  int16_t channel = getPortHandleChannel(portHandle);
+  int16_t module = getPortHandleModule(portHandle);
+  if (channel == InvalidHandleIndex) {
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+
+  if (!HAL_CheckSolenoidChannel(channel)) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  if (!HAL_CheckSolenoidModule(module)) {
+    *status = RESOURCE_OUT_OF_RANGE;
+    return HAL_kInvalidHandle;
+  }
+
+  auto handle = solenoidHandles->Allocate(
+      module * kNumSolenoidChannels + channel, status);
+  if (handle == HAL_kInvalidHandle) {  // out of resources
+    *status = NO_AVAILABLE_RESOURCES;
+    return HAL_kInvalidHandle;
+  }
+  auto solenoidPort = solenoidHandles->Get(handle);
+  if (solenoidPort == nullptr) {  // would only occur on thread issues
+    *status = HAL_HANDLE_ERROR;
+    return HAL_kInvalidHandle;
+  }
+  solenoidPort->module = static_cast<uint8_t>(module);
+  solenoidPort->channel = static_cast<uint8_t>(channel);
+
+  HALSIM_SetPCMSolenoidInitialized(module, channel, true);
+
+  return handle;
+}
+void HAL_FreeSolenoidPort(HAL_SolenoidHandle solenoidPortHandle) {
+  auto port = solenoidHandles->Get(solenoidPortHandle);
+  if (port == nullptr) return;
+  solenoidHandles->Free(solenoidPortHandle);
+  HALSIM_SetPCMSolenoidInitialized(port->module, port->channel, false);
+}
+HAL_Bool HAL_CheckSolenoidModule(int32_t module) {
+  return module < kNumPCMModules && module >= 0;
+}
+
+HAL_Bool HAL_CheckSolenoidChannel(int32_t channel) {
+  return channel < kNumSolenoidChannels && channel >= 0;
+}
+HAL_Bool HAL_GetSolenoid(HAL_SolenoidHandle solenoidPortHandle,
+                         int32_t* status) {
+  auto port = solenoidHandles->Get(solenoidPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return false;
+  }
+
+  return HALSIM_GetPCMSolenoidOutput(port->module, port->channel);
+}
+int32_t HAL_GetAllSolenoids(int32_t module, int32_t* status) {
+  int32_t total = 0;
+  for (int i = 0; i < kNumSolenoidChannels; i++) {
+    int32_t channel = HALSIM_GetPCMSolenoidOutput(module, i) ? 1 : 0;
+    total = total + (channel << i);
+  }
+
+  return total;
+}
+void HAL_SetSolenoid(HAL_SolenoidHandle solenoidPortHandle, HAL_Bool value,
+                     int32_t* status) {
+  auto port = solenoidHandles->Get(solenoidPortHandle);
+  if (port == nullptr) {
+    *status = HAL_HANDLE_ERROR;
+    return;
+  }
+
+  HALSIM_SetPCMSolenoidOutput(port->module, port->channel, value);
+}
+int32_t HAL_GetPCMSolenoidBlackList(int32_t module, int32_t* status) {
+  return 0;
+}
+HAL_Bool HAL_GetPCMSolenoidVoltageStickyFault(int32_t module, int32_t* status) {
+  return 0;
+}
+HAL_Bool HAL_GetPCMSolenoidVoltageFault(int32_t module, int32_t* status) {
+  return 0;
+}
+void HAL_ClearAllPCMStickyFaults(int32_t module, int32_t* status) {}
+void HAL_SetOneShotDuration(HAL_SolenoidHandle solenoidPortHandle,
+                            int32_t durMS, int32_t* status) {}
+void HAL_FireOneShot(HAL_SolenoidHandle solenoidPortHandle, int32_t* status) {}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/Threads.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/Threads.cpp
new file mode 100644
index 0000000..2aa2c4b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/Threads.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "hal/Threads.h"
+
+namespace hal {
+namespace init {
+void InitializeThreads() {}
+}  // namespace init
+}  // namespace hal
+
+int32_t HAL_GetThreadPriority(NativeThreadHandle handle, HAL_Bool* isRealTime,
+                              int32_t* status) {
+  return 0;
+}
+int32_t HAL_GetCurrentThreadPriority(HAL_Bool* isRealTime, int32_t* status) {
+  return 0;
+}
+HAL_Bool HAL_SetThreadPriority(NativeThreadHandle handle, HAL_Bool realTime,
+                               int32_t priority, int32_t* status) {
+  return true;
+}
+HAL_Bool HAL_SetCurrentThreadPriority(HAL_Bool realTime, int32_t priority,
+                                      int32_t* status) {
+  return true;
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AccelerometerDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AccelerometerDataJNI.cpp
new file mode 100644
index 0000000..8964a41
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AccelerometerDataJNI.cpp
@@ -0,0 +1,279 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI.h"
+#include "mockdata/AccelerometerData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    registerActiveCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_registerActiveCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAccelerometerActiveCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    cancelActiveCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_cancelActiveCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAccelerometerActiveCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    getActive
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_getActive
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAccelerometerActive(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    setActive
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_setActive
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetAccelerometerActive(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    registerRangeCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_registerRangeCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAccelerometerRangeCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    cancelRangeCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_cancelRangeCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAccelerometerRangeCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    getRange
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_getRange
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAccelerometerRange(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    setRange
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_setRange
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetAccelerometerRange(index,
+                               static_cast<HAL_AccelerometerRange>(value));
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    registerXCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_registerXCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAccelerometerXCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    cancelXCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_cancelXCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAccelerometerXCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    getX
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_getX
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAccelerometerX(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    setX
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_setX
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAccelerometerX(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    registerYCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_registerYCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAccelerometerYCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    cancelYCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_cancelYCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAccelerometerYCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    getY
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_getY
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAccelerometerY(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    setY
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_setY
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAccelerometerY(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    registerZCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_registerZCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAccelerometerZCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    cancelZCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_cancelZCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAccelerometerZCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    getZ
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_getZ
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAccelerometerZ(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    setZ
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_setZ
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAccelerometerZ(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AccelerometerDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetAccelerometerData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogGyroDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogGyroDataJNI.cpp
new file mode 100644
index 0000000..08d18de
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogGyroDataJNI.cpp
@@ -0,0 +1,178 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI.h"
+#include "mockdata/AnalogGyroData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    registerAngleCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_registerAngleCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogGyroAngleCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    cancelAngleCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_cancelAngleCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogGyroAngleCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    getAngle
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_getAngle
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogGyroAngle(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    setAngle
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_setAngle
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAnalogGyroAngle(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    registerRateCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_registerRateCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogGyroRateCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    cancelRateCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_cancelRateCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogGyroRateCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    getRate
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_getRate
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogGyroRate(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    setRate
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_setRate
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAnalogGyroRate(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogGyroInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogGyroInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogGyroInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetAnalogGyroInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogGyroDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetAnalogGyroData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogInDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogInDataJNI.cpp
new file mode 100644
index 0000000..c6cee7b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogInDataJNI.cpp
@@ -0,0 +1,483 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI.h"
+#include "mockdata/AnalogInData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogInInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogInInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetAnalogInInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerAverageBitsCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerAverageBitsCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogInAverageBitsCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelAverageBitsCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelAverageBitsCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogInAverageBitsCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getAverageBits
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getAverageBits
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInAverageBits(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setAverageBits
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setAverageBits
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetAnalogInAverageBits(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerOversampleBitsCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerOversampleBitsCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogInOversampleBitsCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelOversampleBitsCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelOversampleBitsCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogInOversampleBitsCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getOversampleBits
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getOversampleBits
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInOversampleBits(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setOversampleBits
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setOversampleBits
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetAnalogInOversampleBits(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerVoltageCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerVoltageCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogInVoltageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelVoltageCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelVoltageCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogInVoltageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getVoltage
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInVoltage(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setVoltage
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setVoltage
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAnalogInVoltage(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerAccumulatorInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerAccumulatorInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAnalogInAccumulatorInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelAccumulatorInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelAccumulatorInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(
+      env, handle, index, &HALSIM_CancelAnalogInAccumulatorInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getAccumulatorInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getAccumulatorInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInAccumulatorInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setAccumulatorInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setAccumulatorInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetAnalogInAccumulatorInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerAccumulatorValueCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerAccumulatorValueCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAnalogInAccumulatorValueCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelAccumulatorValueCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelAccumulatorValueCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogInAccumulatorValueCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getAccumulatorValue
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getAccumulatorValue
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInAccumulatorValue(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setAccumulatorValue
+ * Signature: (IJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setAccumulatorValue
+  (JNIEnv*, jclass, jint index, jlong value)
+{
+  HALSIM_SetAnalogInAccumulatorValue(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerAccumulatorCountCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerAccumulatorCountCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAnalogInAccumulatorCountCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelAccumulatorCountCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelAccumulatorCountCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogInAccumulatorCountCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getAccumulatorCount
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getAccumulatorCount
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInAccumulatorCount(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setAccumulatorCount
+ * Signature: (IJ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setAccumulatorCount
+  (JNIEnv*, jclass, jint index, jlong value)
+{
+  HALSIM_SetAnalogInAccumulatorCount(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerAccumulatorCenterCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerAccumulatorCenterCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAnalogInAccumulatorCenterCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelAccumulatorCenterCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelAccumulatorCenterCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogInAccumulatorCenterCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getAccumulatorCenter
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getAccumulatorCenter
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInAccumulatorCenter(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setAccumulatorCenter
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setAccumulatorCenter
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetAnalogInAccumulatorCenter(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    registerAccumulatorDeadbandCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_registerAccumulatorDeadbandCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAnalogInAccumulatorDeadbandCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    cancelAccumulatorDeadbandCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_cancelAccumulatorDeadbandCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogInAccumulatorDeadbandCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    getAccumulatorDeadband
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_getAccumulatorDeadband
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogInAccumulatorDeadband(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    setAccumulatorDeadband
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_setAccumulatorDeadband
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetAnalogInAccumulatorDeadband(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogInDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetAnalogInData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogOutDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogOutDataJNI.cpp
new file mode 100644
index 0000000..af9d6d6
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogOutDataJNI.cpp
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI.h"
+#include "mockdata/AnalogOutData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    registerVoltageCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_registerVoltageCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogOutVoltageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    cancelVoltageCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_cancelVoltageCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogOutVoltageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    getVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_getVoltage
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogOutVoltage(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    setVoltage
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_setVoltage
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAnalogOutVoltage(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterAnalogOutInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogOutInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogOutInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetAnalogOutInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogOutDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetAnalogOutData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogTriggerDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogTriggerDataJNI.cpp
new file mode 100644
index 0000000..66af737
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/AnalogTriggerDataJNI.cpp
@@ -0,0 +1,181 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI.h"
+#include "mockdata/AnalogTriggerData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAnalogTriggerInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelAnalogTriggerInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogTriggerInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetAnalogTriggerInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    registerTriggerLowerBoundCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_registerTriggerLowerBoundCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAnalogTriggerTriggerLowerBoundCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    cancelTriggerLowerBoundCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_cancelTriggerLowerBoundCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(
+      env, handle, index, &HALSIM_CancelAnalogTriggerTriggerLowerBoundCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    getTriggerLowerBound
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_getTriggerLowerBound
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogTriggerTriggerLowerBound(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    setTriggerLowerBound
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_setTriggerLowerBound
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAnalogTriggerTriggerLowerBound(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    registerTriggerUpperBoundCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_registerTriggerUpperBoundCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterAnalogTriggerTriggerUpperBoundCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    cancelTriggerUpperBoundCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_cancelTriggerUpperBoundCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(
+      env, handle, index, &HALSIM_CancelAnalogTriggerTriggerUpperBoundCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    getTriggerUpperBound
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_getTriggerUpperBound
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetAnalogTriggerTriggerUpperBound(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    setTriggerUpperBound
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_setTriggerUpperBound
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetAnalogTriggerTriggerUpperBound(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_AnalogTriggerDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetAnalogTriggerData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/BufferCallbackStore.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/BufferCallbackStore.cpp
new file mode 100644
index 0000000..fbf3adc
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/BufferCallbackStore.cpp
@@ -0,0 +1,125 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "BufferCallbackStore.h"
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "hal/Types.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/HAL_Value.h"
+#include "mockdata/NotifyListener.h"
+
+using namespace wpi::java;
+using namespace sim;
+
+static hal::UnlimitedHandleResource<SIM_JniHandle, BufferCallbackStore,
+                                    hal::HAL_HandleEnum::SimulationJni>*
+    callbackHandles;
+
+namespace sim {
+void InitializeBufferStore() {
+  static hal::UnlimitedHandleResource<SIM_JniHandle, BufferCallbackStore,
+                                      hal::HAL_HandleEnum::SimulationJni>
+      cb;
+  callbackHandles = &cb;
+}
+}  // namespace sim
+
+void BufferCallbackStore::create(JNIEnv* env, jobject obj) {
+  m_call = JGlobal<jobject>(env, obj);
+}
+
+void BufferCallbackStore::performCallback(const char* name, uint8_t* buffer,
+                                          uint32_t length) {
+  JNIEnv* env;
+  JavaVM* vm = sim::GetJVM();
+  bool didAttachThread = false;
+  int tryGetEnv = vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6);
+  if (tryGetEnv == JNI_EDETACHED) {
+    // Thread not attached
+    didAttachThread = true;
+    if (vm->AttachCurrentThread(reinterpret_cast<void**>(&env), nullptr) != 0) {
+      // Failed to attach, log and return
+      wpi::outs() << "Failed to attach\n";
+      wpi::outs().flush();
+      return;
+    }
+  } else if (tryGetEnv == JNI_EVERSION) {
+    wpi::outs() << "Invalid JVM Version requested\n";
+    wpi::outs().flush();
+  }
+
+  auto toCallbackArr =
+      MakeJByteArray(env, wpi::StringRef{reinterpret_cast<const char*>(buffer),
+                                         static_cast<size_t>(length)});
+
+  env->CallVoidMethod(m_call, sim::GetBufferCallback(), MakeJString(env, name),
+                      toCallbackArr, (jint)length);
+
+  jbyte* fromCallbackArr = reinterpret_cast<jbyte*>(
+      env->GetPrimitiveArrayCritical(toCallbackArr, nullptr));
+
+  for (size_t i = 0; i < length; i++) {
+    buffer[i] = fromCallbackArr[i];
+  }
+
+  env->ReleasePrimitiveArrayCritical(toCallbackArr, fromCallbackArr, JNI_ABORT);
+
+  if (env->ExceptionCheck()) {
+    env->ExceptionDescribe();
+  }
+
+  if (didAttachThread) {
+    vm->DetachCurrentThread();
+  }
+}
+
+void BufferCallbackStore::free(JNIEnv* env) { m_call.free(env); }
+
+SIM_JniHandle sim::AllocateBufferCallback(
+    JNIEnv* env, jint index, jobject callback,
+    RegisterBufferCallbackFunc createCallback) {
+  auto callbackStore = std::make_shared<BufferCallbackStore>();
+
+  auto handle = callbackHandles->Allocate(callbackStore);
+
+  if (handle == HAL_kInvalidHandle) {
+    return -1;
+  }
+
+  uintptr_t handleAsPtr = static_cast<uintptr_t>(handle);
+  void* handleAsVoidPtr = reinterpret_cast<void*>(handleAsPtr);
+
+  callbackStore->create(env, callback);
+
+  auto callbackFunc = [](const char* name, void* param, uint8_t* buffer,
+                         uint32_t length) {
+    uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+    SIM_JniHandle handle = static_cast<SIM_JniHandle>(handleTmp);
+    auto data = callbackHandles->Get(handle);
+    if (!data) return;
+
+    data->performCallback(name, buffer, length);
+  };
+
+  auto id = createCallback(index, callbackFunc, handleAsVoidPtr);
+
+  callbackStore->setCallbackId(id);
+
+  return handle;
+}
+
+void sim::FreeBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                             FreeBufferCallbackFunc freeCallback) {
+  auto callback = callbackHandles->Free(handle);
+  freeCallback(index, callback->getCallbackId());
+  callback->free(env);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/BufferCallbackStore.h b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/BufferCallbackStore.h
new file mode 100644
index 0000000..b9d49ac
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/BufferCallbackStore.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "hal/Types.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/HAL_Value.h"
+#include "mockdata/NotifyListener.h"
+
+namespace sim {
+class BufferCallbackStore {
+ public:
+  void create(JNIEnv* env, jobject obj);
+  void performCallback(const char* name, uint8_t* buffer, uint32_t length);
+  void free(JNIEnv* env);
+  void setCallbackId(int32_t id) { callbackId = id; }
+  int32_t getCallbackId() { return callbackId; }
+
+ private:
+  wpi::java::JGlobal<jobject> m_call;
+  int32_t callbackId;
+};
+
+void InitializeBufferStore();
+
+typedef int32_t (*RegisterBufferCallbackFunc)(int32_t index,
+                                              HAL_BufferCallback callback,
+                                              void* param);
+typedef void (*FreeBufferCallbackFunc)(int32_t index, int32_t uid);
+
+SIM_JniHandle AllocateBufferCallback(JNIEnv* env, jint index, jobject callback,
+                                     RegisterBufferCallbackFunc createCallback);
+void FreeBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                        FreeBufferCallbackFunc freeCallback);
+}  // namespace sim
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/CallbackStore.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/CallbackStore.cpp
new file mode 100644
index 0000000..abef9b0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/CallbackStore.cpp
@@ -0,0 +1,194 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "CallbackStore.h"
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "hal/Types.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/HAL_Value.h"
+#include "mockdata/NotifyListener.h"
+
+using namespace wpi::java;
+using namespace sim;
+
+static hal::UnlimitedHandleResource<SIM_JniHandle, CallbackStore,
+                                    hal::HAL_HandleEnum::SimulationJni>*
+    callbackHandles;
+
+namespace sim {
+void InitializeStore() {
+  static hal::UnlimitedHandleResource<SIM_JniHandle, CallbackStore,
+                                      hal::HAL_HandleEnum::SimulationJni>
+      cb;
+  callbackHandles = &cb;
+}
+}  // namespace sim
+
+void CallbackStore::create(JNIEnv* env, jobject obj) {
+  m_call = JGlobal<jobject>(env, obj);
+}
+
+void CallbackStore::performCallback(const char* name, const HAL_Value* value) {
+  JNIEnv* env;
+  JavaVM* vm = sim::GetJVM();
+  bool didAttachThread = false;
+  int tryGetEnv = vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6);
+  if (tryGetEnv == JNI_EDETACHED) {
+    // Thread not attached
+    didAttachThread = true;
+    if (vm->AttachCurrentThread(reinterpret_cast<void**>(&env), nullptr) != 0) {
+      // Failed to attach, log and return
+      wpi::outs() << "Failed to attach\n";
+      wpi::outs().flush();
+      return;
+    }
+  } else if (tryGetEnv == JNI_EVERSION) {
+    wpi::outs() << "Invalid JVM Version requested\n";
+    wpi::outs().flush();
+  }
+
+  env->CallVoidMethod(m_call, sim::GetNotifyCallback(), MakeJString(env, name),
+                      (jint)value->type, (jlong)value->data.v_long,
+                      (jdouble)value->data.v_double);
+
+  if (env->ExceptionCheck()) {
+    env->ExceptionDescribe();
+  }
+
+  if (didAttachThread) {
+    vm->DetachCurrentThread();
+  }
+}
+
+void CallbackStore::free(JNIEnv* env) { m_call.free(env); }
+
+SIM_JniHandle sim::AllocateCallback(JNIEnv* env, jint index, jobject callback,
+                                    jboolean initialNotify,
+                                    RegisterCallbackFunc createCallback) {
+  auto callbackStore = std::make_shared<CallbackStore>();
+
+  auto handle = callbackHandles->Allocate(callbackStore);
+
+  if (handle == HAL_kInvalidHandle) {
+    return -1;
+  }
+
+  uintptr_t handleAsPtr = static_cast<uintptr_t>(handle);
+  void* handleAsVoidPtr = reinterpret_cast<void*>(handleAsPtr);
+
+  callbackStore->create(env, callback);
+
+  auto callbackFunc = [](const char* name, void* param,
+                         const HAL_Value* value) {
+    uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+    SIM_JniHandle handle = static_cast<SIM_JniHandle>(handleTmp);
+    auto data = callbackHandles->Get(handle);
+    if (!data) return;
+
+    data->performCallback(name, value);
+  };
+
+  auto id = createCallback(index, callbackFunc, handleAsVoidPtr, initialNotify);
+
+  callbackStore->setCallbackId(id);
+
+  return handle;
+}
+
+void sim::FreeCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                       FreeCallbackFunc freeCallback) {
+  auto callback = callbackHandles->Free(handle);
+  freeCallback(index, callback->getCallbackId());
+  callback->free(env);
+}
+
+SIM_JniHandle sim::AllocateChannelCallback(
+    JNIEnv* env, jint index, jint channel, jobject callback,
+    jboolean initialNotify, RegisterChannelCallbackFunc createCallback) {
+  auto callbackStore = std::make_shared<CallbackStore>();
+
+  auto handle = callbackHandles->Allocate(callbackStore);
+
+  if (handle == HAL_kInvalidHandle) {
+    return -1;
+  }
+
+  uintptr_t handleAsPtr = static_cast<uintptr_t>(handle);
+  void* handleAsVoidPtr = reinterpret_cast<void*>(handleAsPtr);
+
+  callbackStore->create(env, callback);
+
+  auto callbackFunc = [](const char* name, void* param,
+                         const HAL_Value* value) {
+    uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+    SIM_JniHandle handle = static_cast<SIM_JniHandle>(handleTmp);
+    auto data = callbackHandles->Get(handle);
+    if (!data) return;
+
+    data->performCallback(name, value);
+  };
+
+  auto id = createCallback(index, channel, callbackFunc, handleAsVoidPtr,
+                           initialNotify);
+
+  callbackStore->setCallbackId(id);
+
+  return handle;
+}
+
+void sim::FreeChannelCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                              jint channel,
+                              FreeChannelCallbackFunc freeCallback) {
+  auto callback = callbackHandles->Free(handle);
+  freeCallback(index, channel, callback->getCallbackId());
+  callback->free(env);
+}
+
+SIM_JniHandle sim::AllocateCallbackNoIndex(
+    JNIEnv* env, jobject callback, jboolean initialNotify,
+    RegisterCallbackNoIndexFunc createCallback) {
+  auto callbackStore = std::make_shared<CallbackStore>();
+
+  auto handle = callbackHandles->Allocate(callbackStore);
+
+  if (handle == HAL_kInvalidHandle) {
+    return -1;
+  }
+
+  uintptr_t handleAsPtr = static_cast<uintptr_t>(handle);
+  void* handleAsVoidPtr = reinterpret_cast<void*>(handleAsPtr);
+
+  callbackStore->create(env, callback);
+
+  auto callbackFunc = [](const char* name, void* param,
+                         const HAL_Value* value) {
+    uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+    SIM_JniHandle handle = static_cast<SIM_JniHandle>(handleTmp);
+    auto data = callbackHandles->Get(handle);
+    if (!data) return;
+
+    data->performCallback(name, value);
+  };
+
+  auto id = createCallback(callbackFunc, handleAsVoidPtr, initialNotify);
+
+  callbackStore->setCallbackId(id);
+
+  return handle;
+}
+
+void sim::FreeCallbackNoIndex(JNIEnv* env, SIM_JniHandle handle,
+                              FreeCallbackNoIndexFunc freeCallback) {
+  auto callback = callbackHandles->Free(handle);
+  freeCallback(callback->getCallbackId());
+  callback->free(env);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/CallbackStore.h b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/CallbackStore.h
new file mode 100644
index 0000000..94454b0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/CallbackStore.h
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "hal/Types.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/HAL_Value.h"
+#include "mockdata/NotifyListener.h"
+
+namespace sim {
+class CallbackStore {
+ public:
+  void create(JNIEnv* env, jobject obj);
+  void performCallback(const char* name, const HAL_Value* value);
+  void free(JNIEnv* env);
+  void setCallbackId(int32_t id) { callbackId = id; }
+  int32_t getCallbackId() { return callbackId; }
+
+ private:
+  wpi::java::JGlobal<jobject> m_call;
+  int32_t callbackId;
+};
+
+void InitializeStore();
+
+typedef int32_t (*RegisterCallbackFunc)(int32_t index,
+                                        HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify);
+typedef void (*FreeCallbackFunc)(int32_t index, int32_t uid);
+typedef int32_t (*RegisterChannelCallbackFunc)(int32_t index, int32_t channel,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify);
+typedef void (*FreeChannelCallbackFunc)(int32_t index, int32_t channel,
+                                        int32_t uid);
+typedef int32_t (*RegisterCallbackNoIndexFunc)(HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify);
+typedef void (*FreeCallbackNoIndexFunc)(int32_t uid);
+
+SIM_JniHandle AllocateCallback(JNIEnv* env, jint index, jobject callback,
+                               jboolean initialNotify,
+                               RegisterCallbackFunc createCallback);
+SIM_JniHandle AllocateChannelCallback(
+    JNIEnv* env, jint index, jint channel, jobject callback,
+    jboolean initialNotify, RegisterChannelCallbackFunc createCallback);
+SIM_JniHandle AllocateCallbackNoIndex(
+    JNIEnv* env, jobject callback, jboolean initialNotify,
+    RegisterCallbackNoIndexFunc createCallback);
+void FreeCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                  FreeCallbackFunc freeCallback);
+void FreeChannelCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                         jint channel, FreeChannelCallbackFunc freeCallback);
+void FreeCallbackNoIndex(JNIEnv* env, SIM_JniHandle handle,
+                         FreeCallbackNoIndexFunc freeCallback);
+}  // namespace sim
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/ConstBufferCallbackStore.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/ConstBufferCallbackStore.cpp
new file mode 100644
index 0000000..781725b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/ConstBufferCallbackStore.cpp
@@ -0,0 +1,117 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ConstBufferCallbackStore.h"
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "hal/Types.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/HAL_Value.h"
+#include "mockdata/NotifyListener.h"
+
+using namespace wpi::java;
+using namespace sim;
+
+static hal::UnlimitedHandleResource<SIM_JniHandle, ConstBufferCallbackStore,
+                                    hal::HAL_HandleEnum::SimulationJni>*
+    callbackHandles;
+
+namespace sim {
+void InitializeConstBufferStore() {
+  static hal::UnlimitedHandleResource<SIM_JniHandle, ConstBufferCallbackStore,
+                                      hal::HAL_HandleEnum::SimulationJni>
+      cb;
+  callbackHandles = &cb;
+}
+}  // namespace sim
+
+void ConstBufferCallbackStore::create(JNIEnv* env, jobject obj) {
+  m_call = JGlobal<jobject>(env, obj);
+}
+
+void ConstBufferCallbackStore::performCallback(const char* name,
+                                               const uint8_t* buffer,
+                                               uint32_t length) {
+  JNIEnv* env;
+  JavaVM* vm = sim::GetJVM();
+  bool didAttachThread = false;
+  int tryGetEnv = vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6);
+  if (tryGetEnv == JNI_EDETACHED) {
+    // Thread not attached
+    didAttachThread = true;
+    if (vm->AttachCurrentThread(reinterpret_cast<void**>(&env), nullptr) != 0) {
+      // Failed to attach, log and return
+      wpi::outs() << "Failed to attach\n";
+      wpi::outs().flush();
+      return;
+    }
+  } else if (tryGetEnv == JNI_EVERSION) {
+    wpi::outs() << "Invalid JVM Version requested\n";
+    wpi::outs().flush();
+  }
+
+  auto toCallbackArr =
+      MakeJByteArray(env, wpi::StringRef{reinterpret_cast<const char*>(buffer),
+                                         static_cast<size_t>(length)});
+
+  env->CallVoidMethod(m_call, sim::GetConstBufferCallback(),
+                      MakeJString(env, name), toCallbackArr, (jint)length);
+
+  if (env->ExceptionCheck()) {
+    env->ExceptionDescribe();
+  }
+
+  if (didAttachThread) {
+    vm->DetachCurrentThread();
+  }
+}
+
+void ConstBufferCallbackStore::free(JNIEnv* env) { m_call.free(env); }
+
+SIM_JniHandle sim::AllocateConstBufferCallback(
+    JNIEnv* env, jint index, jobject callback,
+    RegisterConstBufferCallbackFunc createCallback) {
+  auto callbackStore = std::make_shared<ConstBufferCallbackStore>();
+
+  auto handle = callbackHandles->Allocate(callbackStore);
+
+  if (handle == HAL_kInvalidHandle) {
+    return -1;
+  }
+
+  uintptr_t handleAsPtr = static_cast<uintptr_t>(handle);
+  void* handleAsVoidPtr = reinterpret_cast<void*>(handleAsPtr);
+
+  callbackStore->create(env, callback);
+
+  auto callbackFunc = [](const char* name, void* param, const uint8_t* buffer,
+                         uint32_t length) {
+    uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+    SIM_JniHandle handle = static_cast<SIM_JniHandle>(handleTmp);
+    auto data = callbackHandles->Get(handle);
+    if (!data) return;
+
+    data->performCallback(name, buffer, length);
+  };
+
+  auto id = createCallback(index, callbackFunc, handleAsVoidPtr);
+
+  callbackStore->setCallbackId(id);
+
+  return handle;
+}
+
+void sim::FreeConstBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                                  FreeConstBufferCallbackFunc freeCallback) {
+  auto callback = callbackHandles->Free(handle);
+  freeCallback(index, callback->getCallbackId());
+  callback->free(env);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/ConstBufferCallbackStore.h b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/ConstBufferCallbackStore.h
new file mode 100644
index 0000000..1b0f54e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/ConstBufferCallbackStore.h
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "hal/Types.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/HAL_Value.h"
+#include "mockdata/NotifyListener.h"
+
+namespace sim {
+class ConstBufferCallbackStore {
+ public:
+  void create(JNIEnv* env, jobject obj);
+  void performCallback(const char* name, const uint8_t* buffer,
+                       uint32_t length);
+  void free(JNIEnv* env);
+  void setCallbackId(int32_t id) { callbackId = id; }
+  int32_t getCallbackId() { return callbackId; }
+
+ private:
+  wpi::java::JGlobal<jobject> m_call;
+  int32_t callbackId;
+};
+
+void InitializeConstBufferStore();
+
+typedef int32_t (*RegisterConstBufferCallbackFunc)(
+    int32_t index, HAL_ConstBufferCallback callback, void* param);
+typedef void (*FreeConstBufferCallbackFunc)(int32_t index, int32_t uid);
+
+SIM_JniHandle AllocateConstBufferCallback(
+    JNIEnv* env, jint index, jobject callback,
+    RegisterConstBufferCallbackFunc createCallback);
+void FreeConstBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                             FreeConstBufferCallbackFunc freeCallback);
+}  // namespace sim
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DIODataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DIODataJNI.cpp
new file mode 100644
index 0000000..2ad55f9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DIODataJNI.cpp
@@ -0,0 +1,277 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_DIODataJNI.h"
+#include "mockdata/DIOData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDIOInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDIOInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDIOInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetDIOInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    registerValueCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_registerValueCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDIOValueCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    cancelValueCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_cancelValueCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index, &HALSIM_CancelDIOValueCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    getValue
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_getValue
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDIOValue(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    setValue
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_setValue
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetDIOValue(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    registerPulseLengthCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_registerPulseLengthCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDIOPulseLengthCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    cancelPulseLengthCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_cancelPulseLengthCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDIOPulseLengthCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    getPulseLength
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_getPulseLength
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDIOPulseLength(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    setPulseLength
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_setPulseLength
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetDIOPulseLength(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    registerIsInputCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_registerIsInputCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDIOIsInputCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    cancelIsInputCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_cancelIsInputCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDIOIsInputCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    getIsInput
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_getIsInput
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDIOIsInput(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    setIsInput
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_setIsInput
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetDIOIsInput(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    registerFilterIndexCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_registerFilterIndexCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDIOFilterIndexCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    cancelFilterIndexCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_cancelFilterIndexCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDIOFilterIndexCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    getFilterIndex
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_getFilterIndex
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDIOFilterIndex(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    setFilterIndex
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_setFilterIndex
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetDIOFilterIndex(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DIODataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DIODataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetDIOData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DigitalPWMDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DigitalPWMDataJNI.cpp
new file mode 100644
index 0000000..0800917
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DigitalPWMDataJNI.cpp
@@ -0,0 +1,178 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI.h"
+#include "mockdata/DigitalPWMData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDigitalPWMInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDigitalPWMInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDigitalPWMInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetDigitalPWMInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    registerDutyCycleCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_registerDutyCycleCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDigitalPWMDutyCycleCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    cancelDutyCycleCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_cancelDutyCycleCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDigitalPWMDutyCycleCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    getDutyCycle
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_getDutyCycle
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDigitalPWMDutyCycle(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    setDutyCycle
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_setDutyCycle
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetDigitalPWMDutyCycle(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    registerPinCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_registerPinCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterDigitalPWMPinCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    cancelPinCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_cancelPinCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelDigitalPWMPinCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    getPin
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_getPin
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetDigitalPWMPin(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    setPin
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_setPin
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetDigitalPWMPin(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DigitalPWMDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetDigitalPWMData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DriverStationDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DriverStationDataJNI.cpp
new file mode 100644
index 0000000..621650a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/DriverStationDataJNI.cpp
@@ -0,0 +1,461 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cstring>
+
+#include <wpi/jni_util.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI.h"
+#include "mockdata/DriverStationData.h"
+
+using namespace wpi::java;
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    registerEnabledCallback
+ * Signature: (Ljava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_registerEnabledCallback
+  (JNIEnv* env, jclass, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallbackNoIndex(
+      env, callback, initialNotify,
+      &HALSIM_RegisterDriverStationEnabledCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    cancelEnabledCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_cancelEnabledCallback
+  (JNIEnv* env, jclass, jint handle)
+{
+  return sim::FreeCallbackNoIndex(env, handle,
+                                  &HALSIM_CancelDriverStationEnabledCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    getEnabled
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_getEnabled
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetDriverStationEnabled();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setEnabled
+ * Signature: (Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setEnabled
+  (JNIEnv*, jclass, jboolean value)
+{
+  HALSIM_SetDriverStationEnabled(value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    registerAutonomousCallback
+ * Signature: (Ljava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_registerAutonomousCallback
+  (JNIEnv* env, jclass, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallbackNoIndex(
+      env, callback, initialNotify,
+      &HALSIM_RegisterDriverStationAutonomousCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    cancelAutonomousCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_cancelAutonomousCallback
+  (JNIEnv* env, jclass, jint handle)
+{
+  return sim::FreeCallbackNoIndex(
+      env, handle, &HALSIM_CancelDriverStationAutonomousCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    getAutonomous
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_getAutonomous
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetDriverStationAutonomous();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setAutonomous
+ * Signature: (Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setAutonomous
+  (JNIEnv*, jclass, jboolean value)
+{
+  HALSIM_SetDriverStationAutonomous(value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    registerTestCallback
+ * Signature: (Ljava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_registerTestCallback
+  (JNIEnv* env, jclass, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallbackNoIndex(
+      env, callback, initialNotify, &HALSIM_RegisterDriverStationTestCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    cancelTestCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_cancelTestCallback
+  (JNIEnv* env, jclass, jint handle)
+{
+  return sim::FreeCallbackNoIndex(env, handle,
+                                  &HALSIM_CancelDriverStationTestCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    getTest
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_getTest
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetDriverStationTest();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setTest
+ * Signature: (Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setTest
+  (JNIEnv*, jclass, jboolean value)
+{
+  HALSIM_SetDriverStationTest(value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    registerEStopCallback
+ * Signature: (Ljava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_registerEStopCallback
+  (JNIEnv* env, jclass, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallbackNoIndex(
+      env, callback, initialNotify, &HALSIM_RegisterDriverStationEStopCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    cancelEStopCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_cancelEStopCallback
+  (JNIEnv* env, jclass, jint handle)
+{
+  return sim::FreeCallbackNoIndex(env, handle,
+                                  &HALSIM_CancelDriverStationEStopCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    getEStop
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_getEStop
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetDriverStationEStop();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setEStop
+ * Signature: (Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setEStop
+  (JNIEnv*, jclass, jboolean value)
+{
+  HALSIM_SetDriverStationEStop(value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    registerFmsAttachedCallback
+ * Signature: (Ljava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_registerFmsAttachedCallback
+  (JNIEnv* env, jclass, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallbackNoIndex(
+      env, callback, initialNotify,
+      &HALSIM_RegisterDriverStationFmsAttachedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    cancelFmsAttachedCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_cancelFmsAttachedCallback
+  (JNIEnv* env, jclass, jint handle)
+{
+  return sim::FreeCallbackNoIndex(
+      env, handle, &HALSIM_CancelDriverStationFmsAttachedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    getFmsAttached
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_getFmsAttached
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetDriverStationFmsAttached();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setFmsAttached
+ * Signature: (Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setFmsAttached
+  (JNIEnv*, jclass, jboolean value)
+{
+  HALSIM_SetDriverStationFmsAttached(value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    registerDsAttachedCallback
+ * Signature: (Ljava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_registerDsAttachedCallback
+  (JNIEnv* env, jclass, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallbackNoIndex(
+      env, callback, initialNotify,
+      &HALSIM_RegisterDriverStationDsAttachedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    cancelDsAttachedCallback
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_cancelDsAttachedCallback
+  (JNIEnv* env, jclass, jint handle)
+{
+  return sim::FreeCallbackNoIndex(
+      env, handle, &HALSIM_CancelDriverStationDsAttachedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    getDsAttached
+ * Signature: ()Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_getDsAttached
+  (JNIEnv*, jclass)
+{
+  return HALSIM_GetDriverStationDsAttached();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setDsAttached
+ * Signature: (Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setDsAttached
+  (JNIEnv*, jclass, jboolean value)
+{
+  HALSIM_SetDriverStationDsAttached(value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setJoystickAxes
+ * Signature: (B[F)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setJoystickAxes
+  (JNIEnv* env, jclass, jbyte joystickNum, jfloatArray axesArray)
+{
+  HAL_JoystickAxes axes;
+  {
+    wpi::java::JFloatArrayRef jArrayRef(env, axesArray);
+    auto arrayRef = jArrayRef.array();
+    auto arraySize = arrayRef.size();
+    int maxCount =
+        arraySize < HAL_kMaxJoystickAxes ? arraySize : HAL_kMaxJoystickAxes;
+    axes.count = maxCount;
+    for (int i = 0; i < maxCount; i++) {
+      axes.axes[i] = arrayRef[i];
+    }
+  }
+  HALSIM_SetJoystickAxes(joystickNum, &axes);
+  return;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setJoystickPOVs
+ * Signature: (B[S)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setJoystickPOVs
+  (JNIEnv* env, jclass, jbyte joystickNum, jshortArray povsArray)
+{
+  HAL_JoystickPOVs povs;
+  {
+    wpi::java::JShortArrayRef jArrayRef(env, povsArray);
+    auto arrayRef = jArrayRef.array();
+    auto arraySize = arrayRef.size();
+    int maxCount =
+        arraySize < HAL_kMaxJoystickPOVs ? arraySize : HAL_kMaxJoystickPOVs;
+    povs.count = maxCount;
+    for (int i = 0; i < maxCount; i++) {
+      povs.povs[i] = arrayRef[i];
+    }
+  }
+  HALSIM_SetJoystickPOVs(joystickNum, &povs);
+  return;
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setJoystickButtons
+ * Signature: (BII)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setJoystickButtons
+  (JNIEnv* env, jclass, jbyte joystickNum, jint buttons, jint count)
+{
+  if (count > 32) {
+    count = 32;
+  }
+  HAL_JoystickButtons joystickButtons;
+  joystickButtons.count = count;
+  joystickButtons.buttons = buttons;
+  HALSIM_SetJoystickButtons(joystickNum, &joystickButtons);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    setMatchInfo
+ * Signature: (Ljava/lang/String;Ljava/lang/String;III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_setMatchInfo
+  (JNIEnv* env, jclass, jstring eventName, jstring gameSpecificMessage,
+   jint matchNumber, jint replayNumber, jint matchType)
+{
+  JStringRef eventNameRef{env, eventName};
+  JStringRef gameSpecificMessageRef{env, gameSpecificMessage};
+
+  HAL_MatchInfo halMatchInfo;
+  std::snprintf(halMatchInfo.eventName, sizeof(halMatchInfo.eventName), "%s",
+                eventNameRef.c_str());
+  std::snprintf(reinterpret_cast<char*>(halMatchInfo.gameSpecificMessage),
+                sizeof(halMatchInfo.gameSpecificMessage), "%s",
+                gameSpecificMessageRef.c_str());
+  halMatchInfo.gameSpecificMessageSize = gameSpecificMessageRef.size();
+  halMatchInfo.matchType = (HAL_MatchType)matchType;
+  halMatchInfo.matchNumber = matchNumber;
+  halMatchInfo.replayNumber = replayNumber;
+  HALSIM_SetMatchInfo(&halMatchInfo);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    registerAllCallbacks
+ * Signature: (Ljava/lang/Object;Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_registerAllCallbacks
+  (JNIEnv* env, jclass, jobject callback, jboolean initialNotify)
+{
+  sim::AllocateCallbackNoIndex(
+      env, callback, initialNotify,
+      [](HAL_NotifyCallback cb, void* param, HAL_Bool in) {
+        HALSIM_RegisterDriverStationAllCallbacks(cb, param, in);
+        return 0;
+      });
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    notifyNewData
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_notifyNewData
+  (JNIEnv*, jclass)
+{
+  HALSIM_NotifyDriverStationNewData();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI
+ * Method:    resetData
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_DriverStationDataJNI_resetData
+  (JNIEnv*, jclass)
+{
+  HALSIM_ResetDriverStationData();
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/EncoderDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/EncoderDataJNI.cpp
new file mode 100644
index 0000000..8992b0c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/EncoderDataJNI.cpp
@@ -0,0 +1,428 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_EncoderDataJNI.h"
+#include "mockdata/EncoderData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterEncoderInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelEncoderInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetEncoderInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetEncoderInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    registerCountCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_registerCountCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterEncoderCountCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    cancelCountCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_cancelCountCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelEncoderCountCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    getCount
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_getCount
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetEncoderCount(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    setCount
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_setCount
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetEncoderCount(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    registerPeriodCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_registerPeriodCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterEncoderPeriodCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    cancelPeriodCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_cancelPeriodCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelEncoderPeriodCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    getPeriod
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_getPeriod
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetEncoderPeriod(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    setPeriod
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_setPeriod
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetEncoderPeriod(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    registerResetCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_registerResetCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterEncoderResetCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    cancelResetCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_cancelResetCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelEncoderResetCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    getReset
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_getReset
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetEncoderReset(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    setReset
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_setReset
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetEncoderReset(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    registerMaxPeriodCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_registerMaxPeriodCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterEncoderMaxPeriodCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    cancelMaxPeriodCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_cancelMaxPeriodCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelEncoderMaxPeriodCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    getMaxPeriod
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_getMaxPeriod
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetEncoderMaxPeriod(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    setMaxPeriod
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_setMaxPeriod
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetEncoderMaxPeriod(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    registerDirectionCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_registerDirectionCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterEncoderDirectionCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    cancelDirectionCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_cancelDirectionCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelEncoderDirectionCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    getDirection
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_getDirection
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetEncoderDirection(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    setDirection
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_setDirection
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetEncoderDirection(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    registerReverseDirectionCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_registerReverseDirectionCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterEncoderReverseDirectionCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    cancelReverseDirectionCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_cancelReverseDirectionCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelEncoderReverseDirectionCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    getReverseDirection
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_getReverseDirection
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetEncoderReverseDirection(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    setReverseDirection
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_setReverseDirection
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetEncoderReverseDirection(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    registerSamplesToAverageCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_registerSamplesToAverageCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterEncoderSamplesToAverageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    cancelSamplesToAverageCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_cancelSamplesToAverageCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelEncoderSamplesToAverageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    getSamplesToAverage
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_getSamplesToAverage
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetEncoderSamplesToAverage(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    setSamplesToAverage
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_setSamplesToAverage
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetEncoderSamplesToAverage(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_EncoderDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_EncoderDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetEncoderData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/I2CDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/I2CDataJNI.cpp
new file mode 100644
index 0000000..14b3292
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/I2CDataJNI.cpp
@@ -0,0 +1,131 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "BufferCallbackStore.h"
+#include "CallbackStore.h"
+#include "ConstBufferCallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_I2CDataJNI.h"
+#include "mockdata/I2CData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterI2CInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelI2CInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetI2CInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetI2CInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    registerReadCallback
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_registerReadCallback
+  (JNIEnv* env, jclass, jint index, jobject callback)
+{
+  return sim::AllocateBufferCallback(env, index, callback,
+                                     &HALSIM_RegisterI2CReadCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    cancelReadCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_cancelReadCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  sim::FreeBufferCallback(env, handle, index, &HALSIM_CancelI2CReadCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    registerWriteCallback
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_registerWriteCallback
+  (JNIEnv* env, jclass, jint index, jobject callback)
+{
+  return sim::AllocateConstBufferCallback(env, index, callback,
+                                          &HALSIM_RegisterI2CWriteCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    cancelWriteCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_cancelWriteCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  sim::FreeConstBufferCallback(env, handle, index,
+                               &HALSIM_CancelI2CWriteCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_I2CDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_I2CDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetI2CData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PCMDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PCMDataJNI.cpp
new file mode 100644
index 0000000..de6f738
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PCMDataJNI.cpp
@@ -0,0 +1,419 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_PCMDataJNI.h"
+#include "mockdata/PCMData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerSolenoidInitializedCallback
+ * Signature: (IILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerSolenoidInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint channel, jobject callback,
+   jboolean initialNotify)
+{
+  return sim::AllocateChannelCallback(
+      env, index, channel, callback, initialNotify,
+      &HALSIM_RegisterPCMSolenoidInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    cancelSolenoidInitializedCallback
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_cancelSolenoidInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint channel, jint handle)
+{
+  return sim::FreeChannelCallback(env, handle, index, channel,
+                                  &HALSIM_CancelPCMSolenoidInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    getSolenoidInitialized
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_getSolenoidInitialized
+  (JNIEnv*, jclass, jint index, jint channel)
+{
+  return HALSIM_GetPCMSolenoidInitialized(index, channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    setSolenoidInitialized
+ * Signature: (IIZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_setSolenoidInitialized
+  (JNIEnv*, jclass, jint index, jint channel, jboolean value)
+{
+  HALSIM_SetPCMSolenoidInitialized(index, channel, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerSolenoidOutputCallback
+ * Signature: (IILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerSolenoidOutputCallback
+  (JNIEnv* env, jclass, jint index, jint channel, jobject callback,
+   jboolean initialNotify)
+{
+  return sim::AllocateChannelCallback(
+      env, index, channel, callback, initialNotify,
+      &HALSIM_RegisterPCMSolenoidOutputCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    cancelSolenoidOutputCallback
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_cancelSolenoidOutputCallback
+  (JNIEnv* env, jclass, jint index, jint channel, jint handle)
+{
+  return sim::FreeChannelCallback(env, handle, index, channel,
+                                  &HALSIM_CancelPCMSolenoidOutputCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    getSolenoidOutput
+ * Signature: (II)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_getSolenoidOutput
+  (JNIEnv*, jclass, jint index, jint channel)
+{
+  return HALSIM_GetPCMSolenoidOutput(index, channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    setSolenoidOutput
+ * Signature: (IIZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_setSolenoidOutput
+  (JNIEnv*, jclass, jint index, jint channel, jboolean value)
+{
+  HALSIM_SetPCMSolenoidOutput(index, channel, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerCompressorInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerCompressorInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      &HALSIM_RegisterPCMCompressorInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    cancelCompressorInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_cancelCompressorInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPCMCompressorInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    getCompressorInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_getCompressorInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPCMCompressorInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    setCompressorInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_setCompressorInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetPCMCompressorInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerCompressorOnCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerCompressorOnCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPCMCompressorOnCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    cancelCompressorOnCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_cancelCompressorOnCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPCMCompressorOnCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    getCompressorOn
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_getCompressorOn
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPCMCompressorOn(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    setCompressorOn
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_setCompressorOn
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetPCMCompressorOn(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerClosedLoopEnabledCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerClosedLoopEnabledCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPCMClosedLoopEnabledCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    cancelClosedLoopEnabledCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_cancelClosedLoopEnabledCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPCMClosedLoopEnabledCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    getClosedLoopEnabled
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_getClosedLoopEnabled
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPCMClosedLoopEnabled(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    setClosedLoopEnabled
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_setClosedLoopEnabled
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetPCMClosedLoopEnabled(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerPressureSwitchCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerPressureSwitchCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPCMPressureSwitchCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    cancelPressureSwitchCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_cancelPressureSwitchCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPCMPressureSwitchCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    getPressureSwitch
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_getPressureSwitch
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPCMPressureSwitch(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    setPressureSwitch
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_setPressureSwitch
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetPCMPressureSwitch(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerCompressorCurrentCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerCompressorCurrentCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPCMCompressorCurrentCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    cancelCompressorCurrentCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_cancelCompressorCurrentCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPCMCompressorCurrentCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    getCompressorCurrent
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_getCompressorCurrent
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPCMCompressorCurrent(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    setCompressorCurrent
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_setCompressorCurrent
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetPCMCompressorCurrent(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerAllNonSolenoidCallbacks
+ * Signature: (ILjava/lang/Object;Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerAllNonSolenoidCallbacks
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  sim::AllocateCallback(
+      env, index, callback, initialNotify,
+      [](int32_t index, HAL_NotifyCallback cb, void* param, HAL_Bool in) {
+        HALSIM_RegisterPCMAllNonSolenoidCallbacks(index, cb, param, in);
+        return 0;
+      });
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    registerAllSolenoidCallbacks
+ * Signature: (IILjava/lang/Object;Z)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_registerAllSolenoidCallbacks
+  (JNIEnv* env, jclass, jint index, jint channel, jobject callback,
+   jboolean initialNotify)
+{
+  sim::AllocateChannelCallback(
+      env, index, channel, callback, initialNotify,
+      [](int32_t index, int32_t channel, HAL_NotifyCallback cb, void* param,
+         HAL_Bool in) {
+        HALSIM_RegisterPCMAllSolenoidCallbacks(index, channel, cb, param, in);
+        return 0;
+      });
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PCMDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PCMDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetPCMData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PDPDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PDPDataJNI.cpp
new file mode 100644
index 0000000..5d39e87
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PDPDataJNI.cpp
@@ -0,0 +1,230 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_PDPDataJNI.h"
+#include "mockdata/PDPData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPDPInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPDPInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPDPInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetPDPInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    registerTemperatureCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_registerTemperatureCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPDPTemperatureCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    cancelTemperatureCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_cancelTemperatureCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPDPTemperatureCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    getTemperature
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_getTemperature
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPDPTemperature(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    setTemperature
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_setTemperature
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetPDPTemperature(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    registerVoltageCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_registerVoltageCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPDPVoltageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    cancelVoltageCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_cancelVoltageCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPDPVoltageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    getVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_getVoltage
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPDPVoltage(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    setVoltage
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_setVoltage
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetPDPVoltage(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    registerCurrentCallback
+ * Signature: (IILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_registerCurrentCallback
+  (JNIEnv* env, jclass, jint index, jint channel, jobject callback,
+   jboolean initialNotify)
+{
+  return sim::AllocateChannelCallback(env, index, channel, callback,
+                                      initialNotify,
+                                      &HALSIM_RegisterPDPCurrentCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    cancelCurrentCallback
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_cancelCurrentCallback
+  (JNIEnv* env, jclass, jint index, jint channel, jint handle)
+{
+  return sim::FreeChannelCallback(env, handle, index, channel,
+                                  &HALSIM_CancelPDPCurrentCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    getCurrent
+ * Signature: (II)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_getCurrent
+  (JNIEnv*, jclass, jint index, jint channel)
+{
+  return HALSIM_GetPDPCurrent(index, channel);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    setCurrent
+ * Signature: (IID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_setCurrent
+  (JNIEnv*, jclass, jint index, jint channel, jdouble value)
+{
+  HALSIM_SetPDPCurrent(index, channel, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PDPDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PDPDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetPDPData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PWMDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PWMDataJNI.cpp
new file mode 100644
index 0000000..b8a7c41
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/PWMDataJNI.cpp
@@ -0,0 +1,327 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_PWMDataJNI.h"
+#include "mockdata/PWMData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPWMInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPWMInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPWMInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetPWMInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    registerRawValueCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_registerRawValueCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPWMRawValueCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    cancelRawValueCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_cancelRawValueCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPWMRawValueCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    getRawValue
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_getRawValue
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPWMRawValue(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    setRawValue
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_setRawValue
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetPWMRawValue(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    registerSpeedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_registerSpeedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPWMSpeedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    cancelSpeedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_cancelSpeedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index, &HALSIM_CancelPWMSpeedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    getSpeed
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_getSpeed
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPWMSpeed(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    setSpeed
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_setSpeed
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetPWMSpeed(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    registerPositionCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_registerPositionCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPWMPositionCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    cancelPositionCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_cancelPositionCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPWMPositionCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    getPosition
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_getPosition
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPWMPosition(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    setPosition
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_setPosition
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetPWMPosition(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    registerPeriodScaleCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_registerPeriodScaleCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPWMPeriodScaleCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    cancelPeriodScaleCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_cancelPeriodScaleCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPWMPeriodScaleCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    getPeriodScale
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_getPeriodScale
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPWMPeriodScale(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    setPeriodScale
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_setPeriodScale
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetPWMPeriodScale(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    registerZeroLatchCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_registerZeroLatchCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterPWMZeroLatchCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    cancelZeroLatchCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_cancelZeroLatchCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelPWMZeroLatchCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    getZeroLatch
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_getZeroLatch
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetPWMZeroLatch(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    setZeroLatch
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_setZeroLatch
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetPWMZeroLatch(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_PWMDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_PWMDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetPWMData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/RelayDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/RelayDataJNI.cpp
new file mode 100644
index 0000000..bf85407
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/RelayDataJNI.cpp
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_RelayDataJNI.h"
+#include "mockdata/RelayData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    registerInitializedForwardCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_registerInitializedForwardCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRelayInitializedForwardCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    cancelInitializedForwardCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_cancelInitializedForwardCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRelayInitializedForwardCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    getInitializedForward
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_getInitializedForward
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRelayInitializedForward(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    setInitializedForward
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_setInitializedForward
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetRelayInitializedForward(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    registerInitializedReverseCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_registerInitializedReverseCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRelayInitializedReverseCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    cancelInitializedReverseCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_cancelInitializedReverseCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRelayInitializedReverseCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    getInitializedReverse
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_getInitializedReverse
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRelayInitializedReverse(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    setInitializedReverse
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_setInitializedReverse
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetRelayInitializedReverse(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    registerForwardCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_registerForwardCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRelayForwardCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    cancelForwardCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_cancelForwardCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRelayForwardCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    getForward
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_getForward
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRelayForward(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    setForward
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_setForward
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetRelayForward(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    registerReverseCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_registerReverseCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRelayReverseCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    cancelReverseCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_cancelReverseCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRelayReverseCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    getReverse
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_getReverse
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRelayReverse(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    setReverse
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_setReverse
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetRelayReverse(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RelayDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RelayDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetRelayData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/RoboRioDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/RoboRioDataJNI.cpp
new file mode 100644
index 0000000..d69e895
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/RoboRioDataJNI.cpp
@@ -0,0 +1,778 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI.h"
+#include "mockdata/RoboRioData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerFPGAButtonCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerFPGAButtonCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioFPGAButtonCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelFPGAButtonCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelFPGAButtonCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioFPGAButtonCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getFPGAButton
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getFPGAButton
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioFPGAButton(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setFPGAButton
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setFPGAButton
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetRoboRioFPGAButton(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerVInVoltageCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerVInVoltageCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioVInVoltageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelVInVoltageCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelVInVoltageCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioVInVoltageCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getVInVoltage
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getVInVoltage
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioVInVoltage(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setVInVoltage
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setVInVoltage
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetRoboRioVInVoltage(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerVInCurrentCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerVInCurrentCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioVInCurrentCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelVInCurrentCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelVInCurrentCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioVInCurrentCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getVInCurrent
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getVInCurrent
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioVInCurrent(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setVInCurrent
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setVInCurrent
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetRoboRioVInCurrent(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserVoltage6VCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserVoltage6VCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserVoltage6VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserVoltage6VCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserVoltage6VCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserVoltage6VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserVoltage6V
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserVoltage6V
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserVoltage6V(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserVoltage6V
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserVoltage6V
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetRoboRioUserVoltage6V(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserCurrent6VCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserCurrent6VCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserCurrent6VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserCurrent6VCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserCurrent6VCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserCurrent6VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserCurrent6V
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserCurrent6V
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserCurrent6V(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserCurrent6V
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserCurrent6V
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetRoboRioUserCurrent6V(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserActive6VCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserActive6VCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserActive6VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserActive6VCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserActive6VCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserActive6VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserActive6V
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserActive6V
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserActive6V(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserActive6V
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserActive6V
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetRoboRioUserActive6V(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserVoltage5VCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserVoltage5VCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserVoltage5VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserVoltage5VCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserVoltage5VCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserVoltage5VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserVoltage5V
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserVoltage5V
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserVoltage5V(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserVoltage5V
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserVoltage5V
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetRoboRioUserVoltage5V(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserCurrent5VCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserCurrent5VCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserCurrent5VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserCurrent5VCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserCurrent5VCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserCurrent5VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserCurrent5V
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserCurrent5V
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserCurrent5V(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserCurrent5V
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserCurrent5V
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetRoboRioUserCurrent5V(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserActive5VCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserActive5VCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserActive5VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserActive5VCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserActive5VCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserActive5VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserActive5V
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserActive5V
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserActive5V(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserActive5V
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserActive5V
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetRoboRioUserActive5V(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserVoltage3V3Callback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserVoltage3V3Callback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserVoltage3V3Callback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserVoltage3V3Callback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserVoltage3V3Callback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserVoltage3V3Callback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserVoltage3V3
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserVoltage3V3
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserVoltage3V3(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserVoltage3V3
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserVoltage3V3
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetRoboRioUserVoltage3V3(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserCurrent3V3Callback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserCurrent3V3Callback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserCurrent3V3Callback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserCurrent3V3Callback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserCurrent3V3Callback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserCurrent3V3Callback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserCurrent3V3
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserCurrent3V3
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserCurrent3V3(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserCurrent3V3
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserCurrent3V3
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetRoboRioUserCurrent3V3(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserActive3V3Callback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserActive3V3Callback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserActive3V3Callback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserActive3V3Callback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserActive3V3Callback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserActive3V3Callback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserActive3V3
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserActive3V3
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserActive3V3(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserActive3V3
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserActive3V3
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetRoboRioUserActive3V3(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserFaults6VCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserFaults6VCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserFaults6VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserFaults6VCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserFaults6VCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserFaults6VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserFaults6V
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserFaults6V
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserFaults6V(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserFaults6V
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserFaults6V
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetRoboRioUserFaults6V(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserFaults5VCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserFaults5VCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserFaults5VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserFaults5VCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserFaults5VCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserFaults5VCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserFaults5V
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserFaults5V
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserFaults5V(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserFaults5V
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserFaults5V
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetRoboRioUserFaults5V(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    registerUserFaults3V3Callback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_registerUserFaults3V3Callback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterRoboRioUserFaults3V3Callback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    cancelUserFaults3V3Callback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_cancelUserFaults3V3Callback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelRoboRioUserFaults3V3Callback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    getUserFaults3V3
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_getUserFaults3V3
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetRoboRioUserFaults3V3(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    setUserFaults3V3
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_setUserFaults3V3
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetRoboRioUserFaults3V3(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_RoboRioDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetRoboRioData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SPIAccelerometerDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SPIAccelerometerDataJNI.cpp
new file mode 100644
index 0000000..ca12f79
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SPIAccelerometerDataJNI.cpp
@@ -0,0 +1,278 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "CallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI.h"
+#include "mockdata/SPIAccelerometerData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    registerActiveCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_registerActiveCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterSPIAccelerometerActiveCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    cancelActiveCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_cancelActiveCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelSPIAccelerometerActiveCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    getActive
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_getActive
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetSPIAccelerometerActive(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    setActive
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_setActive
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetSPIAccelerometerActive(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    registerRangeCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_registerRangeCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterSPIAccelerometerRangeCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    cancelRangeCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_cancelRangeCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelSPIAccelerometerRangeCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    getRange
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_getRange
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetSPIAccelerometerRange(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    setRange
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_setRange
+  (JNIEnv*, jclass, jint index, jint value)
+{
+  HALSIM_SetSPIAccelerometerRange(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    registerXCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_registerXCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterSPIAccelerometerXCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    cancelXCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_cancelXCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelSPIAccelerometerXCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    getX
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_getX
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetSPIAccelerometerX(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    setX
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_setX
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetSPIAccelerometerX(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    registerYCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_registerYCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterSPIAccelerometerYCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    cancelYCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_cancelYCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelSPIAccelerometerYCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    getY
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_getY
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetSPIAccelerometerY(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    setY
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_setY
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetSPIAccelerometerY(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    registerZCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_registerZCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterSPIAccelerometerZCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    cancelZCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_cancelZCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelSPIAccelerometerZCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    getZ
+ * Signature: (I)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_getZ
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetSPIAccelerometerZ(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    setZ
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_setZ
+  (JNIEnv*, jclass, jint index, jdouble value)
+{
+  HALSIM_SetSPIAccelerometerZ(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIAccelerometerDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetSPIAccelerometerData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SPIDataJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SPIDataJNI.cpp
new file mode 100644
index 0000000..4eb342c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SPIDataJNI.cpp
@@ -0,0 +1,158 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include "BufferCallbackStore.h"
+#include "CallbackStore.h"
+#include "ConstBufferCallbackStore.h"
+#include "SpiReadAutoReceiveBufferCallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_SPIDataJNI.h"
+#include "mockdata/SPIData.h"
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    registerInitializedCallback
+ * Signature: (ILjava/lang/Object;Z)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_registerInitializedCallback
+  (JNIEnv* env, jclass, jint index, jobject callback, jboolean initialNotify)
+{
+  return sim::AllocateCallback(env, index, callback, initialNotify,
+                               &HALSIM_RegisterSPIInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    cancelInitializedCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_cancelInitializedCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  return sim::FreeCallback(env, handle, index,
+                           &HALSIM_CancelSPIInitializedCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    getInitialized
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_getInitialized
+  (JNIEnv*, jclass, jint index)
+{
+  return HALSIM_GetSPIInitialized(index);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    setInitialized
+ * Signature: (IZ)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_setInitialized
+  (JNIEnv*, jclass, jint index, jboolean value)
+{
+  HALSIM_SetSPIInitialized(index, value);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    registerReadCallback
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_registerReadCallback
+  (JNIEnv* env, jclass, jint index, jobject callback)
+{
+  return sim::AllocateBufferCallback(env, index, callback,
+                                     &HALSIM_RegisterSPIReadCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    cancelReadCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_cancelReadCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  sim::FreeBufferCallback(env, handle, index, &HALSIM_CancelSPIReadCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    registerWriteCallback
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_registerWriteCallback
+  (JNIEnv* env, jclass, jint index, jobject callback)
+{
+  return sim::AllocateConstBufferCallback(env, index, callback,
+                                          &HALSIM_RegisterSPIWriteCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    cancelWriteCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_cancelWriteCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  sim::FreeConstBufferCallback(env, handle, index,
+                               &HALSIM_CancelSPIWriteCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    registerReadAutoReceiveBufferCallback
+ * Signature: (ILjava/lang/Object;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_registerReadAutoReceiveBufferCallback
+  (JNIEnv* env, jclass, jint index, jobject callback)
+{
+  return sim::AllocateSpiBufferCallback(
+      env, index, callback, &HALSIM_RegisterSPIReadAutoReceivedDataCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    cancelReadAutoReceiveBufferCallback
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_cancelReadAutoReceiveBufferCallback
+  (JNIEnv* env, jclass, jint index, jint handle)
+{
+  sim::FreeSpiBufferCallback(env, handle, index,
+                             &HALSIM_CancelSPIReadAutoReceivedDataCallback);
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SPIDataJNI
+ * Method:    resetData
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SPIDataJNI_resetData
+  (JNIEnv*, jclass, jint index)
+{
+  HALSIM_ResetSPIData(index);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SimulatorJNI.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SimulatorJNI.cpp
new file mode 100644
index 0000000..d1e0f7d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SimulatorJNI.cpp
@@ -0,0 +1,157 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SimulatorJNI.h"
+
+#include "BufferCallbackStore.h"
+#include "CallbackStore.h"
+#include "ConstBufferCallbackStore.h"
+#include "SpiReadAutoReceiveBufferCallbackStore.h"
+#include "edu_wpi_first_hal_sim_mockdata_SimulatorJNI.h"
+#include "hal/HAL.h"
+#include "hal/cpp/Log.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/MockHooks.h"
+
+using namespace wpi::java;
+
+static JavaVM* jvm = nullptr;
+static JClass simValueCls;
+static JClass notifyCallbackCls;
+static JClass bufferCallbackCls;
+static JClass constBufferCallbackCls;
+static JClass spiReadAutoReceiveBufferCallbackCls;
+static jmethodID notifyCallbackCallback;
+static jmethodID bufferCallbackCallback;
+static jmethodID constBufferCallbackCallback;
+static jmethodID spiReadAutoReceiveBufferCallbackCallback;
+
+namespace sim {
+jint SimOnLoad(JavaVM* vm, void* reserved) {
+  jvm = vm;
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return JNI_ERR;
+
+  simValueCls = JClass(env, "edu/wpi/first/hal/sim/SimValue");
+  if (!simValueCls) return JNI_ERR;
+
+  notifyCallbackCls = JClass(env, "edu/wpi/first/hal/sim/NotifyCallback");
+  if (!notifyCallbackCls) return JNI_ERR;
+
+  notifyCallbackCallback = env->GetMethodID(notifyCallbackCls, "callbackNative",
+                                            "(Ljava/lang/String;IJD)V");
+  if (!notifyCallbackCallback) return JNI_ERR;
+
+  bufferCallbackCls = JClass(env, "edu/wpi/first/hal/sim/BufferCallback");
+  if (!bufferCallbackCls) return JNI_ERR;
+
+  bufferCallbackCallback = env->GetMethodID(bufferCallbackCls, "callback",
+                                            "(Ljava/lang/String;[BI)V");
+  if (!bufferCallbackCallback) return JNI_ERR;
+
+  constBufferCallbackCls =
+      JClass(env, "edu/wpi/first/hal/sim/ConstBufferCallback");
+  if (!constBufferCallbackCls) return JNI_ERR;
+
+  constBufferCallbackCallback = env->GetMethodID(
+      constBufferCallbackCls, "callback", "(Ljava/lang/String;[BI)V");
+  if (!constBufferCallbackCallback) return JNI_ERR;
+
+  spiReadAutoReceiveBufferCallbackCls =
+      JClass(env, "edu/wpi/first/hal/sim/SpiReadAutoReceiveBufferCallback");
+  if (!spiReadAutoReceiveBufferCallbackCls) return JNI_ERR;
+
+  spiReadAutoReceiveBufferCallbackCallback =
+      env->GetMethodID(spiReadAutoReceiveBufferCallbackCls, "callback",
+                       "(Ljava/lang/String;[II)I");
+  if (!spiReadAutoReceiveBufferCallbackCallback) return JNI_ERR;
+
+  InitializeStore();
+  InitializeBufferStore();
+  InitializeConstBufferStore();
+  InitializeSpiBufferStore();
+
+  return JNI_VERSION_1_6;
+}
+
+void SimOnUnload(JavaVM* vm, void* reserved) {
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return;
+
+  simValueCls.free(env);
+  notifyCallbackCls.free(env);
+  bufferCallbackCls.free(env);
+  constBufferCallbackCls.free(env);
+  spiReadAutoReceiveBufferCallbackCls.free(env);
+  jvm = nullptr;
+}
+
+JavaVM* GetJVM() { return jvm; }
+
+jmethodID GetNotifyCallback() { return notifyCallbackCallback; }
+
+jmethodID GetBufferCallback() { return bufferCallbackCallback; }
+
+jmethodID GetConstBufferCallback() { return constBufferCallbackCallback; }
+
+jmethodID GetSpiReadAutoReceiveBufferCallback() {
+  return spiReadAutoReceiveBufferCallbackCallback;
+}
+}  // namespace sim
+
+extern "C" {
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
+ * Method:    waitForProgramStart
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimulatorJNI_waitForProgramStart
+  (JNIEnv*, jclass)
+{
+  HALSIM_WaitForProgramStart();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
+ * Method:    setProgramStarted
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimulatorJNI_setProgramStarted
+  (JNIEnv*, jclass)
+{
+  HALSIM_SetProgramStarted();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
+ * Method:    restartTiming
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimulatorJNI_restartTiming
+  (JNIEnv*, jclass)
+{
+  HALSIM_RestartTiming();
+}
+
+/*
+ * Class:     edu_wpi_first_hal_sim_mockdata_SimulatorJNI
+ * Method:    resetHandles
+ * Signature: ()V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_hal_sim_mockdata_SimulatorJNI_resetHandles
+  (JNIEnv*, jclass)
+{
+  hal::HandleBase::ResetGlobalHandles();
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SimulatorJNI.h b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SimulatorJNI.h
new file mode 100644
index 0000000..60d0ca3
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SimulatorJNI.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/jni_util.h>
+
+#include "hal/Types.h"
+#include "jni.h"
+#include "mockdata/HAL_Value.h"
+
+typedef HAL_Handle SIM_JniHandle;
+
+namespace sim {
+JavaVM* GetJVM();
+
+jmethodID GetNotifyCallback();
+jmethodID GetBufferCallback();
+jmethodID GetConstBufferCallback();
+jmethodID GetSpiReadAutoReceiveBufferCallback();
+}  // namespace sim
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.cpp
new file mode 100644
index 0000000..935c8bf
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.cpp
@@ -0,0 +1,130 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "SpiReadAutoReceiveBufferCallbackStore.h"
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "hal/Types.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/HAL_Value.h"
+#include "mockdata/NotifyListener.h"
+
+using namespace wpi::java;
+using namespace sim;
+
+static hal::UnlimitedHandleResource<
+    SIM_JniHandle, SpiReadAutoReceiveBufferCallbackStore,
+    hal::HAL_HandleEnum::SimulationJni>* callbackHandles;
+
+namespace sim {
+void InitializeSpiBufferStore() {
+  static hal::UnlimitedHandleResource<SIM_JniHandle,
+                                      SpiReadAutoReceiveBufferCallbackStore,
+                                      hal::HAL_HandleEnum::SimulationJni>
+      cb;
+  callbackHandles = &cb;
+}
+}  // namespace sim
+
+void SpiReadAutoReceiveBufferCallbackStore::create(JNIEnv* env, jobject obj) {
+  m_call = JGlobal<jobject>(env, obj);
+}
+
+int32_t SpiReadAutoReceiveBufferCallbackStore::performCallback(
+    const char* name, uint32_t* buffer, int32_t numToRead) {
+  JNIEnv* env;
+  JavaVM* vm = sim::GetJVM();
+  bool didAttachThread = false;
+  int tryGetEnv = vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6);
+  if (tryGetEnv == JNI_EDETACHED) {
+    // Thread not attached
+    didAttachThread = true;
+    if (vm->AttachCurrentThread(reinterpret_cast<void**>(&env), nullptr) != 0) {
+      // Failed to attach, log and return
+      wpi::outs() << "Failed to attach\n";
+      wpi::outs().flush();
+      return -1;
+    }
+  } else if (tryGetEnv == JNI_EVERSION) {
+    wpi::outs() << "Invalid JVM Version requested\n";
+    wpi::outs().flush();
+  }
+
+  auto toCallbackArr = MakeJIntArray(
+      env, wpi::ArrayRef<uint32_t>{buffer, static_cast<size_t>(numToRead)});
+
+  jint ret = env->CallIntMethod(m_call, sim::GetBufferCallback(),
+                                MakeJString(env, name), toCallbackArr,
+                                (jint)numToRead);
+
+  jint* fromCallbackArr = reinterpret_cast<jint*>(
+      env->GetPrimitiveArrayCritical(toCallbackArr, nullptr));
+
+  for (int i = 0; i < ret; i++) {
+    buffer[i] = fromCallbackArr[i];
+  }
+
+  env->ReleasePrimitiveArrayCritical(toCallbackArr, fromCallbackArr, JNI_ABORT);
+
+  if (env->ExceptionCheck()) {
+    env->ExceptionDescribe();
+  }
+
+  if (didAttachThread) {
+    vm->DetachCurrentThread();
+  }
+  return ret;
+}
+
+void SpiReadAutoReceiveBufferCallbackStore::free(JNIEnv* env) {
+  m_call.free(env);
+}
+
+SIM_JniHandle sim::AllocateSpiBufferCallback(
+    JNIEnv* env, jint index, jobject callback,
+    RegisterSpiBufferCallbackFunc createCallback) {
+  auto callbackStore =
+      std::make_shared<SpiReadAutoReceiveBufferCallbackStore>();
+
+  auto handle = callbackHandles->Allocate(callbackStore);
+
+  if (handle == HAL_kInvalidHandle) {
+    return -1;
+  }
+
+  uintptr_t handleAsPtr = static_cast<uintptr_t>(handle);
+  void* handleAsVoidPtr = reinterpret_cast<void*>(handleAsPtr);
+
+  callbackStore->create(env, callback);
+
+  auto callbackFunc = [](const char* name, void* param, uint32_t* buffer,
+                         int32_t numToRead, int32_t* outputCount) {
+    uintptr_t handleTmp = reinterpret_cast<uintptr_t>(param);
+    SIM_JniHandle handle = static_cast<SIM_JniHandle>(handleTmp);
+    auto data = callbackHandles->Get(handle);
+    if (!data) return;
+
+    *outputCount = data->performCallback(name, buffer, numToRead);
+  };
+
+  auto id = createCallback(index, callbackFunc, handleAsVoidPtr);
+
+  callbackStore->setCallbackId(id);
+
+  return handle;
+}
+
+void sim::FreeSpiBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                                FreeSpiBufferCallbackFunc freeCallback) {
+  auto callback = callbackHandles->Free(handle);
+  freeCallback(index, callback->getCallbackId());
+  callback->free(env);
+}
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.h b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.h
new file mode 100644
index 0000000..643a874
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/jni/SpiReadAutoReceiveBufferCallbackStore.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <jni.h>
+
+#include <wpi/jni_util.h>
+
+#include "SimulatorJNI.h"
+#include "hal/Types.h"
+#include "hal/handles/UnlimitedHandleResource.h"
+#include "mockdata/HAL_Value.h"
+#include "mockdata/NotifyListener.h"
+#include "mockdata/SPIData.h"
+
+namespace sim {
+class SpiReadAutoReceiveBufferCallbackStore {
+ public:
+  void create(JNIEnv* env, jobject obj);
+  int32_t performCallback(const char* name, uint32_t* buffer,
+                          int32_t numToRead);
+  void free(JNIEnv* env);
+  void setCallbackId(int32_t id) { callbackId = id; }
+  int32_t getCallbackId() { return callbackId; }
+
+ private:
+  wpi::java::JGlobal<jobject> m_call;
+  int32_t callbackId;
+};
+
+void InitializeSpiBufferStore();
+
+typedef int32_t (*RegisterSpiBufferCallbackFunc)(
+    int32_t index, HAL_SpiReadAutoReceiveBufferCallback callback, void* param);
+typedef void (*FreeSpiBufferCallbackFunc)(int32_t index, int32_t uid);
+
+SIM_JniHandle AllocateSpiBufferCallback(
+    JNIEnv* env, jint index, jobject callback,
+    RegisterSpiBufferCallbackFunc createCallback);
+void FreeSpiBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index,
+                           FreeSpiBufferCallbackFunc freeCallback);
+}  // namespace sim
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AccelerometerData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AccelerometerData.cpp
new file mode 100644
index 0000000..66e129a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AccelerometerData.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "AccelerometerDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAccelerometerData() {
+  static AccelerometerData sad[1];
+  ::hal::SimAccelerometerData = sad;
+}
+}  // namespace init
+}  // namespace hal
+
+AccelerometerData* hal::SimAccelerometerData;
+void AccelerometerData::ResetData() {
+  active.Reset(false);
+  range.Reset(static_cast<HAL_AccelerometerRange>(0));
+  x.Reset(0.0);
+  y.Reset(0.0);
+  z.Reset(0.0);
+}
+
+extern "C" {
+void HALSIM_ResetAccelerometerData(int32_t index) {
+  SimAccelerometerData[index].ResetData();
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                        \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, Accelerometer##CAPINAME, \
+                               SimAccelerometerData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Active, active)
+DEFINE_CAPI(HAL_AccelerometerRange, Range, range)
+DEFINE_CAPI(double, X, x)
+DEFINE_CAPI(double, Y, y)
+DEFINE_CAPI(double, Z, z)
+
+#define REGISTER(NAME)                                               \
+  SimAccelerometerData[index].NAME.RegisterCallback(callback, param, \
+                                                    initialNotify)
+
+void HALSIM_RegisterAccelerometerAllCallbacks(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify) {
+  REGISTER(active);
+  REGISTER(range);
+  REGISTER(x);
+  REGISTER(y);
+  REGISTER(z);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h
new file mode 100644
index 0000000..15e55ac
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AccelerometerDataInternal.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/AccelerometerData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class AccelerometerData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Active)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Range)
+  HAL_SIMDATAVALUE_DEFINE_NAME(X)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Y)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Z)
+
+  static inline HAL_Value MakeRangeValue(HAL_AccelerometerRange value) {
+    return MakeEnum(value);
+  }
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetActiveName> active{false};
+  SimDataValue<HAL_AccelerometerRange, MakeRangeValue, GetRangeName> range{
+      static_cast<HAL_AccelerometerRange>(0)};
+  SimDataValue<double, MakeDouble, GetXName> x{0.0};
+  SimDataValue<double, MakeDouble, GetYName> y{0.0};
+  SimDataValue<double, MakeDouble, GetZName> z{0.0};
+
+  virtual void ResetData();
+};
+extern AccelerometerData* SimAccelerometerData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogGyroData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogGyroData.cpp
new file mode 100644
index 0000000..2508d9b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogGyroData.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "AnalogGyroDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAnalogGyroData() {
+  static AnalogGyroData agd[kNumAccumulators];
+  ::hal::SimAnalogGyroData = agd;
+}
+}  // namespace init
+}  // namespace hal
+
+AnalogGyroData* hal::SimAnalogGyroData;
+void AnalogGyroData::ResetData() {
+  angle.Reset(0.0);
+  rate.Reset(0.0);
+  initialized.Reset(false);
+}
+
+extern "C" {
+void HALSIM_ResetAnalogGyroData(int32_t index) {
+  SimAnalogGyroData[index].ResetData();
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                     \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, AnalogGyro##CAPINAME, \
+                               SimAnalogGyroData, LOWERNAME)
+
+DEFINE_CAPI(double, Angle, angle)
+DEFINE_CAPI(double, Rate, rate)
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+
+#define REGISTER(NAME) \
+  SimAnalogGyroData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterAnalogGyroAllCallbacks(int32_t index,
+                                           HAL_NotifyCallback callback,
+                                           void* param,
+                                           HAL_Bool initialNotify) {
+  REGISTER(angle);
+  REGISTER(rate);
+  REGISTER(initialized);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogGyroDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogGyroDataInternal.h
new file mode 100644
index 0000000..8dfcb52
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogGyroDataInternal.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/AnalogGyroData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class AnalogGyroData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Angle)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Rate)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+
+ public:
+  SimDataValue<double, MakeDouble, GetAngleName> angle{0.0};
+  SimDataValue<double, MakeDouble, GetRateName> rate{0.0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+
+  virtual void ResetData();
+};
+extern AnalogGyroData* SimAnalogGyroData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogInData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogInData.cpp
new file mode 100644
index 0000000..1efdf50
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogInData.cpp
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "AnalogInDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAnalogInData() {
+  static AnalogInData sind[kNumAnalogInputs];
+  ::hal::SimAnalogInData = sind;
+}
+}  // namespace init
+}  // namespace hal
+
+AnalogInData* hal::SimAnalogInData;
+void AnalogInData::ResetData() {
+  initialized.Reset(false);
+  averageBits.Reset(7);
+  oversampleBits.Reset(0);
+  voltage.Reset(0.0);
+  accumulatorInitialized.Reset(false);
+  accumulatorValue.Reset(0);
+  accumulatorCount.Reset(0);
+  accumulatorCenter.Reset(0);
+  accumulatorDeadband.Reset(0);
+}
+
+extern "C" {
+void HALSIM_ResetAnalogInData(int32_t index) {
+  SimAnalogInData[index].ResetData();
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                   \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, AnalogIn##CAPINAME, \
+                               SimAnalogInData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(int32_t, AverageBits, averageBits)
+DEFINE_CAPI(int32_t, OversampleBits, oversampleBits)
+DEFINE_CAPI(double, Voltage, voltage)
+DEFINE_CAPI(HAL_Bool, AccumulatorInitialized, accumulatorInitialized)
+DEFINE_CAPI(int64_t, AccumulatorValue, accumulatorValue)
+DEFINE_CAPI(int64_t, AccumulatorCount, accumulatorCount)
+DEFINE_CAPI(int32_t, AccumulatorCenter, accumulatorCenter)
+DEFINE_CAPI(int32_t, AccumulatorDeadband, accumulatorDeadband)
+
+#define REGISTER(NAME) \
+  SimAnalogInData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterAnalogInAllCallbacks(int32_t index,
+                                         HAL_NotifyCallback callback,
+                                         void* param, HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(averageBits);
+  REGISTER(oversampleBits);
+  REGISTER(voltage);
+  REGISTER(accumulatorInitialized);
+  REGISTER(accumulatorValue);
+  REGISTER(accumulatorCount);
+  REGISTER(accumulatorCenter);
+  REGISTER(accumulatorDeadband);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h
new file mode 100644
index 0000000..94121ca
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/AnalogInData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class AnalogInData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(AverageBits)
+  HAL_SIMDATAVALUE_DEFINE_NAME(OversampleBits)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Voltage)
+  HAL_SIMDATAVALUE_DEFINE_NAME(AccumulatorInitialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(AccumulatorValue)
+  HAL_SIMDATAVALUE_DEFINE_NAME(AccumulatorCount)
+  HAL_SIMDATAVALUE_DEFINE_NAME(AccumulatorCenter)
+  HAL_SIMDATAVALUE_DEFINE_NAME(AccumulatorDeadband)
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<int32_t, MakeInt, GetAverageBitsName> averageBits{7};
+  SimDataValue<int32_t, MakeInt, GetOversampleBitsName> oversampleBits{0};
+  SimDataValue<double, MakeDouble, GetVoltageName> voltage{0.0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetAccumulatorInitializedName>
+      accumulatorInitialized{false};
+  SimDataValue<int64_t, MakeLong, GetAccumulatorValueName> accumulatorValue{0};
+  SimDataValue<int64_t, MakeLong, GetAccumulatorCountName> accumulatorCount{0};
+  SimDataValue<int32_t, MakeInt, GetAccumulatorCenterName> accumulatorCenter{0};
+  SimDataValue<int32_t, MakeInt, GetAccumulatorDeadbandName>
+      accumulatorDeadband{0};
+
+  virtual void ResetData();
+};
+extern AnalogInData* SimAnalogInData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogOutData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogOutData.cpp
new file mode 100644
index 0000000..d4b9116
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogOutData.cpp
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "AnalogOutDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAnalogOutData() {
+  static AnalogOutData siod[kNumAnalogOutputs];
+  ::hal::SimAnalogOutData = siod;
+}
+}  // namespace init
+}  // namespace hal
+
+AnalogOutData* hal::SimAnalogOutData;
+void AnalogOutData::ResetData() {
+  voltage.Reset(0.0);
+  initialized.Reset(0);
+}
+
+extern "C" {
+void HALSIM_ResetAnalogOutData(int32_t index) {
+  SimAnalogOutData[index].ResetData();
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                    \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, AnalogOut##CAPINAME, \
+                               SimAnalogOutData, LOWERNAME)
+
+DEFINE_CAPI(double, Voltage, voltage)
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+
+#define REGISTER(NAME) \
+  SimAnalogOutData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterAnalogOutAllCallbacks(int32_t index,
+                                          HAL_NotifyCallback callback,
+                                          void* param, HAL_Bool initialNotify) {
+  REGISTER(voltage);
+  REGISTER(initialized);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h
new file mode 100644
index 0000000..84af837
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogOutDataInternal.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/AnalogOutData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class AnalogOutData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Voltage)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+
+ public:
+  SimDataValue<double, MakeDouble, GetVoltageName> voltage{0.0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{0};
+
+  virtual void ResetData();
+};
+extern AnalogOutData* SimAnalogOutData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogTriggerData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogTriggerData.cpp
new file mode 100644
index 0000000..64d1a97
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogTriggerData.cpp
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "AnalogTriggerDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeAnalogTriggerData() {
+  static AnalogTriggerData satd[kNumAnalogTriggers];
+  ::hal::SimAnalogTriggerData = satd;
+}
+}  // namespace init
+}  // namespace hal
+
+AnalogTriggerData* hal::SimAnalogTriggerData;
+void AnalogTriggerData::ResetData() {
+  initialized.Reset(0);
+  triggerLowerBound.Reset(0);
+  triggerUpperBound.Reset(0);
+  triggerMode.Reset(static_cast<HALSIM_AnalogTriggerMode>(0));
+}
+
+extern "C" {
+void HALSIM_ResetAnalogTriggerData(int32_t index) {
+  SimAnalogTriggerData[index].ResetData();
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                        \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, AnalogTrigger##CAPINAME, \
+                               SimAnalogTriggerData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(double, TriggerLowerBound, triggerLowerBound)
+DEFINE_CAPI(double, TriggerUpperBound, triggerUpperBound)
+DEFINE_CAPI(HALSIM_AnalogTriggerMode, TriggerMode, triggerMode)
+
+#define REGISTER(NAME)                                               \
+  SimAnalogTriggerData[index].NAME.RegisterCallback(callback, param, \
+                                                    initialNotify)
+
+void HALSIM_RegisterAnalogTriggerAllCallbacks(int32_t index,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(triggerLowerBound);
+  REGISTER(triggerUpperBound);
+  REGISTER(triggerMode);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h
new file mode 100644
index 0000000..131ba7a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/AnalogTriggerDataInternal.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/AnalogTriggerData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class AnalogTriggerData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(TriggerLowerBound)
+  HAL_SIMDATAVALUE_DEFINE_NAME(TriggerUpperBound)
+  HAL_SIMDATAVALUE_DEFINE_NAME(TriggerMode)
+
+  static LLVM_ATTRIBUTE_ALWAYS_INLINE HAL_Value
+  MakeTriggerModeValue(HALSIM_AnalogTriggerMode value) {
+    return MakeEnum(value);
+  }
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{0};
+  SimDataValue<double, MakeDouble, GetTriggerLowerBoundName> triggerLowerBound{
+      0};
+  SimDataValue<double, MakeDouble, GetTriggerUpperBoundName> triggerUpperBound{
+      0};
+  SimDataValue<HALSIM_AnalogTriggerMode, MakeTriggerModeValue,
+               GetTriggerModeName>
+      triggerMode{static_cast<HALSIM_AnalogTriggerMode>(0)};
+
+  virtual void ResetData();
+};
+extern AnalogTriggerData* SimAnalogTriggerData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/CanDataInternal.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/CanDataInternal.cpp
new file mode 100644
index 0000000..e37d865
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/CanDataInternal.cpp
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "CanDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeCanData() {
+  static CanData scd;
+  ::hal::SimCanData = &scd;
+}
+}  // namespace init
+}  // namespace hal
+
+CanData* hal::SimCanData;
+
+void CanData::ResetData() {
+  sendMessage.Reset();
+  receiveMessage.Reset();
+  openStreamSession.Reset();
+  closeStreamSession.Reset();
+  readStreamSession.Reset();
+  getCANStatus.Reset();
+}
+
+extern "C" {
+
+void HALSIM_ResetCanData(void) { SimCanData->ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                             \
+  HAL_SIMCALLBACKREGISTRY_DEFINE_CAPI_NOINDEX(TYPE, HALSIM, Can##CAPINAME, \
+                                              SimCanData, LOWERNAME)
+
+DEFINE_CAPI(HAL_CAN_SendMessageCallback, SendMessage, sendMessage)
+DEFINE_CAPI(HAL_CAN_ReceiveMessageCallback, ReceiveMessage, receiveMessage)
+DEFINE_CAPI(HAL_CAN_OpenStreamSessionCallback, OpenStream, openStreamSession)
+DEFINE_CAPI(HAL_CAN_CloseStreamSessionCallback, CloseStream, closeStreamSession)
+DEFINE_CAPI(HAL_CAN_ReadStreamSessionCallback, ReadStream, readStreamSession)
+DEFINE_CAPI(HAL_CAN_GetCANStatusCallback, GetCANStatus, getCANStatus)
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/CanDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/CanDataInternal.h
new file mode 100644
index 0000000..ffdd351
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/CanDataInternal.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/CanData.h"
+#include "mockdata/SimCallbackRegistry.h"
+
+namespace hal {
+
+class CanData {
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(SendMessage)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(ReceiveMessage)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(OpenStream)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(CloseStream)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(ReadStream)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(GetCanStatus)
+
+ public:
+  SimCallbackRegistry<HAL_CAN_SendMessageCallback, GetSendMessageName>
+      sendMessage;
+  SimCallbackRegistry<HAL_CAN_ReceiveMessageCallback, GetReceiveMessageName>
+      receiveMessage;
+  SimCallbackRegistry<HAL_CAN_OpenStreamSessionCallback, GetOpenStreamName>
+      openStreamSession;
+  SimCallbackRegistry<HAL_CAN_CloseStreamSessionCallback, GetCloseStreamName>
+      closeStreamSession;
+  SimCallbackRegistry<HAL_CAN_ReadStreamSessionCallback, GetReadStreamName>
+      readStreamSession;
+  SimCallbackRegistry<HAL_CAN_GetCANStatusCallback, GetGetCanStatusName>
+      getCANStatus;
+
+  void ResetData();
+};
+
+extern CanData* SimCanData;
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DIOData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DIOData.cpp
new file mode 100644
index 0000000..ea66de3
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DIOData.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "DIODataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeDIOData() {
+  static DIOData sdd[kNumDigitalChannels];
+  ::hal::SimDIOData = sdd;
+}
+}  // namespace init
+}  // namespace hal
+
+DIOData* hal::SimDIOData;
+void DIOData::ResetData() {
+  initialized.Reset(false);
+  value.Reset(true);
+  pulseLength.Reset(0.0);
+  isInput.Reset(true);
+  filterIndex.Reset(-1);
+}
+
+extern "C" {
+void HALSIM_ResetDIOData(int32_t index) { SimDIOData[index].ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                          \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, DIO##CAPINAME, SimDIOData, \
+                               LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(HAL_Bool, Value, value)
+DEFINE_CAPI(double, PulseLength, pulseLength)
+DEFINE_CAPI(HAL_Bool, IsInput, isInput)
+DEFINE_CAPI(int32_t, FilterIndex, filterIndex)
+
+#define REGISTER(NAME) \
+  SimDIOData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterDIOAllCallbacks(int32_t index, HAL_NotifyCallback callback,
+                                    void* param, HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(value);
+  REGISTER(pulseLength);
+  REGISTER(isInput);
+  REGISTER(filterIndex);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DIODataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DIODataInternal.h
new file mode 100644
index 0000000..0b022f9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DIODataInternal.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/DIOData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class DIOData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Value)
+  HAL_SIMDATAVALUE_DEFINE_NAME(PulseLength)
+  HAL_SIMDATAVALUE_DEFINE_NAME(IsInput)
+  HAL_SIMDATAVALUE_DEFINE_NAME(FilterIndex)
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetValueName> value{true};
+  SimDataValue<double, MakeDouble, GetPulseLengthName> pulseLength{0.0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetIsInputName> isInput{true};
+  SimDataValue<int32_t, MakeInt, GetFilterIndexName> filterIndex{-1};
+
+  virtual void ResetData();
+};
+extern DIOData* SimDIOData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp
new file mode 100644
index 0000000..78ee749
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "DigitalPWMDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeDigitalPWMData() {
+  static DigitalPWMData sdpd[kNumDigitalPWMOutputs];
+  ::hal::SimDigitalPWMData = sdpd;
+}
+}  // namespace init
+}  // namespace hal
+
+DigitalPWMData* hal::SimDigitalPWMData;
+void DigitalPWMData::ResetData() {
+  initialized.Reset(false);
+  dutyCycle.Reset(0.0);
+  pin.Reset(0);
+}
+
+extern "C" {
+void HALSIM_ResetDigitalPWMData(int32_t index) {
+  SimDigitalPWMData[index].ResetData();
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                     \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, DigitalPWM##CAPINAME, \
+                               SimDigitalPWMData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(double, DutyCycle, dutyCycle)
+DEFINE_CAPI(int32_t, Pin, pin)
+
+#define REGISTER(NAME) \
+  SimDigitalPWMData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterDigitalPWMAllCallbacks(int32_t index,
+                                           HAL_NotifyCallback callback,
+                                           void* param,
+                                           HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(dutyCycle);
+  REGISTER(pin);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h
new file mode 100644
index 0000000..00d8b4a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/DigitalPWMData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class DigitalPWMData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(DutyCycle)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Pin)
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<double, MakeDouble, GetDutyCycleName> dutyCycle{0.0};
+  SimDataValue<int32_t, MakeInt, GetPinName> pin{0};
+
+  virtual void ResetData();
+};
+extern DigitalPWMData* SimDigitalPWMData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DriverStationData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DriverStationData.cpp
new file mode 100644
index 0000000..d72d6b3
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DriverStationData.cpp
@@ -0,0 +1,209 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <cstdlib>
+#include <cstring>
+#include <string>
+
+#include "DriverStationDataInternal.h"
+#include "hal/DriverStation.h"
+
+namespace hal {
+struct JoystickOutputStore {
+  int64_t outputs = 0;
+  int32_t leftRumble = 0;
+  int32_t rightRumble = 0;
+};
+}  // namespace hal
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeDriverStationData() {
+  static DriverStationData dsd;
+  ::hal::SimDriverStationData = &dsd;
+}
+}  // namespace init
+}  // namespace hal
+
+DriverStationData* hal::SimDriverStationData;
+
+DriverStationData::DriverStationData() { ResetData(); }
+
+void DriverStationData::ResetData() {
+  enabled.Reset(false);
+  autonomous.Reset(false);
+  test.Reset(false);
+  eStop.Reset(false);
+  fmsAttached.Reset(false);
+  dsAttached.Reset(true);
+  allianceStationId.Reset(static_cast<HAL_AllianceStationID>(0));
+  matchTime.Reset(0.0);
+
+  {
+    std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+    m_joystickAxes = std::make_unique<HAL_JoystickAxes[]>(6);
+    m_joystickPOVs = std::make_unique<HAL_JoystickPOVs[]>(6);
+    m_joystickButtons = std::make_unique<HAL_JoystickButtons[]>(6);
+    m_joystickOutputs = std::make_unique<JoystickOutputStore[]>(6);
+    m_joystickDescriptor = std::make_unique<HAL_JoystickDescriptor[]>(6);
+
+    for (int i = 0; i < 6; i++) {
+      m_joystickAxes[i].count = 0;
+      m_joystickPOVs[i].count = 0;
+      m_joystickButtons[i].count = 0;
+      m_joystickDescriptor[i].isXbox = 0;
+      m_joystickDescriptor[i].type = -1;
+      m_joystickDescriptor[i].name[0] = '\0';
+    }
+  }
+  {
+    std::lock_guard<wpi::spinlock> lock(m_matchInfoMutex);
+
+    m_matchInfo = std::make_unique<HAL_MatchInfo>();
+  }
+}
+
+void DriverStationData::GetJoystickAxes(int32_t joystickNum,
+                                        HAL_JoystickAxes* axes) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  *axes = m_joystickAxes[joystickNum];
+}
+void DriverStationData::GetJoystickPOVs(int32_t joystickNum,
+                                        HAL_JoystickPOVs* povs) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  *povs = m_joystickPOVs[joystickNum];
+}
+void DriverStationData::GetJoystickButtons(int32_t joystickNum,
+                                           HAL_JoystickButtons* buttons) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  *buttons = m_joystickButtons[joystickNum];
+}
+void DriverStationData::GetJoystickDescriptor(
+    int32_t joystickNum, HAL_JoystickDescriptor* descriptor) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  *descriptor = m_joystickDescriptor[joystickNum];
+  // Always ensure name is null terminated
+  descriptor->name[255] = '\0';
+}
+void DriverStationData::GetJoystickOutputs(int32_t joystickNum,
+                                           int64_t* outputs,
+                                           int32_t* leftRumble,
+                                           int32_t* rightRumble) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  *leftRumble = m_joystickOutputs[joystickNum].leftRumble;
+  *outputs = m_joystickOutputs[joystickNum].outputs;
+  *rightRumble = m_joystickOutputs[joystickNum].rightRumble;
+}
+void DriverStationData::GetMatchInfo(HAL_MatchInfo* info) {
+  std::lock_guard<wpi::spinlock> lock(m_matchInfoMutex);
+  *info = *m_matchInfo;
+}
+
+void DriverStationData::SetJoystickAxes(int32_t joystickNum,
+                                        const HAL_JoystickAxes* axes) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  m_joystickAxes[joystickNum] = *axes;
+}
+void DriverStationData::SetJoystickPOVs(int32_t joystickNum,
+                                        const HAL_JoystickPOVs* povs) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  m_joystickPOVs[joystickNum] = *povs;
+}
+void DriverStationData::SetJoystickButtons(int32_t joystickNum,
+                                           const HAL_JoystickButtons* buttons) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  m_joystickButtons[joystickNum] = *buttons;
+}
+
+void DriverStationData::SetJoystickDescriptor(
+    int32_t joystickNum, const HAL_JoystickDescriptor* descriptor) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  m_joystickDescriptor[joystickNum] = *descriptor;
+}
+
+void DriverStationData::SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
+                                           int32_t leftRumble,
+                                           int32_t rightRumble) {
+  std::lock_guard<wpi::spinlock> lock(m_joystickDataMutex);
+  m_joystickOutputs[joystickNum].leftRumble = leftRumble;
+  m_joystickOutputs[joystickNum].outputs = outputs;
+  m_joystickOutputs[joystickNum].rightRumble = rightRumble;
+}
+
+void DriverStationData::SetMatchInfo(const HAL_MatchInfo* info) {
+  std::lock_guard<wpi::spinlock> lock(m_matchInfoMutex);
+  *m_matchInfo = *info;
+  *(std::end(m_matchInfo->eventName) - 1) = '\0';
+}
+
+void DriverStationData::NotifyNewData() { HAL_ReleaseDSMutex(); }
+
+extern "C" {
+void HALSIM_ResetDriverStationData(void) { SimDriverStationData->ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                                \
+  HAL_SIMDATAVALUE_DEFINE_CAPI_NOINDEX(TYPE, HALSIM, DriverStation##CAPINAME, \
+                                       SimDriverStationData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Enabled, enabled)
+DEFINE_CAPI(HAL_Bool, Autonomous, autonomous)
+DEFINE_CAPI(HAL_Bool, Test, test)
+DEFINE_CAPI(HAL_Bool, EStop, eStop)
+DEFINE_CAPI(HAL_Bool, FmsAttached, fmsAttached)
+DEFINE_CAPI(HAL_Bool, DsAttached, dsAttached)
+DEFINE_CAPI(HAL_AllianceStationID, AllianceStationId, allianceStationId)
+DEFINE_CAPI(double, MatchTime, matchTime)
+
+void HALSIM_SetJoystickAxes(int32_t joystickNum, const HAL_JoystickAxes* axes) {
+  SimDriverStationData->SetJoystickAxes(joystickNum, axes);
+}
+
+void HALSIM_SetJoystickPOVs(int32_t joystickNum, const HAL_JoystickPOVs* povs) {
+  SimDriverStationData->SetJoystickPOVs(joystickNum, povs);
+}
+
+void HALSIM_SetJoystickButtons(int32_t joystickNum,
+                               const HAL_JoystickButtons* buttons) {
+  SimDriverStationData->SetJoystickButtons(joystickNum, buttons);
+}
+void HALSIM_SetJoystickDescriptor(int32_t joystickNum,
+                                  const HAL_JoystickDescriptor* descriptor) {
+  SimDriverStationData->SetJoystickDescriptor(joystickNum, descriptor);
+}
+
+void HALSIM_GetJoystickOutputs(int32_t joystickNum, int64_t* outputs,
+                               int32_t* leftRumble, int32_t* rightRumble) {
+  SimDriverStationData->GetJoystickOutputs(joystickNum, outputs, leftRumble,
+                                           rightRumble);
+}
+
+void HALSIM_SetMatchInfo(const HAL_MatchInfo* info) {
+  SimDriverStationData->SetMatchInfo(info);
+}
+
+void HALSIM_NotifyDriverStationNewData(void) {
+  SimDriverStationData->NotifyNewData();
+}
+
+#define REGISTER(NAME) \
+  SimDriverStationData->NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterDriverStationAllCallbacks(HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify) {
+  REGISTER(enabled);
+  REGISTER(autonomous);
+  REGISTER(test);
+  REGISTER(eStop);
+  REGISTER(fmsAttached);
+  REGISTER(dsAttached);
+  REGISTER(allianceStationId);
+  REGISTER(matchTime);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
new file mode 100644
index 0000000..f7eb132
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/spinlock.h>
+
+#include "mockdata/DriverStationData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+struct JoystickOutputStore;
+
+class DriverStationData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Enabled)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Autonomous)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Test)
+  HAL_SIMDATAVALUE_DEFINE_NAME(EStop)
+  HAL_SIMDATAVALUE_DEFINE_NAME(FmsAttached)
+  HAL_SIMDATAVALUE_DEFINE_NAME(DsAttached)
+  HAL_SIMDATAVALUE_DEFINE_NAME(AllianceStationId)
+  HAL_SIMDATAVALUE_DEFINE_NAME(MatchTime)
+
+  static LLVM_ATTRIBUTE_ALWAYS_INLINE HAL_Value
+  MakeAllianceStationIdValue(HAL_AllianceStationID value) {
+    return MakeEnum(value);
+  }
+
+ public:
+  DriverStationData();
+  void ResetData();
+
+  void GetJoystickAxes(int32_t joystickNum, HAL_JoystickAxes* axes);
+  void GetJoystickPOVs(int32_t joystickNum, HAL_JoystickPOVs* povs);
+  void GetJoystickButtons(int32_t joystickNum, HAL_JoystickButtons* buttons);
+  void GetJoystickDescriptor(int32_t joystickNum,
+                             HAL_JoystickDescriptor* descriptor);
+  void GetJoystickOutputs(int32_t joystickNum, int64_t* outputs,
+                          int32_t* leftRumble, int32_t* rightRumble);
+  void GetMatchInfo(HAL_MatchInfo* info);
+  void FreeMatchInfo(const HAL_MatchInfo* info);
+
+  void SetJoystickAxes(int32_t joystickNum, const HAL_JoystickAxes* axes);
+  void SetJoystickPOVs(int32_t joystickNum, const HAL_JoystickPOVs* povs);
+  void SetJoystickButtons(int32_t joystickNum,
+                          const HAL_JoystickButtons* buttons);
+  void SetJoystickDescriptor(int32_t joystickNum,
+                             const HAL_JoystickDescriptor* descriptor);
+  void SetJoystickOutputs(int32_t joystickNum, int64_t outputs,
+                          int32_t leftRumble, int32_t rightRumble);
+  void SetMatchInfo(const HAL_MatchInfo* info);
+
+  void NotifyNewData();
+
+  SimDataValue<HAL_Bool, MakeBoolean, GetEnabledName> enabled{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetAutonomousName> autonomous{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetTestName> test{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetEStopName> eStop{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetFmsAttachedName> fmsAttached{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetDsAttachedName> dsAttached{true};
+  SimDataValue<HAL_AllianceStationID, MakeAllianceStationIdValue,
+               GetAllianceStationIdName>
+      allianceStationId{static_cast<HAL_AllianceStationID>(0)};
+  SimDataValue<double, MakeDouble, GetMatchTimeName> matchTime{0.0};
+
+ private:
+  wpi::spinlock m_joystickDataMutex;
+  wpi::spinlock m_matchInfoMutex;
+
+  std::unique_ptr<HAL_JoystickAxes[]> m_joystickAxes;
+  std::unique_ptr<HAL_JoystickPOVs[]> m_joystickPOVs;
+  std::unique_ptr<HAL_JoystickButtons[]> m_joystickButtons;
+
+  std::unique_ptr<JoystickOutputStore[]> m_joystickOutputs;
+  std::unique_ptr<HAL_JoystickDescriptor[]> m_joystickDescriptor;
+  std::unique_ptr<HAL_MatchInfo> m_matchInfo;
+};
+extern DriverStationData* SimDriverStationData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/EncoderData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/EncoderData.cpp
new file mode 100644
index 0000000..59ba48f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/EncoderData.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "EncoderDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeEncoderData() {
+  static EncoderData sed[kNumEncoders];
+  ::hal::SimEncoderData = sed;
+}
+}  // namespace init
+}  // namespace hal
+
+EncoderData* hal::SimEncoderData;
+void EncoderData::ResetData() {
+  digitalChannelA = 0;
+  initialized.Reset(false);
+  count.Reset(0);
+  period.Reset(std::numeric_limits<double>::max());
+  reset.Reset(false);
+  maxPeriod.Reset(0);
+  direction.Reset(false);
+  reverseDirection.Reset(false);
+  samplesToAverage.Reset(0);
+  distancePerPulse.Reset(1);
+}
+
+extern "C" {
+void HALSIM_ResetEncoderData(int32_t index) {
+  SimEncoderData[index].ResetData();
+}
+
+int16_t HALSIM_GetDigitalChannelA(int32_t index) {
+  return SimEncoderData[index].digitalChannelA;
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                  \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, Encoder##CAPINAME, \
+                               SimEncoderData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(int32_t, Count, count)
+DEFINE_CAPI(double, Period, period)
+DEFINE_CAPI(HAL_Bool, Reset, reset)
+DEFINE_CAPI(double, MaxPeriod, maxPeriod)
+DEFINE_CAPI(HAL_Bool, Direction, direction)
+DEFINE_CAPI(HAL_Bool, ReverseDirection, reverseDirection)
+DEFINE_CAPI(int32_t, SamplesToAverage, samplesToAverage)
+DEFINE_CAPI(double, DistancePerPulse, distancePerPulse)
+
+#define REGISTER(NAME) \
+  SimEncoderData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterEncoderAllCallbacks(int32_t index,
+                                        HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(count);
+  REGISTER(period);
+  REGISTER(reset);
+  REGISTER(maxPeriod);
+  REGISTER(direction);
+  REGISTER(reverseDirection);
+  REGISTER(samplesToAverage);
+  REGISTER(distancePerPulse);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/EncoderDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/EncoderDataInternal.h
new file mode 100644
index 0000000..657d977
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/EncoderDataInternal.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <limits>
+
+#include "mockdata/EncoderData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class EncoderData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Count)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Period)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Reset)
+  HAL_SIMDATAVALUE_DEFINE_NAME(MaxPeriod)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Direction)
+  HAL_SIMDATAVALUE_DEFINE_NAME(ReverseDirection)
+  HAL_SIMDATAVALUE_DEFINE_NAME(SamplesToAverage)
+  HAL_SIMDATAVALUE_DEFINE_NAME(DistancePerPulse)
+
+ public:
+  std::atomic<int16_t> digitalChannelA{0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<int32_t, MakeInt, GetCountName> count{0};
+  SimDataValue<double, MakeDouble, GetPeriodName> period{
+      std::numeric_limits<double>::max()};
+  SimDataValue<HAL_Bool, MakeBoolean, GetResetName> reset{false};
+  SimDataValue<double, MakeDouble, GetMaxPeriodName> maxPeriod{0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetDirectionName> direction{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetReverseDirectionName> reverseDirection{
+      false};
+  SimDataValue<int32_t, MakeInt, GetSamplesToAverageName> samplesToAverage{0};
+  SimDataValue<double, MakeDouble, GetDistancePerPulseName> distancePerPulse{1};
+
+  virtual void ResetData();
+};
+extern EncoderData* SimEncoderData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/HALValueInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/HALValueInternal.h
new file mode 100644
index 0000000..f659403
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/HALValueInternal.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "mockdata/HALValue.h"
+#include "mockdata/wpi/StringRef.h"
+
+namespace hal {
+
+class Value;
+
+void ConvertToC(const Value& in, HAL_Value* out);
+std::shared_ptr<Value> ConvertFromC(const HAL_Value& value);
+void ConvertToC(wpi::StringRef in, HALString* out);
+inline wpi::StringRef ConvertFromC(const HALString& str) {
+  return wpi::StringRef(str.str, str.len);
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/I2CData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/I2CData.cpp
new file mode 100644
index 0000000..b228c3b
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/I2CData.cpp
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include "../PortsInternal.h"
+#include "I2CDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeI2CData() {
+  static I2CData sid[2];
+  ::hal::SimI2CData = sid;
+}
+}  // namespace init
+}  // namespace hal
+
+I2CData* hal::SimI2CData;
+
+void I2CData::ResetData() {
+  initialized.Reset(false);
+  read.Reset();
+  write.Reset();
+}
+
+void I2CData::Write(int32_t deviceAddress, const uint8_t* dataToSend,
+                    int32_t sendSize) {
+  write(dataToSend, sendSize);
+}
+
+void I2CData::Read(int32_t deviceAddress, uint8_t* buffer, int32_t count) {
+  read(buffer, count);
+}
+
+extern "C" {
+void HALSIM_ResetI2CData(int32_t index) { SimI2CData[index].ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                          \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, I2C##CAPINAME, SimI2CData, \
+                               LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+
+#undef DEFINE_CAPI
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                                 \
+  HAL_SIMCALLBACKREGISTRY_DEFINE_CAPI(TYPE, HALSIM, I2C##CAPINAME, SimI2CData, \
+                                      LOWERNAME)
+
+DEFINE_CAPI(HAL_BufferCallback, Read, read)
+DEFINE_CAPI(HAL_ConstBufferCallback, Write, write)
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/I2CDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/I2CDataInternal.h
new file mode 100644
index 0000000..1c2df0e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/I2CDataInternal.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/I2CData.h"
+#include "mockdata/SimCallbackRegistry.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class I2CData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(Read)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(Write)
+
+ public:
+  void Write(int32_t deviceAddress, const uint8_t* dataToSend,
+             int32_t sendSize);
+  void Read(int32_t deviceAddress, uint8_t* buffer, int32_t count);
+
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimCallbackRegistry<HAL_BufferCallback, GetReadName> read;
+  SimCallbackRegistry<HAL_ConstBufferCallback, GetWriteName> write;
+
+  void ResetData();
+};
+extern I2CData* SimI2CData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PCMData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PCMData.cpp
new file mode 100644
index 0000000..df68e04
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PCMData.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "PCMDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializePCMData() {
+  static PCMData spd[kNumPCMModules];
+  ::hal::SimPCMData = spd;
+}
+}  // namespace init
+}  // namespace hal
+
+PCMData* hal::SimPCMData;
+void PCMData::ResetData() {
+  for (int i = 0; i < kNumSolenoidChannels; i++) {
+    solenoidInitialized[i].Reset(false);
+    solenoidOutput[i].Reset(false);
+  }
+  compressorInitialized.Reset(false);
+  compressorOn.Reset(false);
+  closedLoopEnabled.Reset(true);
+  pressureSwitch.Reset(false);
+  compressorCurrent.Reset(0.0);
+}
+
+extern "C" {
+void HALSIM_ResetPCMData(int32_t index) { SimPCMData[index].ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                          \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, PCM##CAPINAME, SimPCMData, \
+                               LOWERNAME)
+
+HAL_SIMDATAVALUE_DEFINE_CAPI_CHANNEL(HAL_Bool, HALSIM, PCMSolenoidInitialized,
+                                     SimPCMData, solenoidInitialized)
+HAL_SIMDATAVALUE_DEFINE_CAPI_CHANNEL(HAL_Bool, HALSIM, PCMSolenoidOutput,
+                                     SimPCMData, solenoidOutput)
+DEFINE_CAPI(HAL_Bool, CompressorInitialized, compressorInitialized)
+DEFINE_CAPI(HAL_Bool, CompressorOn, compressorOn)
+DEFINE_CAPI(HAL_Bool, ClosedLoopEnabled, closedLoopEnabled)
+DEFINE_CAPI(HAL_Bool, PressureSwitch, pressureSwitch)
+DEFINE_CAPI(double, CompressorCurrent, compressorCurrent)
+
+#define REGISTER(NAME) \
+  SimPCMData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterPCMAllNonSolenoidCallbacks(int32_t index,
+                                               HAL_NotifyCallback callback,
+                                               void* param,
+                                               HAL_Bool initialNotify) {
+  REGISTER(compressorInitialized);
+  REGISTER(compressorOn);
+  REGISTER(closedLoopEnabled);
+  REGISTER(pressureSwitch);
+  REGISTER(compressorCurrent);
+}
+
+void HALSIM_RegisterPCMAllSolenoidCallbacks(int32_t index, int32_t channel,
+                                            HAL_NotifyCallback callback,
+                                            void* param,
+                                            HAL_Bool initialNotify) {
+  REGISTER(solenoidInitialized[channel]);
+  REGISTER(solenoidOutput[channel]);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PCMDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PCMDataInternal.h
new file mode 100644
index 0000000..4144987
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PCMDataInternal.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "../PortsInternal.h"
+#include "mockdata/PCMData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class PCMData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(SolenoidInitialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(SolenoidOutput)
+  HAL_SIMDATAVALUE_DEFINE_NAME(CompressorInitialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(CompressorOn)
+  HAL_SIMDATAVALUE_DEFINE_NAME(ClosedLoopEnabled)
+  HAL_SIMDATAVALUE_DEFINE_NAME(PressureSwitch)
+  HAL_SIMDATAVALUE_DEFINE_NAME(CompressorCurrent)
+
+  static LLVM_ATTRIBUTE_ALWAYS_INLINE constexpr HAL_Bool
+  GetSolenoidInitializedDefault() {
+    return false;
+  }
+  static LLVM_ATTRIBUTE_ALWAYS_INLINE constexpr HAL_Bool
+  GetSolenoidOutputDefault() {
+    return false;
+  }
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetSolenoidInitializedName,
+               GetSolenoidInitializedDefault>
+      solenoidInitialized[kNumSolenoidChannels];
+  SimDataValue<HAL_Bool, MakeBoolean, GetSolenoidOutputName,
+               GetSolenoidOutputDefault>
+      solenoidOutput[kNumSolenoidChannels];
+  SimDataValue<HAL_Bool, MakeBoolean, GetCompressorInitializedName>
+      compressorInitialized{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetCompressorOnName> compressorOn{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetClosedLoopEnabledName>
+      closedLoopEnabled{true};
+  SimDataValue<HAL_Bool, MakeBoolean, GetPressureSwitchName> pressureSwitch{
+      false};
+  SimDataValue<double, MakeDouble, GetCompressorCurrentName> compressorCurrent{
+      0.0};
+
+  virtual void ResetData();
+};
+extern PCMData* SimPCMData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PDPData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PDPData.cpp
new file mode 100644
index 0000000..9c6143e
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PDPData.cpp
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "PDPDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializePDPData() {
+  static PDPData spd[kNumPDPModules];
+  ::hal::SimPDPData = spd;
+}
+}  // namespace init
+}  // namespace hal
+
+PDPData* hal::SimPDPData;
+void PDPData::ResetData() {
+  initialized.Reset(false);
+  temperature.Reset(0.0);
+  voltage.Reset(12.0);
+  for (int i = 0; i < kNumPDPChannels; i++) {
+    current[i].Reset(0.0);
+  }
+}
+
+extern "C" {
+void HALSIM_ResetPDPData(int32_t index) { SimPDPData[index].ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                          \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, PDP##CAPINAME, SimPDPData, \
+                               LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(double, Temperature, temperature)
+DEFINE_CAPI(double, Voltage, voltage)
+HAL_SIMDATAVALUE_DEFINE_CAPI_CHANNEL(double, HALSIM, PDPCurrent, SimPDPData,
+                                     current)
+
+#define REGISTER(NAME) \
+  SimPDPData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterPDPAllNonCurrentCallbacks(int32_t index, int32_t channel,
+                                              HAL_NotifyCallback callback,
+                                              void* param,
+                                              HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(temperature);
+  REGISTER(voltage);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PDPDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PDPDataInternal.h
new file mode 100644
index 0000000..a7170c7
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PDPDataInternal.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "../PortsInternal.h"
+#include "mockdata/PDPData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class PDPData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Temperature)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Voltage)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Current)
+
+  static LLVM_ATTRIBUTE_ALWAYS_INLINE constexpr double GetCurrentDefault() {
+    return 0.0;
+  }
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<double, MakeDouble, GetTemperatureName> temperature{0.0};
+  SimDataValue<double, MakeDouble, GetVoltageName> voltage{12.0};
+  SimDataValue<double, MakeDouble, GetCurrentName, GetCurrentDefault>
+      current[kNumPDPChannels];
+
+  virtual void ResetData();
+};
+extern PDPData* SimPDPData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PWMData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PWMData.cpp
new file mode 100644
index 0000000..4d2121d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PWMData.cpp
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "PWMDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializePWMData() {
+  static PWMData spd[kNumPWMChannels];
+  ::hal::SimPWMData = spd;
+}
+}  // namespace init
+}  // namespace hal
+
+PWMData* hal::SimPWMData;
+void PWMData::ResetData() {
+  initialized.Reset(false);
+  rawValue.Reset(0);
+  speed.Reset(0);
+  position.Reset(0);
+  periodScale.Reset(0);
+  zeroLatch.Reset(false);
+}
+
+extern "C" {
+void HALSIM_ResetPWMData(int32_t index) { SimPWMData[index].ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                          \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, PWM##CAPINAME, SimPWMData, \
+                               LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+DEFINE_CAPI(int32_t, RawValue, rawValue)
+DEFINE_CAPI(double, Speed, speed)
+DEFINE_CAPI(double, Position, position)
+DEFINE_CAPI(int32_t, PeriodScale, periodScale)
+DEFINE_CAPI(HAL_Bool, ZeroLatch, zeroLatch)
+
+#define REGISTER(NAME) \
+  SimPWMData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterPWMAllCallbacks(int32_t index, HAL_NotifyCallback callback,
+                                    void* param, HAL_Bool initialNotify) {
+  REGISTER(initialized);
+  REGISTER(rawValue);
+  REGISTER(speed);
+  REGISTER(position);
+  REGISTER(periodScale);
+  REGISTER(zeroLatch);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PWMDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PWMDataInternal.h
new file mode 100644
index 0000000..85eae44
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/PWMDataInternal.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/PWMData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class PWMData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMDATAVALUE_DEFINE_NAME(RawValue)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Speed)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Position)
+  HAL_SIMDATAVALUE_DEFINE_NAME(PeriodScale)
+  HAL_SIMDATAVALUE_DEFINE_NAME(ZeroLatch)
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimDataValue<int32_t, MakeInt, GetRawValueName> rawValue{0};
+  SimDataValue<double, MakeDouble, GetSpeedName> speed{0};
+  SimDataValue<double, MakeDouble, GetPositionName> position{0};
+  SimDataValue<int32_t, MakeInt, GetPeriodScaleName> periodScale{0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetZeroLatchName> zeroLatch{false};
+
+  virtual void ResetData();
+};
+extern PWMData* SimPWMData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RelayData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RelayData.cpp
new file mode 100644
index 0000000..4623203
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RelayData.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "RelayDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeRelayData() {
+  static RelayData srd[kNumRelayHeaders];
+  ::hal::SimRelayData = srd;
+}
+}  // namespace init
+}  // namespace hal
+
+RelayData* hal::SimRelayData;
+void RelayData::ResetData() {
+  initializedForward.Reset(false);
+  initializedReverse.Reset(false);
+  forward.Reset(false);
+  reverse.Reset(false);
+}
+
+extern "C" {
+void HALSIM_ResetRelayData(int32_t index) { SimRelayData[index].ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                              \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, Relay##CAPINAME, SimRelayData, \
+                               LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, InitializedForward, initializedForward)
+DEFINE_CAPI(HAL_Bool, InitializedReverse, initializedReverse)
+DEFINE_CAPI(HAL_Bool, Forward, forward)
+DEFINE_CAPI(HAL_Bool, Reverse, reverse)
+
+#define REGISTER(NAME) \
+  SimRelayData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterRelayAllCallbacks(int32_t index,
+                                      HAL_NotifyCallback callback, void* param,
+                                      HAL_Bool initialNotify) {
+  REGISTER(initializedForward);
+  REGISTER(initializedReverse);
+  REGISTER(forward);
+  REGISTER(reverse);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RelayDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RelayDataInternal.h
new file mode 100644
index 0000000..88e79ff
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RelayDataInternal.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/RelayData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class RelayData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(InitializedForward)
+  HAL_SIMDATAVALUE_DEFINE_NAME(InitializedReverse)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Forward)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Reverse)
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedForwardName>
+      initializedForward{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedReverseName>
+      initializedReverse{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetForwardName> forward{false};
+  SimDataValue<HAL_Bool, MakeBoolean, GetReverseName> reverse{false};
+
+  virtual void ResetData();
+};
+extern RelayData* SimRelayData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RoboRioData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RoboRioData.cpp
new file mode 100644
index 0000000..5cff1d9
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RoboRioData.cpp
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "RoboRioDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeRoboRioData() {
+  static RoboRioData srrd[1];
+  ::hal::SimRoboRioData = srrd;
+}
+}  // namespace init
+}  // namespace hal
+
+RoboRioData* hal::SimRoboRioData;
+void RoboRioData::ResetData() {
+  fpgaButton.Reset(false);
+  vInVoltage.Reset(0.0);
+  vInCurrent.Reset(0.0);
+  userVoltage6V.Reset(6.0);
+  userCurrent6V.Reset(0.0);
+  userActive6V.Reset(false);
+  userVoltage5V.Reset(5.0);
+  userCurrent5V.Reset(0.0);
+  userActive5V.Reset(false);
+  userVoltage3V3.Reset(3.3);
+  userCurrent3V3.Reset(0.0);
+  userActive3V3.Reset(false);
+  userFaults6V.Reset(0);
+  userFaults5V.Reset(0);
+  userFaults3V3.Reset(0);
+}
+
+extern "C" {
+void HALSIM_ResetRoboRioData(int32_t index) {
+  SimRoboRioData[index].ResetData();
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                  \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, RoboRio##CAPINAME, \
+                               SimRoboRioData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, FPGAButton, fpgaButton)
+DEFINE_CAPI(double, VInVoltage, vInVoltage)
+DEFINE_CAPI(double, VInCurrent, vInCurrent)
+DEFINE_CAPI(double, UserVoltage6V, userVoltage6V)
+DEFINE_CAPI(double, UserCurrent6V, userCurrent6V)
+DEFINE_CAPI(HAL_Bool, UserActive6V, userActive6V)
+DEFINE_CAPI(double, UserVoltage5V, userVoltage5V)
+DEFINE_CAPI(double, UserCurrent5V, userCurrent5V)
+DEFINE_CAPI(HAL_Bool, UserActive5V, userActive5V)
+DEFINE_CAPI(double, UserVoltage3V3, userVoltage3V3)
+DEFINE_CAPI(double, UserCurrent3V3, userCurrent3V3)
+DEFINE_CAPI(HAL_Bool, UserActive3V3, userActive3V3)
+DEFINE_CAPI(int32_t, UserFaults6V, userFaults6V)
+DEFINE_CAPI(int32_t, UserFaults5V, userFaults5V)
+DEFINE_CAPI(int32_t, UserFaults3V3, userFaults3V3)
+
+#define REGISTER(NAME) \
+  SimRoboRioData[index].NAME.RegisterCallback(callback, param, initialNotify)
+
+void HALSIM_RegisterRoboRioAllCallbacks(int32_t index,
+                                        HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify) {
+  REGISTER(fpgaButton);
+  REGISTER(vInVoltage);
+  REGISTER(vInCurrent);
+  REGISTER(userVoltage6V);
+  REGISTER(userCurrent6V);
+  REGISTER(userActive6V);
+  REGISTER(userVoltage5V);
+  REGISTER(userCurrent5V);
+  REGISTER(userActive5V);
+  REGISTER(userVoltage3V3);
+  REGISTER(userCurrent3V3);
+  REGISTER(userActive3V3);
+  REGISTER(userFaults6V);
+  REGISTER(userFaults5V);
+  REGISTER(userFaults3V3);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
new file mode 100644
index 0000000..92aa0c8
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/RoboRioData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class RoboRioData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(FPGAButton)
+  HAL_SIMDATAVALUE_DEFINE_NAME(VInVoltage)
+  HAL_SIMDATAVALUE_DEFINE_NAME(VInCurrent)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserVoltage6V)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserCurrent6V)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserActive6V)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserVoltage5V)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserCurrent5V)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserActive5V)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserVoltage3V3)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserCurrent3V3)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserActive3V3)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserFaults6V)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserFaults5V)
+  HAL_SIMDATAVALUE_DEFINE_NAME(UserFaults3V3)
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetFPGAButtonName> fpgaButton{false};
+  SimDataValue<double, MakeDouble, GetVInVoltageName> vInVoltage{0.0};
+  SimDataValue<double, MakeDouble, GetVInCurrentName> vInCurrent{0.0};
+  SimDataValue<double, MakeDouble, GetUserVoltage6VName> userVoltage6V{6.0};
+  SimDataValue<double, MakeDouble, GetUserCurrent6VName> userCurrent6V{0.0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetUserActive6VName> userActive6V{false};
+  SimDataValue<double, MakeDouble, GetUserVoltage5VName> userVoltage5V{5.0};
+  SimDataValue<double, MakeDouble, GetUserCurrent5VName> userCurrent5V{0.0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetUserActive5VName> userActive5V{false};
+  SimDataValue<double, MakeDouble, GetUserVoltage3V3Name> userVoltage3V3{3.3};
+  SimDataValue<double, MakeDouble, GetUserCurrent3V3Name> userCurrent3V3{0.0};
+  SimDataValue<HAL_Bool, MakeBoolean, GetUserActive3V3Name> userActive3V3{
+      false};
+  SimDataValue<int32_t, MakeInt, GetUserFaults6VName> userFaults6V{0};
+  SimDataValue<int32_t, MakeInt, GetUserFaults5VName> userFaults5V{0};
+  SimDataValue<int32_t, MakeInt, GetUserFaults3V3Name> userFaults3V3{0};
+
+  virtual void ResetData();
+};
+extern RoboRioData* SimRoboRioData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIAccelerometerData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIAccelerometerData.cpp
new file mode 100644
index 0000000..db7dc1d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIAccelerometerData.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "../PortsInternal.h"
+#include "SPIAccelerometerDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeSPIAccelerometerData() {
+  static SPIAccelerometerData ssad[5];
+  ::hal::SimSPIAccelerometerData = ssad;
+}
+}  // namespace init
+}  // namespace hal
+
+SPIAccelerometerData* hal::SimSPIAccelerometerData;
+void SPIAccelerometerData::ResetData() {
+  active.Reset(false);
+  range.Reset(0);
+  x.Reset(0.0);
+  y.Reset(0.0);
+  z.Reset(0.0);
+}
+
+extern "C" {
+void HALSIM_ResetSPIAccelerometerData(int32_t index) {
+  SimSPIAccelerometerData[index].ResetData();
+}
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                           \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, SPIAccelerometer##CAPINAME, \
+                               SimSPIAccelerometerData, LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Active, active)
+DEFINE_CAPI(int32_t, Range, range)
+DEFINE_CAPI(double, X, x)
+DEFINE_CAPI(double, Y, y)
+DEFINE_CAPI(double, Z, z)
+
+#define REGISTER(NAME)                                                  \
+  SimSPIAccelerometerData[index].NAME.RegisterCallback(callback, param, \
+                                                       initialNotify)
+
+void HALSIM_RegisterSPIAccelerometerAllCallbcaks(int32_t index,
+                                                 HAL_NotifyCallback callback,
+                                                 void* param,
+                                                 HAL_Bool initialNotify) {
+  REGISTER(active);
+  REGISTER(range);
+  REGISTER(x);
+  REGISTER(y);
+  REGISTER(z);
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIAccelerometerDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIAccelerometerDataInternal.h
new file mode 100644
index 0000000..ee9f79d
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIAccelerometerDataInternal.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/SPIAccelerometerData.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+class SPIAccelerometerData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Active)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Range)
+  HAL_SIMDATAVALUE_DEFINE_NAME(X)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Y)
+  HAL_SIMDATAVALUE_DEFINE_NAME(Z)
+
+ public:
+  SimDataValue<HAL_Bool, MakeBoolean, GetActiveName> active{false};
+  SimDataValue<int32_t, MakeInt, GetRangeName> range{0};
+  SimDataValue<double, MakeDouble, GetXName> x{0.0};
+  SimDataValue<double, MakeDouble, GetYName> y{0.0};
+  SimDataValue<double, MakeDouble, GetZName> z{0.0};
+
+  virtual void ResetData();
+};
+extern SPIAccelerometerData* SimSPIAccelerometerData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIData.cpp b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIData.cpp
new file mode 100644
index 0000000..3afc606
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIData.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include "../PortsInternal.h"
+#include "SPIDataInternal.h"
+
+using namespace hal;
+
+namespace hal {
+namespace init {
+void InitializeSPIData() {
+  static SPIData ssd[5];
+  ::hal::SimSPIData = ssd;
+}
+}  // namespace init
+}  // namespace hal
+
+SPIData* hal::SimSPIData;
+void SPIData::ResetData() {
+  initialized.Reset(false);
+  read.Reset();
+  write.Reset();
+  autoReceivedData.Reset();
+}
+
+int32_t SPIData::Read(uint8_t* buffer, int32_t count) {
+  read(buffer, count);
+  return count;
+}
+
+int32_t SPIData::Write(const uint8_t* dataToSend, int32_t sendSize) {
+  write(dataToSend, sendSize);
+  return sendSize;
+}
+
+int32_t SPIData::Transaction(const uint8_t* dataToSend, uint8_t* dataReceived,
+                             int32_t size) {
+  write(dataToSend, size);
+  read(dataReceived, size);
+  return size;
+}
+
+int32_t SPIData::ReadAutoReceivedData(uint32_t* buffer, int32_t numToRead,
+                                      double timeout, int32_t* status) {
+  int32_t outputCount = 0;
+  autoReceivedData(buffer, numToRead, &outputCount);
+  return outputCount;
+}
+
+extern "C" {
+void HALSIM_ResetSPIData(int32_t index) { SimSPIData[index].ResetData(); }
+
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                          \
+  HAL_SIMDATAVALUE_DEFINE_CAPI(TYPE, HALSIM, SPI##CAPINAME, SimSPIData, \
+                               LOWERNAME)
+
+DEFINE_CAPI(HAL_Bool, Initialized, initialized)
+
+#undef DEFINE_CAPI
+#define DEFINE_CAPI(TYPE, CAPINAME, LOWERNAME)                                 \
+  HAL_SIMCALLBACKREGISTRY_DEFINE_CAPI(TYPE, HALSIM, SPI##CAPINAME, SimSPIData, \
+                                      LOWERNAME)
+
+DEFINE_CAPI(HAL_BufferCallback, Read, read)
+DEFINE_CAPI(HAL_ConstBufferCallback, Write, write)
+DEFINE_CAPI(HAL_SpiReadAutoReceiveBufferCallback, ReadAutoReceivedData,
+            autoReceivedData)
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIDataInternal.h b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIDataInternal.h
new file mode 100644
index 0000000..b10e741
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/main/native/sim/mockdata/SPIDataInternal.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "mockdata/SPIData.h"
+#include "mockdata/SimCallbackRegistry.h"
+#include "mockdata/SimDataValue.h"
+
+namespace hal {
+
+class SPIData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(Initialized)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(Read)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(Write)
+  HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(AutoReceive)
+
+ public:
+  int32_t Read(uint8_t* buffer, int32_t count);
+  int32_t Write(const uint8_t* dataToSend, int32_t sendSize);
+  int32_t Transaction(const uint8_t* dataToSend, uint8_t* dataReceived,
+                      int32_t size);
+  int32_t ReadAutoReceivedData(uint32_t* buffer, int32_t numToRead,
+                               double timeout, int32_t* status);
+
+  SimDataValue<HAL_Bool, MakeBoolean, GetInitializedName> initialized{false};
+  SimCallbackRegistry<HAL_BufferCallback, GetReadName> read;
+  SimCallbackRegistry<HAL_ConstBufferCallback, GetWriteName> write;
+  SimCallbackRegistry<HAL_SpiReadAutoReceiveBufferCallback, GetAutoReceiveName>
+      autoReceivedData;
+
+  void ResetData();
+};
+extern SPIData* SimSPIData;
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/java/edu/wpi/first/hal/sim/AccelerometerSimTest.java b/third_party/allwpilib_2019/hal/src/test/java/edu/wpi/first/hal/sim/AccelerometerSimTest.java
new file mode 100644
index 0000000..383165c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/java/edu/wpi/first/hal/sim/AccelerometerSimTest.java
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.hal.sim;
+
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.hal.AccelerometerJNI;
+import edu.wpi.first.hal.HAL;
+
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+class AccelerometerSimTest {
+  static class TriggeredStore {
+    public boolean m_wasTriggered;
+    public boolean m_setValue = true;
+  }
+
+  @Test
+  void testCallbacks() {
+    HAL.initialize(500, 0);
+    AccelerometerSim sim = new AccelerometerSim();
+    sim.resetData();
+
+    TriggeredStore store = new TriggeredStore();
+
+    try (CallbackStore cb = sim.registerActiveCallback((s, v) -> {
+      store.m_wasTriggered = true;
+      store.m_setValue = v.getBoolean();
+    }, false)) {
+      assertFalse(store.m_wasTriggered);
+      AccelerometerJNI.setAccelerometerActive(true);
+      assertTrue(store.m_wasTriggered);
+      assertTrue(store.m_setValue);
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/HALTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/HALTests.cpp
new file mode 100644
index 0000000..b387c14
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/HALTests.cpp
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/Solenoid.h"
+
+namespace hal {
+TEST(HALTests, RuntimeType) {
+  EXPECT_EQ(HAL_RuntimeType::HAL_Mock, HAL_GetRuntimeType());
+}
+
+TEST(HALSOLENOID, SolenoidTest) {
+  int32_t status = 0;
+  HAL_InitializeSolenoidPort(0, &status);
+  EXPECT_NE(status, 0);
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/can/CANTest.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/can/CANTest.cpp
new file mode 100644
index 0000000..6f5549c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/can/CANTest.cpp
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/CANAPI.h"
+#include "hal/HAL.h"
+#include "mockdata/CanData.h"
+
+namespace hal {
+struct CANTestStore {
+  CANTestStore(int32_t deviceId, int32_t* status) {
+    this->deviceId = deviceId;
+    handle = HAL_InitializeCAN(
+        HAL_CANManufacturer::HAL_CAN_Man_kTeamUse, deviceId,
+        HAL_CANDeviceType::HAL_CAN_Dev_kMiscellaneous, status);
+  }
+
+  ~CANTestStore() {
+    if (handle != HAL_kInvalidHandle) {
+      HAL_CleanCAN(handle);
+    }
+  }
+
+  int32_t deviceId;
+  HAL_CANHandle handle;
+};
+
+struct CANReceiveCallbackStore {
+  explicit CANReceiveCallbackStore(int32_t handle) { this->handle = handle; }
+  ~CANReceiveCallbackStore() { HALSIM_CancelCanReceiveMessageCallback(handle); }
+  int32_t handle;
+};
+
+struct CANSendCallbackStore {
+  explicit CANSendCallbackStore(int32_t handle) { this->handle = handle; }
+  ~CANSendCallbackStore() { HALSIM_CancelCanSendMessageCallback(handle); }
+  int32_t handle;
+};
+
+TEST(HALCanTests, CanIdPackingTest) {
+  int32_t status = 0;
+  int32_t deviceId = 12;
+  CANTestStore testStore(deviceId, &status);
+  ASSERT_EQ(0, status);
+
+  std::pair<int32_t, bool> storePair;
+  storePair.second = false;
+
+  auto cbHandle = HALSIM_RegisterCanSendMessageCallback(
+      [](const char* name, void* param, uint32_t messageID, const uint8_t* data,
+         uint8_t dataSize, int32_t periodMs, int32_t* status) {
+        std::pair<int32_t, bool>* paramI =
+            reinterpret_cast<std::pair<int32_t, bool>*>(param);
+        paramI->first = messageID;
+        paramI->second = true;
+      },
+      &storePair);
+
+  CANSendCallbackStore cbStore(cbHandle);
+  uint8_t data[8];
+
+  int32_t apiId = 42;
+
+  HAL_WriteCANPacket(testStore.handle, data, 8, 42, &status);
+
+  ASSERT_EQ(0, status);
+
+  ASSERT_TRUE(storePair.second);
+
+  ASSERT_NE(0, storePair.first);
+
+  ASSERT_EQ(deviceId, storePair.first & 0x3F);
+  ASSERT_EQ(apiId, (storePair.first & 0x0000FFC0) >> 6);
+  ASSERT_EQ(static_cast<int32_t>(HAL_CANManufacturer::HAL_CAN_Man_kTeamUse),
+            (storePair.first & 0x00FF0000) >> 16);
+  ASSERT_EQ(static_cast<int32_t>(HAL_CANDeviceType::HAL_CAN_Dev_kMiscellaneous),
+            (storePair.first & 0x1F000000) >> 24);
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/handles/HandleTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/handles/HandleTests.cpp
new file mode 100644
index 0000000..e893c78
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/handles/HandleTests.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/handles/IndexedClassedHandleResource.h"
+
+#define HAL_TestHandle HAL_Handle
+
+namespace {
+class MyTestClass {};
+}  // namespace
+
+namespace hal {
+TEST(HandleTests, ClassedHandleTest) {
+  hal::IndexedClassedHandleResource<HAL_TestHandle, MyTestClass, 8,
+                                    HAL_HandleEnum::Vendor>
+      testClass;
+  int32_t status = 0;
+  testClass.Allocate(0, std::make_unique<MyTestClass>(), &status);
+  EXPECT_EQ(0, status);
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..33990f0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/main.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/HAL.h"
+
+int main(int argc, char** argv) {
+  HAL_Initialize(500, 0);
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/AnalogInDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/AnalogInDataTests.cpp
new file mode 100644
index 0000000..791be79
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/AnalogInDataTests.cpp
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/AnalogInput.h"
+#include "hal/HAL.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/AnalogInData.h"
+
+namespace hal {
+
+std::string gTestAnalogInCallbackName;
+HAL_Value gTestAnalogInCallbackValue;
+
+void TestAnalogInInitializationCallback(const char* name, void* param,
+                                        const struct HAL_Value* value) {
+  gTestAnalogInCallbackName = name;
+  gTestAnalogInCallbackValue = *value;
+}
+
+TEST(AnalogInSimTests, TestAnalogInInitialization) {
+  const int INDEX_TO_TEST = 1;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterAnalogInInitializedCallback(
+      INDEX_TO_TEST, &TestAnalogInInitializationCallback, &callbackParam,
+      false);
+  ASSERT_TRUE(0 != callbackId);
+
+  int32_t status;
+  HAL_PortHandle portHandle;
+  HAL_DigitalHandle analogInHandle;
+
+  // Use out of range index
+  status = 0;
+  portHandle = 8000;
+  gTestAnalogInCallbackName = "Unset";
+  analogInHandle = HAL_InitializeAnalogInputPort(portHandle, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, analogInHandle);
+  EXPECT_EQ(PARAMETER_OUT_OF_RANGE, status);
+  EXPECT_STREQ("Unset", gTestAnalogInCallbackName.c_str());
+
+  // Successful setup
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestAnalogInCallbackName = "Unset";
+  analogInHandle = HAL_InitializeAnalogInputPort(portHandle, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != analogInHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestAnalogInCallbackName.c_str());
+
+  // Double initialize... should fail
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestAnalogInCallbackName = "Unset";
+  analogInHandle = HAL_InitializeAnalogInputPort(portHandle, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, analogInHandle);
+  EXPECT_EQ(RESOURCE_IS_ALLOCATED, status);
+  EXPECT_STREQ("Unset", gTestAnalogInCallbackName.c_str());
+
+  // Reset, should allow you to re-register
+  hal::HandleBase::ResetGlobalHandles();
+  HALSIM_ResetAnalogInData(INDEX_TO_TEST);
+  callbackId = HALSIM_RegisterAnalogInInitializedCallback(
+      INDEX_TO_TEST, &TestAnalogInInitializationCallback, &callbackParam,
+      false);
+
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestAnalogInCallbackName = "Unset";
+  analogInHandle = HAL_InitializeAnalogInputPort(portHandle, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != analogInHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestAnalogInCallbackName.c_str());
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/AnalogOutDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/AnalogOutDataTests.cpp
new file mode 100644
index 0000000..8f6d6f0
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/AnalogOutDataTests.cpp
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/AnalogOutput.h"
+#include "hal/HAL.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/AnalogOutData.h"
+
+namespace hal {
+
+std::string gTestAnalogOutCallbackName;
+HAL_Value gTestAnalogOutCallbackValue;
+
+void TestAnalogOutInitializationCallback(const char* name, void* param,
+                                         const struct HAL_Value* value) {
+  gTestAnalogOutCallbackName = name;
+  gTestAnalogOutCallbackValue = *value;
+}
+
+TEST(AnalogOutSimTests, TestAnalogOutInitialization) {
+  const int INDEX_TO_TEST = 1;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterAnalogOutInitializedCallback(
+      INDEX_TO_TEST, &TestAnalogOutInitializationCallback, &callbackParam,
+      false);
+  ASSERT_TRUE(0 != callbackId);
+
+  int32_t status;
+  HAL_PortHandle portHandle;
+  HAL_DigitalHandle analogOutHandle;
+
+  // Use out of range index
+  status = 0;
+  portHandle = 8000;
+  gTestAnalogOutCallbackName = "Unset";
+  analogOutHandle = HAL_InitializeAnalogOutputPort(portHandle, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, analogOutHandle);
+  EXPECT_EQ(PARAMETER_OUT_OF_RANGE, status);
+  EXPECT_STREQ("Unset", gTestAnalogOutCallbackName.c_str());
+
+  // Successful setup
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestAnalogOutCallbackName = "Unset";
+  analogOutHandle = HAL_InitializeAnalogOutputPort(portHandle, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != analogOutHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestAnalogOutCallbackName.c_str());
+
+  // Double initialize... should fail
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestAnalogOutCallbackName = "Unset";
+  analogOutHandle = HAL_InitializeAnalogOutputPort(portHandle, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, analogOutHandle);
+  EXPECT_EQ(RESOURCE_IS_ALLOCATED, status);
+  EXPECT_STREQ("Unset", gTestAnalogOutCallbackName.c_str());
+
+  // Reset, should allow you to re-register
+  hal::HandleBase::ResetGlobalHandles();
+  HALSIM_ResetAnalogOutData(INDEX_TO_TEST);
+  callbackId = HALSIM_RegisterAnalogOutInitializedCallback(
+      INDEX_TO_TEST, &TestAnalogOutInitializationCallback, &callbackParam,
+      false);
+
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestAnalogOutCallbackName = "Unset";
+  analogOutHandle = HAL_InitializeAnalogOutputPort(portHandle, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != analogOutHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestAnalogOutCallbackName.c_str());
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/DIODataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/DIODataTests.cpp
new file mode 100644
index 0000000..19fe994
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/DIODataTests.cpp
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/DIO.h"
+#include "hal/HAL.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/DIOData.h"
+
+namespace hal {
+
+std::string gTestDigitalIoCallbackName;
+HAL_Value gTestDigitalIoCallbackValue;
+
+void TestDigitalIoInitializationCallback(const char* name, void* param,
+                                         const struct HAL_Value* value) {
+  gTestDigitalIoCallbackName = name;
+  gTestDigitalIoCallbackValue = *value;
+}
+
+TEST(DigitalIoSimTests, TestDigitalIoInitialization) {
+  const int INDEX_TO_TEST = 3;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterDIOInitializedCallback(
+      INDEX_TO_TEST, &TestDigitalIoInitializationCallback, &callbackParam,
+      false);
+  ASSERT_TRUE(0 != callbackId);
+
+  int32_t status;
+  HAL_PortHandle portHandle;
+  HAL_DigitalHandle digitalIoHandle;
+
+  // Use out of range index
+  status = 0;
+  portHandle = 8000;
+  gTestDigitalIoCallbackName = "Unset";
+  digitalIoHandle = HAL_InitializeDIOPort(portHandle, true, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, digitalIoHandle);
+  EXPECT_EQ(PARAMETER_OUT_OF_RANGE, status);
+  EXPECT_STREQ("Unset", gTestDigitalIoCallbackName.c_str());
+
+  // Successful setup
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestDigitalIoCallbackName = "Unset";
+  digitalIoHandle = HAL_InitializeDIOPort(portHandle, true, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != digitalIoHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestDigitalIoCallbackName.c_str());
+
+  // Double initialize... should fail
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestDigitalIoCallbackName = "Unset";
+  digitalIoHandle = HAL_InitializeDIOPort(portHandle, true, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, digitalIoHandle);
+  EXPECT_EQ(RESOURCE_IS_ALLOCATED, status);
+  EXPECT_STREQ("Unset", gTestDigitalIoCallbackName.c_str());
+
+  // Reset, should allow you to re-register
+  hal::HandleBase::ResetGlobalHandles();
+  HALSIM_ResetDIOData(INDEX_TO_TEST);
+  callbackId = HALSIM_RegisterDIOInitializedCallback(
+      INDEX_TO_TEST, &TestDigitalIoInitializationCallback, &callbackParam,
+      false);
+
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestDigitalIoCallbackName = "Unset";
+  digitalIoHandle = HAL_InitializeDIOPort(portHandle, true, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != digitalIoHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestDigitalIoCallbackName.c_str());
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/DriverStationDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/DriverStationDataTests.cpp
new file mode 100644
index 0000000..35c0d54
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/DriverStationDataTests.cpp
@@ -0,0 +1,143 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <cstring>
+
+#include "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/Solenoid.h"
+#include "mockdata/DriverStationData.h"
+
+namespace hal {
+
+TEST(DriverStationTests, JoystickTests) {
+  HAL_JoystickAxes axes;
+  HAL_JoystickPOVs povs;
+  HAL_JoystickButtons buttons;
+
+  // Check default values before anything has been set
+  for (int joystickNum = 0; joystickNum < 6; ++joystickNum) {
+    HAL_GetJoystickAxes(joystickNum, &axes);
+    HAL_GetJoystickPOVs(joystickNum, &povs);
+    HAL_GetJoystickButtons(joystickNum, &buttons);
+
+    EXPECT_EQ(0, axes.count);
+    for (int i = 0; i < HAL_kMaxJoystickAxes; ++i) {
+      EXPECT_EQ(0, axes.axes[i]);
+    }
+
+    EXPECT_EQ(0, povs.count);
+    for (int i = 0; i < HAL_kMaxJoystickPOVs; ++i) {
+      EXPECT_EQ(0, povs.povs[i]);
+    }
+
+    EXPECT_EQ(0, buttons.count);
+    EXPECT_EQ(0u, buttons.buttons);
+  }
+
+  HAL_JoystickAxes set_axes;
+  std::memset(&set_axes, 0, sizeof(HAL_JoystickAxes));
+  HAL_JoystickPOVs set_povs;
+  std::memset(&set_povs, 0, sizeof(HAL_JoystickPOVs));
+  HAL_JoystickButtons set_buttons;
+  std::memset(&set_buttons, 0, sizeof(HAL_JoystickButtons));
+
+  // Set values
+  int joystickUnderTest = 4;
+  set_axes.count = 5;
+  for (int i = 0; i < set_axes.count; ++i) {
+    set_axes.axes[i] = i * .125;
+  }
+
+  set_povs.count = 3;
+  for (int i = 0; i < set_povs.count; ++i) {
+    set_povs.povs[i] = i * 15 + 12;
+  }
+
+  set_buttons.count = 8;
+  set_buttons.buttons = 0xDEADBEEF;
+
+  HALSIM_SetJoystickAxes(joystickUnderTest, &set_axes);
+  HALSIM_SetJoystickPOVs(joystickUnderTest, &set_povs);
+  HALSIM_SetJoystickButtons(joystickUnderTest, &set_buttons);
+
+  // Check the set values
+  HAL_GetJoystickAxes(joystickUnderTest, &axes);
+  HAL_GetJoystickPOVs(joystickUnderTest, &povs);
+  HAL_GetJoystickButtons(joystickUnderTest, &buttons);
+
+  EXPECT_EQ(5, axes.count);
+  EXPECT_NEAR(0.000, axes.axes[0], 0.000001);
+  EXPECT_NEAR(0.125, axes.axes[1], 0.000001);
+  EXPECT_NEAR(0.250, axes.axes[2], 0.000001);
+  EXPECT_NEAR(0.375, axes.axes[3], 0.000001);
+  EXPECT_NEAR(0.500, axes.axes[4], 0.000001);
+  EXPECT_NEAR(0, axes.axes[5], 0.000001);  // Should not have been set, still 0
+  EXPECT_NEAR(0, axes.axes[6], 0.000001);  // Should not have been set, still 0
+
+  EXPECT_EQ(3, povs.count);
+  EXPECT_EQ(12, povs.povs[0]);
+  EXPECT_EQ(27, povs.povs[1]);
+  EXPECT_EQ(42, povs.povs[2]);
+  EXPECT_EQ(0, povs.povs[3]);  // Should not have been set, still 0
+  EXPECT_EQ(0, povs.povs[4]);  // Should not have been set, still 0
+  EXPECT_EQ(0, povs.povs[5]);  // Should not have been set, still 0
+  EXPECT_EQ(0, povs.povs[6]);  // Should not have been set, still 0
+
+  EXPECT_EQ(8, buttons.count);
+  EXPECT_EQ(0xDEADBEEFu, buttons.buttons);
+
+  // Reset
+  HALSIM_ResetDriverStationData();
+  for (int joystickNum = 0; joystickNum < 6; ++joystickNum) {
+    HAL_GetJoystickAxes(joystickNum, &axes);
+    HAL_GetJoystickPOVs(joystickNum, &povs);
+    HAL_GetJoystickButtons(joystickNum, &buttons);
+
+    EXPECT_EQ(0, axes.count);
+    for (int i = 0; i < HAL_kMaxJoystickAxes; ++i) {
+      EXPECT_EQ(0, axes.axes[i]);
+    }
+
+    EXPECT_EQ(0, povs.count);
+    for (int i = 0; i < HAL_kMaxJoystickPOVs; ++i) {
+      EXPECT_EQ(0, povs.povs[i]);
+    }
+
+    EXPECT_EQ(0, buttons.count);
+    EXPECT_EQ(0u, buttons.buttons);
+  }
+}
+
+TEST(DriverStationTests, EventInfoTest) {
+  std::string eventName = "UnitTest";
+  std::string gameData = "Insert game specific info here :D";
+  HAL_MatchInfo info;
+  std::snprintf(info.eventName, sizeof(info.eventName), "%s",
+                eventName.c_str());
+  std::snprintf(reinterpret_cast<char*>(info.gameSpecificMessage),
+                sizeof(info.gameSpecificMessage), "%s", gameData.c_str());
+  info.gameSpecificMessageSize = gameData.size();
+  info.matchNumber = 5;
+  info.matchType = HAL_MatchType::HAL_kMatchType_qualification;
+  info.replayNumber = 42;
+  HALSIM_SetMatchInfo(&info);
+
+  HAL_MatchInfo dataBack;
+  HAL_GetMatchInfo(&dataBack);
+
+  std::string gsm{reinterpret_cast<char*>(dataBack.gameSpecificMessage),
+                  dataBack.gameSpecificMessageSize};
+
+  EXPECT_STREQ(eventName.c_str(), dataBack.eventName);
+  EXPECT_EQ(gameData, gsm);
+  EXPECT_EQ(5, dataBack.matchNumber);
+  EXPECT_EQ(HAL_MatchType::HAL_kMatchType_qualification, dataBack.matchType);
+  EXPECT_EQ(42, dataBack.replayNumber);
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/I2CDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/I2CDataTests.cpp
new file mode 100644
index 0000000..3a8e01c
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/I2CDataTests.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/I2C.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/I2CData.h"
+
+namespace hal {
+
+std::string gTestI2CCallbackName;
+HAL_Value gTestI2CCallbackValue;
+
+void TestI2CInitializationCallback(const char* name, void* param,
+                                   const struct HAL_Value* value) {
+  gTestI2CCallbackName = name;
+  gTestI2CCallbackValue = *value;
+}
+
+TEST(I2CSimTests, TestI2CInitialization) {
+  const int INDEX_TO_TEST = 1;
+
+  int32_t status;
+  HAL_I2CPort port;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterI2CInitializedCallback(
+      INDEX_TO_TEST, &TestI2CInitializationCallback, &callbackParam, false);
+  ASSERT_TRUE(0 != callbackId);
+
+  status = 0;
+  port = HAL_I2C_kMXP;
+  gTestI2CCallbackName = "Unset";
+  HAL_InitializeI2C(port, &status);
+  EXPECT_STREQ("Initialized", gTestI2CCallbackName.c_str());
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PCMDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PCMDataTests.cpp
new file mode 100644
index 0000000..50a8ae3
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PCMDataTests.cpp
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/Solenoid.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/PCMData.h"
+
+namespace hal {
+
+std::string gTestSolenoidCallbackName;
+HAL_Value gTestSolenoidCallbackValue;
+
+void TestSolenoidInitializationCallback(const char* name, void* param,
+                                        const struct HAL_Value* value) {
+  gTestSolenoidCallbackName = name;
+  gTestSolenoidCallbackValue = *value;
+}
+
+TEST(SolenoidSimTests, TestSolenoidInitialization) {
+  const int MODULE_TO_TEST = 2;
+  const int CHANNEL_TO_TEST = 3;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterPCMSolenoidInitializedCallback(
+      MODULE_TO_TEST, CHANNEL_TO_TEST, &TestSolenoidInitializationCallback,
+      &callbackParam, false);
+  ASSERT_TRUE(0 != callbackId);
+
+  int32_t status;
+  HAL_PortHandle portHandle;
+  HAL_DigitalHandle solenoidHandle;
+
+  // Use out of range index
+  status = 0;
+  portHandle = 8000;
+  gTestSolenoidCallbackName = "Unset";
+  solenoidHandle = HAL_InitializeSolenoidPort(portHandle, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, solenoidHandle);
+  EXPECT_EQ(HAL_HANDLE_ERROR, status);
+  EXPECT_STREQ("Unset", gTestSolenoidCallbackName.c_str());
+
+  // Successful setup
+  status = 0;
+  portHandle = HAL_GetPortWithModule(MODULE_TO_TEST, CHANNEL_TO_TEST);
+  gTestSolenoidCallbackName = "Unset";
+  solenoidHandle = HAL_InitializeSolenoidPort(portHandle, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != solenoidHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("SolenoidInitialized", gTestSolenoidCallbackName.c_str());
+
+  // Double initialize... should fail
+  status = 0;
+  portHandle = HAL_GetPortWithModule(MODULE_TO_TEST, CHANNEL_TO_TEST);
+  gTestSolenoidCallbackName = "Unset";
+  solenoidHandle = HAL_InitializeSolenoidPort(portHandle, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, solenoidHandle);
+  EXPECT_EQ(NO_AVAILABLE_RESOURCES, status);
+  EXPECT_STREQ("Unset", gTestSolenoidCallbackName.c_str());
+
+  // Reset, should allow you to re-register
+  hal::HandleBase::ResetGlobalHandles();
+  HALSIM_ResetPCMData(MODULE_TO_TEST);
+  callbackId = HALSIM_RegisterPCMSolenoidInitializedCallback(
+      MODULE_TO_TEST, CHANNEL_TO_TEST, &TestSolenoidInitializationCallback,
+      &callbackParam, false);
+  ASSERT_TRUE(0 != callbackId);
+
+  status = 0;
+  portHandle = HAL_GetPortWithModule(MODULE_TO_TEST, CHANNEL_TO_TEST);
+  gTestSolenoidCallbackName = "Unset";
+  solenoidHandle = HAL_InitializeSolenoidPort(portHandle, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != solenoidHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("SolenoidInitialized", gTestSolenoidCallbackName.c_str());
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PDPDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PDPDataTests.cpp
new file mode 100644
index 0000000..a46454f
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PDPDataTests.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/PDP.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/PDPData.h"
+
+namespace hal {
+
+std::string gTestPdpCallbackName;
+HAL_Value gTestPdpCallbackValue;
+
+void TestPdpInitializationCallback(const char* name, void* param,
+                                   const struct HAL_Value* value) {
+  gTestPdpCallbackName = name;
+  gTestPdpCallbackValue = *value;
+}
+
+TEST(PdpSimTests, TestPdpInitialization) {
+  const int INDEX_TO_TEST = 1;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterPDPInitializedCallback(
+      INDEX_TO_TEST, &TestPdpInitializationCallback, &callbackParam, false);
+  ASSERT_TRUE(0 != callbackId);
+
+  int32_t status;
+
+  // Use out of range index
+  status = 0;
+  gTestPdpCallbackName = "Unset";
+  HAL_InitializePDP(INDEX_TO_TEST, &status);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestPdpCallbackName.c_str());
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PWMDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PWMDataTests.cpp
new file mode 100644
index 0000000..447a510
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/PWMDataTests.cpp
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/PWM.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/PWMData.h"
+
+namespace hal {
+
+std::string gTestPwmCallbackName;
+HAL_Value gTestPwmCallbackValue;
+
+void TestPwmInitializationCallback(const char* name, void* param,
+                                   const struct HAL_Value* value) {
+  gTestPwmCallbackName = name;
+  gTestPwmCallbackValue = *value;
+}
+
+TEST(PWMSimTests, TestPwmInitialization) {
+  const int INDEX_TO_TEST = 7;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterPWMInitializedCallback(
+      INDEX_TO_TEST, &TestPwmInitializationCallback, &callbackParam, false);
+  ASSERT_TRUE(0 != callbackId);
+
+  int32_t status;
+  HAL_PortHandle portHandle;
+  HAL_DigitalHandle pwmHandle;
+
+  // Use out of range index
+  status = 0;
+  portHandle = 8000;
+  gTestPwmCallbackName = "Unset";
+  pwmHandle = HAL_InitializePWMPort(portHandle, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, pwmHandle);
+  EXPECT_EQ(PARAMETER_OUT_OF_RANGE, status);
+  EXPECT_STREQ("Unset", gTestPwmCallbackName.c_str());
+
+  // Successful setup
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestPwmCallbackName = "Unset";
+  pwmHandle = HAL_InitializePWMPort(portHandle, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != pwmHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestPwmCallbackName.c_str());
+
+  // Double initialize... should fail
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestPwmCallbackName = "Unset";
+  pwmHandle = HAL_InitializePWMPort(portHandle, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, pwmHandle);
+  EXPECT_EQ(RESOURCE_IS_ALLOCATED, status);
+  EXPECT_STREQ("Unset", gTestPwmCallbackName.c_str());
+
+  // Reset, should allow you to re-register
+  hal::HandleBase::ResetGlobalHandles();
+  HALSIM_ResetPWMData(INDEX_TO_TEST);
+  callbackId = HALSIM_RegisterPWMInitializedCallback(
+      INDEX_TO_TEST, &TestPwmInitializationCallback, &callbackParam, false);
+
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestPwmCallbackName = "Unset";
+  pwmHandle = HAL_InitializePWMPort(portHandle, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != pwmHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("Initialized", gTestPwmCallbackName.c_str());
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/RelayDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/RelayDataTests.cpp
new file mode 100644
index 0000000..408657a
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/RelayDataTests.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/Relay.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/RelayData.h"
+
+namespace hal {
+
+std::string gTestRelayCallbackName;
+HAL_Value gTestRelayCallbackValue;
+
+void TestRelayInitializationCallback(const char* name, void* param,
+                                     const struct HAL_Value* value) {
+  gTestRelayCallbackName = name;
+  gTestRelayCallbackValue = *value;
+}
+
+TEST(RelaySimTests, TestRelayInitialization) {
+  const int INDEX_TO_TEST = 3;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterRelayInitializedForwardCallback(
+      INDEX_TO_TEST, &TestRelayInitializationCallback, &callbackParam, false);
+  ASSERT_TRUE(0 != callbackId);
+
+  int32_t status;
+  HAL_PortHandle portHandle;
+  HAL_DigitalHandle pdpHandle;
+
+  // Use out of range index
+  status = 0;
+  portHandle = 8000;
+  gTestRelayCallbackName = "Unset";
+  pdpHandle = HAL_InitializeRelayPort(portHandle, true, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, pdpHandle);
+  EXPECT_EQ(PARAMETER_OUT_OF_RANGE, status);
+  EXPECT_STREQ("Unset", gTestRelayCallbackName.c_str());
+
+  // Successful setup
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestRelayCallbackName = "Unset";
+  pdpHandle = HAL_InitializeRelayPort(portHandle, true, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != pdpHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("InitializedForward", gTestRelayCallbackName.c_str());
+
+  // Double initialize... should fail
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestRelayCallbackName = "Unset";
+  pdpHandle = HAL_InitializeRelayPort(portHandle, true, &status);
+  EXPECT_EQ(HAL_kInvalidHandle, pdpHandle);
+  EXPECT_EQ(RESOURCE_IS_ALLOCATED, status);
+  EXPECT_STREQ("Unset", gTestRelayCallbackName.c_str());
+
+  // Reset, should allow you to re-register
+  hal::HandleBase::ResetGlobalHandles();
+  HALSIM_ResetRelayData(INDEX_TO_TEST);
+  callbackId = HALSIM_RegisterRelayInitializedForwardCallback(
+      INDEX_TO_TEST, &TestRelayInitializationCallback, &callbackParam, false);
+
+  status = 0;
+  portHandle = HAL_GetPort(INDEX_TO_TEST);
+  gTestRelayCallbackName = "Unset";
+  pdpHandle = HAL_InitializeRelayPort(portHandle, true, &status);
+  EXPECT_TRUE(HAL_kInvalidHandle != pdpHandle);
+  EXPECT_EQ(0, status);
+  EXPECT_STREQ("InitializedForward", gTestRelayCallbackName.c_str());
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/SPIDataTests.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/SPIDataTests.cpp
new file mode 100644
index 0000000..64c8555
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/mockdata/SPIDataTests.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "hal/SPI.h"
+#include "hal/handles/HandlesInternal.h"
+#include "mockdata/SPIData.h"
+
+namespace hal {
+
+std::string gTestSpiCallbackName;
+HAL_Value gTestSpiCallbackValue;
+
+void TestSpiInitializationCallback(const char* name, void* param,
+                                   const struct HAL_Value* value) {
+  gTestSpiCallbackName = name;
+  gTestSpiCallbackValue = *value;
+}
+
+TEST(SpiSimTests, TestSpiInitialization) {
+  const int INDEX_TO_TEST = 2;
+
+  int32_t status;
+  HAL_SPIPort port;
+
+  int callbackParam = 0;
+  int callbackId = HALSIM_RegisterSPIInitializedCallback(
+      INDEX_TO_TEST, &TestSpiInitializationCallback, &callbackParam, false);
+  ASSERT_TRUE(0 != callbackId);
+
+  status = 0;
+  port = HAL_SPI_kOnboardCS2;
+  gTestSpiCallbackName = "Unset";
+  HAL_InitializeSPI(port, &status);
+  EXPECT_STREQ("Initialized", gTestSpiCallbackName.c_str());
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/sim/AccelerometerSimTest.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/sim/AccelerometerSimTest.cpp
new file mode 100644
index 0000000..54be6e3
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/sim/AccelerometerSimTest.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "gtest/gtest.h"
+#include "hal/Accelerometer.h"
+#include "hal/HAL.h"
+#include "simulation/AccelerometerSim.h"
+
+using namespace frc::sim;
+
+namespace hal {
+
+TEST(AcclerometerSimTests, TestActiveCallback) {
+  HAL_Initialize(500, 0);
+
+  AccelerometerSim sim{0};
+
+  sim.ResetData();
+
+  bool wasTriggered = false;
+  bool lastValue = false;
+
+  auto cb = sim.RegisterActiveCallback(
+      [&](wpi::StringRef name, const HAL_Value* value) {
+        wasTriggered = true;
+        lastValue = value->data.v_boolean;
+      },
+      false);
+
+  EXPECT_FALSE(wasTriggered);
+
+  HAL_SetAccelerometerActive(true);
+
+  EXPECT_TRUE(wasTriggered);
+  EXPECT_TRUE(lastValue);
+}
+
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/hal/src/test/native/cpp/sim/SimInitializationTest.cpp b/third_party/allwpilib_2019/hal/src/test/native/cpp/sim/SimInitializationTest.cpp
new file mode 100644
index 0000000..fdd34cd
--- /dev/null
+++ b/third_party/allwpilib_2019/hal/src/test/native/cpp/sim/SimInitializationTest.cpp
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "gtest/gtest.h"
+#include "hal/HAL.h"
+#include "simulation/AccelerometerSim.h"
+#include "simulation/AnalogGyroSim.h"
+#include "simulation/AnalogInSim.h"
+#include "simulation/AnalogOutSim.h"
+#include "simulation/AnalogTriggerSim.h"
+#include "simulation/DIOSim.h"
+#include "simulation/DigitalPWMSim.h"
+#include "simulation/DriverStationSim.h"
+#include "simulation/EncoderSim.h"
+#include "simulation/PCMSim.h"
+#include "simulation/PDPSim.h"
+#include "simulation/PWMSim.h"
+#include "simulation/RelaySim.h"
+#include "simulation/RoboRioSim.h"
+#include "simulation/SPIAccelerometerSim.h"
+
+using namespace frc::sim;
+
+namespace hal {
+
+TEST(SimInitializationTests, TestAllInitialize) {
+  HAL_Initialize(500, 0);
+  AccelerometerSim acsim{0};
+  AnalogGyroSim agsim{0};
+  AnalogInSim aisim{0};
+  AnalogOutSim aosim{0};
+  AnalogTriggerSim atsim{0};
+  DigitalPWMSim dpsim{0};
+  DIOSim diosim{0};
+  DriverStationSim dssim;
+  (void)dssim;
+  EncoderSim esim{0};
+  PCMSim pcmsim{0};
+  PDPSim pdpsim{0};
+  PWMSim pwmsim{0};
+  RelaySim rsim{0};
+  RoboRioSim rrsim{0};
+  SPIAccelerometerSim sasim{0};
+}
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/myRobot/build.gradle b/third_party/allwpilib_2019/myRobot/build.gradle
new file mode 100644
index 0000000..0c047e8
--- /dev/null
+++ b/third_party/allwpilib_2019/myRobot/build.gradle
@@ -0,0 +1,145 @@
+plugins {
+    id 'java'
+    id 'application'
+    id 'cpp'
+    id 'visual-studio'
+}
+
+apply plugin: 'edu.wpi.first.NativeUtils'
+
+apply from: '../shared/config.gradle'
+
+ext {
+    sharedCvConfigs = [myRobotCpp: []]
+    staticCvConfigs = [myRobotCppStatic: []]
+    useJava = true
+    useCpp = true
+    skipDev = true
+}
+
+ext {
+    chipObjectComponents = ['myRobotCpp', 'myRobotCppStatic']
+    netCommComponents = ['myRobotCpp', 'myRobotCppStatic']
+    useNiJava = true
+}
+
+apply from: "${rootDir}/shared/nilibraries.gradle"
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+mainClassName = 'Main'
+
+apply plugin: 'com.github.johnrengelman.shadow'
+
+repositories {
+    mavenCentral()
+}
+
+dependencies {
+    compile project(':wpilibj')
+    compile project(':hal')
+    compile project(':wpiutil')
+    compile project(':ntcore')
+    compile project(':cscore')
+    compile project(':cameraserver')
+}
+
+jar {
+    manifest { attributes 'Robot-Class': 'MyRobot' }
+}
+
+model {
+    components {
+        myRobotCpp(NativeExecutableSpec) {
+            targetBuildTypes 'debug'
+            baseName = 'FRCUserProgram'
+            sources {
+                cpp {
+                    source {
+                        srcDirs = ['src/main/native/cpp']
+                        includes = ['**/*.cpp']
+                    }
+                    exportedHeaders {
+                        srcDirs = ['src/main/native/include']
+                        includes = ['**/*.h']
+                    }
+                }
+            }
+            binaries.all { binary ->
+                    lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                    project(':hal').addHalDependency(binary, 'shared')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+            }
+        }
+        myRobotCppStatic(NativeExecutableSpec) {
+            targetBuildTypes 'debug'
+            baseName = 'FRCUserProgram'
+            sources {
+                cpp {
+                    source {
+                        srcDirs = ['src/main/native/cpp']
+                        includes = ['**/*.cpp']
+                    }
+                    exportedHeaders {
+                        srcDirs = ['src/main/native/include']
+                        includes = ['**/*.h']
+                    }
+                }
+            }
+            binaries.all { binary ->
+                    lib project: ':wpilibc', library: 'wpilibc', linkage: 'static'
+                    lib project: ':ntcore', library: 'ntcore', linkage: 'static'
+                    lib project: ':cscore', library: 'cscore', linkage: 'static'
+                    project(':hal').addHalDependency(binary, 'static')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+                    lib project: ':cameraserver', library: 'cameraserver', linkage: 'static'
+            }
+        }
+    }
+    tasks {
+        def c = $.components
+        project.tasks.create('runCpp', Exec) {
+            group = 'WPILib'
+            description = "Run the myRobotCpp executable"
+            def found = false
+            def systemArch = getCurrentArch()
+            c.each {
+                if (it in NativeExecutableSpec && it.name == "myRobotCpp") {
+                    it.binaries.each {
+                        if (!found) {
+                            def arch = it.targetPlatform.architecture.name
+                            if (arch == systemArch) {
+                                dependsOn it.tasks.install
+                                commandLine it.tasks.install.runScriptFile.get().asFile.toString()
+                                def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib'
+                                run.dependsOn it.tasks.install
+                                run.systemProperty 'java.library.path', filePath
+                                run.environment 'LD_LIBRARY_PATH', filePath
+                                run.workingDir filePath
+
+                                found = true
+                            }
+                        }
+                    }
+                }
+            }
+        }
+        installAthena(Task) {
+            $.binaries.each {
+                if (it in NativeExecutableBinarySpec && it.targetPlatform.architecture.name == 'athena' && it.component.name == 'myRobotCpp') {
+                    dependsOn it.tasks.install
+                }
+            }
+        }
+        installAthenaStatic(Task) {
+            $.binaries.each {
+                if (it in NativeExecutableBinarySpec && it.targetPlatform.architecture.name == 'athena' && it.component.name == 'myRobotCppStatic') {
+                    dependsOn it.tasks.install
+                }
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/myRobot/src/main/java/Main.java b/third_party/allwpilib_2019/myRobot/src/main/java/Main.java
new file mode 100644
index 0000000..aee472a
--- /dev/null
+++ b/third_party/allwpilib_2019/myRobot/src/main/java/Main.java
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(MyRobot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/myRobot/src/main/java/MyRobot.java b/third_party/allwpilib_2019/myRobot/src/main/java/MyRobot.java
new file mode 100644
index 0000000..fc69d42
--- /dev/null
+++ b/third_party/allwpilib_2019/myRobot/src/main/java/MyRobot.java
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+import edu.wpi.first.wpilibj.TimedRobot;
+
+@SuppressWarnings("all")
+public class MyRobot extends TimedRobot {
+  /**
+   * This function is run when the robot is first started up and should be
+   * used for any initialization code.
+   */
+  @Override
+  public void robotInit() {}
+
+  /**
+   * This function is run once each time the robot enters autonomous mode
+   */
+  @Override
+  public void autonomousInit() {}
+
+  /**
+   * This function is called periodically during autonomous
+   */
+  @Override
+  public void autonomousPeriodic() {}
+
+  /**
+   * This function is called once each time the robot enters tele-operated mode
+   */
+  @Override
+  public void teleopInit() {}
+
+  /**
+   * This function is called periodically during operator control
+   */
+  @Override
+  public void teleopPeriodic() {}
+
+  /**
+   * This function is called periodically during test mode
+   */
+  @Override
+  public void testPeriodic() {}
+
+  /**
+   * This function is called periodically during all modes
+   */
+  @Override
+  public void robotPeriodic() {}
+}
diff --git a/third_party/allwpilib_2019/myRobot/src/main/native/cpp/MyRobot.cpp b/third_party/allwpilib_2019/myRobot/src/main/native/cpp/MyRobot.cpp
new file mode 100644
index 0000000..ff066d8
--- /dev/null
+++ b/third_party/allwpilib_2019/myRobot/src/main/native/cpp/MyRobot.cpp
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/TimedRobot.h>
+
+class MyRobot : public frc::TimedRobot {
+  /**
+   * This function is run when the robot is first started up and should be
+   * used for any initialization code.
+   */
+  void RobotInit() override {}
+
+  /**
+   * This function is run once each time the robot enters autonomous mode
+   */
+  void AutonomousInit() override {}
+
+  /**
+   * This function is called periodically during autonomous
+   */
+  void AutonomousPeriodic() override {}
+
+  /**
+   * This function is called once each time the robot enters tele-operated mode
+   */
+  void TeleopInit() override {}
+
+  /**
+   * This function is called periodically during operator control
+   */
+  void TeleopPeriodic() override {}
+
+  /**
+   * This function is called periodically during test mode
+   */
+  void TestPeriodic() override {}
+
+  /**
+   * This function is called periodically during all modes
+   */
+  void RobotPeriodic() override {}
+};
+
+int main() { return frc::StartRobot<MyRobot>(); }
diff --git a/third_party/allwpilib_2019/ntcore/.styleguide b/third_party/allwpilib_2019/ntcore/.styleguide
new file mode 100644
index 0000000..4c00fa9
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/.styleguide
@@ -0,0 +1,31 @@
+cHeaderFileInclude {
+  _c\.h$
+}
+
+cppHeaderFileInclude {
+  (?<!_c)\.h$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+generatedFileExclude {
+  ntcore/doc/
+}
+
+repoRootNameOverride {
+  ntcore
+}
+
+includeGuardRoots {
+  ntcore/src/main/native/cpp/
+  ntcore/src/main/native/include/
+  ntcore/src/test/native/cpp/
+}
+
+includeOtherLibs {
+  ^support/
+  ^wpi/
+}
diff --git a/third_party/allwpilib_2019/ntcore/CMakeLists.txt b/third_party/allwpilib_2019/ntcore/CMakeLists.txt
new file mode 100644
index 0000000..47e2264
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/CMakeLists.txt
@@ -0,0 +1,72 @@
+project(ntcore)
+
+file(GLOB
+    ntcore_native_src src/main/native/cpp/*.cpp
+    ntcore_native_src src/main/native/cpp/networktables/*.cpp
+    ntcore_native_src src/main/native/cpp/tables/*.cpp)
+add_library(ntcore ${ntcore_native_src})
+set_target_properties(ntcore PROPERTIES DEBUG_POSTFIX "d")
+target_include_directories(ntcore PUBLIC
+                $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/ntcore>)
+target_link_libraries(ntcore PUBLIC wpiutil)
+
+set_property(TARGET ntcore PROPERTY FOLDER "libraries")
+
+install(TARGETS ntcore EXPORT ntcore DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/ntcore")
+
+if (MSVC)
+    set (ntcore_config_dir ${wpilib_dest})
+else()
+    set (ntcore_config_dir share/ntcore)
+endif()
+
+install(FILES ntcore-config.cmake DESTINATION ${ntcore_config_dir})
+install(EXPORT ntcore DESTINATION ${ntcore_config_dir})
+
+# Java bindings
+if (NOT WITHOUT_JAVA)
+    find_package(Java REQUIRED)
+    find_package(JNI REQUIRED)
+    include(UseJava)
+    set(CMAKE_JAVA_COMPILE_FLAGS "-Xlint:unchecked")
+
+    file(GLOB
+        ntcore_jni_src src/main/native/cpp/jni/NetworkTablesJNI.cpp)
+
+    file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+    set(CMAKE_JNI_TARGET true)
+
+    if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+        set(CMAKE_JAVA_COMPILE_FLAGS "-h" "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+        add_jar(ntcore_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar OUTPUT_NAME ntcore)
+    else()
+        add_jar(ntcore_jar ${JAVA_SOURCES} INCLUDE_JARS wpiutil_jar OUTPUT_NAME ntcore GENERATE_NATIVE_HEADERS ntcore_jni_headers)
+    endif()
+
+    get_property(NTCORE_JAR_FILE TARGET ntcore_jar PROPERTY JAR_FILE)
+    install(FILES ${NTCORE_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+    set_property(TARGET ntcore_jar PROPERTY FOLDER "java")
+
+    add_library(ntcorejni ${ntcore_jni_src})
+    target_link_libraries(ntcorejni PUBLIC ntcore wpiutil)
+
+    set_property(TARGET ntcorejni PROPERTY FOLDER "libraries")
+
+    if (MSVC)
+        install(TARGETS ntcorejni RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+    endif()
+
+    if(${CMAKE_VERSION} VERSION_LESS "3.11.0")
+        target_include_directories(ntcorejni PRIVATE ${JNI_INCLUDE_DIRS})
+        target_include_directories(ntcorejni PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/jniheaders")
+    else()
+        target_link_libraries(ntcorejni PRIVATE ntcore_jni_headers)
+    endif()
+    add_dependencies(ntcorejni ntcore_jar)
+
+    install(TARGETS ntcorejni EXPORT ntcorejni DESTINATION "${main_lib_dest}")
+
+endif()
diff --git a/third_party/allwpilib_2019/ntcore/build.gradle b/third_party/allwpilib_2019/ntcore/build.gradle
new file mode 100644
index 0000000..659b0f9
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/build.gradle
@@ -0,0 +1,49 @@
+ext {
+    nativeName = 'ntcore'
+    devMain = 'edu.wpi.first.ntcore.DevMain'
+}
+
+apply from: "${rootDir}/shared/jni/setupBuild.gradle"
+
+model {
+    // Exports config is a utility to enable exporting all symbols in a C++ library on windows to a DLL.
+    // This removes the need for DllExport on a library. However, the gradle C++ builder has a bug
+    // where some extra symbols are added that cannot be resolved at link time. This configuration
+    // lets you specify specific symbols to exlude from exporting.
+    exportsConfigs {
+        ntcore(ExportsConfig) {
+            x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVbad_cast',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure']
+            x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVbad_cast',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure']
+        }
+        ntcoreJNI(ExportsConfig) {
+            x86SymbolFilter = { symbols ->
+                def retList = []
+                symbols.each { symbol ->
+                    if (symbol.startsWith('NT_')) {
+                        retList << symbol
+                    }
+                }
+                return retList
+            }
+            x64SymbolFilter = { symbols ->
+                def retList = []
+                symbols.each { symbol ->
+                    if (symbol.startsWith('NT_')) {
+                        retList << symbol
+                    }
+                }
+                return retList
+            }
+        }
+    }
+}
+
+pmdMain {
+    pmdMain.enabled = false
+}
diff --git a/third_party/allwpilib_2019/ntcore/doc/alloy-model.adoc b/third_party/allwpilib_2019/ntcore/doc/alloy-model.adoc
new file mode 100644
index 0000000..35ca7d8
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/doc/alloy-model.adoc
@@ -0,0 +1,198 @@
+= Network Tables Alloy Model
+
+Alloy (http://alloy.mit.edu/alloy/) is a formal logic tool that can analyze
+first-order logic expressions. Under the proposed sequence number -based
+protocol, assuming that all nodes start from the same state, Alloy is unable to
+find a way where two nodes with the same sequence number have different state
+when activity ceases.
+
+The model used is included below. Although Alloy cannot test all cases, since
+such an exhaustive search is intractable, it provides a high level of
+confidence in the proposed protocol.
+
+----
+--- Models a distributed, centralized hash table system called NetworkTables
+--- System state is protected by sequence numbers; the server's value for a certain sequence number always wins
+--- Paul Malmsten, 2012 pmalmsten@gmail.com
+
+open util/ordering[Time] as TO
+open util/natural as natural
+
+sig Time {}
+sig State {}
+
+--- Define nodes and server
+sig Node {
+    state: State -> Time,
+    sequenceNumber: Natural -> Time
+}
+
+--- Only one server
+one sig Server extends Node {
+}
+
+--- Define possible events
+abstract sig Event {
+    pre,post: Time,
+    receiver: one Node
+}
+
+// For all events, event.post is the time directly following event.pre
+fact {
+    all e:Event {
+        e.post = e.pre.next
+    }
+}
+
+// Represents that state has changed on a node
+sig StateChangeEvent extends Event {
+}
+
+// Represents that state has been transferred from one node to another
+sig StateTransferEvent extends Event {
+    sender: one Node
+}
+
+fact {
+    --- Every node must assume at most one state
+    all t:Time, n:Node | #n.state.t = 1
+
+    --- Every node must assume one sequence number
+    all t:Time, n:Node | #n.sequenceNumber.t = 1
+
+    --- Sequence numbers may only increment
+    all t:Time - last, n:Node | let t' = t.next | natural/gte[n.sequenceNumber.t', n.sequenceNumber.t]
+}
+
+
+fact stateChangedImpliesAStateTransfer {
+    all sce:StateChangeEvent {
+        // A StateChange on a client causes a transfer to the Server if its sequence number is greater than the server's
+        sce.receiver in Node - Server and natural/gt[sce.receiver.sequenceNumber.(sce.post), Server.sequenceNumber.(sce.post)]
+         implies
+            some ste:StateTransferEvent {
+                ste.pre = sce.post and ste.sender = sce.receiver and ste.receiver = Server
+            }
+    }
+
+    all sce:StateChangeEvent {
+        // A StateChange on the server causes a transfer to all clients
+        sce.receiver = Server implies
+            all n:Node - Server {
+                some ste:StateTransferEvent {
+                     ste.pre = sce.post and ste.sender = Server and ste.receiver = n
+                }
+            }
+    }
+
+    all sce:StateTransferEvent {
+        // A StateTransfer to the server causes a transfer to all clients
+        sce.receiver = Server implies
+            all n:Node - Server {
+                some ste:StateTransferEvent {
+                     ste.pre = sce.post and ste.sender = Server and ste.receiver = n
+                }
+            }
+    }
+}
+
+fact stateTransferEventsMoveState {
+    all ste:StateTransferEvent {
+        ste.sender = Server and not ste.receiver = Server or ste.receiver = Server and not ste.sender = Server
+
+        // Nodes can only post to the server if their sequence number is greater than the servers
+        ste.receiver = Server implies natural/gt[ste.sender.sequenceNumber.(ste.pre), ste.receiver.sequenceNumber.(ste.pre)]
+
+        // Server can only post to clients if its sequence number is greater than or equal to the client
+        ste.sender = Server implies natural/gte[ste.sender.sequenceNumber.(ste.pre), ste.receiver.sequenceNumber.(ste.pre)]
+
+        // Actual transfer
+        (ste.receiver.state.(ste.post) = ste.sender.state.(ste.pre) and
+          ste.receiver.sequenceNumber.(ste.post) = ste.sender.sequenceNumber.(ste.pre))
+    }
+}
+
+
+fact noEventsPendingAtEnd {
+    no e:Event {
+        e.pre = last
+    }
+}
+
+fact noDuplicateEvents {
+    all e,e2:Event {
+        // Two different events with the same receiver imply they occurred at different times
+        e.receiver = e2.receiver and e != e2 implies e.pre != e2.pre
+    }
+}
+
+fact noStateTransfersToSelf {
+    all ste:StateTransferEvent {
+        ste.sender != ste.receiver
+    }
+}
+
+fact noDuplicateStateTransferEvents {
+    all ste,ste2:StateTransferEvent {
+        // Two state transfer events with the same nodes imply that they occurred at different times
+        ste.sender = ste2.sender and ste.receiver = ste2.receiver and ste != ste2 implies ste.pre != ste2.pre
+    }
+}
+
+--- Trace (time invariant)
+fact trace {
+    all t:Time - last | let t' = t.next {
+        all n:Node {
+                // A node in (pre.t).receiver means it is being pointed to by some event that will happen over the next time step
+                n in (pre.t).receiver implies n.state.t' != n.state.t and n.sequenceNumber.t' != n.sequenceNumber.t    // A node which receives some sort of event at time t causes it to change state
+                                                       else n.state.t' = n.state.t and n.sequenceNumber.t' = n.sequenceNumber.t     // Otherwise, it does not change state
+        }
+    }
+}
+
+--- Things we might like to be true, but are not always true
+
+pred atLeastOneEvent {
+    #Event >= 1
+}
+
+pred allNodesStartAtSameStateAndSequenceNumber {
+    all n,n2:Node {
+        n.state.first = n2.state.first and n.sequenceNumber.first = n2.sequenceNumber.first
+    }
+}
+
+pred noStateChangeEventsAtEnd {
+    no e:StateChangeEvent {
+        e.post = last
+    }
+}
+
+--- Demonstration (Alloy will try to satisfy this)
+
+pred show {
+    atLeastOneEvent
+}
+run show
+
+--- Assertions (Alloy will try to break these)
+
+assert allNodesConsistentAtEnd {
+    allNodesStartAtSameStateAndSequenceNumber implies
+        all n,n2:Node {
+            // At the end of a sequence (last) all nodes with the same sequence number have the same state
+            n.sequenceNumber.last = n2.sequenceNumber.last implies n.state.last = n2.state.last
+        }
+}
+check allNodesConsistentAtEnd for 3 Event, 10 Node, 3 State, 5 Time, 5 Natural
+check allNodesConsistentAtEnd for 8 Event, 2 Node, 5 State, 9 Time, 9 Natural
+
+assert serverHasHighestSeqNumAtEnd {
+    allNodesStartAtSameStateAndSequenceNumber implies
+        all n:Node - Server{
+            // At the end of a sequence (last) all nodes with the same sequence number have the same state
+            natural/gte[Server.sequenceNumber.last, n.sequenceNumber.last]
+        }
+}
+check serverHasHighestSeqNumAtEnd for 3 Event, 10 Node, 3 State, 5 Time, 5 Natural
+----
diff --git a/third_party/allwpilib_2019/ntcore/doc/networktables2.adoc b/third_party/allwpilib_2019/ntcore/doc/networktables2.adoc
new file mode 100644
index 0000000..8471f86
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/doc/networktables2.adoc
@@ -0,0 +1,456 @@
+= Network Tables Protocol Specification, Version 2.0
+WPILib Developers <wpilib@wpi.edu>
+Protocol Revision 2.0 (0x0200), 1/8/2013
+:toc:
+:toc-placement: preamble
+:sectanchors:
+
+This document defines a network protocol for a key-value store that may be read
+from and written to by multiple remote clients. A central server, most often
+running on a FIRST FRC robot controller, is responsible for providing
+information consistency and for facilitating communication between clients.
+This document describes protocol revision 2.0 (0x0200).
+
+Information consistency is guaranteed through the use of a sequence number
+associated with each key-value pair. An update of a key-value pair increments
+the associated sequence number, and this update information is shared with all
+participating clients. The central server only applies and redistributes
+updates which have a larger sequence number than its own, which guarantees that
+a client must have received a server's most recent state before it can replace
+it with a new value.
+
+This is a backwards-incompatible rework of the Network Tables network protocol
+originally introduced for the 2012 FIRST Robotics Competition. Note that this
+revision of the Network Tables protocol no longer includes the concept of
+sub-tables. We suggest that instead of representing sub-tables as first-class
+data types in the network protocol, it would be easy for an implementation to
+provide a similar API abstraction by adding prefixes to keys. For example, we
+suggest using Unix-style path strings to define sub-table hierarchies. The
+prefix ensures that sub-table namespaces do not collide in a global hashtable
+without requiring an explicit sub-table representation.
+
+In addition, the explicit concept of grouping multiple updates such that they
+are all visible at the same time to user code on a remote device was discarded.
+Instead, array types for all common elements are provided. By using an array
+data type, users may achieve the same level of atomicity for common operations
+(e.g. sending a cartesian coordinate pair) without requiring the complexity of
+arbitrarily grouped updates.
+
+This document conforms to <<rfc2119>> - Key words for use in RFCs to Indicate
+Requirement Levels.
+
+[[references]]
+== References
+
+[[rfc1982,RFC 1982]]
+* RFC 1982, Serial Number Arithmetic, http://tools.ietf.org/html/rfc1982
+
+[[rfc2119,RFC 2119]]
+* RFC 2119, Key words for use in RFCs to Indicate Requirement Levels,
+http://tools.ietf.org/html/rfc2119
+
+[[definitions]]
+== Definitions
+
+[[def-client]]
+Client:: An implementation of this protocol running in client configuration.
+Any number of Clients may exist for a given Network.
+
+[[def-entry]]
+Entry:: A data value identified by a string name.
+
+[[def-entry-id]]
+Entry ID:: An unsigned 2-byte ID by which the Server and Clients refer to an
+Entry across the network instead of using the full string key for the Entry.
+Entry IDs range from 0x0000 to 0xFFFE (0xFFFF is reserved for an Entry
+Assignment issued by a Client).
+
+[[def-server]]
+Server:: An implementation of this protocol running in server configuration.
+One and only one Server must exist for a given Network.
+
+[[def-network]]
+Network:: One or more Client nodes connected to a Server.
+
+[[def-user-code]]
+User Code:: User-supplied code which may interact with a Client or Server. User
+Code should be executed on the same computer as the Client or Server instance
+it interacts with.
+
+[[def-sequence-number]]
+Sequence Number:: An unsigned number which allows the Server to resolve update
+conflicts between Clients and/or the Server. Sequence numbers may overflow.
+Sequential arithmetic comparisons, which must be used with Sequence Numbers,
+are defined by RFC 1982.
+
+[[def-protocol-revision]]
+Protocol Revision:: A 16-bit unsigned integer which indicates the version of
+the network tables protocol that a client wishes to use. The protocol revision
+assigned to this version of the network tables specification is listed at the
+top of this document. This number is listed in dot-decimal notation as well as
+its equivalent hexadecimal value.
+
+== Transport Layer
+
+Conventional implementations of this protocol should use TCP for reliable
+communication; the Server should listen on TCP port 1735 for incoming
+connections.
+
+== Example Exchanges
+
+[[exchange-connect]]
+=== Client Connects to the Server
+
+Directly after client establishes a connection with the Server, the following
+procedure must be followed:
+
+. The Client sends a <<msg-client-hello>> message to the Server
+
+. The Server sends one <<msg-assign>> for every field it currently recognizes.
+
+. The Server sends a <<msg-server-hello-complete>> message.
+
+. For all Entries the Client recognizes that the Server did not identify with a
+Entry Assignment, the client follows the <<exchange-client-creates-entry>>
+protocol.
+
+In the event that the Server does not support the protocol revision that the
+Client has requested in a Client Hello message, the Server must instead issue a
+<<msg-protocol-unsupported>> message to the joining client and close the
+connection.
+
+[[exchange-client-creates-entry]]
+=== Client Creates an Entry
+
+When User Code on a Client assigns a value to an Entry that the Server has not
+yet issued a Entry Assignment for, the following procedure must be followed:
+
+. The Client sends an <<msg-assign>> with an Entry ID of 0xFFFF.
+
+. The Server issues an <<msg-assign>> to all Clients (including the sender) for
+the new field containing a real Entry ID and Sequence Number for the new field.
+
+In the event that User Code on the Client updates the value of the
+to-be-announced field again before the expected Entry Assignment is received,
+then the Client must save the new value and take no other action (the most
+recent value of the field should be issued when the Entry Assignment arrives,
+if it differs from the value contained in the received Entry Assignment).
+
+In the event that the Client receives a Entry Assignment from the Server for
+the Entry that it intended to issue an Entry Assignment for, before it issued
+its own Entry Assignment, the procedure may end early.
+
+In the event that the Server receives a duplicate Entry Assignment from a
+Client (likely due to the client having not yet received the Server's Entry
+Assignment), the Server should ignore the duplicate Entry Assignment.
+
+[[exchange-client-updates-entry]]
+=== Client Updates an Entry
+
+When User Code on a Client updates the value of an Entry, the Client must send
+an <<msg-update>> message to the Server. The Sequence Number included in the
+Entry Update message must be the most recently received Sequence Number for the
+Entry to be updated incremented by one.
+
+.Example:
+
+. Client receives Entry Assignment message for Entry "a" with integer value 1,
+Entry ID of 0, and Sequence Number 1.
+
+. User Code on Client updates value of Entry "a" to 16 (arbitrary).
+
+. Client sends Entry Update message to Server for Entry 0 with a Sequence
+Number of 2 and a value of 16.
+
+When the Server receives an Entry Update message, it first checks the Sequence
+Number in the message against the Server's value for the Sequence Number
+associated with the Entry to be updated. If the received Sequence Number is
+strictly greater than (aside: see definition of "greater than" under the
+definition of Sequence Number) the Server's Sequence Number for the Entry to be
+updated, the Server must apply the new value for the indicated Entry and repeat
+the Entry Update message to all other connected Clients.
+
+If the received Sequence Number is less than or equal (see definition of "less
+than or equal" in RFC 1982) to the Server's Sequence Number for the Entry to be
+updated, this implies that the Client which issued the Entry Update message has
+not yet received one or more Entry Update message(s) that the Server recently
+sent to it; therefore, the Server must ignore the received Entry Update
+message. In the event that comparison between two Sequence Numbers is undefined
+(see RFC 1982), then the Server must always win (it ignores the Entry Update
+message under consideration).
+
+[[update-rate]]
+NOTE: If User Code modifies the value of an Entry too quickly, 1) users may not
+see every value appear on remote machines, and 2) the consistency protection
+offered by the Entry's Sequence Number may be lost (by overflowing before
+remote devices hear recent values). It is recommended that implementations
+detect when user code updates an Entry more frequently than once every 5
+milliseconds and print a warning message to the user (and/or offer some other
+means of informing User Code of this condition).
+
+[[exchange-server-creates-entry]]
+=== Server Creates an Entry
+
+When User Code on the Server assigns a value to a Entry which does not exist,
+the Server must issue an <<msg-assign>> message to all connected clients.
+
+[[exchange-server-updates-entry]]
+=== Server Updates an Entry
+
+When User Code on the Server updates the value of an Entry, the Server must
+apply the new value to the Entry immediately, increment the associated Entry's
+Sequence Number, and issue a <<msg-update>> message containing the new value
+and Sequence Number of the associated Entry to all connected Clients.
+
+NOTE: See <<update-rate,Note>> under <<exchange-client-updates-entry>>.
+
+[[exchange-keep-alive]]
+=== Keep Alive
+
+To maintain a connection and prove a socket is still open, a Client or Server
+may issue <<msg-keep-alive>> messages. Clients and the Server should ignore
+incoming Keep Alive messages.
+
+The intent is that by writing a Keep Alive to a socket, a Client forces its
+network layer (TCP) to reevaluate the state of the network connection as it
+attempts to deliver the Keep Alive message. In the event that a connection is
+no longer usable, a Client's network layer should inform the Client that it is
+no longer usable within a few attempts to send a Keep Alive message.
+
+To provide timely connection status information, Clients should send a Keep
+Alive message to the Server after every 1 second period of connection
+inactivity (i.e. no information is being sent to the Server). Clients should
+not send Keep Alive messages more frequently than once every 100 milliseconds.
+
+Since the Server does not require as timely information about the status of a
+connection, it is not required to send Keep Alive messages during a period of
+inactivity.
+
+[[bandwidth]]
+== Bandwidth and Latency Considerations
+
+To reduce unnecessary bandwidth usage, implementations of this protocol should:
+
+* Send an Entry Update if and only if the value of an Entry is changed to a
+value that is different from its prior value.
+
+* Buffer messages and transmit them in groups, when possible, to reduce
+transport protocol overhead.
+
+* Only send the most recent value of an Entry. When User Code updates the value
+of an Entry more than once before the new value is transmitted, only the latest
+value of the Entry should be sent.
+
+It is important to note that these behaviors will increase the latency between
+when a Client or Server updates the value of an Entry and when all Clients
+reflect the new value. The exact behavior of this buffering is left to
+implementations to determine, although the chosen scheme should reflect the
+needs of User Code. Implementations may include a method by which User Code can
+specify the maximum tolerable send latency.
+
+[[entry-types]]
+== Entry Types
+
+Entry Type must assume one the following values:
+
+[cols="1,3"]
+|===
+|Numeric Value |Type
+
+|0x00
+|Boolean
+
+|0x01
+|Double
+
+|0x02
+|String
+
+|0x10
+|Boolean Array
+
+|0x11
+|Double Array
+
+|0x12
+|String Array
+|===
+
+[[entry-values]]
+== Entry Values
+
+Entry Value must assume the following structure as indicated by Entry Type:
+
+[cols="1,3"]
+|===
+|Entry Type |Entry Value Format
+
+|[[entry-value-boolean]]Boolean
+|1 byte, unsigned; True = 0x01, False = 0x00
+
+|[[entry-value-double]]Double
+|8 bytes, IEEE 754 floating-point "double format" bit layout; (big endian)
+
+|[[entry-value-string]]String
+|2 byte, unsigned length prefix (big endian) of the number of raw bytes to
+follow, followed by the string encoded in UTF-8
+
+|[[entry-value-boolean-array]]Boolean Array
+|1 byte, unsigned, number of elements within the array to follow
+
+N bytes - The raw bytes representing each Boolean element contained within the
+array, beginning with the item at index 0 within the array.
+
+|[[entry-value-double-array]]Double Array
+|1 byte, unsigned, number of elements within the array to follow
+
+N bytes - The raw bytes representing each Double element contained within the
+array, beginning with the item at index 0 within the array.
+
+|[[entry-value-string-array]]String Array
+|1 byte, unsigned, number of elements within the array to follow
+
+N bytes - The raw bytes representing each String element contained within the
+array, beginning with the item at index 0 within the array.
+|===
+
+== Message Structures
+
+All messages are of the following format:
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|Message Type
+|1 byte, unsigned
+
+|Message Data
+|N bytes (length determined by Message Type)
+|===
+
+[[msg-keep-alive]]
+=== Keep Alive
+
+Indicates that the remote party is checking the status of a network connection.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x00 - Keep Alive
+|1 byte, unsigned; Message Type
+|===
+
+[[msg-client-hello]]
+=== Client Hello
+
+A Client issues a Client Hello message when first establishing a connection.
+The Client Protocol Revision field specifies the Network Table protocol
+revision that the Client would like to use.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x01 - Client Hello
+|1 byte, unsigned; Message Type
+
+|Client Protocol Revision
+|2 bytes, Unsigned 16-bit integer (big-endian).
+
+See <<def-protocol-revision,Protocol Revision>>
+|===
+
+[[msg-protocol-unsupported]]
+=== Protocol Version Unsupported
+
+A Server issues a Protocol Version Unsupported message to a Client to inform it
+that the requested protocol revision is not supported. It also includes the
+most recent protocol revision which it supports, such that a Client may
+reconnect under a prior protocol revision if able.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x02 - Protocol Version Unsupported
+|1 byte, unsigned; Message Type
+
+|Server Supported Protocol Revision
+|2 bytes, Unsigned 16-bit integer (big-endian).
+
+See <<def-protocol-revision,Protocol Revision>>
+|===
+
+[[msg-server-hello-complete]]
+=== Server Hello Complete
+
+A Server issues a Server Hello Complete message when it has finished informing
+a newly-connected client of all of the fields it currently recognizes.
+Following the receipt of this message, a Client should inform the Server of
+any/all additional fields that it recognizes that the Server did not announce.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x03 - Server Hello Complete
+|1 byte, unsigned; Message Type
+|===
+
+[[msg-assign]]
+=== Entry Assignment
+
+A Entry Assignment message informs the remote party of a new Entry. An Entry
+Assignment's value field must be the most recent value of the field being
+assigned at the time that the Entry Assignment is sent.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x10 - Entry Assignment
+|1 byte, unsigned; Message Type
+
+|Entry Name
+|<<entry-value-string,String>>
+
+|Entry Type
+|1 byte, unsigned; see <<entry-types,Entry Types>>
+
+|Entry ID
+|2 bytes, unsigned
+
+|Entry Sequence Number
+|2 bytes, unsigned
+
+|Entry Value
+|N bytes, length depends on Entry Type
+|===
+
+If the Entry ID is 0xFFFF, then this assignment represents a request from a
+Client to the Server. In this event, the Entry ID field and the Entry Sequence
+Number field must not be stored or relied upon as they otherwise would be.
+
+[[msg-update]]
+=== Entry Update
+
+An Entry Update message informs a remote party of a new value for an Entry.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x11 - Entry Update
+|1 byte, unsigned; Message Type
+
+|Entry ID
+|2 bytes, unsigned
+
+|Entry Sequence Number
+|2 bytes, unsigned
+
+|Entry Value
+|N bytes, length dependent on value type
+|===
diff --git a/third_party/allwpilib_2019/ntcore/doc/networktables3.adoc b/third_party/allwpilib_2019/ntcore/doc/networktables3.adoc
new file mode 100644
index 0000000..af8b953
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/doc/networktables3.adoc
@@ -0,0 +1,885 @@
+= Network Tables Protocol Specification, Version 3.0
+WPILib Developers <wpilib@wpi.edu>
+Protocol Revision 3.0 (0x0300), 6/12/2015
+:toc:
+:toc-placement: preamble
+:sectanchors:
+
+This document defines a network protocol for a key-value store that may be read
+from and written to by multiple remote clients. A central server, most often
+running on a FIRST FRC robot controller, is responsible for providing
+information consistency and for facilitating communication between clients.
+This document describes protocol revision 3.0 (0x0300).
+
+Information consistency is guaranteed through the use of a sequence number
+associated with each key-value pair. An update of a key-value pair increments
+the associated sequence number, and this update information is shared with all
+participating clients. The central server only applies and redistributes
+updates which have a larger sequence number than its own, which guarantees that
+a client must have received a server's most recent state before it can replace
+it with a new value.
+
+This is a backwards-compatible update of <<networktables2,version 2.0>> of the
+Network Tables network protocol. The protocol is designed such that 3.0 clients
+and servers can interoperate with 2.0 clients and servers with the only loss of
+functionality being the extended features introduced in 3.0.
+
+This document conforms to <<rfc2119>> - Key words for use in RFCs to Indicate
+Requirement Levels.
+
+== Summary of Changes from 2.0 to 3.0
+
+3 way connection handshake:: When a Client establishes a connection, after
+receiving the <<msg-server-hello-complete>> message and sending its local
+entries, it finishes with a <<msg-client-hello-complete>> message to the
+server. This enables the Server to be aware of when the Client is fully
+synchronized.
+
+String length encoding:: String length is now encoded as unsigned <<leb128>>
+rather than as a 2-byte unsigned integer. This both allows string lengths
+longer than 64K and is more space efficient for the common case of short
+strings (<128 byte strings only require a single byte for length).
+
+Entry deletion:: Entries may now be deleted by any member of the Network using
+the <<msg-delete>> and <<msg-clear-all>> messages. Note that in a Network
+consisting of mixed 2.0 and 3.0 Clients, deletion may be ineffective because
+the deletion message will not be propagated to the 2.0 Clients.
+
+// TODO: needs more description in the text of how these messages are
+// propagated
+
+Remote procedure call:: The Server may create specially-typed entries that
+inform Clients of remotely callable functions on the Server. Clients can then
+execute these functions via the Network Tables protocol. See <<rpc-operation>>.
+
+Raw data type:: An arbitrary data type has been added. While string could be
+used to encode raw data, the reason for a different data type is so that
+dashboards can choose not to display the raw data (or display it in a different
+format).
+
+Client and server self-identification:: Clients self-identify with a
+user-defined string name when connecting to the Server (this is part of the new
+<<msg-client-hello-complete>> message). This provides a more reliable method
+than simply the remote IP address for determining on the Server side whether or
+not a particular Client is connected.  While Clients are less likely to care
+what Server they are connected to, for completeness a similar Server
+self-identification string has been added to the Server Hello Complete message.
+Note that Server connection information is not provided from the Server to
+Clients (at least in a way built into the protocol), so it is not possible for
+a Client to determine what other Clients are connected to the Server.
+
+Server reboot detection:: The Server keeps an internal list of all Client
+identity strings that have ever connected to it (this list is always empty at
+Server start). During the initial connection process, the Server sends the
+Client a flag (as part of the new <<msg-server-hello>> message) that indicates
+whether or not the Client was already on this list. Clients use this flag to
+determine whether the Server has rebooted since the previous connection.
+
+Entry flags:: Each Entry now has an 8-bit flags value associated with it (see
+<<entry-flags>>). The initial value of the flags are provided as part of the
+<<msg-assign>> message. The value of the flags may be updated by any member of
+the Network via use of the <<msg-flags-update>> message.
+
+Entry persistence:: The Server is required to provide a feature to
+automatically save entries (including their last known values) across Server
+restarts. By default, no values are automatically saved in this manner, but
+any member of the Network may set the “Persistent” Entry Flag on an Entry to
+indicate to the server that the Entry must be persisted by the Server. The
+Server must periodically save such flagged Entries to a file; on Server start,
+the Server reads the file to create the initial set of Server Entries.
+
+More robust Entry Update message encoding:: The entry type has been added to
+the <<msg-update>> message. This is used only to specify the length of value
+encoded in the Entry Update message, and has no effect on the Client or Server
+handling of Entry Updates. Clients and Servers must ignore Entry Update
+messages with mismatching type to their currently stored value. This increases
+robustness of Entry Updates in the presence of Entry Assignments with varying
+type (which should be uncommon, but this fixes a weakness in the 2.0 protocol).
+
+////
+TODO
+
+Synchronization on reconnect:: The approach to how Clients should handle
+conflicting values when reconnecting to a Server has been clarified.
+
+////
+
+[[references]]
+== References
+
+[[networktables2]]
+* <<networktables2.adoc#,Network Tables Protocol Specification, Protocol
+Revision 2.0 (0x0200)>>, dated 1/8/2013.
+
+[[leb128,LEB128]]
+* LEB128 definition in DWARF Specification 3.0
+(http://dwarfstd.org/doc/Dwarf3.pdf, section 7.6 and Appendix C, also explained
+in http://en.wikipedia.org/wiki/LEB128)
+
+[[rfc1982,RFC1982]]
+* RFC 1982, Serial Number Arithmetic, http://tools.ietf.org/html/rfc1982
+
+[[rfc2119,RFC2119]]
+* RFC 2119, Key words for use in RFCs to Indicate Requirement Levels,
+http://tools.ietf.org/html/rfc2119
+
+[[definitions]]
+== Definitions
+
+[[def-client]]
+Client:: An implementation of this protocol running in client configuration.
+Any number of Clients may exist for a given Network.
+
+[[def-entry]]
+Entry:: A data value identified by a string name.
+
+[[def-entry-id]]
+Entry ID:: An unsigned 2-byte ID by which the Server and Clients refer to an
+Entry across the network instead of using the full string key for the Entry.
+Entry IDs range from 0x0000 to 0xFFFE (0xFFFF is reserved for an Entry
+Assignment issued by a Client).
+
+[[def-server]]
+Server:: An implementation of this protocol running in server configuration.
+One and only one Server must exist for a given Network.
+
+[[def-network]]
+Network:: One or more Client nodes connected to a Server.
+
+[[def-user-code]]
+User Code:: User-supplied code which may interact with a Client or Server. User
+Code should be executed on the same computer as the Client or Server instance
+it interacts with.
+
+[[def-sequence-number]]
+Sequence Number:: An unsigned number which allows the Server to resolve update
+conflicts between Clients and/or the Server. Sequence numbers may overflow.
+Sequential arithmetic comparisons, which must be used with Sequence Numbers,
+are defined by <<rfc1982>>.
+
+[[def-protocol-revision]]
+Protocol Revision:: A 16-bit unsigned integer which indicates the version of
+the network tables protocol that a client wishes to use. The protocol revision
+assigned to this version of the network tables specification is listed at the
+top of this document. This number is listed in dot-decimal notation as well as
+its equivalent hexadecimal value.
+
+== Transport Layer
+
+Conventional implementations of this protocol should use TCP for reliable
+communication; the Server should listen on TCP port 1735 for incoming
+connections.
+
+== Example Exchanges
+
+[[exchange-connect]]
+=== Client Connects to the Server
+
+Directly after client establishes a connection with the Server, the following
+procedure must be followed:
+
+. The Client sends a <<msg-client-hello>> message to the Server
+
+. The Server sends a <<msg-server-hello>> message.
+
+. The Server sends one <<msg-assign>> for every field it currently recognizes.
+
+. The Server sends a <<msg-server-hello-complete>> message.
+
+. For all Entries the Client recognizes that the Server did not identify with a
+Entry Assignment, the client follows the <<exchange-client-creates-entry>>
+protocol.
+
+. The Client sends a <<msg-client-hello-complete>> message.
+
+In the event that the Server does not support the protocol revision that the
+Client has requested in a Client Hello message, the Server must instead issue a
+<<msg-protocol-unsupported>> message to the joining client and close the
+connection.
+
+[[exchange-client-creates-entry]]
+=== Client Creates an Entry
+
+When User Code on a Client assigns a value to an Entry that the Server has not
+yet issued a Entry Assignment for, the following procedure must be followed:
+
+. The Client sends an <<msg-assign>> with an Entry ID of 0xFFFF.
+
+. The Server issues an <<msg-assign>> to all Clients (including the sender) for
+the new field containing a real Entry ID and Sequence Number for the new field.
+
+In the event that User Code on the Client updates the value of the
+to-be-announced field again before the expected Entry Assignment is received,
+then the Client must save the new value and take no other action (the most
+recent value of the field should be issued when the Entry Assignment arrives,
+if it differs from the value contained in the received Entry Assignment).
+
+In the event that the Client receives a Entry Assignment from the Server for
+the Entry that it intended to issue an Entry Assignment for, before it issued
+its own Entry Assignment, the procedure may end early.
+
+In the event that the Server receives a duplicate Entry Assignment from a
+Client (likely due to the client having not yet received the Server's Entry
+Assignment), the Server should ignore the duplicate Entry Assignment.
+
+[[exchange-client-updates-entry]]
+=== Client Updates an Entry
+
+When User Code on a Client updates the value of an Entry, the Client must send
+an <<msg-update>> message to the Server. The Sequence Number included in the
+Entry Update message must be the most recently received Sequence Number for the
+Entry to be updated incremented by one.
+
+.Example:
+
+. Client receives Entry Assignment message for Entry "a" with integer value 1,
+Entry ID of 0, and Sequence Number 1.
+
+. User Code on Client updates value of Entry "a" to 16 (arbitrary).
+
+. Client sends Entry Update message to Server for Entry 0 with a Sequence
+Number of 2 and a value of 16.
+
+When the Server receives an Entry Update message, it first checks the Sequence
+Number in the message against the Server's value for the Sequence Number
+associated with the Entry to be updated. If the received Sequence Number is
+strictly greater than (aside: see definition of "greater than" under the
+definition of Sequence Number) the Server's Sequence Number for the Entry to be
+updated, the Server must apply the new value for the indicated Entry and repeat
+the Entry Update message to all other connected Clients.
+
+If the received Sequence Number is less than or equal (see definition of "less
+than or equal" in RFC 1982) to the Server's Sequence Number for the Entry to be
+updated, this implies that the Client which issued the Entry Update message has
+not yet received one or more Entry Update message(s) that the Server recently
+sent to it; therefore, the Server must ignore the received Entry Update
+message. In the event that comparison between two Sequence Numbers is undefined
+(see RFC 1982), then the Server must always win (it ignores the Entry Update
+message under consideration).
+
+[[update-rate]]
+NOTE: If User Code modifies the value of an Entry too quickly, 1) users may not
+see every value appear on remote machines, and 2) the consistency protection
+offered by the Entry's Sequence Number may be lost (by overflowing before
+remote devices hear recent values). It is recommended that implementations
+detect when user code updates an Entry more frequently than once every 5
+milliseconds and print a warning message to the user (and/or offer some other
+means of informing User Code of this condition).
+
+[[exchange-client-updates-flags]]
+=== Client Updates an Entry's Flags
+
+When User Code on a Client updates an Entry's flags, the Client must apply the
+new flags to the Entry immediately, and send an <<msg-flags-update>> message to
+the Server.
+
+When the Server receives an Entry Flags Update message, it must apply the new
+flags to the indicated Entry and repeat the Entry Flags Update message to all
+other connected Clients.
+
+[[exchange-client-deletes-entry]]
+=== Client Deletes an Entry
+
+When User Code on a Client deletes an Entry, the Client must immediately delete
+the Entry, and send an <<msg-delete>> message to the Server.
+
+When the Server receives an Entry Delete message, it must delete the indicated
+Entry and repeat the Entry Delete message to all other connected Clients.
+
+[[exchange-server-creates-entry]]
+=== Server Creates an Entry
+
+When User Code on the Server assigns a value to a Entry which does not exist,
+the Server must issue an <<msg-assign>> message to all connected clients.
+
+[[exchange-server-updates-entry]]
+=== Server Updates an Entry
+
+When User Code on the Server updates the value of an Entry, the Server must
+apply the new value to the Entry immediately, increment the associated Entry's
+Sequence Number, and issue a <<msg-update>> message containing the new value
+and Sequence Number of the associated Entry to all connected Clients.
+
+NOTE: See <<update-rate,Note>> under <<exchange-client-updates-entry>>.
+
+[[exchange-server-updates-flags]]
+=== Server Updates an Entry's Flags
+
+When User Code on the Server updates an Entry's flags, the Server must apply
+the new flags to the Entry immediately, and issue a <<msg-flags-update>>
+message containing the new flags value to all connected Clients.
+
+[[exchange-server-deletes-entry]]
+=== Server Deletes an Entry
+
+When User Code on the Server deletes an Entry, the Server must immediately
+delete the Entry, and issue a <<msg-delete>> message to all connected Clients.
+
+[[exchange-keep-alive]]
+=== Keep Alive
+
+To maintain a connection and prove a socket is still open, a Client or Server
+may issue <<msg-keep-alive>> messages. Clients and the Server should ignore
+incoming Keep Alive messages.
+
+The intent is that by writing a Keep Alive to a socket, a Client forces its
+network layer (TCP) to reevaluate the state of the network connection as it
+attempts to deliver the Keep Alive message. In the event that a connection is
+no longer usable, a Client's network layer should inform the Client that it is
+no longer usable within a few attempts to send a Keep Alive message.
+
+To provide timely connection status information, Clients should send a Keep
+Alive message to the Server after every 1 second period of connection
+inactivity (i.e. no information is being sent to the Server). Clients should
+not send Keep Alive messages more frequently than once every 100 milliseconds.
+
+Since the Server does not require as timely information about the status of a
+connection, it is not required to send Keep Alive messages during a period of
+inactivity.
+
+[[bandwidth]]
+== Bandwidth and Latency Considerations
+
+To reduce unnecessary bandwidth usage, implementations of this protocol should:
+
+* Send an Entry Update if and only if the value of an Entry is changed to a
+value that is different from its prior value.
+
+* Buffer messages and transmit them in groups, when possible, to reduce
+transport protocol overhead.
+
+* Only send the most recent value of an Entry. When User Code updates the value
+of an Entry more than once before the new value is transmitted, only the latest
+value of the Entry should be sent.
+
+It is important to note that these behaviors will increase the latency between
+when a Client or Server updates the value of an Entry and when all Clients
+reflect the new value. The exact behavior of this buffering is left to
+implementations to determine, although the chosen scheme should reflect the
+needs of User Code. Implementations may include a method by which User Code can
+specify the maximum tolerable send latency.
+
+[[entry-types]]
+== Entry Types
+
+Entry Type must assume one the following values:
+
+[cols="1,3"]
+|===
+|Numeric Value |Type
+
+|0x00
+|Boolean
+
+|0x01
+|Double
+
+|0x02
+|String
+
+|0x03
+|Raw Data
+
+|0x10
+|Boolean Array
+
+|0x11
+|Double Array
+
+|0x12
+|String Array
+
+|0x20
+|Remote Procedure Call Definition
+|===
+
+[[entry-values]]
+== Entry Values
+
+Entry Value must assume the following structure as indicated by Entry Type:
+
+[cols="1,3"]
+|===
+|Entry Type |Entry Value Format
+
+|[[entry-value-boolean]]Boolean
+|1 byte, unsigned; True = 0x01, False = 0x00
+
+|[[entry-value-double]]Double
+|8 bytes, IEEE 754 floating-point "double format" bit layout; (big endian)
+
+|[[entry-value-string]]String
+|N bytes, unsigned <<leb128>> encoded length of the number of raw bytes to
+follow, followed by the string encoded in UTF-8
+
+|[[entry-value-raw]]Raw Data
+|N bytes, unsigned LEB128 encoded length of the number of raw bytes to follow,
+followed by the raw bytes.
+
+While the raw data definition is unspecified, it's recommended that users use
+the first byte of the raw data to "tag" the type of data actually being stored.
+
+|[[entry-value-boolean-array]]Boolean Array
+|1 byte, unsigned, number of elements within the array to follow
+
+N bytes - The raw bytes representing each Boolean element contained within the
+array, beginning with the item at index 0 within the array.
+
+|[[entry-value-double-array]]Double Array
+|1 byte, unsigned, number of elements within the array to follow
+
+N bytes - The raw bytes representing each Double element contained within the
+array, beginning with the item at index 0 within the array.
+
+|[[entry-value-string-array]]String Array
+|1 byte, unsigned, number of elements within the array to follow
+
+N bytes - The raw bytes representing each String element contained within the
+array, beginning with the item at index 0 within the array.
+
+|[[entry-value-rpc]]Remote Procedure Call Definition
+|N bytes, unsigned LEB128 encoded length of the number of raw bytes to follow.
+
+N bytes - data as defined in Remote Procedure Call Definition Data
+|===
+
+[[entry-flags]]
+== Entry Flags
+
+Entry Flags are as follows:
+
+[cols="1,3"]
+|===
+|Bit Mask |Bit Value Meaning
+
+|[[entry-flag-persistent]]0x01 (least significant bit) - Persistent
+
+|0x00: Entry is not persistent. The entry and its value will not be retained
+across a server restart.
+
+0x01: Entry is persistent. Updates to the value are automatically saved and
+the entry will be automatically created and the last known value restored when
+the server starts.
+
+|0xFE
+|Reserved
+|===
+
+== Message Structures
+
+All messages are of the following format:
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|Message Type
+|1 byte, unsigned
+
+|Message Data
+|N bytes (length determined by Message Type)
+|===
+
+[[msg-keep-alive]]
+=== Keep Alive
+
+Indicates that the remote party is checking the status of a network connection.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x00 - Keep Alive
+|1 byte, unsigned; Message Type
+|===
+
+[[msg-client-hello]]
+=== Client Hello
+
+A Client issues a Client Hello message when first establishing a connection.
+The Client Protocol Revision field specifies the Network Table protocol
+revision that the Client would like to use.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x01 - Client Hello
+|1 byte, unsigned; Message Type
+
+|Client Protocol Revision
+|2 bytes, Unsigned 16-bit integer (big-endian). See
+<<def-protocol-revision,Protocol Revision>>.
+
+|Client identity (name)
+|<<entry-value-string,String>>
+|===
+
+[[msg-protocol-unsupported]]
+=== Protocol Version Unsupported
+
+A Server issues a Protocol Version Unsupported message to a Client to inform it
+that the requested protocol revision is not supported. It also includes the
+most recent protocol revision which it supports, such that a Client may
+reconnect under a prior protocol revision if able.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x02 - Protocol Version Unsupported
+|1 byte, unsigned; Message Type
+
+|Server Supported Protocol Revision
+|2 bytes, Unsigned 16-bit integer (big-endian). See
+<<def-protocol-revision,Protocol Revision>>.
+|===
+
+[[msg-server-hello-complete]]
+=== Server Hello Complete
+
+A Server issues a Server Hello Complete message when it has finished informing
+a newly-connected client of all of the fields it currently recognizes.
+Following the receipt of this message, a Client should inform the Server of
+any/all additional fields that it recognizes that the Server did not announce.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x03 - Server Hello Complete
+|1 byte, unsigned; Message Type
+|===
+
+[[msg-server-hello]]
+=== Server Hello
+
+A Server issues a Server Hello message in response to a Client Hello message,
+immediately prior to informing a newly-connected client of all of the fields it
+currently recognizes.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x04 - Server Hello
+|1 byte, unsigned; Message Type
+
+|Flags
+a|1 byte, unsigned.
+
+Least Significant Bit (bit 0): reconnect flag
+
+* 0 if this is the first time (since server start) the server has seen the
+client
+
+* 1 if the server has previously seen (since server start) the client (as
+identified in the <<msg-client-hello,Client Hello>> message)
+
+Bits 1-7: Reserved, set to 0.
+
+|Server identity (name)
+|<<entry-value-string,String>>
+|===
+
+[[msg-client-hello-complete]]
+=== Client Hello Complete
+
+A Client issues a Client Hello Complete message when it has finished informing
+the Server of any/all of the additional fields it recognizes that the Server
+did not announce.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x05 - Client Hello Complete
+|1 byte, unsigned; Message Type
+|===
+
+[[msg-assign]]
+=== Entry Assignment
+
+A Entry Assignment message informs the remote party of a new Entry. An Entry
+Assignment's value field must be the most recent value of the field being
+assigned at the time that the Entry Assignment is sent.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x10 - Entry Assignment
+|1 byte, unsigned; Message Type
+
+|Entry Name
+|<<entry-value-string,String>>
+
+|Entry Type
+|1 byte, unsigned; see <<entry-types,Entry Types>>
+
+|Entry ID
+|2 bytes, unsigned
+
+|Entry Sequence Number
+|2 bytes, unsigned
+
+|Entry Flags
+|1 byte, unsigned; see <<entry-flags,Entry Flags>>
+
+|Entry Value
+|N bytes, length depends on Entry Type
+|===
+
+If the Entry ID is 0xFFFF, then this assignment represents a request from a
+Client to the Server. In this event, the Entry ID field and the Entry Sequence
+Number field must not be stored or relied upon as they otherwise would be.
+
+[[msg-update]]
+=== Entry Update
+
+An Entry Update message informs a remote party of a new value for an Entry.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x11 - Entry Update
+|1 byte, unsigned; Message Type
+
+|Entry ID
+|2 bytes, unsigned
+
+|Entry Sequence Number
+|2 bytes, unsigned
+
+|Entry Type
+|1 byte, unsigned; see <<entry-types,Entry Types>>.
+
+Note this type is only used to determine the length of the entry value, and
+does NOT change the stored entry type if it is different (due to an intervening
+Entry Assignment); Clients and Servers must ignore Entry Update messages with
+mismatching entry type.
+
+|Entry Value
+|N bytes, length dependent on value type
+|===
+
+[[msg-flags-update]]
+=== Entry Flags Update
+
+An Entry Flags Update message informs a remote party of new flags for an Entry.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x12 - Entry Flags Update
+|1 byte, unsigned; Message Type
+
+|Entry ID
+|2 bytes, unsigned
+
+|Entry Flags
+|1 byte, unsigned; see <<entry-flags,Entry Flags>>
+|===
+
+Entries may be globally deleted using the following messages. These messages
+must be rebroadcast by the server in the same fashion as the Entry Update
+message. Clients and servers must remove the requested entry/entries from
+their local tables. Update messages received after the Entry Delete message
+for the deleted Entry ID must be ignored by Clients and Servers until a new
+Assignment message for that Entry ID is issued.
+
+[[msg-delete]]
+=== Entry Delete
+
+Deletes a single entry or procedure.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x13 - Entry Delete
+|1 byte, unsigned; message type
+
+|Entry ID
+|2 bytes, unsigned
+|===
+
+[[msg-clear-all]]
+=== Clear All Entries
+
+Deletes all entries. The magic value is required to be exactly this value
+(this is to avoid accidental misinterpretation of the message).
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x14 - Clear All Entries
+|1 byte, unsigned; message type
+
+|Magic Value (0xD06CB27A)
+|4 bytes; exact value required (big endian)
+|===
+
+[[msg-rpc-execute]]
+=== Remote Procedure Call (RPC) Execute
+
+Executes a remote procedure. Intended for client to server use only.
+
+The client shall provide a value for every RPC parameter specified in the
+corresponding RPC entry definition.
+
+The server shall ignore any Execute RPC message whose decoding does not match
+the parameters defined in the corresponding RPC entry definition.
+
+Note that the parameter length is encoded the same way regardless of the RPC
+version and encapsulates the entirety of the parameters, so protocol layer
+decoders do not need to know the RPC details in order to process the message.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x20 - Execute RPC
+|1 byte, unsigned; message type
+
+|RPC Definition Entry ID
+|2 bytes, unsigned
+
+|Unique ID
+|2 bytes, unsigned; incremented value for matching return values to call.
+
+|Parameter Value Length
+|N bytes, unsigned <<leb128>> encoded length of:
+
+RPC definition version 0: total number of raw bytes in this message
+
+RPC definition version 1: total number of bytes of parameter values in this
+message
+|Parameter Value(s)
+|RPC definition version 0: N raw bytes.
+
+RPC definition version 1: Array of values; N bytes for each parameter (length
+dependent on the parameter type defined in the
+<<rpc-definition,RPC entry definition>>).
+|===
+
+[[msg-rpc-response]]
+=== RPC Response
+
+Return responses from a remote procedure call. Even calls with zero outputs
+will respond.
+
+Note that the result length is encoded the same way regardless of the RPC
+version and encapsulates the entirety of the result, so protocol layer decoders
+do not need to know the RPC details in order to process the message.
+
+[cols="1,3"]
+|===
+|Field Name |Field Type
+
+|0x21 - RPC Response
+|1 byte, unsigned; message type
+
+|RPC Definition Entry ID
+|2 bytes, unsigned
+
+|Unique ID
+|2 bytes, unsigned; matching ID from <<msg-rpc-execute,RPC Execute>> message
+
+|Result Value Length
+|N bytes, unsigned <<leb128>> encoded length of:
+
+RPC definition version 0: total number of raw bytes in this message
+
+RPC definition version 1: total number of bytes of result values in this
+message
+|Result Value(s)
+|RPC definition version 0: N raw bytes.
+
+RPC definition version 1: Array of values; N bytes for each result (length
+dependent on the result type defined in the
+<<rpc-definition,RPC entry definition>>).
+|===
+
+[[rpc-operation]]
+== Remote Procedure Call (RPC) Operation
+
+Remote procedure call entries shall only be assigned by the server.
+
+Remote procedure call execute messages will result in asynchronous execution of
+the corresponding function on the server.
+
+Client implementations shall not transmit an Execute RPC message and return an
+error to user code that attempts to call an undefined RPC, call one with
+incorrectly typed parameters, or attempts to make a call when the Client is not
+connected to a Server.
+
+Remote procedure calls cannot be persisted.
+
+[[rpc-definition]]
+=== Remote Procedure Call Definition Data
+
+There are currently two versions of RPC definitions: version 0 and version 1.
+The first byte in the RPC definition entry determines the version.
+
+[[rpc-definition-v0]]
+==== Version 0
+
+RPC version 0 is the most straightforward: the data provided in the RPC
+definition entry consists of just a single 0 byte (indicating RPC
+definition version 0).  RPC version 0 execute and response messages do
+not contain discrete parameter and result values respectively; instead the
+entire parameter value or result value is treated as a raw byte sequence; the
+interpretation of the raw bytes is application specific--users are encouraged
+to consider using encodings such as CBOR or MessagePack for more complex
+self-describing data structures.
+
+[cols="1,3"]
+|===
+|RPC Definition Version
+|1 byte, unsigned; set to 0, indicating version 0
+|===
+
+[[rpc-definition-v1]]
+==== Version 1
+
+The data provided in the RPC version 1 definition entry is more
+complex and consists of:
+
+[cols="1,3"]
+|===
+|RPC Definition Version
+|1 byte, unsigned; set to 1, indicating version 1
+
+|Procedure (Entry) Name
+|<<entry-value-string,String>>
+
+|Number of Parameters
+|1 byte, unsigned (may be 0)
+
+2+s|Parameter Specification (one set per input parameter)
+
+|Parameter Type
+|1 byte, unsigned; <<entry-types,Entry Type>> for parameter value
+
+|Parameter Name
+|<<entry-value-string,String>>
+
+|Parameter Default Value
+|N bytes; length based on parameter type (encoded consistent with corresponding
+<<entry-values,Entry Value>> definition)
+
+|Number of Output Results
+|1 byte, unsigned (may be 0)
+
+2+s|Result Specification (one set per output)
+
+|Result Type
+|1 byte, unsigned; <<entry-types,Entry Type>> for value
+
+|Result Name
+|<<entry-value-string,String>>
+|===
diff --git a/third_party/allwpilib_2019/ntcore/manualTests/java/Client.java b/third_party/allwpilib_2019/ntcore/manualTests/java/Client.java
new file mode 100644
index 0000000..1d5f181
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/manualTests/java/Client.java
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+import edu.wpi.first.wpilibj.networktables.*;
+import edu.wpi.first.wpilibj.tables.*;
+
+public class Client {
+  private static class MyLogger implements NetworkTablesJNI.LoggerFunction {
+    public void apply(int level, String file, int line, String msg) {
+      System.err.println(msg);
+    }
+  }
+
+  public static void main(String[] args) {
+    NetworkTablesJNI.setLogger(new MyLogger(), 0);
+    NetworkTable.setIPAddress("127.0.0.1");
+    NetworkTable.setPort(10000);
+    NetworkTable.setClientMode();
+    NetworkTable nt = NetworkTable.getTable("");
+    try { Thread.sleep(2000); } catch (InterruptedException e) {}
+    try {
+      System.out.println("Got foo: " + nt.getNumber("foo"));
+    } catch(TableKeyNotDefinedException ex) {
+    }
+    nt.putBoolean("bar", false);
+    nt.setFlags("bar", NetworkTable.PERSISTENT);
+    nt.putBoolean("bar2", true);
+    nt.putBoolean("bar2", false);
+    nt.putBoolean("bar2", true);
+    nt.putString("str", "hello world");
+    double[] nums = new double[3];
+    nums[0] = 0.5;
+    nums[1] = 1.2;
+    nums[2] = 3.0;
+    nt.putNumberArray("numarray", nums);
+    String[] strs = new String[2];
+    strs[0] = "Hello";
+    strs[1] = "World";
+    nt.putStringArray("strarray", strs);
+    try { Thread.sleep(10000); } catch (InterruptedException e) {}
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/manualTests/java/Server.java b/third_party/allwpilib_2019/ntcore/manualTests/java/Server.java
new file mode 100644
index 0000000..7f4dbc6
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/manualTests/java/Server.java
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+import edu.wpi.first.wpilibj.networktables.*;
+import edu.wpi.first.wpilibj.tables.*;
+
+public class Server {
+  private static class MyLogger implements NetworkTablesJNI.LoggerFunction {
+    public void apply(int level, String file, int line, String msg) {
+      System.err.println(msg);
+    }
+  }
+
+  public static void main(String[] args) {
+    NetworkTablesJNI.setLogger(new MyLogger(), 0);
+    NetworkTable.setIPAddress("127.0.0.1");
+    NetworkTable.setPort(10000);
+    NetworkTable.setServerMode();
+    NetworkTable nt = NetworkTable.getTable("");
+    try { Thread.sleep(1000); } catch (InterruptedException e) {}
+    nt.putNumber("foo", 0.5);
+    nt.setFlags("foo", NetworkTable.PERSISTENT);
+    nt.putNumber("foo2", 0.5);
+    nt.putNumber("foo2", 0.7);
+    nt.putNumber("foo2", 0.6);
+    nt.putNumber("foo2", 0.5);
+    try { Thread.sleep(10000); } catch (InterruptedException e) {}
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/manualTests/native/client.cpp b/third_party/allwpilib_2019/ntcore/manualTests/native/client.cpp
new file mode 100644
index 0000000..3bcb7c0
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/manualTests/native/client.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <chrono>
+#include <climits>
+#include <cstdio>
+#include <thread>
+
+#include "ntcore.h"
+
+int main() {
+  auto inst = nt::GetDefaultInstance();
+  nt::AddLogger(inst,
+                [](const nt::LogMessage& msg) {
+                  std::fputs(msg.message.c_str(), stderr);
+                  std::fputc('\n', stderr);
+                },
+                0, UINT_MAX);
+  nt::StartClient(inst, "127.0.0.1", 10000);
+  std::this_thread::sleep_for(std::chrono::seconds(2));
+
+  auto foo = nt::GetEntry(inst, "/foo");
+  auto foo_val = nt::GetEntryValue(foo);
+  if (foo_val && foo_val->IsDouble())
+    std::printf("Got foo: %g\n", foo_val->GetDouble());
+
+  auto bar = nt::GetEntry(inst, "/bar");
+  nt::SetEntryValue(bar, nt::Value::MakeBoolean(false));
+  nt::SetEntryFlags(bar, NT_PERSISTENT);
+
+  auto bar2 = nt::GetEntry(inst, "/bar2");
+  nt::SetEntryValue(bar2, nt::Value::MakeBoolean(true));
+  nt::SetEntryValue(bar2, nt::Value::MakeBoolean(false));
+  nt::SetEntryValue(bar2, nt::Value::MakeBoolean(true));
+  std::this_thread::sleep_for(std::chrono::seconds(10));
+}
diff --git a/third_party/allwpilib_2019/ntcore/manualTests/native/rpc_local.cpp b/third_party/allwpilib_2019/ntcore/manualTests/native/rpc_local.cpp
new file mode 100644
index 0000000..b8352d6
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/manualTests/native/rpc_local.cpp
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <chrono>
+#include <climits>
+#include <cstdio>
+#include <thread>
+
+#include <support/json.h>
+
+#include "ntcore.h"
+
+void callback1(const nt::RpcAnswer& answer) {
+  wpi::json params;
+  try {
+    params = wpi::json::from_cbor(answer.params);
+  } catch (wpi::json::parse_error err) {
+    std::fputs("could not decode params?\n", stderr);
+    return;
+  }
+  if (!params.is_number()) {
+    std::fputs("did not get number\n", stderr);
+    return;
+  }
+  double val = params.get<double>();
+  std::fprintf(stderr, "called with %g\n", val);
+
+  answer.PostResponse(wpi::json::to_cbor(val + 1.2));
+}
+
+int main() {
+  auto inst = nt::GetDefaultInstance();
+  nt::AddLogger(inst,
+                [](const nt::LogMessage& msg) {
+                  std::fputs(msg.message.c_str(), stderr);
+                  std::fputc('\n', stderr);
+                },
+                0, UINT_MAX);
+
+  nt::StartServer(inst, "rpc_local.ini", "", 10000);
+  auto entry = nt::GetEntry(inst, "func1");
+  nt::CreateRpc(entry, nt::StringRef("", 1), callback1);
+  std::fputs("calling rpc\n", stderr);
+  unsigned int call1_uid = nt::CallRpc(entry, wpi::json::to_cbor(2.0));
+  std::string call1_result_str;
+  std::fputs("waiting for rpc result\n", stderr);
+  nt::GetRpcResult(entry, call1_uid, &call1_result_str);
+  wpi::json call1_result;
+  try {
+    call1_result = wpi::json::from_cbor(call1_result_str);
+  } catch (wpi::json::parse_error err) {
+    std::fputs("could not decode result?\n", stderr);
+    return 1;
+  }
+  if (!call1_result.is_number()) {
+    std::fputs("result is not number?\n", stderr);
+    return 1;
+  }
+  std::fprintf(stderr, "got %g\n", call1_result.get<double>());
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/ntcore/manualTests/native/rpc_speed.cpp b/third_party/allwpilib_2019/ntcore/manualTests/native/rpc_speed.cpp
new file mode 100644
index 0000000..70558ef
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/manualTests/native/rpc_speed.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <chrono>
+#include <climits>
+#include <cstdio>
+#include <iostream>
+#include <thread>
+
+#include <support/json.h>
+
+#include "ntcore.h"
+
+void callback1(const nt::RpcAnswer& answer) {
+  wpi::json params;
+  try {
+    params = wpi::json::from_cbor(answer.params);
+  } catch (wpi::json::parse_error err) {
+    std::fputs("could not decode params?\n", stderr);
+    return;
+  }
+  if (!params.is_number()) {
+    std::fputs("did not get number\n", stderr);
+    return;
+  }
+  double val = params.get<double>();
+  answer.PostResponse(wpi::json::to_cbor(val + 1.2));
+}
+
+int main() {
+  auto inst = nt::GetDefaultInstance();
+  nt::StartServer(inst, "rpc_speed.ini", "", 10000);
+  auto entry = nt::GetEntry(inst, "func1");
+  nt::CreateRpc(entry, nt::StringRef("", 1), callback1);
+  std::string call1_result_str;
+
+  auto start2 = std::chrono::high_resolution_clock::now();
+  auto start = nt::Now();
+  for (int i = 0; i < 10000; ++i) {
+    unsigned int call1_uid = nt::CallRpc(entry, wpi::json::to_cbor(i));
+    nt::GetRpcResult(entry, call1_uid, &call1_result_str);
+    wpi::json call1_result;
+    try {
+      call1_result = wpi::json::from_cbor(call1_result_str);
+    } catch (wpi::json::parse_error err) {
+      std::fputs("could not decode result?\n", stderr);
+      return 1;
+    }
+    if (!call1_result.is_number()) {
+      std::fputs("result is not number?\n", stderr);
+      return 1;
+    }
+  }
+  auto end2 = std::chrono::high_resolution_clock::now();
+  auto end = nt::Now();
+  std::cerr << "nt::Now start=" << start << " end=" << end << '\n';
+  std::cerr << "std::chrono start="
+            << std::chrono::duration_cast<std::chrono::nanoseconds>(
+                   start2.time_since_epoch())
+                   .count()
+            << " end="
+            << std::chrono::duration_cast<std::chrono::nanoseconds>(
+                   end2.time_since_epoch())
+                   .count()
+            << '\n';
+  std::fprintf(stderr, "time/call = %g us\n", (end - start) / 10.0 / 10000.0);
+  std::chrono::duration<double, std::micro> diff = end2 - start2;
+  std::cerr << "time/call = " << (diff.count() / 10000.0) << " us\n";
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/ntcore/manualTests/native/server.cpp b/third_party/allwpilib_2019/ntcore/manualTests/native/server.cpp
new file mode 100644
index 0000000..9513bf8
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/manualTests/native/server.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <chrono>
+#include <climits>
+#include <cstdio>
+#include <thread>
+
+#include "ntcore.h"
+
+int main() {
+  auto inst = nt::GetDefaultInstance();
+  nt::AddLogger(inst,
+                [](const nt::LogMessage& msg) {
+                  std::fputs(msg.message.c_str(), stderr);
+                  std::fputc('\n', stderr);
+                },
+                0, UINT_MAX);
+  nt::StartServer(inst, "persistent.ini", "", 10000);
+  std::this_thread::sleep_for(std::chrono::seconds(1));
+
+  auto foo = nt::GetEntry(inst, "/foo");
+  nt::SetEntryValue(foo, nt::Value::MakeDouble(0.5));
+  nt::SetEntryFlags(foo, NT_PERSISTENT);
+
+  auto foo2 = nt::GetEntry(inst, "/foo2");
+  nt::SetEntryValue(foo2, nt::Value::MakeDouble(0.5));
+  nt::SetEntryValue(foo2, nt::Value::MakeDouble(0.7));
+  nt::SetEntryValue(foo2, nt::Value::MakeDouble(0.6));
+  nt::SetEntryValue(foo2, nt::Value::MakeDouble(0.5));
+
+  std::this_thread::sleep_for(std::chrono::seconds(10));
+}
diff --git a/third_party/allwpilib_2019/ntcore/ntcore-config.cmake b/third_party/allwpilib_2019/ntcore/ntcore-config.cmake
new file mode 100644
index 0000000..6be1dda
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/ntcore-config.cmake
@@ -0,0 +1,5 @@
+include(CMakeFindDependencyMacro)

+find_dependency(wpiutil)

+

+get_filename_component(SELF_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)

+include(${SELF_DIR}/ntcore.cmake)

diff --git a/third_party/allwpilib_2019/ntcore/src/dev/java/edu/wpi/first/ntcore/DevMain.java b/third_party/allwpilib_2019/ntcore/src/dev/java/edu/wpi/first/ntcore/DevMain.java
new file mode 100644
index 0000000..547af0a
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/dev/java/edu/wpi/first/ntcore/DevMain.java
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.ntcore;
+
+import edu.wpi.first.networktables.NetworkTablesJNI;
+import edu.wpi.first.wpiutil.RuntimeDetector;
+
+public final class DevMain {
+  /**
+   * Main method.
+   */
+  public static void main(String[] args) {
+    System.out.println("Hello World!");
+    System.out.println(RuntimeDetector.getPlatformPath());
+    NetworkTablesJNI.flush(NetworkTablesJNI.getDefaultInstance());
+  }
+
+  private DevMain() {
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/ntcore/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..1153347
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/dev/native/cpp/main.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include "ntcore.h"
+
+int main() {
+  auto myValue = nt::GetEntry(nt::GetDefaultInstance(), "MyValue");
+
+  nt::SetEntryValue(myValue, nt::Value::MakeString("Hello World"));
+
+  std::cout << nt::GetEntryValue(myValue)->GetString() << std::endl;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java
new file mode 100644
index 0000000..b060f2f
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionInfo.java
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables Connection information.
+ */
+public final class ConnectionInfo {
+  /**
+   * The remote identifier (as set on the remote node by
+   * {@link NetworkTableInstance#setNetworkIdentity(String)}).
+   */
+  @SuppressWarnings("MemberName")
+  public final String remote_id;
+
+  /**
+   * The IP address of the remote node.
+   */
+  @SuppressWarnings("MemberName")
+  public final String remote_ip;
+
+  /**
+   * The port number of the remote node.
+   */
+  @SuppressWarnings("MemberName")
+  public final int remote_port;
+
+  /**
+   * The last time any update was received from the remote node (same scale as
+   * returned by {@link NetworkTablesJNI#now()}).
+   */
+  @SuppressWarnings("MemberName")
+  public final long last_update;
+
+  /**
+   * The protocol version being used for this connection.  This is in protocol
+   * layer format, so 0x0200 = 2.0, 0x0300 = 3.0).
+   */
+  @SuppressWarnings("MemberName")
+  public final int protocol_version;
+
+  /** Constructor.
+   * This should generally only be used internally to NetworkTables.
+   *
+   * @param remoteId Remote identifier
+   * @param remoteIp Remote IP address
+   * @param remotePort Remote port number
+   * @param lastUpdate Last time an update was received
+   * @param protocolVersion The protocol version used for the connection
+   */
+  public ConnectionInfo(String remoteId, String remoteIp, int remotePort, long lastUpdate,
+                        int protocolVersion) {
+    remote_id = remoteId;
+    remote_ip = remoteIp;
+    remote_port = remotePort;
+    last_update = lastUpdate;
+    protocol_version = protocolVersion;
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java
new file mode 100644
index 0000000..129bf1a
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/ConnectionNotification.java
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables Connection notification.
+ */
+public final class ConnectionNotification {
+  /**
+   *  Listener that was triggered.
+   */
+  @SuppressWarnings("MemberName")
+  public final int listener;
+
+  /**
+   * True if event is due to connection being established.
+   */
+  @SuppressWarnings("MemberName")
+  public final boolean connected;
+
+  /**
+   * Connection information.
+   */
+  @SuppressWarnings("MemberName")
+  public final ConnectionInfo conn;
+
+  /** Constructor.
+   * This should generally only be used internally to NetworkTables.
+   *
+   * @param inst Instance
+   * @param listener Listener that was triggered
+   * @param connected Connected if true
+   * @param conn Connection information
+   */
+  public ConnectionNotification(NetworkTableInstance inst, int listener, boolean connected,
+                                ConnectionInfo conn) {
+    this.m_inst = inst;
+    this.listener = listener;
+    this.connected = connected;
+    this.conn = conn;
+  }
+
+  private final NetworkTableInstance m_inst;
+
+  public NetworkTableInstance getInstance() {
+    return m_inst;
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java
new file mode 100644
index 0000000..b516cc7
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryInfo.java
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables Entry information.
+ */
+public final class EntryInfo {
+  /** Entry handle. */
+  @SuppressWarnings("MemberName")
+  public final int entry;
+
+  /** Entry name. */
+  @SuppressWarnings("MemberName")
+  public final String name;
+
+  /** Entry type. */
+  @SuppressWarnings("MemberName")
+  public final NetworkTableType type;
+
+  /** Entry flags. */
+  @SuppressWarnings("MemberName")
+  public final int flags;
+
+  /** Timestamp of last change to entry (type or value). */
+  @SuppressWarnings("MemberName")
+  public final long last_change;
+
+  /** Constructor.
+   * This should generally only be used internally to NetworkTables.
+   *
+   * @param inst Instance
+   * @param entry Entry handle
+   * @param name Name
+   * @param type Type (integer version of {@link NetworkTableType})
+   * @param flags Flags
+   * @param lastChange Timestamp of last change
+   */
+  public EntryInfo(NetworkTableInstance inst, int entry, String name, int type, int flags,
+                   long lastChange) {
+    this.m_inst = inst;
+    this.entry = entry;
+    this.name = name;
+    this.type = NetworkTableType.getFromInt(type);
+    this.flags = flags;
+    this.last_change = lastChange;
+  }
+
+  /* Network table instance. */
+  private final NetworkTableInstance m_inst;
+
+  /* Cached entry object. */
+  private NetworkTableEntry m_entryObject;
+
+  /**
+   * Get the entry as an object.
+   *
+   * @return NetworkTableEntry for this entry.
+   */
+  NetworkTableEntry getEntry() {
+    if (m_entryObject == null) {
+      m_entryObject = new NetworkTableEntry(m_inst, entry);
+    }
+    return m_entryObject;
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryListenerFlags.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryListenerFlags.java
new file mode 100644
index 0000000..9cdc0f0
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryListenerFlags.java
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * Flag values for use with entry listeners.
+ *
+ * <p>The flags are a bitmask and must be OR'ed together to indicate the
+ * combination of events desired to be received.
+ *
+ * <p>The constants kNew, kDelete, kUpdate, and kFlags represent different events
+ * that can occur to entries.
+ *
+ * <p>By default, notifications are only generated for remote changes occurring
+ * after the listener is created.  The constants kImmediate and kLocal are
+ * modifiers that cause notifications to be generated at other times.
+ */
+public interface EntryListenerFlags {
+  /**
+   * Initial listener addition.
+   *
+   * <p>Set this flag to receive immediate notification of entries matching the
+   * flag criteria (generally only useful when combined with kNew).
+   */
+  int kImmediate = 0x01;
+
+  /**
+   * Changed locally.
+   *
+   * <p>Set this flag to receive notification of both local changes and changes
+   * coming from remote nodes.  By default, notifications are only generated
+   * for remote changes.  Must be combined with some combination of kNew,
+   * kDelete, kUpdate, and kFlags to receive notifications of those respective
+   * events.
+   */
+  int kLocal = 0x02;
+
+  /**
+   * Newly created entry.
+   *
+   * <p>Set this flag to receive a notification when an entry is created.
+   */
+  int kNew = 0x04;
+
+  /**
+   * Entry was deleted.
+   *
+   * <p>Set this flag to receive a notification when an entry is deleted.
+   */
+  int kDelete = 0x08;
+
+  /**
+   * Entry's value changed.
+   *
+   * <p>Set this flag to receive a notification when an entry's value (or type)
+   * changes.
+   */
+  int kUpdate = 0x10;
+
+  /**
+   * Entry's flags changed.
+   *
+   * <p>Set this flag to receive a notification when an entry's flags value
+   * changes.
+   */
+  int kFlags = 0x20;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java
new file mode 100644
index 0000000..159b968
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/EntryNotification.java
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables Entry notification.
+ */
+public final class EntryNotification {
+  /**
+   * Listener that was triggered.
+   */
+  @SuppressWarnings("MemberName")
+  public final int listener;
+
+  /**
+   * Entry handle.
+   */
+  @SuppressWarnings("MemberName")
+  public final int entry;
+
+  /**
+   * Entry name.
+   */
+  @SuppressWarnings("MemberName")
+  public final String name;
+
+  /**
+   * The new value.
+   */
+  @SuppressWarnings("MemberName")
+  public final NetworkTableValue value;
+
+  /**
+   * Update flags.  For example, {@link EntryListenerFlags#kNew} if the key did
+   * not previously exist.
+   */
+  @SuppressWarnings("MemberName")
+  public final int flags;
+
+  /** Constructor.
+   * This should generally only be used internally to NetworkTables.
+   *
+   * @param inst Instance
+   * @param listener Listener that was triggered
+   * @param entry Entry handle
+   * @param name Entry name
+   * @param value The new value
+   * @param flags Update flags
+   */
+  public EntryNotification(NetworkTableInstance inst, int listener, int entry, String name,
+                           NetworkTableValue value, int flags) {
+    this.m_inst = inst;
+    this.listener = listener;
+    this.entry = entry;
+    this.name = name;
+    this.value = value;
+    this.flags = flags;
+  }
+
+  /* Network table instance. */
+  private final NetworkTableInstance m_inst;
+
+  /* Cached entry object. */
+  NetworkTableEntry m_entryObject;
+
+  /**
+   * Get the entry as an object.
+   *
+   * @return NetworkTableEntry for this entry.
+   */
+  public NetworkTableEntry getEntry() {
+    if (m_entryObject == null) {
+      m_entryObject = new NetworkTableEntry(m_inst, entry);
+    }
+    return m_entryObject;
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java
new file mode 100644
index 0000000..2cf22ec
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/LogMessage.java
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables log message.
+ */
+public final class LogMessage {
+  /**
+   * Logging levels.
+   */
+  public static final int kCritical = 50;
+  public static final int kError = 40;
+  public static final int kWarning = 30;
+  public static final int kInfo = 20;
+  public static final int kDebug = 10;
+  public static final int kDebug1 = 9;
+  public static final int kDebug2 = 8;
+  public static final int kDebug3 = 7;
+  public static final int kDebug4 = 6;
+
+  /**
+   * The logger that generated the message.
+   */
+  @SuppressWarnings("MemberName")
+  public final int logger;
+
+  /**
+   * Log level of the message.
+   */
+  @SuppressWarnings("MemberName")
+  public final int level;
+
+  /**
+   * The filename of the source file that generated the message.
+   */
+  @SuppressWarnings("MemberName")
+  public final String filename;
+
+  /**
+   * The line number in the source file that generated the message.
+   */
+  @SuppressWarnings("MemberName")
+  public final int line;
+
+  /**
+   * The message.
+   */
+  @SuppressWarnings("MemberName")
+  public final String message;
+
+  /** Constructor.
+   * This should generally only be used internally to NetworkTables.
+   *
+   * @param inst Instance
+   * @param logger Logger
+   * @param level Log level
+   * @param filename Filename
+   * @param line Line number
+   * @param message Message
+   */
+  public LogMessage(NetworkTableInstance inst, int logger, int level, String filename, int line,
+                    String message) {
+    this.m_inst = inst;
+    this.logger = logger;
+    this.level = level;
+    this.filename = filename;
+    this.line = line;
+    this.message = message;
+  }
+
+  private final NetworkTableInstance m_inst;
+
+  NetworkTableInstance getInstance() {
+    return m_inst;
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTable.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTable.java
new file mode 100644
index 0000000..1cd21bf
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTable.java
@@ -0,0 +1,423 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.util.ArrayList;
+import java.util.HashSet;
+import java.util.List;
+import java.util.Objects;
+import java.util.Set;
+import java.util.concurrent.ConcurrentHashMap;
+import java.util.concurrent.ConcurrentMap;
+import java.util.function.Consumer;
+
+/**
+ * A network table that knows its subtable path.
+ */
+public final class NetworkTable {
+  /**
+   * The path separator for sub-tables and keys.
+   */
+  public static final char PATH_SEPARATOR = '/';
+
+  private final String m_path;
+  private final String m_pathWithSep;
+  private final NetworkTableInstance m_inst;
+
+  /**
+   * Gets the "base name" of a key. For example, "/foo/bar" becomes "bar".
+   * If the key has a trailing slash, returns an empty string.
+   *
+   * @param key key
+   * @return base name
+   */
+  public static String basenameKey(String key) {
+    final int slash = key.lastIndexOf(PATH_SEPARATOR);
+    if (slash == -1) {
+      return key;
+    }
+    return key.substring(slash + 1);
+  }
+
+  /**
+   * Normalizes an network table key to contain no consecutive slashes and
+   * optionally start with a leading slash. For example:
+   *
+   * <pre><code>
+   * normalizeKey("/foo/bar", true)  == "/foo/bar"
+   * normalizeKey("foo/bar", true)   == "/foo/bar"
+   * normalizeKey("/foo/bar", false) == "foo/bar"
+   * normalizeKey("foo//bar", false) == "foo/bar"
+   * </code></pre>
+   *
+   * @param key              the key to normalize
+   * @param withLeadingSlash whether or not the normalized key should begin
+   *                         with a leading slash
+   * @return normalized key
+   */
+  public static String normalizeKey(String key, boolean withLeadingSlash) {
+    String normalized;
+    if (withLeadingSlash) {
+      normalized = PATH_SEPARATOR + key;
+    } else {
+      normalized = key;
+    }
+    normalized = normalized.replaceAll(PATH_SEPARATOR + "{2,}", String.valueOf(PATH_SEPARATOR));
+
+    if (!withLeadingSlash && normalized.charAt(0) == PATH_SEPARATOR) {
+      // remove leading slash, if present
+      normalized = normalized.substring(1);
+    }
+    return normalized;
+  }
+
+  /**
+   * Normalizes a network table key to start with exactly one leading slash
+   * ("/") and contain no consecutive slashes. For example,
+   * {@code "//foo/bar/"} becomes {@code "/foo/bar/"} and
+   * {@code "///a/b/c"} becomes {@code "/a/b/c"}.
+   *
+   * <p>This is equivalent to {@code normalizeKey(key, true)}
+   *
+   * @param key the key to normalize
+   * @return normalized key
+   */
+  public static String normalizeKey(String key) {
+    return normalizeKey(key, true);
+  }
+
+  /**
+   * Gets a list of the names of all the super tables of a given key. For
+   * example, the key "/foo/bar/baz" has a hierarchy of "/", "/foo",
+   * "/foo/bar", and "/foo/bar/baz".
+   *
+   * @param key the key
+   * @return List of super tables
+   */
+  public static List<String> getHierarchy(String key) {
+    final String normal = normalizeKey(key, true);
+    List<String> hierarchy = new ArrayList<>();
+    if (normal.length() == 1) {
+      hierarchy.add(normal);
+      return hierarchy;
+    }
+    for (int i = 1; ; i = normal.indexOf(PATH_SEPARATOR, i + 1)) {
+      if (i == -1) {
+        // add the full key
+        hierarchy.add(normal);
+        break;
+      } else {
+        hierarchy.add(normal.substring(0, i));
+      }
+    }
+    return hierarchy;
+  }
+
+  /**
+   * Constructor.  Use NetworkTableInstance.getTable() or getSubTable() instead.
+   */
+  NetworkTable(NetworkTableInstance inst, String path) {
+    m_path = path;
+    m_pathWithSep = path + PATH_SEPARATOR;
+    m_inst = inst;
+  }
+
+  /**
+   * Gets the instance for the table.
+   *
+   * @return Instance
+   */
+  public NetworkTableInstance getInstance() {
+    return m_inst;
+  }
+
+  @Override
+  public String toString() {
+    return "NetworkTable: " + m_path;
+  }
+
+  private final ConcurrentMap<String, NetworkTableEntry> m_entries = new ConcurrentHashMap<>();
+
+  /**
+   * Gets the entry for a sub key.
+   *
+   * @param key the key name
+   * @return Network table entry.
+   */
+  public NetworkTableEntry getEntry(String key) {
+    NetworkTableEntry entry = m_entries.get(key);
+    if (entry == null) {
+      entry = m_inst.getEntry(m_pathWithSep + key);
+      m_entries.putIfAbsent(key, entry);
+    }
+    return entry;
+  }
+
+  /**
+   * Listen to keys only within this table.
+   *
+   * @param listener    listener to add
+   * @param flags       {@link EntryListenerFlags} bitmask
+   * @return Listener handle
+   */
+  public int addEntryListener(TableEntryListener listener, int flags) {
+    final int prefixLen = m_path.length() + 1;
+    return m_inst.addEntryListener(m_pathWithSep, event -> {
+      String relativeKey = event.name.substring(prefixLen);
+      if (relativeKey.indexOf(PATH_SEPARATOR) != -1) {
+        // part of a sub table
+        return;
+      }
+      listener.valueChanged(this, relativeKey, event.getEntry(), event.value, event.flags);
+    }, flags);
+  }
+
+  /**
+   * Listen to a single key.
+   *
+   * @param key         the key name
+   * @param listener    listener to add
+   * @param flags       {@link EntryListenerFlags} bitmask
+   * @return Listener handle
+   */
+  public int addEntryListener(String key, TableEntryListener listener, int flags) {
+    final NetworkTableEntry entry = getEntry(key);
+    return m_inst.addEntryListener(entry,
+        event -> listener.valueChanged(this, key, entry, event.value, event.flags), flags);
+  }
+
+  /**
+   * Remove an entry listener.
+   *
+   * @param listener    listener handle
+   */
+  public void removeEntryListener(int listener) {
+    m_inst.removeEntryListener(listener);
+  }
+
+  /**
+   * Listen for sub-table creation.
+   * This calls the listener once for each newly created sub-table.
+   * It immediately calls the listener for any existing sub-tables.
+   *
+   * @param listener        listener to add
+   * @param localNotify     notify local changes as well as remote
+   * @return Listener handle
+   */
+  public int addSubTableListener(TableListener listener, boolean localNotify) {
+    int flags = EntryListenerFlags.kNew | EntryListenerFlags.kImmediate;
+    if (localNotify) {
+      flags |= EntryListenerFlags.kLocal;
+    }
+
+    final int prefixLen = m_path.length() + 1;
+    final NetworkTable parent = this;
+
+    return m_inst.addEntryListener(m_pathWithSep, new Consumer<EntryNotification>() {
+      final Set<String> m_notifiedTables = new HashSet<>();
+
+      @Override
+      public void accept(EntryNotification event) {
+        String relativeKey = event.name.substring(prefixLen);
+        int endSubTable = relativeKey.indexOf(PATH_SEPARATOR);
+        if (endSubTable == -1) {
+          return;
+        }
+        String subTableKey = relativeKey.substring(0, endSubTable);
+        if (m_notifiedTables.contains(subTableKey)) {
+          return;
+        }
+        m_notifiedTables.add(subTableKey);
+        listener.tableCreated(parent, subTableKey, parent.getSubTable(subTableKey));
+      }
+    }, flags);
+  }
+
+  /**
+   * Remove a sub-table listener.
+   *
+   * @param listener    listener handle
+   */
+  public void removeTableListener(int listener) {
+    m_inst.removeEntryListener(listener);
+  }
+
+  /**
+   * Returns the table at the specified key. If there is no table at the
+   * specified key, it will create a new table
+   *
+   * @param key the name of the table relative to this one
+   * @return a sub table relative to this one
+   */
+  public NetworkTable getSubTable(String key) {
+    return new NetworkTable(m_inst, m_pathWithSep + key);
+  }
+
+  /**
+   * Checks the table and tells if it contains the specified key.
+   *
+   * @param key the key to search for
+   * @return true if the table as a value assigned to the given key
+   */
+  public boolean containsKey(String key) {
+    return !("".equals(key)) && getEntry(key).exists();
+  }
+
+  /**
+   * Checks the table and tells if it contains the specified sub table.
+   *
+   * @param key the key to search for
+   * @return true if there is a subtable with the key which contains at least one key/subtable of
+   *     its own
+   */
+  public boolean containsSubTable(String key) {
+    int[] handles = NetworkTablesJNI.getEntries(m_inst.getHandle(),
+        m_pathWithSep + key + PATH_SEPARATOR, 0);
+    return handles.length != 0;
+  }
+
+  /**
+   * Gets all keys in the table (not including sub-tables).
+   *
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return keys currently in the table
+   */
+  public Set<String> getKeys(int types) {
+    Set<String> keys = new HashSet<>();
+    int prefixLen = m_path.length() + 1;
+    for (EntryInfo info : m_inst.getEntryInfo(m_pathWithSep, types)) {
+      String relativeKey = info.name.substring(prefixLen);
+      if (relativeKey.indexOf(PATH_SEPARATOR) != -1) {
+        continue;
+      }
+      keys.add(relativeKey);
+      // populate entries as we go
+      if (m_entries.get(relativeKey) == null) {
+        m_entries.putIfAbsent(relativeKey, new NetworkTableEntry(m_inst, info.entry));
+      }
+    }
+    return keys;
+  }
+
+  /**
+   * Gets all keys in the table (not including sub-tables).
+   *
+   * @return keys currently in the table
+   */
+  public Set<String> getKeys() {
+    return getKeys(0);
+  }
+
+  /**
+   * Gets the names of all subtables in the table.
+   *
+   * @return subtables currently in the table
+   */
+  public Set<String> getSubTables() {
+    Set<String> keys = new HashSet<>();
+    int prefixLen = m_path.length() + 1;
+    for (EntryInfo info : m_inst.getEntryInfo(m_pathWithSep, 0)) {
+      String relativeKey = info.name.substring(prefixLen);
+      int endSubTable = relativeKey.indexOf(PATH_SEPARATOR);
+      if (endSubTable == -1) {
+        continue;
+      }
+      keys.add(relativeKey.substring(0, endSubTable));
+    }
+    return keys;
+  }
+
+  /**
+   * Deletes the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   */
+  public void delete(String key) {
+    getEntry(key).delete();
+  }
+
+  /**
+   * Put a value in the table.
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  boolean putValue(String key, NetworkTableValue value) {
+    return getEntry(key).setValue(value);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  boolean setDefaultValue(String key, NetworkTableValue defaultValue) {
+    return getEntry(key).setDefaultValue(defaultValue);
+  }
+
+  /**
+   * Gets the value associated with a key as an object.
+   *
+   * @param key the key of the value to look up
+   * @return the value associated with the given key, or nullptr if the key does not exist
+   */
+  NetworkTableValue getValue(String key) {
+    return getEntry(key).getValue();
+  }
+
+  /**
+   * Get the path of the NetworkTable.
+   */
+  public String getPath() {
+    return m_path;
+  }
+
+  /**
+   * Save table values to a file.  The file format used is identical to
+   * that used for SavePersistent.
+   *
+   * @param filename  filename
+   * @throws PersistentException if error saving file
+   */
+  public void saveEntries(String filename) throws PersistentException {
+    m_inst.saveEntries(filename, m_pathWithSep);
+  }
+
+  /**
+   * Load table values from a file.  The file format used is identical to
+   * that used for SavePersistent / LoadPersistent.
+   *
+   * @param filename  filename
+   * @return List of warnings (errors result in an exception instead)
+   * @throws PersistentException if error saving file
+   */
+  public String[] loadEntries(String filename) throws PersistentException {
+    return m_inst.loadEntries(filename, m_pathWithSep);
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (other == this) {
+      return true;
+    }
+    if (!(other instanceof NetworkTable)) {
+      return false;
+    }
+    NetworkTable ntOther = (NetworkTable) other;
+    return m_inst.equals(ntOther.m_inst) && m_path.equals(ntOther.m_path);
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_inst, m_path);
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEntry.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEntry.java
new file mode 100644
index 0000000..63ed984
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableEntry.java
@@ -0,0 +1,875 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.nio.ByteBuffer;
+import java.util.function.Consumer;
+
+/**
+ * NetworkTables Entry.
+ */
+public final class NetworkTableEntry {
+  /**
+   * Flag values (as returned by {@link #getFlags()}).
+   */
+  public static final int kPersistent = 0x01;
+
+  /**
+   * Construct from native handle.
+   *
+   * @param inst Instance
+   * @param handle Native handle
+   */
+  public NetworkTableEntry(NetworkTableInstance inst, int handle) {
+    m_inst = inst;
+    m_handle = handle;
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  /**
+   * Gets the native handle for the entry.
+   *
+   * @return Native handle
+   */
+  public int getHandle() {
+    return m_handle;
+  }
+
+  /**
+   * Gets the instance for the entry.
+   *
+   * @return Instance
+   */
+  public NetworkTableInstance getInstance() {
+    return m_inst;
+  }
+
+  /**
+   * Determines if the entry currently exists.
+   *
+   * @return True if the entry exists, false otherwise.
+   */
+  public boolean exists() {
+    return NetworkTablesJNI.getType(m_handle) != 0;
+  }
+
+  /**
+   * Gets the name of the entry (the key).
+   *
+   * @return the entry's name
+   */
+  public String getName() {
+    return NetworkTablesJNI.getEntryName(m_handle);
+  }
+
+  /**
+   * Gets the type of the entry.
+   *
+   * @return the entry's type
+   */
+  public NetworkTableType getType() {
+    return NetworkTableType.getFromInt(NetworkTablesJNI.getType(m_handle));
+  }
+
+  /**
+   * Returns the flags.
+   *
+   * @return the flags (bitmask)
+   */
+  public int getFlags() {
+    return NetworkTablesJNI.getEntryFlags(m_handle);
+  }
+
+  /**
+   * Gets the last time the entry's value was changed.
+   *
+   * @return Entry last change time
+   */
+  public long getLastChange() {
+    return NetworkTablesJNI.getEntryLastChange(m_handle);
+  }
+
+  /**
+   * Gets combined information about the entry.
+   *
+   * @return Entry information
+   */
+  public EntryInfo getInfo() {
+    return NetworkTablesJNI.getEntryInfoHandle(m_inst, m_handle);
+  }
+
+  /**
+   * Gets the entry's value.
+   * Returns a value with type NetworkTableType.kUnassigned if the value
+   * does not exist.
+   *
+   * @return the entry's value
+   */
+  public NetworkTableValue getValue() {
+    return NetworkTablesJNI.getValue(m_handle);
+  }
+
+  /**
+   * Gets the entry's value as a boolean. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public boolean getBoolean(boolean defaultValue) {
+    return NetworkTablesJNI.getBoolean(m_handle, defaultValue);
+  }
+
+  /**
+   * Gets the entry's value as a double. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public double getDouble(double defaultValue) {
+    return NetworkTablesJNI.getDouble(m_handle, defaultValue);
+  }
+
+  /**
+   * Gets the entry's value as a double. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public Number getNumber(Number defaultValue) {
+    return NetworkTablesJNI.getDouble(m_handle, defaultValue.doubleValue());
+  }
+
+  /**
+   * Gets the entry's value as a string. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public String getString(String defaultValue) {
+    return NetworkTablesJNI.getString(m_handle, defaultValue);
+  }
+
+  /**
+   * Gets the entry's value as a raw value (byte array). If the entry does not
+   * exist or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public byte[] getRaw(byte[] defaultValue) {
+    return NetworkTablesJNI.getRaw(m_handle, defaultValue);
+  }
+
+  /**
+   * Gets the entry's value as a boolean array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public boolean[] getBooleanArray(boolean[] defaultValue) {
+    return NetworkTablesJNI.getBooleanArray(m_handle, defaultValue);
+  }
+
+  /**
+   * Gets the entry's value as a boolean array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public Boolean[] getBooleanArray(Boolean[] defaultValue) {
+    return NetworkTableValue.fromNative(NetworkTablesJNI.getBooleanArray(m_handle,
+        NetworkTableValue.toNative(defaultValue)));
+  }
+
+  /**
+   * Gets the entry's value as a double array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public double[] getDoubleArray(double[] defaultValue) {
+    return NetworkTablesJNI.getDoubleArray(m_handle, defaultValue);
+  }
+
+  /**
+   * Gets the entry's value as a double array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public Double[] getDoubleArray(Double[] defaultValue) {
+    return NetworkTableValue.fromNative(NetworkTablesJNI.getDoubleArray(m_handle,
+        NetworkTableValue.toNative(defaultValue)));
+  }
+
+  /**
+   * Gets the entry's value as a double array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public Number[] getNumberArray(Number[] defaultValue) {
+    return NetworkTableValue.fromNative(NetworkTablesJNI.getDoubleArray(m_handle,
+        NetworkTableValue.toNative(defaultValue)));
+  }
+
+  /**
+   * Gets the entry's value as a string array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  public String[] getStringArray(String[] defaultValue) {
+    return NetworkTablesJNI.getStringArray(m_handle, defaultValue);
+  }
+
+  /**
+   * Checks if a data value is of a type that can be placed in a NetworkTable entry.
+   *
+   * @param data the data to check
+   * @return true if the data can be placed in an entry, false if it cannot
+   */
+  public static boolean isValidDataType(Object data) {
+    return data instanceof Number
+        || data instanceof Boolean
+        || data instanceof String
+        || data instanceof double[]
+        || data instanceof Double[]
+        || data instanceof Number[]
+        || data instanceof boolean[]
+        || data instanceof Boolean[]
+        || data instanceof String[]
+        || data instanceof byte[]
+        || data instanceof Byte[];
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  public boolean setDefaultValue(Object defaultValue) {
+    if (defaultValue instanceof NetworkTableValue) {
+      long time = ((NetworkTableValue) defaultValue).getTime();
+      Object otherValue = ((NetworkTableValue) defaultValue).getValue();
+      switch (((NetworkTableValue) defaultValue).getType()) {
+        case kBoolean:
+          return NetworkTablesJNI.setDefaultBoolean(m_handle, time,
+              ((Boolean) otherValue).booleanValue());
+        case kDouble:
+          return NetworkTablesJNI.setDefaultDouble(m_handle, time,
+              ((Number) otherValue).doubleValue());
+        case kString:
+          return NetworkTablesJNI.setDefaultString(m_handle, time, (String) otherValue);
+        case kRaw:
+          return NetworkTablesJNI.setDefaultRaw(m_handle, time, (byte[]) otherValue);
+        case kBooleanArray:
+          return NetworkTablesJNI.setDefaultBooleanArray(m_handle, time, (boolean[]) otherValue);
+        case kDoubleArray:
+          return NetworkTablesJNI.setDefaultDoubleArray(m_handle, time, (double[]) otherValue);
+        case kStringArray:
+          return NetworkTablesJNI.setDefaultStringArray(m_handle, time, (String[]) otherValue);
+        case kRpc:
+          // TODO
+        default:
+          return true;
+      }
+    } else if (defaultValue instanceof Boolean) {
+      return setDefaultBoolean((Boolean) defaultValue);
+    } else if (defaultValue instanceof Number) {
+      return setDefaultNumber((Number) defaultValue);
+    } else if (defaultValue instanceof String) {
+      return setDefaultString((String) defaultValue);
+    } else if (defaultValue instanceof byte[])  {
+      return setDefaultRaw((byte[]) defaultValue);
+    } else if (defaultValue instanceof boolean[])  {
+      return setDefaultBooleanArray((boolean[]) defaultValue);
+    } else if (defaultValue instanceof double[])  {
+      return setDefaultDoubleArray((double[]) defaultValue);
+    } else if (defaultValue instanceof Boolean[])  {
+      return setDefaultBooleanArray((Boolean[]) defaultValue);
+    } else if (defaultValue instanceof Number[])  {
+      return setDefaultNumberArray((Number[]) defaultValue);
+    } else if (defaultValue instanceof String[])  {
+      return setDefaultStringArray((String[]) defaultValue);
+    } else {
+      throw new IllegalArgumentException("Value of type " + defaultValue.getClass().getName()
+        + " cannot be put into a table");
+    }
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultBoolean(boolean defaultValue) {
+    return NetworkTablesJNI.setDefaultBoolean(m_handle, 0, defaultValue);
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultDouble(double defaultValue) {
+    return NetworkTablesJNI.setDefaultDouble(m_handle, 0, defaultValue);
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultNumber(Number defaultValue) {
+    return NetworkTablesJNI.setDefaultDouble(m_handle, 0, defaultValue.doubleValue());
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultString(String defaultValue) {
+    return NetworkTablesJNI.setDefaultString(m_handle, 0, defaultValue);
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultRaw(byte[] defaultValue) {
+    return NetworkTablesJNI.setDefaultRaw(m_handle, 0, defaultValue);
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultBooleanArray(boolean[] defaultValue) {
+    return NetworkTablesJNI.setDefaultBooleanArray(m_handle, 0, defaultValue);
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultBooleanArray(Boolean[] defaultValue) {
+    return NetworkTablesJNI.setDefaultBooleanArray(m_handle,
+        0, NetworkTableValue.toNative(defaultValue));
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultDoubleArray(double[] defaultValue) {
+    return NetworkTablesJNI.setDefaultDoubleArray(m_handle, 0, defaultValue);
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultNumberArray(Number[] defaultValue) {
+    return NetworkTablesJNI.setDefaultDoubleArray(m_handle,
+        0, NetworkTableValue.toNative(defaultValue));
+  }
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDefaultStringArray(String[] defaultValue) {
+    return NetworkTablesJNI.setDefaultStringArray(m_handle, 0, defaultValue);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  public boolean setValue(Object value) {
+    if (value instanceof NetworkTableValue) {
+      long time = ((NetworkTableValue) value).getTime();
+      Object otherValue = ((NetworkTableValue) value).getValue();
+      switch (((NetworkTableValue) value).getType()) {
+        case kBoolean:
+          return NetworkTablesJNI.setBoolean(m_handle, time, ((Boolean) otherValue).booleanValue(),
+              false);
+        case kDouble:
+          return NetworkTablesJNI.setDouble(m_handle, time, ((Number) otherValue).doubleValue(),
+              false);
+        case kString:
+          return NetworkTablesJNI.setString(m_handle, time, (String) otherValue, false);
+        case kRaw:
+          return NetworkTablesJNI.setRaw(m_handle, time, (byte[]) otherValue, false);
+        case kBooleanArray:
+          return NetworkTablesJNI.setBooleanArray(m_handle, time, (boolean[]) otherValue, false);
+        case kDoubleArray:
+          return NetworkTablesJNI.setDoubleArray(m_handle, time, (double[]) otherValue, false);
+        case kStringArray:
+          return NetworkTablesJNI.setStringArray(m_handle, time, (String[]) otherValue, false);
+        case kRpc:
+          // TODO
+        default:
+          return true;
+      }
+    } else if (value instanceof Boolean) {
+      return setBoolean((Boolean) value);
+    } else if (value instanceof Number) {
+      return setNumber((Number) value);
+    } else if (value instanceof String) {
+      return setString((String) value);
+    } else if (value instanceof byte[]) {
+      return setRaw((byte[]) value);
+    } else if (value instanceof boolean[]) {
+      return setBooleanArray((boolean[]) value);
+    } else if (value instanceof double[]) {
+      return setDoubleArray((double[]) value);
+    } else if (value instanceof Boolean[]) {
+      return setBooleanArray((Boolean[]) value);
+    } else if (value instanceof Number[]) {
+      return setNumberArray((Number[]) value);
+    } else if (value instanceof String[]) {
+      return setStringArray((String[]) value);
+    } else {
+      throw new IllegalArgumentException("Value of type " + value.getClass().getName()
+        + " cannot be put into a table");
+    }
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setBoolean(boolean value) {
+    return NetworkTablesJNI.setBoolean(m_handle, 0, value, false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDouble(double value) {
+    return NetworkTablesJNI.setDouble(m_handle, 0, value, false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setNumber(Number value) {
+    return NetworkTablesJNI.setDouble(m_handle, 0, value.doubleValue(), false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setString(String value) {
+    return NetworkTablesJNI.setString(m_handle, 0, value, false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setRaw(byte[] value) {
+    return NetworkTablesJNI.setRaw(m_handle, 0, value, false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @param len the length of the value
+   * @return False if the entry exists with a different type
+   */
+  public boolean setRaw(ByteBuffer value, int len) {
+    if (!value.isDirect()) {
+      throw new IllegalArgumentException("must be a direct buffer");
+    }
+    if (value.capacity() < len) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + len);
+    }
+    return NetworkTablesJNI.setRaw(m_handle, 0, value, len, false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setBooleanArray(boolean[] value) {
+    return NetworkTablesJNI.setBooleanArray(m_handle, 0, value, false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setBooleanArray(Boolean[] value) {
+    return NetworkTablesJNI.setBooleanArray(m_handle, 0, NetworkTableValue.toNative(value), false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setDoubleArray(double[] value) {
+    return NetworkTablesJNI.setDoubleArray(m_handle, 0, value, false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setNumberArray(Number[] value) {
+    return NetworkTablesJNI.setDoubleArray(m_handle, 0, NetworkTableValue.toNative(value), false);
+  }
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  public boolean setStringArray(String[] value) {
+    return NetworkTablesJNI.setStringArray(m_handle, 0, value, false);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   * @throws IllegalArgumentException if the value is not a known type
+   */
+  public void forceSetValue(Object value) {
+    if (value instanceof NetworkTableValue) {
+      long time = ((NetworkTableValue) value).getTime();
+      Object otherValue = ((NetworkTableValue) value).getValue();
+      switch (((NetworkTableValue) value).getType()) {
+        case kBoolean:
+          NetworkTablesJNI.setBoolean(m_handle, time, ((Boolean) otherValue).booleanValue(), true);
+          return;
+        case kDouble:
+          NetworkTablesJNI.setDouble(m_handle, time, ((Number) otherValue).doubleValue(), true);
+          return;
+        case kString:
+          NetworkTablesJNI.setString(m_handle, time, (String) otherValue, true);
+          return;
+        case kRaw:
+          NetworkTablesJNI.setRaw(m_handle, time, (byte[]) otherValue, true);
+          return;
+        case kBooleanArray:
+          NetworkTablesJNI.setBooleanArray(m_handle, time, (boolean[]) otherValue, true);
+          return;
+        case kDoubleArray:
+          NetworkTablesJNI.setDoubleArray(m_handle, time, (double[]) otherValue, true);
+          return;
+        case kStringArray:
+          NetworkTablesJNI.setStringArray(m_handle, time, (String[]) otherValue, true);
+          return;
+        case kRpc:
+          // TODO
+        default:
+          return;
+      }
+    } else if (value instanceof Boolean) {
+      forceSetBoolean((Boolean) value);
+    } else if (value instanceof Number) {
+      forceSetNumber((Number) value);
+    } else if (value instanceof String) {
+      forceSetString((String) value);
+    } else if (value instanceof byte[]) {
+      forceSetRaw((byte[]) value);
+    } else if (value instanceof boolean[]) {
+      forceSetBooleanArray((boolean[]) value);
+    } else if (value instanceof double[]) {
+      forceSetDoubleArray((double[]) value);
+    } else if (value instanceof Boolean[]) {
+      forceSetBooleanArray((Boolean[]) value);
+    } else if (value instanceof Number[]) {
+      forceSetNumberArray((Number[]) value);
+    } else if (value instanceof String[]) {
+      forceSetStringArray((String[]) value);
+    } else {
+      throw new IllegalArgumentException("Value of type " + value.getClass().getName()
+        + " cannot be put into a table");
+    }
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetBoolean(boolean value) {
+    NetworkTablesJNI.setBoolean(m_handle, 0, value, true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetDouble(double value) {
+    NetworkTablesJNI.setDouble(m_handle, 0, value, true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetNumber(Number value) {
+    NetworkTablesJNI.setDouble(m_handle, 0, value.doubleValue(), true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetString(String value) {
+    NetworkTablesJNI.setString(m_handle, 0, value, true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetRaw(byte[] value) {
+    NetworkTablesJNI.setRaw(m_handle, 0, value, true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetBooleanArray(boolean[] value) {
+    NetworkTablesJNI.setBooleanArray(m_handle, 0, value, true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetBooleanArray(Boolean[] value) {
+    NetworkTablesJNI.setBooleanArray(m_handle, 0, NetworkTableValue.toNative(value), true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetDoubleArray(double[] value) {
+    NetworkTablesJNI.setDoubleArray(m_handle, 0, value, true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetNumberArray(Number[] value) {
+    NetworkTablesJNI.setDoubleArray(m_handle, 0, NetworkTableValue.toNative(value), true);
+  }
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  public void forceSetStringArray(String[] value) {
+    NetworkTablesJNI.setStringArray(m_handle, 0, value, true);
+  }
+
+  /**
+   * Sets flags.
+   *
+   * @param flags the flags to set (bitmask)
+   */
+  public void setFlags(int flags) {
+    NetworkTablesJNI.setEntryFlags(m_handle, getFlags() | flags);
+  }
+
+  /**
+   * Clears flags.
+   *
+   * @param flags the flags to clear (bitmask)
+   */
+  public void clearFlags(int flags) {
+    NetworkTablesJNI.setEntryFlags(m_handle, getFlags() & ~flags);
+  }
+
+  /**
+   * Make value persistent through program restarts.
+   */
+  public void setPersistent() {
+    setFlags(kPersistent);
+  }
+
+  /**
+   * Stop making value persistent through program restarts.
+   */
+  public void clearPersistent() {
+    clearFlags(kPersistent);
+  }
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   *
+   * @return True if the value is persistent.
+   */
+  public boolean isPersistent() {
+    return (getFlags() & kPersistent) != 0;
+  }
+
+  /**
+   * Deletes the entry.
+   */
+  public void delete() {
+    NetworkTablesJNI.deleteEntry(m_handle);
+  }
+
+  /**
+   * Create a callback-based RPC entry point.  Only valid to use on the server.
+   * The callback function will be called when the RPC is called.
+   * This function creates RPC version 0 definitions (raw data in and out).
+   *
+   * @param callback  callback function
+   */
+  public void createRpc(Consumer<RpcAnswer> callback) {
+    m_inst.createRpc(this, callback);
+  }
+
+  /**
+   * Call a RPC function.  May be used on either the client or server.
+   * This function is non-blocking.  Either {@link RpcCall#getResult()} or
+   * {@link RpcCall#cancelResult()} must be called on the return value to either
+   * get or ignore the result of the call.
+   *
+   * @param params      parameter
+   * @return RPC call object.
+   */
+  public RpcCall callRpc(byte[] params) {
+    return new RpcCall(this, NetworkTablesJNI.callRpc(m_handle, params));
+  }
+
+  /**
+   * Add a listener for changes to the entry.
+   *
+   * @param listener the listener to add
+   * @param flags bitmask specifying desired notifications
+   * @return listener handle
+   */
+  public int addListener(Consumer<EntryNotification> listener, int flags) {
+    return m_inst.addEntryListener(this, listener, flags);
+  }
+
+  /**
+   * Remove a listener from receiving entry events.
+   *
+   * @param listener the listener to be removed
+   */
+  public void removeListener(int listener) {
+    m_inst.removeEntryListener(listener);
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (other == this) {
+      return true;
+    }
+    if (!(other instanceof NetworkTableEntry)) {
+      return false;
+    }
+
+    return m_handle == ((NetworkTableEntry) other).m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  private NetworkTableInstance m_inst;
+  private int m_handle;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java
new file mode 100644
index 0000000..2564f70
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableInstance.java
@@ -0,0 +1,1165 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.util.HashMap;
+import java.util.Map;
+import java.util.concurrent.ConcurrentHashMap;
+import java.util.concurrent.ConcurrentMap;
+import java.util.concurrent.TimeUnit;
+import java.util.concurrent.locks.Condition;
+import java.util.concurrent.locks.ReentrantLock;
+import java.util.function.Consumer;
+
+/**
+ * NetworkTables Instance.
+ *
+ * <p>Instances are completely independent from each other.  Table operations on
+ * one instance will not be visible to other instances unless the instances are
+ * connected via the network.  The main limitation on instances is that you
+ * cannot have two servers on the same network port.  The main utility of
+ * instances is for unit testing, but they can also enable one program to
+ * connect to two different NetworkTables networks.
+ *
+ * <p>The global "default" instance (as returned by {@link #getDefault()}) is
+ * always available, and is intended for the common case when there is only
+ * a single NetworkTables instance being used in the program.
+ *
+ * <p>Additional instances can be created with the {@link #create()} function.
+ * A reference must be kept to the NetworkTableInstance returned by this
+ * function to keep it from being garbage collected.
+ */
+public final class NetworkTableInstance implements AutoCloseable {
+  /**
+   * Client/server mode flag values (as returned by {@link #getNetworkMode()}).
+   * This is a bitmask.
+   */
+  public static final int kNetModeNone = 0x00;
+  public static final int kNetModeServer = 0x01;
+  public static final int kNetModeClient = 0x02;
+  public static final int kNetModeStarting = 0x04;
+  public static final int kNetModeFailure = 0x08;
+
+  /**
+   * The default port that network tables operates on.
+   */
+  public static final int kDefaultPort = 1735;
+
+  /**
+   * Construct from native handle.
+   *
+   * @param handle Native handle
+   */
+  private NetworkTableInstance(int handle) {
+    m_owned = false;
+    m_handle = handle;
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  /**
+   * Destroys the instance (if created by {@link #create()}).
+   */
+  @Override
+  public synchronized void close() {
+    if (m_owned && m_handle != 0) {
+      NetworkTablesJNI.destroyInstance(m_handle);
+    }
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return m_handle != 0;
+  }
+
+  /* The default instance. */
+  private static NetworkTableInstance s_defaultInstance;
+
+  /**
+   * Get global default instance.
+   *
+   * @return Global default instance
+   */
+  public static synchronized NetworkTableInstance getDefault() {
+    if (s_defaultInstance == null) {
+      s_defaultInstance = new NetworkTableInstance(NetworkTablesJNI.getDefaultInstance());
+    }
+    return s_defaultInstance;
+  }
+
+  /**
+   * Create an instance.
+   * Note: A reference to the returned instance must be retained to ensure the
+   * instance is not garbage collected.
+   *
+   * @return Newly created instance
+   */
+  public static NetworkTableInstance create() {
+    NetworkTableInstance inst = new NetworkTableInstance(NetworkTablesJNI.createInstance());
+    inst.m_owned = true;
+    return inst;
+  }
+
+  /**
+   * Gets the native handle for the entry.
+   *
+   * @return Native handle
+   */
+  public int getHandle() {
+    return m_handle;
+  }
+
+  /**
+   * Gets the entry for a key.
+   *
+   * @param name Key
+   * @return Network table entry.
+   */
+  public NetworkTableEntry getEntry(String name) {
+    return new NetworkTableEntry(this, NetworkTablesJNI.getEntry(m_handle, name));
+  }
+
+  /**
+   * Get entries starting with the given prefix.
+   * The results are optionally filtered by string prefix and entry type to
+   * only return a subset of all entries.
+   *
+   * @param prefix entry name required prefix; only entries whose name
+   *     starts with this string are returned
+   * @param types bitmask of types; 0 is treated as a "don't care"
+   * @return Array of entries.
+   */
+  public NetworkTableEntry[] getEntries(String prefix, int types) {
+    int[] handles = NetworkTablesJNI.getEntries(m_handle, prefix, types);
+    NetworkTableEntry[] entries = new NetworkTableEntry[handles.length];
+    for (int i = 0; i < handles.length; i++) {
+      entries[i] = new NetworkTableEntry(this, handles[i]);
+    }
+    return entries;
+  }
+
+  /**
+   * Get information about entries starting with the given prefix.
+   * The results are optionally filtered by string prefix and entry type to
+   * only return a subset of all entries.
+   *
+   * @param prefix entry name required prefix; only entries whose name
+   *     starts with this string are returned
+   * @param types bitmask of types; 0 is treated as a "don't care"
+   * @return Array of entry information.
+   */
+  public EntryInfo[] getEntryInfo(String prefix, int types) {
+    return NetworkTablesJNI.getEntryInfo(this, m_handle, prefix, types);
+  }
+
+  /* Cache of created tables. */
+  private final ConcurrentMap<String, NetworkTable> m_tables = new ConcurrentHashMap<>();
+
+  /**
+   * Gets the table with the specified key.
+   *
+   * @param key the key name
+   * @return The network table
+   */
+  public NetworkTable getTable(String key) {
+    // prepend leading / if not present
+    String theKey;
+    if (key.isEmpty() || key.equals("/")) {
+      theKey = "";
+    } else if (key.charAt(0) == NetworkTable.PATH_SEPARATOR) {
+      theKey = key;
+    } else {
+      theKey = NetworkTable.PATH_SEPARATOR + key;
+    }
+
+    // cache created tables
+    NetworkTable table = m_tables.get(theKey);
+    if (table == null) {
+      table = new NetworkTable(this, theKey);
+      NetworkTable oldTable = m_tables.putIfAbsent(theKey, table);
+      if (oldTable != null) {
+        table = oldTable;
+      }
+    }
+    return table;
+  }
+
+  /**
+   * Deletes ALL keys in ALL subtables (except persistent values).
+   * Use with caution!
+   */
+  public void deleteAllEntries() {
+    NetworkTablesJNI.deleteAllEntries(m_handle);
+  }
+
+  /*
+   * Callback Creation Functions
+   */
+
+  private static class EntryConsumer<T> {
+    final NetworkTableEntry m_entry;
+    final Consumer<T> m_consumer;
+
+    EntryConsumer(NetworkTableEntry entry, Consumer<T> consumer) {
+      m_entry = entry;
+      m_consumer = consumer;
+    }
+  }
+
+  private final ReentrantLock m_entryListenerLock = new ReentrantLock();
+  private final Map<Integer, EntryConsumer<EntryNotification>> m_entryListeners = new HashMap<>();
+  private Thread m_entryListenerThread;
+  private int m_entryListenerPoller;
+  private boolean m_entryListenerWaitQueue;
+  private final Condition m_entryListenerWaitQueueCond = m_entryListenerLock.newCondition();
+
+  private void startEntryListenerThread() {
+    m_entryListenerThread = new Thread(() -> {
+      boolean wasInterrupted = false;
+      while (!Thread.interrupted()) {
+        EntryNotification[] events;
+        try {
+          events = NetworkTablesJNI.pollEntryListener(this, m_entryListenerPoller);
+        } catch (InterruptedException ex) {
+          m_entryListenerLock.lock();
+          try {
+            if (m_entryListenerWaitQueue) {
+              m_entryListenerWaitQueue = false;
+              m_entryListenerWaitQueueCond.signalAll();
+              continue;
+            }
+          } finally {
+            m_entryListenerLock.unlock();
+          }
+          Thread.currentThread().interrupt();
+          // don't try to destroy poller, as its handle is likely no longer valid
+          wasInterrupted = true;
+          break;
+        }
+        for (EntryNotification event : events) {
+          EntryConsumer<EntryNotification> listener;
+          m_entryListenerLock.lock();
+          try {
+            listener = m_entryListeners.get(event.listener);
+          } finally {
+            m_entryListenerLock.unlock();
+          }
+          if (listener != null) {
+            event.m_entryObject = listener.m_entry;
+            try {
+              listener.m_consumer.accept(event);
+            } catch (Throwable throwable) {
+              System.err.println("Unhandled exception during entry listener callback: "
+                  + throwable.toString());
+              throwable.printStackTrace();
+            }
+          }
+        }
+      }
+      m_entryListenerLock.lock();
+      try {
+        if (!wasInterrupted) {
+          NetworkTablesJNI.destroyEntryListenerPoller(m_entryListenerPoller);
+        }
+        m_entryListenerPoller = 0;
+      } finally {
+        m_entryListenerLock.unlock();
+      }
+    }, "NTEntryListener");
+    m_entryListenerThread.setDaemon(true);
+    m_entryListenerThread.start();
+  }
+
+  /**
+   * Add a listener for all entries starting with a certain prefix.
+   *
+   * @param prefix            UTF-8 string prefix
+   * @param listener          listener to add
+   * @param flags             {@link EntryListenerFlags} bitmask
+   * @return Listener handle
+   */
+  public int addEntryListener(String prefix, Consumer<EntryNotification> listener, int flags) {
+    m_entryListenerLock.lock();
+    try {
+      if (m_entryListenerPoller == 0) {
+        m_entryListenerPoller = NetworkTablesJNI.createEntryListenerPoller(m_handle);
+        startEntryListenerThread();
+      }
+      int handle = NetworkTablesJNI.addPolledEntryListener(m_entryListenerPoller, prefix, flags);
+      m_entryListeners.put(handle, new EntryConsumer<>(null, listener));
+      return handle;
+    } finally {
+      m_entryListenerLock.unlock();
+    }
+  }
+
+  /**
+   * Add a listener for a particular entry.
+   *
+   * @param entry             the entry
+   * @param listener          listener to add
+   * @param flags             {@link EntryListenerFlags} bitmask
+   * @return Listener handle
+   */
+  public int addEntryListener(NetworkTableEntry entry,
+                              Consumer<EntryNotification> listener,
+                              int flags) {
+    if (!equals(entry.getInstance())) {
+      throw new IllegalArgumentException("entry does not belong to this instance");
+    }
+    m_entryListenerLock.lock();
+    try {
+      if (m_entryListenerPoller == 0) {
+        m_entryListenerPoller = NetworkTablesJNI.createEntryListenerPoller(m_handle);
+        startEntryListenerThread();
+      }
+      int handle = NetworkTablesJNI.addPolledEntryListener(m_entryListenerPoller, entry.getHandle(),
+          flags);
+      m_entryListeners.put(handle, new EntryConsumer<>(entry, listener));
+      return handle;
+    } finally {
+      m_entryListenerLock.unlock();
+    }
+  }
+
+  /**
+   * Remove an entry listener.
+   *
+   * @param listener Listener handle to remove
+   */
+  public void removeEntryListener(int listener) {
+    NetworkTablesJNI.removeEntryListener(listener);
+  }
+
+  /**
+   * Wait for the entry listener queue to be empty.  This is primarily useful
+   * for deterministic testing.  This blocks until either the entry listener
+   * queue is empty (e.g. there are no more events that need to be passed along
+   * to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+   *                  or a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+  */
+  public boolean waitForEntryListenerQueue(double timeout) {
+    if (!NetworkTablesJNI.waitForEntryListenerQueue(m_handle, timeout)) {
+      return false;
+    }
+    m_entryListenerLock.lock();
+    try {
+      if (m_entryListenerPoller != 0) {
+        m_entryListenerWaitQueue = true;
+        NetworkTablesJNI.cancelPollEntryListener(m_entryListenerPoller);
+        while (m_entryListenerWaitQueue) {
+          try {
+            if (timeout < 0) {
+              m_entryListenerWaitQueueCond.await();
+            } else {
+              return m_entryListenerWaitQueueCond.await((long) (timeout * 1e9),
+                  TimeUnit.NANOSECONDS);
+            }
+          } catch (InterruptedException ex) {
+            Thread.currentThread().interrupt();
+            return true;
+          }
+        }
+      }
+    } finally {
+      m_entryListenerLock.unlock();
+    }
+    return true;
+  }
+
+  private final ReentrantLock m_connectionListenerLock = new ReentrantLock();
+  private final Map<Integer, Consumer<ConnectionNotification>> m_connectionListeners
+      = new HashMap<>();
+  private Thread m_connectionListenerThread;
+  private int m_connectionListenerPoller;
+  private boolean m_connectionListenerWaitQueue;
+  private final Condition m_connectionListenerWaitQueueCond
+      = m_connectionListenerLock.newCondition();
+
+  private void startConnectionListenerThread() {
+    m_connectionListenerThread = new Thread(() -> {
+      boolean wasInterrupted = false;
+      while (!Thread.interrupted()) {
+        ConnectionNotification[] events;
+        try {
+          events = NetworkTablesJNI.pollConnectionListener(this, m_connectionListenerPoller);
+        } catch (InterruptedException ex) {
+          m_connectionListenerLock.lock();
+          try {
+            if (m_connectionListenerWaitQueue) {
+              m_connectionListenerWaitQueue = false;
+              m_connectionListenerWaitQueueCond.signalAll();
+              continue;
+            }
+          } finally {
+            m_connectionListenerLock.unlock();
+          }
+          Thread.currentThread().interrupt();
+          // don't try to destroy poller, as its handle is likely no longer valid
+          wasInterrupted = true;
+          break;
+        }
+        for (ConnectionNotification event : events) {
+          Consumer<ConnectionNotification> listener;
+          m_connectionListenerLock.lock();
+          try {
+            listener = m_connectionListeners.get(event.listener);
+          } finally {
+            m_connectionListenerLock.unlock();
+          }
+          if (listener != null) {
+            try {
+              listener.accept(event);
+            } catch (Throwable throwable) {
+              System.err.println("Unhandled exception during connection listener callback: "
+                  + throwable.toString());
+              throwable.printStackTrace();
+            }
+          }
+        }
+      }
+      m_connectionListenerLock.lock();
+      try {
+        if (!wasInterrupted) {
+          NetworkTablesJNI.destroyConnectionListenerPoller(m_connectionListenerPoller);
+        }
+        m_connectionListenerPoller = 0;
+      } finally {
+        m_connectionListenerLock.unlock();
+      }
+    }, "NTConnectionListener");
+    m_connectionListenerThread.setDaemon(true);
+    m_connectionListenerThread.start();
+  }
+
+  /**
+   * Add a connection listener.
+   *
+   * @param listener Listener to add
+   * @param immediateNotify Notify listener of all existing connections
+   * @return Listener handle
+   */
+  public int addConnectionListener(Consumer<ConnectionNotification> listener,
+                                   boolean immediateNotify) {
+    m_connectionListenerLock.lock();
+    try {
+      if (m_connectionListenerPoller == 0) {
+        m_connectionListenerPoller = NetworkTablesJNI.createConnectionListenerPoller(m_handle);
+        startConnectionListenerThread();
+      }
+      int handle = NetworkTablesJNI.addPolledConnectionListener(m_connectionListenerPoller,
+          immediateNotify);
+      m_connectionListeners.put(handle, listener);
+      return handle;
+    } finally {
+      m_connectionListenerLock.unlock();
+    }
+  }
+
+  /**
+   * Remove a connection listener.
+   *
+   * @param listener Listener handle to remove
+   */
+  public void removeConnectionListener(int listener) {
+    m_connectionListenerLock.lock();
+    try {
+      m_connectionListeners.remove(listener);
+    } finally {
+      m_connectionListenerLock.unlock();
+    }
+    NetworkTablesJNI.removeConnectionListener(listener);
+  }
+
+  /**
+   * Wait for the connection listener queue to be empty.  This is primarily useful
+   * for deterministic testing.  This blocks until either the connection listener
+   * queue is empty (e.g. there are no more events that need to be passed along
+   * to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+   *                  or a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  public boolean waitForConnectionListenerQueue(double timeout) {
+    if (!NetworkTablesJNI.waitForConnectionListenerQueue(m_handle, timeout)) {
+      return false;
+    }
+    m_connectionListenerLock.lock();
+    try {
+      if (m_connectionListenerPoller != 0) {
+        m_connectionListenerWaitQueue = true;
+        NetworkTablesJNI.cancelPollConnectionListener(m_connectionListenerPoller);
+        while (m_connectionListenerWaitQueue) {
+          try {
+            if (timeout < 0) {
+              m_connectionListenerWaitQueueCond.await();
+            } else {
+              return m_connectionListenerWaitQueueCond.await((long) (timeout * 1e9),
+                  TimeUnit.NANOSECONDS);
+            }
+          } catch (InterruptedException ex) {
+            Thread.currentThread().interrupt();
+            return true;
+          }
+        }
+      }
+    } finally {
+      m_connectionListenerLock.unlock();
+    }
+    return true;
+  }
+
+  /*
+   * Remote Procedure Call Functions
+   */
+
+  private final ReentrantLock m_rpcCallLock = new ReentrantLock();
+  private final Map<Integer, EntryConsumer<RpcAnswer>> m_rpcCalls = new HashMap<>();
+  private Thread m_rpcCallThread;
+  private int m_rpcCallPoller;
+  private boolean m_rpcCallWaitQueue;
+  private final Condition m_rpcCallWaitQueueCond = m_rpcCallLock.newCondition();
+
+  private void startRpcCallThread() {
+    m_rpcCallThread = new Thread(() -> {
+      boolean wasInterrupted = false;
+      while (!Thread.interrupted()) {
+        RpcAnswer[] events;
+        try {
+          events = NetworkTablesJNI.pollRpc(this, m_rpcCallPoller);
+        } catch (InterruptedException ex) {
+          m_rpcCallLock.lock();
+          try {
+            if (m_rpcCallWaitQueue) {
+              m_rpcCallWaitQueue = false;
+              m_rpcCallWaitQueueCond.signalAll();
+              continue;
+            }
+          } finally {
+            m_rpcCallLock.unlock();
+          }
+          Thread.currentThread().interrupt();
+          // don't try to destroy poller, as its handle is likely no longer valid
+          wasInterrupted = true;
+          break;
+        }
+        for (RpcAnswer event : events) {
+          EntryConsumer<RpcAnswer> listener;
+          m_rpcCallLock.lock();
+          try {
+            listener = m_rpcCalls.get(event.entry);
+          } finally {
+            m_rpcCallLock.unlock();
+          }
+          if (listener != null) {
+            event.m_entryObject = listener.m_entry;
+            try {
+              listener.m_consumer.accept(event);
+            } catch (Throwable throwable) {
+              System.err.println("Unhandled exception during RPC callback: "
+                  + throwable.toString());
+              throwable.printStackTrace();
+            }
+            event.finish();
+          }
+        }
+      }
+      m_rpcCallLock.lock();
+      try {
+        if (!wasInterrupted) {
+          NetworkTablesJNI.destroyRpcCallPoller(m_rpcCallPoller);
+        }
+        m_rpcCallPoller = 0;
+      } finally {
+        m_rpcCallLock.unlock();
+      }
+    }, "NTRpcCall");
+    m_rpcCallThread.setDaemon(true);
+    m_rpcCallThread.start();
+  }
+
+  private static final byte[] rev0def = new byte[] {0};
+
+  /**
+   * Create a callback-based RPC entry point.  Only valid to use on the server.
+   * The callback function will be called when the RPC is called.
+   * This function creates RPC version 0 definitions (raw data in and out).
+   *
+   * @param entry     the entry
+   * @param callback  callback function
+   */
+  public void createRpc(NetworkTableEntry entry, Consumer<RpcAnswer> callback) {
+    m_rpcCallLock.lock();
+    try {
+      if (m_rpcCallPoller == 0) {
+        m_rpcCallPoller = NetworkTablesJNI.createRpcCallPoller(m_handle);
+        startRpcCallThread();
+      }
+      NetworkTablesJNI.createPolledRpc(entry.getHandle(), rev0def, m_rpcCallPoller);
+      m_rpcCalls.put(entry.getHandle(), new EntryConsumer<>(entry, callback));
+    } finally {
+      m_rpcCallLock.unlock();
+    }
+  }
+
+  /**
+   * Wait for the incoming RPC call queue to be empty.  This is primarily useful
+   * for deterministic testing.  This blocks until either the RPC call
+   * queue is empty (e.g. there are no more events that need to be passed along
+   * to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+   *                  or a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  public boolean waitForRpcCallQueue(double timeout) {
+    if (!NetworkTablesJNI.waitForRpcCallQueue(m_handle, timeout)) {
+      return false;
+    }
+    m_rpcCallLock.lock();
+    try {
+      if (m_rpcCallPoller != 0) {
+        m_rpcCallWaitQueue = true;
+        NetworkTablesJNI.cancelPollRpc(m_rpcCallPoller);
+        while (m_rpcCallWaitQueue) {
+          try {
+            if (timeout < 0) {
+              m_rpcCallWaitQueueCond.await();
+            } else {
+              return m_rpcCallWaitQueueCond.await((long) (timeout * 1e9), TimeUnit.NANOSECONDS);
+            }
+          } catch (InterruptedException ex) {
+            Thread.currentThread().interrupt();
+            return true;
+          }
+        }
+      }
+    } finally {
+      m_rpcCallLock.unlock();
+    }
+    return true;
+  }
+
+  /*
+   * Client/Server Functions
+   */
+
+  /**
+   * Set the network identity of this node.
+   * This is the name used during the initial connection handshake, and is
+   * visible through ConnectionInfo on the remote node.
+   *
+   * @param name      identity to advertise
+   */
+  public void setNetworkIdentity(String name) {
+    NetworkTablesJNI.setNetworkIdentity(m_handle, name);
+  }
+
+  /**
+   * Get the current network mode.
+   *
+   * @return Bitmask of NetworkMode.
+   */
+  public int getNetworkMode() {
+    return NetworkTablesJNI.getNetworkMode(m_handle);
+  }
+
+  /**
+   * Starts a server using the networktables.ini as the persistent file,
+   * using the default listening address and port.
+   */
+  public void startServer() {
+    startServer("networktables.ini");
+  }
+
+  /**
+   * Starts a server using the specified persistent filename, using the default
+   * listening address and port.
+   *
+   * @param persistFilename  the name of the persist file to use
+   */
+  public void startServer(String persistFilename) {
+    startServer(persistFilename, "");
+  }
+
+  /**
+   * Starts a server using the specified filename and listening address,
+   * using the default port.
+   *
+   * @param persistFilename  the name of the persist file to use
+   * @param listenAddress    the address to listen on, or empty to listen on any
+   *                         address
+   */
+  public void startServer(String persistFilename, String listenAddress) {
+    startServer(persistFilename, listenAddress, kDefaultPort);
+  }
+
+  /**
+   * Starts a server using the specified filename, listening address, and port.
+   *
+   * @param persistFilename  the name of the persist file to use
+   * @param listenAddress    the address to listen on, or empty to listen on any
+   *                         address
+   * @param port             port to communicate over
+   */
+  public void startServer(String persistFilename, String listenAddress, int port) {
+    NetworkTablesJNI.startServer(m_handle, persistFilename, listenAddress, port);
+  }
+
+  /**
+   * Stops the server if it is running.
+   */
+  public void stopServer() {
+    NetworkTablesJNI.stopServer(m_handle);
+  }
+
+  /**
+   * Starts a client.  Use SetServer to set the server name and port.
+   */
+  public void startClient() {
+    NetworkTablesJNI.startClient(m_handle);
+  }
+
+  /**
+   * Starts a client using the specified server and the default port.
+   *
+   * @param serverName  server name
+   */
+  public void startClient(String serverName) {
+    startClient(serverName, kDefaultPort);
+  }
+
+  /**
+   * Starts a client using the specified server and port.
+   *
+   * @param serverName  server name
+   * @param port        port to communicate over
+   */
+  public void startClient(String serverName, int port) {
+    NetworkTablesJNI.startClient(m_handle, serverName, port);
+  }
+
+  /**
+   * Starts a client using the specified servers and default port.  The
+   * client will attempt to connect to each server in round robin fashion.
+   *
+   * @param serverNames   array of server names
+   */
+  public void startClient(String[] serverNames) {
+    startClient(serverNames, kDefaultPort);
+  }
+
+  /**
+   * Starts a client using the specified servers and port number.  The
+   * client will attempt to connect to each server in round robin fashion.
+   *
+   * @param serverNames   array of server names
+   * @param port          port to communicate over
+   */
+  public void startClient(String[] serverNames, int port) {
+    int[] ports = new int[serverNames.length];
+    for (int i = 0; i < serverNames.length; i++) {
+      ports[i] = port;
+    }
+    startClient(serverNames, ports);
+  }
+
+  /**
+   * Starts a client using the specified (server, port) combinations.  The
+   * client will attempt to connect to each server in round robin fashion.
+   *
+   * @param serverNames   array of server names
+   * @param ports         array of port numbers
+   */
+  public void startClient(String[] serverNames, int[] ports) {
+    NetworkTablesJNI.startClient(m_handle, serverNames, ports);
+  }
+
+  /**
+   * Starts a client using commonly known robot addresses for the specified
+   * team using the default port number.
+   *
+   * @param team        team number
+   */
+  public void startClientTeam(int team) {
+    startClientTeam(team, kDefaultPort);
+  }
+
+  /**
+   * Starts a client using commonly known robot addresses for the specified
+   * team.
+   *
+   * @param team        team number
+   * @param port        port to communicate over
+   */
+  public void startClientTeam(int team, int port) {
+    NetworkTablesJNI.startClientTeam(m_handle, team, port);
+  }
+
+  /**
+   * Stops the client if it is running.
+   */
+  public void stopClient() {
+    NetworkTablesJNI.stopClient(m_handle);
+  }
+
+  /**
+   * Sets server address and port for client (without restarting client).
+   * Changes the port to the default port.
+   *
+   * @param serverName  server name
+   */
+  public void setServer(String serverName) {
+    setServer(serverName, kDefaultPort);
+  }
+
+  /**
+   * Sets server address and port for client (without restarting client).
+   *
+   * @param serverName  server name
+   * @param port        port to communicate over
+   */
+  public void setServer(String serverName, int port) {
+    NetworkTablesJNI.setServer(m_handle, serverName, port);
+  }
+
+  /**
+   * Sets server addresses and port for client (without restarting client).
+   * Changes the port to the default port.  The client will attempt to connect
+   * to each server in round robin fashion.
+   *
+   * @param serverNames   array of server names
+   */
+  public void setServer(String[] serverNames) {
+    setServer(serverNames, kDefaultPort);
+  }
+
+  /**
+   * Sets server addresses and port for client (without restarting client).
+   * The client will attempt to connect to each server in round robin fashion.
+   *
+   * @param serverNames   array of server names
+   * @param port          port to communicate over
+   */
+  public void setServer(String[] serverNames, int port) {
+    int[] ports = new int[serverNames.length];
+    for (int i = 0; i < serverNames.length; i++) {
+      ports[i] = port;
+    }
+    setServer(serverNames, ports);
+  }
+
+  /**
+   * Sets server addresses and ports for client (without restarting client).
+   * The client will attempt to connect to each server in round robin fashion.
+   *
+   * @param serverNames   array of server names
+   * @param ports         array of port numbers
+   */
+  public void setServer(String[] serverNames, int[] ports) {
+    NetworkTablesJNI.setServer(m_handle, serverNames, ports);
+  }
+
+  /**
+   * Sets server addresses and port for client (without restarting client).
+   * Changes the port to the default port.  The client will attempt to connect
+   * to each server in round robin fashion.
+   *
+   * @param team        team number
+   */
+  public void setServerTeam(int team) {
+    setServerTeam(team, kDefaultPort);
+  }
+
+  /**
+   * Sets server addresses and port for client (without restarting client).
+   * Connects using commonly known robot addresses for the specified team.
+   *
+   * @param team        team number
+   * @param port        port to communicate over
+   */
+  public void setServerTeam(int team, int port) {
+    NetworkTablesJNI.setServerTeam(m_handle, team, port);
+  }
+
+  /**
+   * Starts requesting server address from Driver Station.
+   * This connects to the Driver Station running on localhost to obtain the
+   * server IP address, and connects with the default port.
+   */
+  public void startDSClient() {
+    startDSClient(kDefaultPort);
+  }
+
+  /**
+   * Starts requesting server address from Driver Station.
+   * This connects to the Driver Station running on localhost to obtain the
+   * server IP address.
+   *
+   * @param port server port to use in combination with IP from DS
+   */
+  public void startDSClient(int port) {
+    NetworkTablesJNI.startDSClient(m_handle, port);
+  }
+
+  /**
+   * Stops requesting server address from Driver Station.
+   */
+  public void stopDSClient() {
+    NetworkTablesJNI.stopDSClient(m_handle);
+  }
+
+  /**
+   * Set the periodic update rate.
+   * Sets how frequently updates are sent to other nodes over the network.
+   *
+   * @param interval update interval in seconds (range 0.01 to 1.0)
+   */
+  public void setUpdateRate(double interval) {
+    NetworkTablesJNI.setUpdateRate(m_handle, interval);
+  }
+
+  /**
+   * Flushes all updated values immediately to the network.
+   * Note: This is rate-limited to protect the network from flooding.
+   * This is primarily useful for synchronizing network updates with
+   * user code.
+   */
+  public void flush() {
+    NetworkTablesJNI.flush(m_handle);
+  }
+
+  /**
+   * Gets information on the currently established network connections.
+   * If operating as a client, this will return either zero or one values.
+   *
+   * @return array of connection information
+   */
+  public ConnectionInfo[] getConnections() {
+    return NetworkTablesJNI.getConnections(m_handle);
+  }
+
+  /**
+   * Return whether or not the instance is connected to another node.
+   *
+   * @return True if connected.
+   */
+  public boolean isConnected() {
+    return NetworkTablesJNI.isConnected(m_handle);
+  }
+
+  /**
+   * Saves persistent keys to a file.  The server does this automatically.
+   *
+   * @param filename file name
+   * @throws PersistentException if error saving file
+   */
+  public void savePersistent(String filename) throws PersistentException {
+    NetworkTablesJNI.savePersistent(m_handle, filename);
+  }
+
+  /**
+   * Loads persistent keys from a file.  The server does this automatically.
+   *
+   * @param filename file name
+   * @return List of warnings (errors result in an exception instead)
+   * @throws PersistentException if error reading file
+   */
+  public String[] loadPersistent(String filename) throws PersistentException {
+    return NetworkTablesJNI.loadPersistent(m_handle, filename);
+  }
+
+  /**
+   * Save table values to a file.  The file format used is identical to
+   * that used for SavePersistent.
+   *
+   * @param filename  filename
+   * @param prefix    save only keys starting with this prefix
+   * @throws PersistentException if error saving file
+   */
+  public void saveEntries(String filename, String prefix) throws PersistentException {
+    NetworkTablesJNI.saveEntries(m_handle, filename, prefix);
+  }
+
+  /**
+   * Load table values from a file.  The file format used is identical to
+   * that used for SavePersistent / LoadPersistent.
+   *
+   * @param filename  filename
+   * @param prefix    load only keys starting with this prefix
+   * @return List of warnings (errors result in an exception instead)
+   * @throws PersistentException if error saving file
+   */
+  public String[] loadEntries(String filename, String prefix) throws PersistentException {
+    return NetworkTablesJNI.loadEntries(m_handle, filename, prefix);
+  }
+
+  private final ReentrantLock m_loggerLock = new ReentrantLock();
+  private final Map<Integer, Consumer<LogMessage>> m_loggers = new HashMap<>();
+  private Thread m_loggerThread;
+  private int m_loggerPoller;
+  private boolean m_loggerWaitQueue;
+  private final Condition m_loggerWaitQueueCond = m_loggerLock.newCondition();
+
+  private void startLogThread() {
+    m_loggerThread = new Thread(() -> {
+      boolean wasInterrupted = false;
+      while (!Thread.interrupted()) {
+        LogMessage[] events;
+        try {
+          events = NetworkTablesJNI.pollLogger(this, m_loggerPoller);
+        } catch (InterruptedException ex) {
+          Thread.currentThread().interrupt();
+          // don't try to destroy poller, as its handle is likely no longer valid
+          wasInterrupted = true;
+          break;
+        }
+        for (LogMessage event : events) {
+          Consumer<LogMessage> logger;
+          m_loggerLock.lock();
+          try {
+            logger = m_loggers.get(event.logger);
+          } finally {
+            m_loggerLock.unlock();
+          }
+          if (logger != null) {
+            try {
+              logger.accept(event);
+            } catch (Throwable throwable) {
+              System.err.println("Unhandled exception during logger callback: "
+                  + throwable.toString());
+              throwable.printStackTrace();
+            }
+          }
+        }
+      }
+      m_loggerLock.lock();
+      try {
+        if (!wasInterrupted) {
+          NetworkTablesJNI.destroyLoggerPoller(m_loggerPoller);
+        }
+        m_rpcCallPoller = 0;
+      } finally {
+        m_loggerLock.unlock();
+      }
+    }, "NTLogger");
+    m_loggerThread.setDaemon(true);
+    m_loggerThread.start();
+  }
+
+  /**
+   * Add logger callback function.  By default, log messages are sent to stderr;
+   * this function sends log messages with the specified levels to the provided
+   * callback function instead.  The callback function will only be called for
+   * log messages with level greater than or equal to minLevel and less than or
+   * equal to maxLevel; messages outside this range will be silently ignored.
+   *
+   * @param func        log callback function
+   * @param minLevel    minimum log level
+   * @param maxLevel    maximum log level
+   * @return Logger handle
+   */
+  public int addLogger(Consumer<LogMessage> func, int minLevel, int maxLevel) {
+    m_loggerLock.lock();
+    try {
+      if (m_loggerPoller == 0) {
+        m_loggerPoller = NetworkTablesJNI.createLoggerPoller(m_handle);
+        startLogThread();
+      }
+      int handle = NetworkTablesJNI.addPolledLogger(m_loggerPoller, minLevel, maxLevel);
+      m_loggers.put(handle, func);
+      return handle;
+    } finally {
+      m_loggerLock.unlock();
+    }
+  }
+
+  /**
+   * Remove a logger.
+   *
+   * @param logger Logger handle to remove
+   */
+  public void removeLogger(int logger) {
+    m_loggerLock.lock();
+    try {
+      m_loggers.remove(logger);
+    } finally {
+      m_loggerLock.unlock();
+    }
+    NetworkTablesJNI.removeLogger(logger);
+  }
+
+  /**
+   * Wait for the incoming log event queue to be empty.  This is primarily useful
+   * for deterministic testing.  This blocks until either the log event
+   * queue is empty (e.g. there are no more events that need to be passed along
+   * to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+   *                  or a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  public boolean waitForLoggerQueue(double timeout) {
+    if (!NetworkTablesJNI.waitForLoggerQueue(m_handle, timeout)) {
+      return false;
+    }
+    m_loggerLock.lock();
+    try {
+      if (m_loggerPoller != 0) {
+        m_loggerWaitQueue = true;
+        NetworkTablesJNI.cancelPollLogger(m_loggerPoller);
+        while (m_loggerWaitQueue) {
+          try {
+            if (timeout < 0) {
+              m_loggerWaitQueueCond.await();
+            } else {
+              return m_loggerWaitQueueCond.await((long) (timeout * 1e9), TimeUnit.NANOSECONDS);
+            }
+          } catch (InterruptedException ex) {
+            Thread.currentThread().interrupt();
+            return true;
+          }
+        }
+      }
+    } finally {
+      m_loggerLock.unlock();
+    }
+    return true;
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (other == this) {
+      return true;
+    }
+    if (!(other instanceof NetworkTableInstance)) {
+      return false;
+    }
+
+    return m_handle == ((NetworkTableInstance) other).m_handle;
+  }
+
+  @Override
+  public int hashCode() {
+    return m_handle;
+  }
+
+  private boolean m_owned;
+  private int m_handle;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableType.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableType.java
new file mode 100644
index 0000000..54a9f55
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableType.java
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * Network table data types.
+ */
+public enum NetworkTableType {
+  kUnassigned(0),
+  kBoolean(0x01),
+  kDouble(0x02),
+  kString(0x04),
+  kRaw(0x08),
+  kBooleanArray(0x10),
+  kDoubleArray(0x20),
+  kStringArray(0x40),
+  kRpc(0x80);
+
+  @SuppressWarnings("MemberName")
+  private final int value;
+
+  NetworkTableType(int value) {
+    this.value = value;
+  }
+
+  public int getValue() {
+    return value;
+  }
+
+  /**
+   * Convert from the numerical representation of type to an enum type.
+   *
+   * @param value The numerical representation of kind
+   * @return The kind
+   */
+  public static NetworkTableType getFromInt(int value) {
+    switch (value) {
+      case 0x01: return kBoolean;
+      case 0x02: return kDouble;
+      case 0x04: return kString;
+      case 0x08: return kRaw;
+      case 0x10: return kBooleanArray;
+      case 0x20: return kDoubleArray;
+      case 0x40: return kStringArray;
+      case 0x80: return kRpc;
+      default: return kUnassigned;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java
new file mode 100644
index 0000000..e1179ea
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTableValue.java
@@ -0,0 +1,516 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.util.Objects;
+
+/**
+ * A network table entry value.
+ */
+public final class NetworkTableValue {
+  NetworkTableValue(NetworkTableType type, Object value, long time) {
+    m_type = type;
+    m_value = value;
+    m_time = time;
+  }
+
+  NetworkTableValue(NetworkTableType type, Object value) {
+    this(type, value, NetworkTablesJNI.now());
+  }
+
+  NetworkTableValue(int type, Object value, long time) {
+    this(NetworkTableType.getFromInt(type), value, time);
+  }
+
+  /**
+   * Get the data type.
+   *
+   * @return The type.
+   */
+  public NetworkTableType getType() {
+    return m_type;
+  }
+
+  /**
+   * Get the data value stored.
+   *
+   * @return The type.
+   */
+  public Object getValue() {
+    return m_value;
+  }
+
+  /**
+   * Get the creation time of the value.
+   *
+   * @return The time, in the units returned by NetworkTablesJNI.now().
+   */
+  public long getTime() {
+    return m_time;
+  }
+
+  /*
+   * Type Checkers
+   */
+
+  /**
+   * Determine if entry value contains a value or is unassigned.
+   *
+   * @return True if the entry value contains a value.
+   */
+  public boolean isValid() {
+    return m_type != NetworkTableType.kUnassigned;
+  }
+
+  /**
+   * Determine if entry value contains a boolean.
+   *
+   * @return True if the entry value is of boolean type.
+   */
+  public boolean isBoolean() {
+    return m_type == NetworkTableType.kBoolean;
+  }
+
+  /**
+   * Determine if entry value contains a double.
+   *
+   * @return True if the entry value is of double type.
+   */
+  public boolean isDouble() {
+    return m_type == NetworkTableType.kDouble;
+  }
+
+  /**
+   * Determine if entry value contains a string.
+   *
+   * @return True if the entry value is of string type.
+   */
+  public boolean isString() {
+    return m_type == NetworkTableType.kString;
+  }
+
+  /**
+   * Determine if entry value contains a raw.
+   *
+   * @return True if the entry value is of raw type.
+   */
+  public boolean isRaw() {
+    return m_type == NetworkTableType.kRaw;
+  }
+
+  /**
+   * Determine if entry value contains a rpc definition.
+   *
+   * @return True if the entry value is of rpc definition type.
+   */
+  public boolean isRpc() {
+    return m_type == NetworkTableType.kRpc;
+  }
+
+  /**
+   * Determine if entry value contains a boolean array.
+   *
+   * @return True if the entry value is of boolean array type.
+   */
+  public boolean isBooleanArray() {
+    return m_type == NetworkTableType.kBooleanArray;
+  }
+
+  /**
+   * Determine if entry value contains a double array.
+   *
+   * @return True if the entry value is of double array type.
+   */
+  public boolean isDoubleArray() {
+    return m_type == NetworkTableType.kDoubleArray;
+  }
+
+  /**
+   * Determine if entry value contains a string array.
+   *
+   * @return True if the entry value is of string array type.
+   */
+  public boolean isStringArray() {
+    return m_type == NetworkTableType.kStringArray;
+  }
+
+  /*
+   * Type-Safe Getters
+   */
+
+  /**
+   * Get the entry's boolean value.
+   *
+   * @return The boolean value.
+   * @throws ClassCastException if the entry value is not of boolean type.
+   */
+  public boolean getBoolean() {
+    if (m_type != NetworkTableType.kBoolean) {
+      throw new ClassCastException("cannot convert " + m_type + " to boolean");
+    }
+    return ((Boolean) m_value).booleanValue();
+  }
+
+  /**
+   * Get the entry's double value.
+   *
+   * @return The double value.
+   * @throws ClassCastException if the entry value is not of double type.
+   */
+  public double getDouble() {
+    if (m_type != NetworkTableType.kDouble) {
+      throw new ClassCastException("cannot convert " + m_type + " to double");
+    }
+    return ((Number) m_value).doubleValue();
+  }
+
+  /**
+   * Get the entry's string value.
+   *
+   * @return The string value.
+   * @throws ClassCastException if the entry value is not of string type.
+   */
+  public String getString() {
+    if (m_type != NetworkTableType.kString) {
+      throw new ClassCastException("cannot convert " + m_type + " to string");
+    }
+    return (String) m_value;
+  }
+
+  /**
+   * Get the entry's raw value.
+   *
+   * @return The raw value.
+   * @throws ClassCastException if the entry value is not of raw type.
+   */
+  public byte[] getRaw() {
+    if (m_type != NetworkTableType.kRaw) {
+      throw new ClassCastException("cannot convert " + m_type + " to raw");
+    }
+    return (byte[]) m_value;
+  }
+
+  /**
+   * Get the entry's rpc definition value.
+   *
+   * @return The rpc definition value.
+   * @throws ClassCastException if the entry value is not of rpc definition type.
+   */
+  public byte[] getRpc() {
+    if (m_type != NetworkTableType.kRpc) {
+      throw new ClassCastException("cannot convert " + m_type + " to rpc");
+    }
+    return (byte[]) m_value;
+  }
+
+  /**
+   * Get the entry's boolean array value.
+   *
+   * @return The boolean array value.
+   * @throws ClassCastException if the entry value is not of boolean array type.
+   */
+  public boolean[] getBooleanArray() {
+    if (m_type != NetworkTableType.kBooleanArray) {
+      throw new ClassCastException("cannot convert " + m_type + " to boolean array");
+    }
+    return (boolean[]) m_value;
+  }
+
+  /**
+   * Get the entry's double array value.
+   *
+   * @return The double array value.
+   * @throws ClassCastException if the entry value is not of double array type.
+   */
+  public double[] getDoubleArray() {
+    if (m_type != NetworkTableType.kDoubleArray) {
+      throw new ClassCastException("cannot convert " + m_type + " to double array");
+    }
+    return (double[]) m_value;
+  }
+
+  /**
+   * Get the entry's string array value.
+   *
+   * @return The string array value.
+   * @throws ClassCastException if the entry value is not of string array type.
+   */
+  public String[] getStringArray() {
+    if (m_type != NetworkTableType.kStringArray) {
+      throw new ClassCastException("cannot convert " + m_type + " to string array");
+    }
+    return (String[]) m_value;
+  }
+
+  /*
+   * Factory functions.
+   */
+
+  /**
+   * Creates a boolean entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeBoolean(boolean value) {
+    return new NetworkTableValue(NetworkTableType.kBoolean, Boolean.valueOf(value));
+  }
+
+  /**
+   * Creates a boolean entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeBoolean(boolean value, long time) {
+    return new NetworkTableValue(NetworkTableType.kBoolean, Boolean.valueOf(value), time);
+  }
+
+  /**
+   * Creates a double entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeDouble(double value) {
+    return new NetworkTableValue(NetworkTableType.kDouble, Double.valueOf(value));
+  }
+
+  /**
+   * Creates a double entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeDouble(double value, long time) {
+    return new NetworkTableValue(NetworkTableType.kDouble, Double.valueOf(value), time);
+  }
+
+  /**
+   * Creates a string entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeString(String value) {
+    return new NetworkTableValue(NetworkTableType.kString, value);
+  }
+
+  /**
+   * Creates a string entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeString(String value, long time) {
+    return new NetworkTableValue(NetworkTableType.kString, value, time);
+  }
+
+  /**
+   * Creates a raw entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeRaw(byte[] value) {
+    return new NetworkTableValue(NetworkTableType.kRaw, value);
+  }
+
+  /**
+   * Creates a raw entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeRaw(byte[] value, long time) {
+    return new NetworkTableValue(NetworkTableType.kRaw, value, time);
+  }
+
+  /**
+   * Creates a rpc entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeRpc(byte[] value) {
+    return new NetworkTableValue(NetworkTableType.kRpc, value);
+  }
+
+  /**
+   * Creates a rpc entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeRpc(byte[] value, long time) {
+    return new NetworkTableValue(NetworkTableType.kRpc, value, time);
+  }
+
+  /**
+   * Creates a boolean array entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeBooleanArray(boolean[] value) {
+    return new NetworkTableValue(NetworkTableType.kBooleanArray, value);
+  }
+
+  /**
+   * Creates a boolean array entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeBooleanArray(boolean[] value, long time) {
+    return new NetworkTableValue(NetworkTableType.kBooleanArray, value, time);
+  }
+
+  /**
+   * Creates a boolean array entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeBooleanArray(Boolean[] value) {
+    return new NetworkTableValue(NetworkTableType.kBooleanArray, toNative(value));
+  }
+
+  /**
+   * Creates a boolean array entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeBooleanArray(Boolean[] value, long time) {
+    return new NetworkTableValue(NetworkTableType.kBooleanArray, toNative(value), time);
+  }
+
+  /**
+   * Creates a double array entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeDoubleArray(double[] value) {
+    return new NetworkTableValue(NetworkTableType.kDoubleArray, value);
+  }
+
+  /**
+   * Creates a double array entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeDoubleArray(double[] value, long time) {
+    return new NetworkTableValue(NetworkTableType.kDoubleArray, value, time);
+  }
+
+  /**
+   * Creates a double array entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeDoubleArray(Number[] value) {
+    return new NetworkTableValue(NetworkTableType.kDoubleArray, toNative(value));
+  }
+
+  /**
+   * Creates a double array entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeDoubleArray(Number[] value, long time) {
+    return new NetworkTableValue(NetworkTableType.kDoubleArray, toNative(value), time);
+  }
+
+  /**
+   * Creates a string array entry value.
+   *
+   * @param value the value
+   * @return The entry value
+   */
+  public static NetworkTableValue makeStringArray(String[] value) {
+    return new NetworkTableValue(NetworkTableType.kStringArray, value);
+  }
+
+  /**
+   * Creates a string array entry value.
+   *
+   * @param value the value
+   * @param time the creation time to use (instead of the current time)
+   * @return The entry value
+   */
+  public static NetworkTableValue makeStringArray(String[] value, long time) {
+    return new NetworkTableValue(NetworkTableType.kStringArray, value, time);
+  }
+
+  @Override
+  public boolean equals(Object other) {
+    if (other == this) {
+      return true;
+    }
+    if (!(other instanceof NetworkTableValue)) {
+      return false;
+    }
+    NetworkTableValue ntOther = (NetworkTableValue) other;
+    return m_type == ntOther.m_type && m_value.equals(ntOther.m_value);
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(m_type, m_value);
+  }
+
+  static boolean[] toNative(Boolean[] arr) {
+    boolean[] out = new boolean[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i];
+    }
+    return out;
+  }
+
+  static double[] toNative(Number[] arr) {
+    double[] out = new double[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i].doubleValue();
+    }
+    return out;
+  }
+
+  static Boolean[] fromNative(boolean[] arr) {
+    Boolean[] out = new Boolean[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i];
+    }
+    return out;
+  }
+
+  static Double[] fromNative(double[] arr) {
+    Double[] out = new Double[arr.length];
+    for (int i = 0; i < arr.length; i++) {
+      out[i] = arr[i];
+    }
+    return out;
+  }
+
+  private NetworkTableType m_type;
+  private Object m_value;
+  private long m_time;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTablesJNI.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTablesJNI.java
new file mode 100644
index 0000000..1d736fc
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/NetworkTablesJNI.java
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.io.IOException;
+import java.nio.ByteBuffer;
+
+import edu.wpi.first.wpiutil.RuntimeLoader;
+
+public final class NetworkTablesJNI {
+  static boolean libraryLoaded = false;
+  static RuntimeLoader<NetworkTablesJNI> loader = null;
+
+  static {
+    if (!libraryLoaded) {
+      try {
+        loader = new RuntimeLoader<>("ntcorejni", RuntimeLoader.getDefaultExtractionRoot(), NetworkTablesJNI.class);
+        loader.loadLibrary();
+      } catch (IOException ex) {
+        ex.printStackTrace();
+        System.exit(1);
+      }
+      libraryLoaded = true;
+    }
+  }
+
+  public static native int getDefaultInstance();
+  public static native int createInstance();
+  public static native void destroyInstance(int inst);
+  public static native int getInstanceFromHandle(int handle);
+
+  public static native int getEntry(int inst, String key);
+  public static native int[] getEntries(int inst, String prefix, int types);
+  public static native String getEntryName(int entry);
+  public static native long getEntryLastChange(int entry);
+
+  public static native int getType(int entry);
+
+  public static native boolean setBoolean(int entry, long time, boolean value, boolean force);
+  public static native boolean setDouble(int entry, long time, double value, boolean force);
+  public static native boolean setString(int entry, long time, String value, boolean force);
+  public static native boolean setRaw(int entry, long time, byte[] value, boolean force);
+  public static native boolean setRaw(int entry, long time, ByteBuffer value, int len, boolean force);
+  public static native boolean setBooleanArray(int entry, long time, boolean[] value, boolean force);
+  public static native boolean setDoubleArray(int entry, long time, double[] value, boolean force);
+  public static native boolean setStringArray(int entry, long time, String[] value, boolean force);
+
+  public static native NetworkTableValue getValue(int entry);
+
+  public static native boolean getBoolean(int entry, boolean defaultValue);
+  public static native double getDouble(int entry, double defaultValue);
+  public static native String getString(int entry, String defaultValue);
+  public static native byte[] getRaw(int entry, byte[] defaultValue);
+  public static native boolean[] getBooleanArray(int entry, boolean[] defaultValue);
+  public static native double[] getDoubleArray(int entry, double[] defaultValue);
+  public static native String[] getStringArray(int entry, String[] defaultValue);
+  public static native boolean setDefaultBoolean(int entry, long time, boolean defaultValue);
+
+  public static native boolean setDefaultDouble(int entry, long time, double defaultValue);
+  public static native boolean setDefaultString(int entry, long time, String defaultValue);
+  public static native boolean setDefaultRaw(int entry, long time, byte[] defaultValue);
+  public static native boolean setDefaultBooleanArray(int entry, long time, boolean[] defaultValue);
+  public static native boolean setDefaultDoubleArray(int entry, long time, double[] defaultValue);
+  public static native boolean setDefaultStringArray(int entry, long time, String[] defaultValue);
+
+  public static native void setEntryFlags(int entry, int flags);
+  public static native int getEntryFlags(int entry);
+
+  public static native void deleteEntry(int entry);
+
+  public static native void deleteAllEntries(int inst);
+
+  public static native EntryInfo getEntryInfoHandle(NetworkTableInstance inst, int entry);
+  public static native EntryInfo[] getEntryInfo(NetworkTableInstance instObject, int inst, String prefix, int types);
+
+  public static native int createEntryListenerPoller(int inst);
+  public static native void destroyEntryListenerPoller(int poller);
+  public static native int addPolledEntryListener(int poller, String prefix, int flags);
+  public static native int addPolledEntryListener(int poller, int entry, int flags);
+  public static native EntryNotification[] pollEntryListener(NetworkTableInstance inst, int poller) throws InterruptedException;
+  public static native EntryNotification[] pollEntryListenerTimeout(NetworkTableInstance inst, int poller, double timeout) throws InterruptedException;
+  public static native void cancelPollEntryListener(int poller);
+  public static native void removeEntryListener(int entryListener);
+  public static native boolean waitForEntryListenerQueue(int inst, double timeout);
+
+  public static native int createConnectionListenerPoller(int inst);
+  public static native void destroyConnectionListenerPoller(int poller);
+  public static native int addPolledConnectionListener(int poller, boolean immediateNotify);
+  public static native ConnectionNotification[] pollConnectionListener(NetworkTableInstance inst, int poller) throws InterruptedException;
+  public static native ConnectionNotification[] pollConnectionListenerTimeout(NetworkTableInstance inst, int poller, double timeout) throws InterruptedException;
+  public static native void cancelPollConnectionListener(int poller);
+  public static native void removeConnectionListener(int connListener);
+  public static native boolean waitForConnectionListenerQueue(int inst, double timeout);
+
+  public static native int createRpcCallPoller(int inst);
+  public static native void destroyRpcCallPoller(int poller);
+  public static native void createPolledRpc(int entry, byte[] def, int poller);
+  public static native RpcAnswer[] pollRpc(NetworkTableInstance inst, int poller) throws InterruptedException;
+  public static native RpcAnswer[] pollRpcTimeout(NetworkTableInstance inst, int poller, double timeout) throws InterruptedException;
+  public static native void cancelPollRpc(int poller);
+  public static native boolean waitForRpcCallQueue(int inst, double timeout);
+  public static native boolean postRpcResponse(int entry, int call, byte[] result);
+  public static native int callRpc(int entry, byte[] params);
+  public static native byte[] getRpcResult(int entry, int call);
+  public static native byte[] getRpcResult(int entry, int call, double timeout);
+  public static native void cancelRpcResult(int entry, int call);
+
+  public static native byte[] getRpc(int entry, byte[] defaultValue);
+
+  public static native void setNetworkIdentity(int inst, String name);
+  public static native int getNetworkMode(int inst);
+  public static native void startServer(int inst, String persistFilename, String listenAddress, int port);
+  public static native void stopServer(int inst);
+  public static native void startClient(int inst);
+  public static native void startClient(int inst, String serverName, int port);
+  public static native void startClient(int inst, String[] serverNames, int[] ports);
+  public static native void startClientTeam(int inst, int team, int port);
+  public static native void stopClient(int inst);
+  public static native void setServer(int inst, String serverName, int port);
+  public static native void setServer(int inst, String[] serverNames, int[] ports);
+  public static native void setServerTeam(int inst, int team, int port);
+  public static native void startDSClient(int inst, int port);
+  public static native void stopDSClient(int inst);
+  public static native void setUpdateRate(int inst, double interval);
+
+  public static native void flush(int inst);
+
+  public static native ConnectionInfo[] getConnections(int inst);
+
+  public static native boolean isConnected(int inst);
+
+  public static native void savePersistent(int inst, String filename) throws PersistentException;
+  public static native String[] loadPersistent(int inst, String filename) throws PersistentException;  // returns warnings
+
+  public static native void saveEntries(int inst, String filename, String prefix) throws PersistentException;
+  public static native String[] loadEntries(int inst, String filename, String prefix) throws PersistentException;  // returns warnings
+
+  public static native long now();
+
+  public static native int createLoggerPoller(int inst);
+  public static native void destroyLoggerPoller(int poller);
+  public static native int addPolledLogger(int poller, int minLevel, int maxLevel);
+  public static native LogMessage[] pollLogger(NetworkTableInstance inst, int poller) throws InterruptedException;
+  public static native LogMessage[] pollLoggerTimeout(NetworkTableInstance inst, int poller, double timeout) throws InterruptedException;
+  public static native void cancelPollLogger(int poller);
+  public static native void removeLogger(int logger);
+  public static native boolean waitForLoggerQueue(int inst, double timeout);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/PersistentException.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/PersistentException.java
new file mode 100644
index 0000000..205b015
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/PersistentException.java
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.io.IOException;
+
+/**
+ * An exception thrown when persistent load/save fails in a {@link NetworkTable}.
+ */
+public final class PersistentException extends IOException {
+  public static final long serialVersionUID = 0;
+
+  public PersistentException(String message) {
+    super(message);
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java
new file mode 100644
index 0000000..91e1aa4
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/RpcAnswer.java
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables Remote Procedure Call (Server Side).
+ */
+public final class RpcAnswer {
+  /** Entry handle. */
+  @SuppressWarnings("MemberName")
+  public final int entry;
+
+  /** Call handle. */
+  @SuppressWarnings("MemberName")
+  public int call;
+
+  /** Entry name. */
+  @SuppressWarnings("MemberName")
+  public final String name;
+
+  /** Call raw parameters. */
+  @SuppressWarnings("MemberName")
+  public final byte[] params;
+
+  /** Connection that called the RPC. */
+  @SuppressWarnings("MemberName")
+  public final ConnectionInfo conn;
+
+  /** Constructor.
+   * This should generally only be used internally to NetworkTables.
+   *
+   * @param inst Instance
+   * @param entry Entry handle
+   * @param call Call handle
+   * @param name Entry name
+   * @param params Call raw parameters
+   * @param conn Connection info
+   */
+  public RpcAnswer(NetworkTableInstance inst, int entry, int call, String name, byte[] params,
+                   ConnectionInfo conn) {
+    this.m_inst = inst;
+    this.entry = entry;
+    this.call = call;
+    this.name = name;
+    this.params = params;
+    this.conn = conn;
+  }
+
+  static final byte[] emptyResponse = new byte[] {};
+
+  /*
+   * Finishes an RPC answer by replying empty if the user did not respond.
+   * Called internally by the callback thread.
+   */
+  void finish() {
+    if (call != 0) {
+      NetworkTablesJNI.postRpcResponse(entry, call, emptyResponse);
+      call = 0;
+    }
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return call != 0;
+  }
+
+  /**
+   * Post RPC response (return value) for a polled RPC.
+   *
+   * @param result  result raw data that will be provided to remote caller
+   * @return        true if the response was posted, otherwise false
+   */
+  public boolean postResponse(byte[] result) {
+    boolean ret = NetworkTablesJNI.postRpcResponse(entry, call, result);
+    call = 0;
+    return ret;
+  }
+
+  /* Network table instance. */
+  private final NetworkTableInstance m_inst;
+
+  /* Cached entry object. */
+  NetworkTableEntry m_entryObject;
+
+  /**
+   * Get the entry as an object.
+   *
+   * @return NetworkTableEntry for the RPC.
+   */
+  NetworkTableEntry getEntry() {
+    if (m_entryObject == null) {
+      m_entryObject = new NetworkTableEntry(m_inst, entry);
+    }
+    return m_entryObject;
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/RpcCall.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/RpcCall.java
new file mode 100644
index 0000000..1b377f6
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/RpcCall.java
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * NetworkTables Remote Procedure Call.
+ */
+public final class RpcCall implements AutoCloseable {
+  /** Constructor.
+   * This should generally only be used internally to NetworkTables.
+   *
+   * @param entry Entry
+   * @param call Call handle
+   */
+  public RpcCall(NetworkTableEntry entry, int call) {
+    m_entry = entry;
+    m_call = call;
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  /**
+   * Cancels the result if no other action taken.
+   */
+  @Override
+  public synchronized void close() {
+    if (m_call != 0) {
+      cancelResult();
+    }
+  }
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  public boolean isValid() {
+    return m_call != 0;
+  }
+
+  /**
+   * Get the RPC entry.
+   *
+   * @return NetworkTableEntry for the RPC.
+   */
+  public NetworkTableEntry getEntry() {
+    return m_entry;
+  }
+
+  /**
+   * Get the call native handle.
+   *
+   * @return Native handle.
+   */
+  public int getCall() {
+    return m_call;
+  }
+
+  /**
+   * Get the result (return value).  This function blocks until
+   * the result is received.
+   *
+   * @return Received result (output)
+   */
+  public byte[] getResult() {
+    byte[] result = NetworkTablesJNI.getRpcResult(m_entry.getHandle(), m_call);
+    if (result.length != 0) {
+      m_call = 0;
+    }
+    return result;
+  }
+
+  /**
+   * Get the result (return value).  This function blocks until
+   * the result is received or it times out.
+   *
+   * @param timeout     timeout, in seconds
+   * @return Received result (output)
+   */
+  public byte[] getResult(double timeout) {
+    byte[] result = NetworkTablesJNI.getRpcResult(m_entry.getHandle(), m_call, timeout);
+    if (result.length != 0) {
+      m_call = 0;
+    }
+    return result;
+  }
+
+  /**
+   * Ignore the result.  This function is non-blocking.
+   */
+  public void cancelResult() {
+    NetworkTablesJNI.cancelRpcResult(m_entry.getHandle(), m_call);
+  }
+
+  private final NetworkTableEntry m_entry;
+  private int m_call;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/TableEntryListener.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/TableEntryListener.java
new file mode 100644
index 0000000..676e57e
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/TableEntryListener.java
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * A listener that listens to changes in values in a {@link NetworkTable}.
+ */
+@FunctionalInterface
+public interface TableEntryListener extends EntryListenerFlags {
+  /**
+   * Called when a key-value pair is changed in a {@link NetworkTable}.
+   *
+   * @param table the table the key-value pair exists in
+   * @param key the key associated with the value that changed
+   * @param entry the entry associated with the value that changed
+   * @param value the new value
+   * @param flags update flags; for example, EntryListenerFlags.kNew if the key
+   *     did not previously exist in the table
+   */
+  void valueChanged(NetworkTable table, String key, NetworkTableEntry entry,
+                    NetworkTableValue value, int flags);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/TableListener.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/TableListener.java
new file mode 100644
index 0000000..3c686e5
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/networktables/TableListener.java
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+/**
+ * A listener that listens to new tables in a {@link NetworkTable}.
+ */
+@FunctionalInterface
+public interface TableListener {
+  /**
+   * Called when a new table is created within a {@link NetworkTable}.
+   *
+   * @param parent the parent of the table
+   * @param name the name of the new table
+   * @param table the new table
+   */
+  void tableCreated(NetworkTable parent, String name, NetworkTable table);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/networktables/NetworkTable.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/networktables/NetworkTable.java
new file mode 100644
index 0000000..f360a19
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/networktables/NetworkTable.java
@@ -0,0 +1,1189 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.networktables;
+
+import java.nio.ByteBuffer;
+import java.util.ArrayList;
+import java.util.HashMap;
+import java.util.HashSet;
+import java.util.List;
+import java.util.Objects;
+import java.util.Set;
+import java.util.concurrent.ConcurrentHashMap;
+import java.util.concurrent.ConcurrentMap;
+import java.util.function.Consumer;
+
+import edu.wpi.first.networktables.ConnectionInfo;
+import edu.wpi.first.networktables.ConnectionNotification;
+import edu.wpi.first.networktables.EntryInfo;
+import edu.wpi.first.networktables.EntryNotification;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.networktables.NetworkTableType;
+import edu.wpi.first.networktables.NetworkTableValue;
+import edu.wpi.first.networktables.NetworkTablesJNI;
+import edu.wpi.first.networktables.PersistentException;
+import edu.wpi.first.wpilibj.tables.IRemote;
+import edu.wpi.first.wpilibj.tables.IRemoteConnectionListener;
+import edu.wpi.first.wpilibj.tables.ITable;
+import edu.wpi.first.wpilibj.tables.ITableListener;
+
+/**
+ * A network table that knows its subtable path.
+ * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable} instead.
+ */
+@Deprecated
+@SuppressWarnings("checkstyle:all")
+public class NetworkTable implements ITable, IRemote {
+  /**
+   * The path separator for sub-tables and keys
+   *
+   */
+  public static final char PATH_SEPARATOR = '/';
+  /**
+   * The default port that network tables operates on
+   */
+  public static final int DEFAULT_PORT = 1735;
+
+  private static boolean client = false;
+  private static boolean enableDS = true;
+  private static boolean running = false;
+  private static int port = DEFAULT_PORT;
+  private static String persistentFilename = "networktables.ini";
+
+  private synchronized static void checkInit() {
+    if (running)
+      throw new IllegalStateException(
+          "Network tables has already been initialized");
+  }
+
+  /**
+   * initializes network tables
+   * @deprecated Use {@link NetworkTableInstance#startServer()} or
+   * {@link NetworkTableInstance#startClient()} instead.
+   */
+  @Deprecated
+  public synchronized static void initialize() {
+    if (running)
+      shutdown();
+    NetworkTableInstance inst = NetworkTableInstance.getDefault();
+    if (client) {
+      inst.startClient();
+      if (enableDS)
+        inst.startDSClient(port);
+    } else
+      inst.startServer(persistentFilename, "", port);
+    running = true;
+  }
+
+  /**
+   * shuts down network tables
+   * @deprecated Use {@link NetworkTableInstance#stopServer()} or
+   * {@link NetworkTableInstance#stopClient()} instead.
+   */
+  @Deprecated
+  public synchronized static void shutdown() {
+    if (!running)
+      return;
+    NetworkTableInstance inst = NetworkTableInstance.getDefault();
+    if (client) {
+      inst.stopDSClient();
+      inst.stopClient();
+    } else
+      inst.stopServer();
+    running = false;
+  }
+
+  /**
+   * set that network tables should be a server
+   * This must be called before initialize or getTable
+   * @deprecated Use {@link NetworkTableInstance#startServer()} instead.
+   */
+  @Deprecated
+  public synchronized static void setServerMode() {
+    if (!client)
+      return;
+    checkInit();
+    client = false;
+  }
+
+  /**
+   * set that network tables should be a client
+   * This must be called before initialize or getTable
+   * @deprecated Use {@link NetworkTableInstance#startClient()} instead.
+   */
+  @Deprecated
+  public synchronized static void setClientMode() {
+    if (client)
+      return;
+    checkInit();
+    client = true;
+  }
+
+  /**
+   * set the team the robot is configured for (this will set the mdns address that
+   * network tables will connect to in client mode)
+   * This must be called before initialize or getTable
+   * @param team the team number
+   * @deprecated Use {@link NetworkTableInstance#setServerTeam(int)} or
+   * {@link NetworkTableInstance#startClientTeam(int)} instead.
+   */
+  @Deprecated
+  public synchronized static void setTeam(int team) {
+    NetworkTableInstance inst = NetworkTableInstance.getDefault();
+    inst.setServerTeam(team, port);
+    if (enableDS)
+      inst.startDSClient(port);
+  }
+
+  /**
+   * @param address the address that network tables will connect to in client
+   * mode
+   * @deprecated Use {@link NetworkTableInstance#setServer(String)} or
+   * {@link NetworkTableInstance#startClient(String)} instead.
+   */
+  @Deprecated
+  public synchronized static void setIPAddress(final String address) {
+    String[] addresses = new String[1];
+    addresses[0] = address;
+    setIPAddress(addresses);
+  }
+
+  /**
+   * @param addresses the adresses that network tables will connect to in
+   * client mode (in round robin order)
+   * @deprecated Use {@link NetworkTableInstance#setServer(String[])} or
+   * {@link NetworkTableInstance#startClient(String[])} instead.
+   */
+  @Deprecated
+  public synchronized static void setIPAddress(final String[] addresses) {
+    NetworkTableInstance inst = NetworkTableInstance.getDefault();
+    inst.setServer(addresses, port);
+
+    // Stop the DS client if we're explicitly connecting to localhost
+    if (addresses.length > 0 &&
+        (addresses[0].equals("localhost") || addresses[0].equals("127.0.0.1")))
+      inst.stopDSClient();
+    else if (enableDS)
+      inst.startDSClient(port);
+  }
+
+  /**
+   * Set the port number that network tables will connect to in client
+   * mode or listen to in server mode.
+   * @param aport the port number
+   * @deprecated Use the appropriate parameters to
+   * {@link NetworkTableInstance#setServer(String, int)},
+   * {@link NetworkTableInstance#startClient(String, int)},
+   * {@link NetworkTableInstance#startServer(String, String, int)}, and
+   * {@link NetworkTableInstance#startDSClient(int)} instead.
+   */
+  @Deprecated
+  public synchronized static void setPort(int aport) {
+    if (port == aport)
+      return;
+    checkInit();
+    port = aport;
+  }
+
+  /**
+   * Enable requesting the server address from the Driver Station.
+   * @param enabled whether to enable the connection to the local DS
+   * @deprecated Use {@link NetworkTableInstance#startDSClient()} and
+   * {@link NetworkTableInstance#stopDSClient()} instead.
+   */
+  @Deprecated
+  public synchronized static void setDSClientEnabled(boolean enabled) {
+    NetworkTableInstance inst = NetworkTableInstance.getDefault();
+    enableDS = enabled;
+    if (enableDS)
+      inst.startDSClient(port);
+    else
+      inst.stopDSClient();
+  }
+
+  /**
+   * Sets the persistent filename.
+   * @param filename the filename that the network tables server uses for
+   * automatic loading and saving of persistent values
+   * @deprecated Use the appropriate parameter to
+   * {@link NetworkTableInstance#startServer()} instead.
+   */
+  @Deprecated
+  public synchronized static void setPersistentFilename(final String filename) {
+    if (persistentFilename.equals(filename))
+      return;
+    checkInit();
+    persistentFilename = filename;
+  }
+
+  /**
+   * Sets the network identity.
+   * This is provided in the connection info on the remote end.
+   * @param name identity
+   * @deprecated Use {@link NetworkTableInstance#setNetworkIdentity(String)}
+   * instead.
+   */
+  @Deprecated
+  public static void setNetworkIdentity(String name) {
+    NetworkTableInstance.getDefault().setNetworkIdentity(name);
+  }
+
+  public static boolean[] toNative(Boolean[] arr) {
+    boolean[] out = new boolean[arr.length];
+    for (int i = 0; i < arr.length; i++)
+      out[i] = arr[i];
+    return out;
+  }
+
+  public static double[] toNative(Number[] arr) {
+    double[] out = new double[arr.length];
+    for (int i = 0; i < arr.length; i++)
+      out[i] = arr[i].doubleValue();
+    return out;
+  }
+
+  public static Boolean[] fromNative(boolean[] arr) {
+    Boolean[] out = new Boolean[arr.length];
+    for (int i = 0; i < arr.length; i++)
+      out[i] = arr[i];
+    return out;
+  }
+
+  public static Double[] fromNative(double[] arr) {
+    Double[] out = new Double[arr.length];
+    for (int i = 0; i < arr.length; i++)
+      out[i] = arr[i];
+    return out;
+  }
+
+  /**
+   * Gets the table with the specified key. If the table does not exist, a new
+   * table will be created.<br>
+   * This will automatically initialize network tables if it has not been
+   * already
+   *
+   * @deprecated Use {@link NetworkTableInstance#getTable(String)} instead.
+   *
+   * @param key   the key name
+   * @return the network table requested
+   */
+  @Deprecated
+  public synchronized static NetworkTable getTable(String key) {
+    if (!running)
+      initialize();
+    String theKey;
+    if (key.isEmpty() || key.equals("/")) {
+      theKey = "";
+    } else if (key.charAt(0) == NetworkTable.PATH_SEPARATOR) {
+      theKey = key;
+    } else {
+      theKey = NetworkTable.PATH_SEPARATOR + key;
+    }
+    return new NetworkTable(NetworkTableInstance.getDefault(), theKey);
+  }
+
+  private final String path;
+  private final String pathWithSep;
+  private final NetworkTableInstance inst;
+
+  NetworkTable(NetworkTableInstance inst, String path) {
+    this.path = path;
+    this.pathWithSep = path + PATH_SEPARATOR;
+    this.inst = inst;
+  }
+
+  @Override
+  public String toString() { return "NetworkTable: " + path; }
+
+  private final ConcurrentMap<String, NetworkTableEntry> entries = new ConcurrentHashMap<String, NetworkTableEntry>();
+
+  /**
+   * Gets the entry for a subkey.
+   * @param key the key name
+   * @return Network table entry.
+   */
+  private NetworkTableEntry getEntry(String key) {
+    NetworkTableEntry entry = entries.get(key);
+    if (entry == null) {
+      entry = inst.getEntry(pathWithSep + key);
+      entries.putIfAbsent(key, entry);
+    }
+    return entry;
+  }
+
+  /**
+   * Gets the current network connections.
+   * @return An array of connection information.
+   * @deprecated Use {@link NetworkTableInstance#getConnections()} instead.
+   */
+  @Deprecated
+  public static ConnectionInfo[] connections() {
+    return NetworkTableInstance.getDefault().getConnections();
+  }
+
+  /**
+   * Determine whether or not a network connection is active.
+   * @return True if connected, false if not connected.
+   * @deprecated Use {@link NetworkTableInstance#isConnected()} instead.
+   */
+  @Override
+  @Deprecated
+  public boolean isConnected() {
+    return inst.isConnected();
+  }
+
+  /**
+   * Determine whether NetworkTables is operating as a server or as a client.
+   * @return True if operating as a server, false otherwise.
+   * @deprecated Use {@link NetworkTableInstance#getNetworkMode()} instead.
+   */
+  @Override
+  @Deprecated
+  public boolean isServer() {
+    return (inst.getNetworkMode() & NetworkTableInstance.kNetModeServer) != 0;
+  }
+
+  /* Backwards compatibility shims for IRemoteConnectionListener */
+  private static class ConnectionListenerAdapter implements Consumer<ConnectionNotification> {
+    public int uid;
+    private final IRemote targetSource;
+    private final IRemoteConnectionListener targetListener;
+
+    public ConnectionListenerAdapter(IRemote targetSource, IRemoteConnectionListener targetListener) {
+      this.targetSource = targetSource;
+      this.targetListener = targetListener;
+    }
+
+    @Override
+    public void accept(ConnectionNotification event) {
+      if (event.connected)
+        targetListener.connectedEx(targetSource, event.conn);
+      else
+        targetListener.disconnectedEx(targetSource, event.conn);
+    }
+  }
+
+  private static final HashMap<IRemoteConnectionListener,ConnectionListenerAdapter> globalConnectionListenerMap = new HashMap<IRemoteConnectionListener,ConnectionListenerAdapter>();
+
+  private static IRemote staticRemote = new IRemote() {
+    @Override
+    public void addConnectionListener(IRemoteConnectionListener listener, boolean immediateNotify) {
+      NetworkTable.addGlobalConnectionListener(listener, immediateNotify);
+    }
+    @Override
+    public void removeConnectionListener(IRemoteConnectionListener listener) {
+      NetworkTable.removeGlobalConnectionListener(listener);
+    }
+    @Override
+    public boolean isConnected() {
+      ConnectionInfo[] conns = NetworkTableInstance.getDefault().getConnections();
+      return conns.length > 0;
+    }
+    @Override
+    public boolean isServer() {
+      return (NetworkTableInstance.getDefault().getNetworkMode() & NetworkTableInstance.kNetModeServer) != 0;
+    }
+  };
+
+  private final HashMap<IRemoteConnectionListener,ConnectionListenerAdapter> connectionListenerMap = new HashMap<IRemoteConnectionListener,ConnectionListenerAdapter>();
+
+  /**
+   * Add a connection listener.
+   * @param listener connection listener
+   * @param immediateNotify call listener immediately for all existing connections
+   * @deprecated Use {@link NetworkTableInstance#addConnectionListener(Consumer, boolean)} instead.
+   */
+  @Deprecated
+  public static synchronized void addGlobalConnectionListener(IRemoteConnectionListener listener, boolean immediateNotify) {
+    ConnectionListenerAdapter adapter = new ConnectionListenerAdapter(staticRemote, listener);
+    if (globalConnectionListenerMap.putIfAbsent(listener, adapter) != null) {
+      throw new IllegalStateException("Cannot add the same listener twice");
+    }
+    adapter.uid = NetworkTableInstance.getDefault().addConnectionListener(adapter, immediateNotify);
+  }
+
+  /**
+   * Remove a connection listener.
+   * @param listener connection listener
+   * @deprecated Use {@link NetworkTableInstance#removeConnectionListener(int)} instead.
+   */
+  @Deprecated
+  public static synchronized void removeGlobalConnectionListener(IRemoteConnectionListener listener) {
+    ConnectionListenerAdapter adapter = globalConnectionListenerMap.remove(listener);
+    if (adapter != null) {
+      NetworkTableInstance.getDefault().removeConnectionListener(adapter.uid);
+    }
+  }
+
+  /**
+   * Add a connection listener.
+   * @param listener connection listener
+   * @param immediateNotify call listener immediately for all existing connections
+   * @deprecated Use {@link NetworkTableInstance#addConnectionListener(Consumer, boolean)} instead.
+   */
+  @Override
+  @Deprecated
+  public synchronized void addConnectionListener(IRemoteConnectionListener listener,
+                                                 boolean immediateNotify) {
+    ConnectionListenerAdapter adapter = new ConnectionListenerAdapter(this, listener);
+    if (connectionListenerMap.putIfAbsent(listener, adapter) != null) {
+      throw new IllegalStateException("Cannot add the same listener twice");
+    }
+    adapter.uid = inst.addConnectionListener(adapter, immediateNotify);
+  }
+
+  /**
+   * Remove a connection listener.
+   * @param listener connection listener
+   * @deprecated Use {@link NetworkTableInstance#removeConnectionListener(int)} instead.
+   */
+  @Override
+  @Deprecated
+  public synchronized void removeConnectionListener(IRemoteConnectionListener listener) {
+    ConnectionListenerAdapter adapter = connectionListenerMap.get(listener);
+    if (adapter != null && connectionListenerMap.remove(listener, adapter)) {
+      inst.removeConnectionListener(adapter.uid);
+    }
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable#addEntryListener(TableEntryListener, int)} instead
+   * (with flags value of NOTIFY_NEW | NOTIFY_UPDATE).
+   */
+  @Override
+  @Deprecated
+  public void addTableListener(ITableListener listener) {
+    addTableListenerEx(listener, NOTIFY_NEW | NOTIFY_UPDATE);
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable#addEntryListener(TableEntryListener, int)} instead
+   * (with flags value of NOTIFY_NEW | NOTIFY_UPDATE | NOTIFY_IMMEDIATE).
+   */
+  @Override
+  @Deprecated
+  public void addTableListener(ITableListener listener,
+                               boolean immediateNotify) {
+    int flags = NOTIFY_NEW | NOTIFY_UPDATE;
+    if (immediateNotify)
+      flags |= NOTIFY_IMMEDIATE;
+    addTableListenerEx(listener, flags);
+  }
+
+  /* Base class for listeners; stores uid to implement remove functions */
+  private static class ListenerBase {
+    public int uid;
+  }
+
+  private static class OldTableListenerAdapter extends ListenerBase implements Consumer<EntryNotification> {
+    private final int prefixLen;
+    private final ITable targetSource;
+    private final ITableListener targetListener;
+
+    public OldTableListenerAdapter(int prefixLen, ITable targetSource, ITableListener targetListener) {
+      this.prefixLen = prefixLen;
+      this.targetSource = targetSource;
+      this.targetListener = targetListener;
+    }
+
+    @Override
+    public void accept(EntryNotification event) {
+      String relativeKey = event.name.substring(prefixLen);
+      if (relativeKey.indexOf(PATH_SEPARATOR) != -1)
+        return;
+      targetListener.valueChangedEx(targetSource, relativeKey, event.value.getValue(), event.flags);
+    }
+  }
+
+  private final HashMap<ITableListener,List<ListenerBase>> oldListenerMap = new HashMap<ITableListener,List<ListenerBase>>();
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable#addEntryListener(TableEntryListener, int)} instead.
+   */
+  @Override
+  @Deprecated
+  public synchronized void addTableListenerEx(ITableListener listener,
+                                              int flags) {
+    List<ListenerBase> adapters = oldListenerMap.get(listener);
+    if (adapters == null) {
+      adapters = new ArrayList<ListenerBase>();
+      oldListenerMap.put(listener, adapters);
+    }
+    OldTableListenerAdapter adapter =
+        new OldTableListenerAdapter(path.length() + 1, this, listener);
+    adapter.uid = inst.addEntryListener(pathWithSep, adapter, flags);
+    adapters.add(adapter);
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable#addEntryListener(String, TableEntryListener, int)}
+   * or {@link NetworkTableEntry#addListener(Consumer, int)} instead.
+   */
+  @Override
+  @Deprecated
+  public void addTableListener(String key, ITableListener listener,
+                               boolean immediateNotify) {
+    int flags = NOTIFY_NEW | NOTIFY_UPDATE;
+    if (immediateNotify)
+      flags |= NOTIFY_IMMEDIATE;
+    addTableListenerEx(key, listener, flags);
+  }
+
+  private static class OldKeyListenerAdapter extends ListenerBase implements Consumer<EntryNotification> {
+    private final String relativeKey;
+    private final ITable targetSource;
+    private final ITableListener targetListener;
+
+    public OldKeyListenerAdapter(String relativeKey, ITable targetSource, ITableListener targetListener) {
+      this.relativeKey = relativeKey;
+      this.targetSource = targetSource;
+      this.targetListener = targetListener;
+    }
+
+    @Override
+    public void accept(EntryNotification event) {
+      targetListener.valueChangedEx(targetSource, relativeKey, event.value.getValue(), event.flags);
+    }
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable#addEntryListener(String, TableEntryListener, int)}
+   * or {@link NetworkTableEntry#addListener(Consumer, int)} instead.
+   */
+  @Override
+  @Deprecated
+  public synchronized void addTableListenerEx(String key,
+                                              ITableListener listener,
+                                              int flags) {
+    List<ListenerBase> adapters = oldListenerMap.get(listener);
+    if (adapters == null) {
+      adapters = new ArrayList<ListenerBase>();
+      oldListenerMap.put(listener, adapters);
+    }
+    OldKeyListenerAdapter adapter = new OldKeyListenerAdapter(key, this, listener);
+    adapter.uid = inst.addEntryListener(getEntry(key), adapter, flags);
+    adapters.add(adapter);
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable#addSubTableListener(TableListener, boolean)}
+   * instead.
+   */
+  @Override
+  @Deprecated
+  public void addSubTableListener(final ITableListener listener) {
+    addSubTableListener(listener, false);
+  }
+
+  private static class OldSubListenerAdapter extends ListenerBase implements Consumer<EntryNotification> {
+    private final int prefixLen;
+    private final ITable targetSource;
+    private final ITableListener targetListener;
+    private final Set<String> notifiedTables = new HashSet<String>();
+
+    public OldSubListenerAdapter(int prefixLen, ITable targetSource, ITableListener targetListener) {
+      this.prefixLen = prefixLen;
+      this.targetSource = targetSource;
+      this.targetListener = targetListener;
+    }
+
+    @Override
+    public void accept(EntryNotification event) {
+      String relativeKey = event.name.substring(prefixLen);
+      int endSubTable = relativeKey.indexOf(PATH_SEPARATOR);
+      if (endSubTable == -1)
+        return;
+      String subTableKey = relativeKey.substring(0, endSubTable);
+      if (notifiedTables.contains(subTableKey))
+        return;
+      notifiedTables.add(subTableKey);
+      targetListener.valueChangedEx(targetSource, subTableKey, targetSource.getSubTable(subTableKey), event.flags);
+    }
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable#addSubTableListener(TableListener, boolean)}
+   * instead.
+   */
+  @Override
+  @Deprecated
+  public synchronized void addSubTableListener(final ITableListener listener,
+                                               boolean localNotify) {
+    List<ListenerBase> adapters = oldListenerMap.get(listener);
+    if (adapters == null) {
+      adapters = new ArrayList<ListenerBase>();
+      oldListenerMap.put(listener, adapters);
+    }
+    OldSubListenerAdapter adapter =
+        new OldSubListenerAdapter(path.length() + 1, this, listener);
+    int flags = NOTIFY_NEW | NOTIFY_IMMEDIATE;
+    if (localNotify)
+      flags |= NOTIFY_LOCAL;
+    adapter.uid = inst.addEntryListener(pathWithSep, adapter, flags);
+    adapters.add(adapter);
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable#removeTableListener(int)} instead.
+   */
+  @Override
+  @Deprecated
+  public synchronized void removeTableListener(ITableListener listener) {
+    List<ListenerBase> adapters = oldListenerMap.remove(listener);
+    if (adapters != null) {
+      for (ListenerBase adapter : adapters)
+        inst.removeEntryListener(adapter.uid);
+    }
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public ITable getSubTable(String key) {
+    return new NetworkTable(inst, pathWithSep + key);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean containsKey(String key) {
+    return getEntry(key).exists();
+  }
+
+  @Override
+  public boolean containsSubTable(String key) {
+    int[] handles = NetworkTablesJNI.getEntries(inst.getHandle(), pathWithSep + key + PATH_SEPARATOR, 0);
+    return handles.length != 0;
+  }
+
+  /**
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return keys currently in the table
+   */
+  @Override
+  public Set<String> getKeys(int types) {
+    Set<String> keys = new HashSet<String>();
+    int prefixLen = path.length() + 1;
+    for (EntryInfo info : inst.getEntryInfo(pathWithSep, types)) {
+      String relativeKey = info.name.substring(prefixLen);
+      if (relativeKey.indexOf(PATH_SEPARATOR) != -1)
+        continue;
+      keys.add(relativeKey);
+      // populate entries as we go
+      if (entries.get(relativeKey) == null) {
+        entries.putIfAbsent(relativeKey, new NetworkTableEntry(inst, info.entry));
+      }
+    }
+    return keys;
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public Set<String> getKeys() {
+    return getKeys(0);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public Set<String> getSubTables() {
+    Set<String> keys = new HashSet<String>();
+    int prefixLen = path.length() + 1;
+    for (EntryInfo info : inst.getEntryInfo(pathWithSep, 0)) {
+      String relativeKey = info.name.substring(prefixLen);
+      int endSubTable = relativeKey.indexOf(PATH_SEPARATOR);
+      if (endSubTable == -1)
+        continue;
+      keys.add(relativeKey.substring(0, endSubTable));
+    }
+    return keys;
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putNumber(String key, double value) {
+    return getEntry(key).setNumber(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultNumber(String key, double defaultValue) {
+    return getEntry(key).setDefaultDouble(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public double getNumber(String key, double defaultValue) {
+    return getEntry(key).getDouble(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putString(String key, String value) {
+    return getEntry(key).setString(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultString(String key, String defaultValue) {
+    return getEntry(key).setDefaultString(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public String getString(String key, String defaultValue) {
+    return getEntry(key).getString(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putBoolean(String key, boolean value) {
+    return getEntry(key).setBoolean(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultBoolean(String key, boolean defaultValue) {
+    return getEntry(key).setDefaultBoolean(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean getBoolean(String key, boolean defaultValue) {
+    return getEntry(key).getBoolean(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putBooleanArray(String key, boolean[] value) {
+    return getEntry(key).setBooleanArray(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putBooleanArray(String key, Boolean[] value) {
+    return getEntry(key).setBooleanArray(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultBooleanArray(String key, boolean[] defaultValue) {
+    return getEntry(key).setDefaultBooleanArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultBooleanArray(String key, Boolean[] defaultValue) {
+    return getEntry(key).setDefaultBooleanArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean[] getBooleanArray(String key, boolean[] defaultValue) {
+    return getEntry(key).getBooleanArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public Boolean[] getBooleanArray(String key, Boolean[] defaultValue) {
+    return getEntry(key).getBooleanArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putNumberArray(String key, double[] value) {
+    return getEntry(key).setDoubleArray(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putNumberArray(String key, Double[] value) {
+    return getEntry(key).setNumberArray(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultNumberArray(String key, double[] defaultValue) {
+    return getEntry(key).setDefaultDoubleArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultNumberArray(String key, Double[] defaultValue) {
+    return getEntry(key).setDefaultNumberArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public double[] getNumberArray(String key, double[] defaultValue) {
+    return getEntry(key).getDoubleArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public Double[] getNumberArray(String key, Double[] defaultValue) {
+    return getEntry(key).getDoubleArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putStringArray(String key, String[] value) {
+    return getEntry(key).setStringArray(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultStringArray(String key, String[] defaultValue) {
+    return getEntry(key).setDefaultStringArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public String[] getStringArray(String key, String[] defaultValue) {
+    return getEntry(key).getStringArray(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putRaw(String key, byte[] value) {
+    return getEntry(key).setRaw(value);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean setDefaultRaw(String key, byte[] defaultValue) {
+    return getEntry(key).setDefaultRaw(defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean putRaw(String key, ByteBuffer value, int len) {
+    return getEntry(key).setRaw(value, len);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public byte[] getRaw(String key, byte[] defaultValue) {
+    return getEntry(key).getRaw(defaultValue);
+  }
+
+  /**
+   * Put a value in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putValue(String key, NetworkTableValue value) {
+    return getEntry(key).setValue(value);
+  }
+
+  /**
+   * Sets the current value in the table if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultValue(String key, NetworkTableValue defaultValue) {
+    return getEntry(key).setDefaultValue(defaultValue);
+  }
+
+  /**
+   * Gets the value associated with a key as a NetworkTableValue object.
+   * @param key the key of the value to look up
+   * @return the value associated with the given key
+   */
+  public NetworkTableValue getValue(String key) {
+    return getEntry(key).getValue();
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTableEntry#setValue(Object)}
+   * instead, e.g. `NetworkTable.getEntry(key).setValue(NetworkTableEntry.makeBoolean(false));`
+   * or `NetworkTable.getEntry(key).setValue(new Boolean(false));`
+   */
+  @Override
+  @Deprecated
+  public boolean putValue(String key, Object value) throws IllegalArgumentException {
+    if (value instanceof Boolean)
+      return putBoolean(key, ((Boolean)value).booleanValue());
+    else if (value instanceof Number)
+      return putDouble(key, ((Number)value).doubleValue());
+    else if (value instanceof String)
+      return putString(key, (String)value);
+    else if (value instanceof byte[])
+      return putRaw(key, (byte[])value);
+    else if (value instanceof boolean[])
+      return putBooleanArray(key, (boolean[])value);
+    else if (value instanceof double[])
+      return putNumberArray(key, (double[])value);
+    else if (value instanceof Boolean[])
+      return putBooleanArray(key, toNative((Boolean[])value));
+    else if (value instanceof Number[])
+      return putNumberArray(key, toNative((Number[])value));
+    else if (value instanceof String[])
+      return putStringArray(key, (String[])value);
+    else if (value instanceof NetworkTableValue)
+      return getEntry(key).setValue((NetworkTableValue)value);
+    else
+      throw new IllegalArgumentException("Value of type " + value.getClass().getName() + " cannot be put into a table");
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link edu.wpi.first.networktables.NetworkTableEntry#getValue()}
+   * instead, e.g. `NetworkTable.getEntry(key).getValue();`
+   */
+  @Override
+  @Deprecated
+  public Object getValue(String key, Object defaultValue) {
+    NetworkTableValue value = getValue(key);
+    if (value.getType() == NetworkTableType.kUnassigned) {
+      return defaultValue;
+    }
+    return value.getValue();
+  }
+
+  /** The persistent flag value. */
+  public static final int PERSISTENT = 1;
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public void setPersistent(String key) {
+    getEntry(key).setPersistent();
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public void clearPersistent(String key) {
+    getEntry(key).clearPersistent();
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public boolean isPersistent(String key) {
+    return getEntry(key).isPersistent();
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public void setFlags(String key, int flags) {
+    getEntry(key).setFlags(flags);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public void clearFlags(String key, int flags) {
+    getEntry(key).clearFlags(flags);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public int getFlags(String key) {
+    return getEntry(key).getFlags();
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public void delete(String key) {
+    getEntry(key).delete();
+  }
+
+  /**
+   * Deletes ALL keys in ALL subtables.  Use with caution!
+   * @deprecated Use {@link NetworkTableInstance#deleteAllEntries()} instead.
+   */
+  @Deprecated
+  public static void globalDeleteAll() {
+    NetworkTableInstance.getDefault().deleteAllEntries();
+  }
+
+  /**
+   * Flushes all updated values immediately to the network.
+   * Note: This is rate-limited to protect the network from flooding.
+   * This is primarily useful for synchronizing network updates with
+   * user code.
+   * @deprecated Use {@link NetworkTableInstance#flush()} instead.
+   */
+  @Deprecated
+  public static void flush() {
+    NetworkTableInstance.getDefault().flush();
+  }
+
+  /**
+   * Set the periodic update rate.
+   *
+   * @param interval update interval in seconds (range 0.01 to 1.0)
+   * @deprecated Use {@link NetworkTableInstance#setUpdateRate(double)}
+   * instead.
+   */
+  @Deprecated
+  public static void setUpdateRate(double interval) {
+    NetworkTableInstance.getDefault().setUpdateRate(interval);
+  }
+
+  /**
+   * Saves persistent keys to a file.  The server does this automatically.
+   *
+   * @param filename file name
+   * @throws PersistentException if error saving file
+   * @deprecated Use {@link NetworkTableInstance#savePersistent(String)}
+   * instead.
+   */
+  @Deprecated
+  public static void savePersistent(String filename) throws PersistentException {
+    NetworkTableInstance.getDefault().savePersistent(filename);
+  }
+
+  /**
+   * Loads persistent keys from a file.  The server does this automatically.
+   *
+   * @param filename file name
+   * @return List of warnings (errors result in an exception instead)
+   * @throws PersistentException if error reading file
+   * @deprecated Use {@link NetworkTableInstance#loadPersistent(String)}
+   * instead.
+   */
+  @Deprecated
+  public static String[] loadPersistent(String filename) throws PersistentException {
+    return NetworkTableInstance.getDefault().loadPersistent(filename);
+  }
+
+  /*
+   * Deprecated Methods
+   */
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link #putNumber(String, double)} instead.
+   */
+  @Override
+  @Deprecated
+  public boolean putDouble(String key, double value) {
+    return putNumber(key, value);
+  }
+
+  /**
+   * {@inheritDoc}
+   * @deprecated Use {@link #getNumber(String, double)} instead.
+   */
+  @Override
+  @Deprecated
+  public double getDouble(String key, double defaultValue) {
+    return getNumber(key, defaultValue);
+  }
+
+  /**
+   * {@inheritDoc}
+   */
+  @Override
+  public String getPath() {
+    return path;
+  }
+
+  @Override
+  public boolean equals(Object o) {
+    if (o == this) {
+      return true;
+    }
+    if (!(o instanceof NetworkTable)) {
+      return false;
+    }
+    NetworkTable other = (NetworkTable) o;
+    return inst.equals(other.inst) && path.equals(other.path);
+  }
+
+  @Override
+  public int hashCode() {
+    return Objects.hash(inst, path);
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/IRemote.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/IRemote.java
new file mode 100644
index 0000000..22b6f96
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/IRemote.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.tables;
+
+
+/**
+ * Represents an object that has a remote connection.
+ * @deprecated Use {@link edu.wpi.first.networktables.NetworkTableInstance}.
+ */
+@Deprecated
+@SuppressWarnings("checkstyle:all")
+public interface IRemote {
+  /**
+   * Register an object to listen for connection and disconnection events
+   *
+   * @param listener the listener to be register
+   * @param immediateNotify if the listener object should be notified of the current connection state
+   */
+  public void addConnectionListener(IRemoteConnectionListener listener, boolean immediateNotify);
+
+  /**
+   * Unregister a listener from connection events
+   *
+   * @param listener the listener to be unregistered
+   */
+  public void removeConnectionListener(IRemoteConnectionListener listener);
+
+  /**
+   * Get the current state of the objects connection
+   * @return the current connection state
+   */
+    public boolean isConnected();
+
+  /**
+   * If the object is acting as a server
+   * @return if the object is a server
+   */
+    public boolean isServer();
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/IRemoteConnectionListener.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/IRemoteConnectionListener.java
new file mode 100644
index 0000000..a3ff118
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/IRemoteConnectionListener.java
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.tables;
+
+import edu.wpi.first.networktables.ConnectionInfo;
+
+/**
+ * A listener that listens for connection changes in a {@link IRemote} object.
+ * @deprecated Use Consumer&lt;{@link edu.wpi.first.networktables.ConnectionNotification}&gt;.
+ */
+@Deprecated
+@SuppressWarnings("checkstyle:all")
+public interface IRemoteConnectionListener {
+  /**
+   * Called when an IRemote is connected
+   * @param remote the object that connected
+   */
+  public void connected(IRemote remote);
+  /**
+   * Called when an IRemote is disconnected
+   * @param remote the object that disconnected
+   */
+  public void disconnected(IRemote remote);
+  /**
+   * Extended version of connected called when an IRemote is connected.
+    * Contains the connection info of the connected remote
+   * @param remote the object that connected
+   * @param info the connection info for the connected remote
+   */
+  default public void connectedEx(IRemote remote, ConnectionInfo info) {
+    connected(remote);
+  }
+  /**
+   * Extended version of connected called when an IRemote is disconnected.
+   * Contains the connection info of the disconnected remote
+   * @param remote the object that disconnected
+   * @param info the connection info for the disconnected remote
+   */
+  default public void disconnectedEx(IRemote remote, ConnectionInfo info) {
+    disconnected(remote);
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/ITable.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/ITable.java
new file mode 100644
index 0000000..2d0d5d6
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/ITable.java
@@ -0,0 +1,488 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.tables;
+
+import java.nio.ByteBuffer;
+import java.util.Set;
+
+
+/**
+ * A table whose values can be read and written to.
+ * @deprecated Use {@link edu.wpi.first.networktables.NetworkTable}.
+ */
+@Deprecated
+@SuppressWarnings("checkstyle:all")
+public interface ITable {
+
+  /**
+   * Checks the table and tells if it contains the specified key
+   *
+   * @param key the key to search for
+   * @return true if the table as a value assigned to the given key
+   */
+  public boolean containsKey(String key);
+
+  /**
+   * @param key the key to search for
+   * @return true if there is a subtable with the key which contains at least
+   * one key/subtable of its own
+   */
+  public boolean containsSubTable(String key);
+
+  /**
+   * Returns the table at the specified key. If there is no table at the
+   * specified key, it will create a new table
+   *
+   * @param key the name of the table relative to this one
+   * @return a sub table relative to this one
+   */
+  public ITable getSubTable(String key);
+
+  /**
+   * Gets all keys in the table (not including sub-tables).
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return keys currently in the table
+   */
+  public Set<String> getKeys(int types);
+
+  /**
+   * Gets all keys in the table (not including sub-tables).
+   * @return keys currently in the table
+   */
+  public Set<String> getKeys();
+
+  /**
+   * Gets the names of all subtables in the table.
+   * @return subtables currently in the table
+   */
+  public Set<String> getSubTables();
+
+  /**
+   * Makes a key's value persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  public void setPersistent(String key);
+
+  /**
+   * Stop making a key's value persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  public void clearPersistent(String key);
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   * @return True if the value is persistent.
+   */
+  public boolean isPersistent(String key);
+
+  /**
+   * Sets flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to set (bitmask)
+   */
+  public void setFlags(String key, int flags);
+
+  /**
+   * Clears flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to clear (bitmask)
+   */
+  public void clearFlags(String key, int flags);
+
+  /**
+   * Returns the flags for the specified key.
+   *
+   * @param key the key name
+   * @return the flags, or 0 if the key is not defined
+   */
+  public int getFlags(String key);
+
+  /**
+   * Deletes the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   */
+  public void delete(String key);
+
+  /**
+   * Gets the value associated with a key as an object.
+   * NOTE: If the value is a double, it will return a Double object,
+   * not a primitive.  To get the primitive, use
+   * {@link #getDouble(String, double)}.
+   * @param key the key of the value to look up
+   * @param defaultValue the default value if the key is null
+   * @return the value associated with the given key
+   */
+  public Object getValue(String key, Object defaultValue);
+
+  /**
+   * Put a value in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   * @throws IllegalArgumentException when the value is not supported by the
+   * table
+   */
+  public boolean putValue(String key, Object value)
+      throws IllegalArgumentException;
+
+  /**
+   * Put a number in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putNumber(String key, double value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultNumber(String key, double defaultValue);
+
+  /**
+   * Returns the number the key maps to. If the key does not exist or is of
+   * different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public double getNumber(String key, double defaultValue);
+
+  /**
+   * Put a string in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putString(String key, String value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultString(String key, String defaultValue);
+
+  /**
+   * Returns the string the key maps to. If the key does not exist or is of
+   * different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public String getString(String key, String defaultValue);
+
+  /**
+   * Put a boolean in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putBoolean(String key, boolean value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultBoolean(String key, boolean defaultValue);
+
+  /**
+   * Returns the boolean the key maps to. If the key does not exist or is of
+   * different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public boolean getBoolean(String key, boolean defaultValue);
+
+  /**
+   * Put a boolean array in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putBooleanArray(String key, boolean[] value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultBooleanArray(String key, boolean[] defaultValue);
+
+  /**
+   * Put a boolean array in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putBooleanArray(String key, Boolean[] value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultBooleanArray(String key, Boolean[] defaultValue);
+
+  /**
+   * Returns the boolean array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public boolean[] getBooleanArray(String key, boolean[] defaultValue);
+  /**
+   * Returns the boolean array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public Boolean[] getBooleanArray(String key, Boolean[] defaultValue);
+
+  /**
+   * Put a number array in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putNumberArray(String key, double[] value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultNumberArray(String key, double[] defaultValue);
+
+  /**
+   * Put a number array in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putNumberArray(String key, Double[] value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultNumberArray(String key, Double[] defaultValue);
+
+  /**
+   * Returns the number array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public double[] getNumberArray(String key, double[] defaultValue);
+  /**
+   * Returns the number array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public Double[] getNumberArray(String key, Double[] defaultValue);
+
+  /**
+   * Put a string array in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putStringArray(String key, String[] value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultStringArray(String key, String[] defaultValue);
+
+  /**
+   * Returns the string array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public String[] getStringArray(String key, String[] defaultValue);
+
+  /**
+   * Put a raw value (byte array) in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putRaw(String key, byte[] value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doens't exist.
+   * @return False if the table key exists with a different type
+   */
+  public boolean setDefaultRaw(String key, byte[] defaultValue);
+
+  /**
+   * Put a raw value (bytes from a byte buffer) in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @param len the length of the value
+   * @return False if the table key already exists with a different type
+   */
+  public boolean putRaw(String key, ByteBuffer value, int len);
+
+  /**
+   * Returns the raw value (byte array) the key maps to. If the key does not
+   * exist or is of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  public byte[] getRaw(String key, byte[] defaultValue);
+
+  /** Notifier flag values. */
+  public static final int NOTIFY_IMMEDIATE = 0x01;
+  public static final int NOTIFY_LOCAL = 0x02;
+  public static final int NOTIFY_NEW = 0x04;
+  public static final int NOTIFY_DELETE = 0x08;
+  public static final int NOTIFY_UPDATE = 0x10;
+  public static final int NOTIFY_FLAGS = 0x20;
+
+  /**
+   * Add a listener for changes to the table
+   * @param listener the listener to add
+   */
+  public void addTableListener(ITableListener listener);
+  /**
+   * Add a listener for changes to the table
+   * @param listener the listener to add
+   * @param immediateNotify if true then this listener will be notified of all
+   * current entries (marked as new)
+   */
+  public void addTableListener(ITableListener listener,
+                               boolean immediateNotify);
+  /**
+   * Add a listener for changes to the table
+   * @param listener the listener to add
+   * @param flags bitmask specifying desired notifications
+   */
+  public void addTableListenerEx(ITableListener listener, int flags);
+
+  /**
+   * Add a listener for changes to a specific key the table
+   * @param key the key to listen for
+   * @param listener the listener to add
+   * @param immediateNotify if true then this listener will be notified of all
+   * current entries (marked as new)
+   */
+  public void addTableListener(String key, ITableListener listener,
+                               boolean immediateNotify);
+  /**
+   * Add a listener for changes to a specific key the table
+   * @param key the key to listen for
+   * @param listener the listener to add
+   * @param flags bitmask specifying desired notifications
+   */
+  public void addTableListenerEx(String key, ITableListener listener,
+                                 int flags);
+  /**
+   * This will immediately notify the listener of all current sub tables
+   * @param listener the listener to notify
+   */
+  public void addSubTableListener(final ITableListener listener);
+  /**
+   * This will immediately notify the listener of all current sub tables
+   * @param listener the listener to notify
+   * @param localNotify if true then this listener will be notified of all
+   * local changes in addition to all remote changes
+   */
+  public void addSubTableListener(final ITableListener listener,
+                                  boolean localNotify);
+  /**
+   * Remove a listener from receiving table events
+   * @param listener the listener to be removed
+   */
+  public void removeTableListener(ITableListener listener);
+
+  /*
+   * Deprecated Methods
+   */
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   * The key can not be null.
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   * @param key the key
+   * @param value the value
+   * @return False if the table key already exists with a different type
+   * @throws IllegalArgumentException if key is null
+   * @deprecated Use {@link #putNumber(String, double)} instead.
+   */
+  @Deprecated
+  public boolean putDouble(String key, double value);
+
+  /**
+   * Returns the value at the specified key.
+   * @param key the key
+   * @param defaultValue the value returned if the key is undefined
+   * @return the value
+   * @throws IllegalArgumentException if the value mapped to by the key is not a
+   * double
+   * @throws IllegalArgumentException if the key is null
+   * @deprecated Use {@link #getNumber(String, double)} instead.
+   */
+  @Deprecated
+  public double getDouble(String key, double defaultValue);
+
+  /**
+   * Gets the full path of this table.  Does not include the trailing "/".
+   * @return The path to this table (e.g. "", "/foo").
+   */
+  public String getPath();
+
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/ITableListener.java b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/ITableListener.java
new file mode 100644
index 0000000..b08312b
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/java/edu/wpi/first/wpilibj/tables/ITableListener.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.tables;
+
+/**
+ * A listener that listens to changes in values in a {@link ITable}.
+ * @deprecated Use Consumer&lt;{@link edu.wpi.first.networktables.EntryNotification}&gt;,
+ * {@link edu.wpi.first.networktables.TableEntryListener}, or
+ * {@link edu.wpi.first.networktables.TableListener} as appropriate.
+ */
+@FunctionalInterface
+@Deprecated
+@SuppressWarnings("checkstyle:all")
+public interface ITableListener {
+    /**
+     * Called when a key-value pair is changed in a {@link ITable}
+     * @param source the table the key-value pair exists in
+     * @param key the key associated with the value that changed
+     * @param value the new value
+     * @param isNew true if the key did not previously exist in the table, otherwise it is false
+     */
+    public void valueChanged(ITable source, String key, Object value, boolean isNew);
+
+    /**
+     * Extended version of valueChanged.  Called when a key-value pair is
+     * changed in a {@link ITable}.  The default implementation simply calls
+     * valueChanged().  If this is overridden, valueChanged() will not be
+     * called.
+     * @param source the table the key-value pair exists in
+     * @param key the key associated with the value that changed
+     * @param value the new value
+     * @param flags update flags; for example, NOTIFY_NEW if the key did not
+     * previously exist in the table
+     */
+    default public void valueChangedEx(ITable source, String key, Object value, int flags) {
+        // NOTIFY_NEW = 0x04
+        valueChanged(source, key, value, (flags & 0x04) != 0);
+    }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/CallbackManager.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/CallbackManager.h
new file mode 100644
index 0000000..0fd9617
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/CallbackManager.h
@@ -0,0 +1,327 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_CALLBACKMANAGER_H_
+#define NTCORE_CALLBACKMANAGER_H_
+
+#include <atomic>
+#include <climits>
+#include <functional>
+#include <memory>
+#include <queue>
+#include <utility>
+#include <vector>
+
+#include <wpi/SafeThread.h>
+#include <wpi/UidVector.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+namespace nt {
+
+namespace impl {
+
+template <typename Callback>
+class ListenerData {
+ public:
+  ListenerData() = default;
+  explicit ListenerData(Callback callback_) : callback(callback_) {}
+  explicit ListenerData(unsigned int poller_uid_) : poller_uid(poller_uid_) {}
+
+  explicit operator bool() const { return callback || poller_uid != UINT_MAX; }
+
+  Callback callback;
+  unsigned int poller_uid = UINT_MAX;
+};
+
+// CRTP callback manager thread
+// @tparam Derived        derived class
+// @tparam NotifierData   data buffered for each callback
+// @tparam ListenerData   data stored for each listener
+// Derived must define the following functions:
+//   bool Matches(const ListenerData& listener, const NotifierData& data);
+//   void SetListener(NotifierData* data, unsigned int listener_uid);
+//   void DoCallback(Callback callback, const NotifierData& data);
+template <typename Derived, typename TUserInfo,
+          typename TListenerData =
+              ListenerData<std::function<void(const TUserInfo& info)>>,
+          typename TNotifierData = TUserInfo>
+class CallbackThread : public wpi::SafeThread {
+ public:
+  typedef TUserInfo UserInfo;
+  typedef TNotifierData NotifierData;
+  typedef TListenerData ListenerData;
+
+  ~CallbackThread() {
+    // Wake up any blocked pollers
+    for (size_t i = 0; i < m_pollers.size(); ++i) {
+      if (auto poller = m_pollers[i]) poller->Terminate();
+    }
+  }
+
+  void Main() override;
+
+  wpi::UidVector<ListenerData, 64> m_listeners;
+
+  std::queue<std::pair<unsigned int, NotifierData>> m_queue;
+  wpi::condition_variable m_queue_empty;
+
+  struct Poller {
+    void Terminate() {
+      {
+        std::lock_guard<wpi::mutex> lock(poll_mutex);
+        terminating = true;
+      }
+      poll_cond.notify_all();
+    }
+    std::queue<NotifierData> poll_queue;
+    wpi::mutex poll_mutex;
+    wpi::condition_variable poll_cond;
+    bool terminating = false;
+    bool cancelling = false;
+  };
+  wpi::UidVector<std::shared_ptr<Poller>, 64> m_pollers;
+
+  // Must be called with m_mutex held
+  template <typename... Args>
+  void SendPoller(unsigned int poller_uid, Args&&... args) {
+    if (poller_uid > m_pollers.size()) return;
+    auto poller = m_pollers[poller_uid];
+    if (!poller) return;
+    {
+      std::lock_guard<wpi::mutex> lock(poller->poll_mutex);
+      poller->poll_queue.emplace(std::forward<Args>(args)...);
+    }
+    poller->poll_cond.notify_one();
+  }
+};
+
+template <typename Derived, typename TUserInfo, typename TListenerData,
+          typename TNotifierData>
+void CallbackThread<Derived, TUserInfo, TListenerData, TNotifierData>::Main() {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  while (m_active) {
+    while (m_queue.empty()) {
+      m_cond.wait(lock);
+      if (!m_active) return;
+    }
+
+    while (!m_queue.empty()) {
+      if (!m_active) return;
+      auto item = std::move(m_queue.front());
+
+      if (item.first != UINT_MAX) {
+        if (item.first < m_listeners.size()) {
+          auto& listener = m_listeners[item.first];
+          if (listener &&
+              static_cast<Derived*>(this)->Matches(listener, item.second)) {
+            static_cast<Derived*>(this)->SetListener(&item.second, item.first);
+            if (listener.callback) {
+              lock.unlock();
+              static_cast<Derived*>(this)->DoCallback(listener.callback,
+                                                      item.second);
+              lock.lock();
+            } else if (listener.poller_uid != UINT_MAX) {
+              SendPoller(listener.poller_uid, std::move(item.second));
+            }
+          }
+        }
+      } else {
+        // Use index because iterator might get invalidated.
+        for (size_t i = 0; i < m_listeners.size(); ++i) {
+          auto& listener = m_listeners[i];
+          if (!listener) continue;
+          if (!static_cast<Derived*>(this)->Matches(listener, item.second))
+            continue;
+          static_cast<Derived*>(this)->SetListener(&item.second, i);
+          if (listener.callback) {
+            lock.unlock();
+            static_cast<Derived*>(this)->DoCallback(listener.callback,
+                                                    item.second);
+            lock.lock();
+          } else if (listener.poller_uid != UINT_MAX) {
+            SendPoller(listener.poller_uid, item.second);
+          }
+        }
+      }
+      m_queue.pop();
+    }
+
+    m_queue_empty.notify_all();
+  }
+}
+
+}  // namespace impl
+
+// CRTP callback manager
+// @tparam Derived  derived class
+// @tparam Thread   custom thread (must be derived from impl::CallbackThread)
+//
+// Derived must define the following functions:
+//   void Start();
+template <typename Derived, typename Thread>
+class CallbackManager {
+  friend class RpcServerTest;
+
+ public:
+  void Stop() { m_owner.Stop(); }
+
+  void Remove(unsigned int listener_uid) {
+    auto thr = m_owner.GetThread();
+    if (!thr) return;
+    thr->m_listeners.erase(listener_uid);
+  }
+
+  unsigned int CreatePoller() {
+    static_cast<Derived*>(this)->Start();
+    auto thr = m_owner.GetThread();
+    return thr->m_pollers.emplace_back(
+        std::make_shared<typename Thread::Poller>());
+  }
+
+  void RemovePoller(unsigned int poller_uid) {
+    auto thr = m_owner.GetThread();
+    if (!thr) return;
+
+    // Remove any listeners that are associated with this poller
+    for (size_t i = 0; i < thr->m_listeners.size(); ++i) {
+      if (thr->m_listeners[i].poller_uid == poller_uid)
+        thr->m_listeners.erase(i);
+    }
+
+    // Wake up any blocked pollers
+    if (poller_uid >= thr->m_pollers.size()) return;
+    auto poller = thr->m_pollers[poller_uid];
+    if (!poller) return;
+    poller->Terminate();
+    return thr->m_pollers.erase(poller_uid);
+  }
+
+  bool WaitForQueue(double timeout) {
+    auto thr = m_owner.GetThread();
+    if (!thr) return true;
+
+    auto& lock = thr.GetLock();
+    auto timeout_time = std::chrono::steady_clock::now() +
+                        std::chrono::duration<double>(timeout);
+    while (!thr->m_queue.empty()) {
+      if (!thr->m_active) return true;
+      if (timeout == 0) return false;
+      if (timeout < 0) {
+        thr->m_queue_empty.wait(lock);
+      } else {
+        auto cond_timed_out = thr->m_queue_empty.wait_until(lock, timeout_time);
+        if (cond_timed_out == std::cv_status::timeout) return false;
+      }
+    }
+
+    return true;
+  }
+
+  std::vector<typename Thread::UserInfo> Poll(unsigned int poller_uid) {
+    bool timed_out = false;
+    return Poll(poller_uid, -1, &timed_out);
+  }
+
+  std::vector<typename Thread::UserInfo> Poll(unsigned int poller_uid,
+                                              double timeout, bool* timed_out) {
+    std::vector<typename Thread::UserInfo> infos;
+    std::shared_ptr<typename Thread::Poller> poller;
+    {
+      auto thr = m_owner.GetThread();
+      if (!thr) return infos;
+      if (poller_uid > thr->m_pollers.size()) return infos;
+      poller = thr->m_pollers[poller_uid];
+      if (!poller) return infos;
+    }
+
+    std::unique_lock<wpi::mutex> lock(poller->poll_mutex);
+    auto timeout_time = std::chrono::steady_clock::now() +
+                        std::chrono::duration<double>(timeout);
+    *timed_out = false;
+    while (poller->poll_queue.empty()) {
+      if (poller->terminating) return infos;
+      if (poller->cancelling) {
+        // Note: this only works if there's a single thread calling this
+        // function for any particular poller, but that's the intended use.
+        poller->cancelling = false;
+        return infos;
+      }
+      if (timeout == 0) {
+        *timed_out = true;
+        return infos;
+      }
+      if (timeout < 0) {
+        poller->poll_cond.wait(lock);
+      } else {
+        auto cond_timed_out = poller->poll_cond.wait_until(lock, timeout_time);
+        if (cond_timed_out == std::cv_status::timeout) {
+          *timed_out = true;
+          return infos;
+        }
+      }
+    }
+
+    while (!poller->poll_queue.empty()) {
+      infos.emplace_back(std::move(poller->poll_queue.front()));
+      poller->poll_queue.pop();
+    }
+    return infos;
+  }
+
+  void CancelPoll(unsigned int poller_uid) {
+    std::shared_ptr<typename Thread::Poller> poller;
+    {
+      auto thr = m_owner.GetThread();
+      if (!thr) return;
+      if (poller_uid > thr->m_pollers.size()) return;
+      poller = thr->m_pollers[poller_uid];
+      if (!poller) return;
+    }
+
+    {
+      std::lock_guard<wpi::mutex> lock(poller->poll_mutex);
+      poller->cancelling = true;
+    }
+    poller->poll_cond.notify_one();
+  }
+
+ protected:
+  template <typename... Args>
+  void DoStart(Args&&... args) {
+    m_owner.Start(std::forward<Args>(args)...);
+  }
+
+  template <typename... Args>
+  unsigned int DoAdd(Args&&... args) {
+    static_cast<Derived*>(this)->Start();
+    auto thr = m_owner.GetThread();
+    return thr->m_listeners.emplace_back(std::forward<Args>(args)...);
+  }
+
+  template <typename... Args>
+  void Send(unsigned int only_listener, Args&&... args) {
+    auto thr = m_owner.GetThread();
+    if (!thr || thr->m_listeners.empty()) return;
+    thr->m_queue.emplace(std::piecewise_construct,
+                         std::make_tuple(only_listener),
+                         std::forward_as_tuple(std::forward<Args>(args)...));
+    thr->m_cond.notify_one();
+  }
+
+  typename wpi::SafeThreadOwner<Thread>::Proxy GetThread() const {
+    return m_owner.GetThread();
+  }
+
+ private:
+  wpi::SafeThreadOwner<Thread> m_owner;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_CALLBACKMANAGER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ConnectionNotifier.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ConnectionNotifier.cpp
new file mode 100644
index 0000000..340aad0
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ConnectionNotifier.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "ConnectionNotifier.h"
+
+using namespace nt;
+
+ConnectionNotifier::ConnectionNotifier(int inst) : m_inst(inst) {}
+
+void ConnectionNotifier::Start() { DoStart(m_inst); }
+
+unsigned int ConnectionNotifier::Add(
+    std::function<void(const ConnectionNotification& event)> callback) {
+  return DoAdd(callback);
+}
+
+unsigned int ConnectionNotifier::AddPolled(unsigned int poller_uid) {
+  return DoAdd(poller_uid);
+}
+
+void ConnectionNotifier::NotifyConnection(bool connected,
+                                          const ConnectionInfo& conn_info,
+                                          unsigned int only_listener) {
+  Send(only_listener, 0, connected, conn_info);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ConnectionNotifier.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ConnectionNotifier.h
new file mode 100644
index 0000000..65eec06
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ConnectionNotifier.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_CONNECTIONNOTIFIER_H_
+#define NTCORE_CONNECTIONNOTIFIER_H_
+
+#include "CallbackManager.h"
+#include "Handle.h"
+#include "IConnectionNotifier.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+namespace impl {
+
+class ConnectionNotifierThread
+    : public CallbackThread<ConnectionNotifierThread, ConnectionNotification> {
+ public:
+  explicit ConnectionNotifierThread(int inst) : m_inst(inst) {}
+
+  bool Matches(const ListenerData& /*listener*/,
+               const ConnectionNotification& /*data*/) {
+    return true;
+  }
+
+  void SetListener(ConnectionNotification* data, unsigned int listener_uid) {
+    data->listener =
+        Handle(m_inst, listener_uid, Handle::kConnectionListener).handle();
+  }
+
+  void DoCallback(
+      std::function<void(const ConnectionNotification& event)> callback,
+      const ConnectionNotification& data) {
+    callback(data);
+  }
+
+  int m_inst;
+};
+
+}  // namespace impl
+
+class ConnectionNotifier
+    : public IConnectionNotifier,
+      public CallbackManager<ConnectionNotifier,
+                             impl::ConnectionNotifierThread> {
+  friend class ConnectionNotifierTest;
+  friend class CallbackManager<ConnectionNotifier,
+                               impl::ConnectionNotifierThread>;
+
+ public:
+  explicit ConnectionNotifier(int inst);
+
+  void Start();
+
+  unsigned int Add(std::function<void(const ConnectionNotification& event)>
+                       callback) override;
+  unsigned int AddPolled(unsigned int poller_uid) override;
+
+  void NotifyConnection(bool connected, const ConnectionInfo& conn_info,
+                        unsigned int only_listener = UINT_MAX) override;
+
+ private:
+  int m_inst;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_CONNECTIONNOTIFIER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Dispatcher.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Dispatcher.cpp
new file mode 100644
index 0000000..ea54fe4
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Dispatcher.cpp
@@ -0,0 +1,641 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "Dispatcher.h"
+
+#include <algorithm>
+#include <iterator>
+
+#include <wpi/TCPAcceptor.h>
+#include <wpi/TCPConnector.h>
+
+#include "IConnectionNotifier.h"
+#include "IStorage.h"
+#include "Log.h"
+#include "NetworkConnection.h"
+
+using namespace nt;
+
+void Dispatcher::StartServer(const Twine& persist_filename,
+                             const char* listen_address, unsigned int port) {
+  std::string listen_address_copy(StringRef(listen_address).trim());
+  DispatcherBase::StartServer(
+      persist_filename,
+      std::unique_ptr<wpi::NetworkAcceptor>(new wpi::TCPAcceptor(
+          static_cast<int>(port), listen_address_copy.c_str(), m_logger)));
+}
+
+void Dispatcher::SetServer(const char* server_name, unsigned int port) {
+  std::string server_name_copy(StringRef(server_name).trim());
+  SetConnector([=]() -> std::unique_ptr<wpi::NetworkStream> {
+    return wpi::TCPConnector::connect(server_name_copy.c_str(),
+                                      static_cast<int>(port), m_logger, 1);
+  });
+}
+
+void Dispatcher::SetServer(
+    ArrayRef<std::pair<StringRef, unsigned int>> servers) {
+  wpi::SmallVector<std::pair<std::string, int>, 16> servers_copy;
+  for (const auto& server : servers)
+    servers_copy.emplace_back(std::string{server.first.trim()},
+                              static_cast<int>(server.second));
+
+  SetConnector([=]() -> std::unique_ptr<wpi::NetworkStream> {
+    wpi::SmallVector<std::pair<const char*, int>, 16> servers_copy2;
+    for (const auto& server : servers_copy)
+      servers_copy2.emplace_back(server.first.c_str(), server.second);
+    return wpi::TCPConnector::connect_parallel(servers_copy2, m_logger, 1);
+  });
+}
+
+void Dispatcher::SetServerTeam(unsigned int team, unsigned int port) {
+  std::pair<StringRef, unsigned int> servers[5];
+
+  // 10.te.am.2
+  wpi::SmallString<32> fixed;
+  {
+    wpi::raw_svector_ostream oss{fixed};
+    oss << "10." << static_cast<int>(team / 100) << '.'
+        << static_cast<int>(team % 100) << ".2";
+    servers[0] = std::make_pair(oss.str(), port);
+  }
+
+  // 172.22.11.2
+  servers[1] = std::make_pair("172.22.11.2", port);
+
+  // roboRIO-<team>-FRC.local
+  wpi::SmallString<32> mdns;
+  {
+    wpi::raw_svector_ostream oss{mdns};
+    oss << "roboRIO-" << team << "-FRC.local";
+    servers[2] = std::make_pair(oss.str(), port);
+  }
+
+  // roboRIO-<team>-FRC.lan
+  wpi::SmallString<32> mdns_lan;
+  {
+    wpi::raw_svector_ostream oss{mdns_lan};
+    oss << "roboRIO-" << team << "-FRC.lan";
+    servers[3] = std::make_pair(oss.str(), port);
+  }
+
+  // roboRIO-<team>-FRC.frc-field.local
+  wpi::SmallString<64> field_local;
+  {
+    wpi::raw_svector_ostream oss{field_local};
+    oss << "roboRIO-" << team << "-FRC.frc-field.local";
+    servers[4] = std::make_pair(oss.str(), port);
+  }
+
+  SetServer(servers);
+}
+
+void Dispatcher::SetServerOverride(const char* server_name, unsigned int port) {
+  std::string server_name_copy(StringRef(server_name).trim());
+  SetConnectorOverride([=]() -> std::unique_ptr<wpi::NetworkStream> {
+    return wpi::TCPConnector::connect(server_name_copy.c_str(),
+                                      static_cast<int>(port), m_logger, 1);
+  });
+}
+
+void Dispatcher::ClearServerOverride() { ClearConnectorOverride(); }
+
+DispatcherBase::DispatcherBase(IStorage& storage, IConnectionNotifier& notifier,
+                               wpi::Logger& logger)
+    : m_storage(storage), m_notifier(notifier), m_logger(logger) {
+  m_active = false;
+  m_update_rate = 100;
+}
+
+DispatcherBase::~DispatcherBase() { Stop(); }
+
+unsigned int DispatcherBase::GetNetworkMode() const { return m_networkMode; }
+
+void DispatcherBase::StartServer(
+    const Twine& persist_filename,
+    std::unique_ptr<wpi::NetworkAcceptor> acceptor) {
+  {
+    std::lock_guard<wpi::mutex> lock(m_user_mutex);
+    if (m_active) return;
+    m_active = true;
+  }
+  m_networkMode = NT_NET_MODE_SERVER | NT_NET_MODE_STARTING;
+  m_persist_filename = persist_filename.str();
+  m_server_acceptor = std::move(acceptor);
+
+  // Load persistent file.  Ignore errors, but pass along warnings.
+  if (!persist_filename.isTriviallyEmpty() &&
+      (!persist_filename.isSingleStringRef() ||
+       !persist_filename.getSingleStringRef().empty())) {
+    bool first = true;
+    m_storage.LoadPersistent(
+        persist_filename, [&](size_t line, const char* msg) {
+          if (first) {
+            first = false;
+            WARNING("When reading initial persistent values from '"
+                    << persist_filename << "':");
+          }
+          WARNING(persist_filename << ":" << line << ": " << msg);
+        });
+  }
+
+  m_storage.SetDispatcher(this, true);
+
+  m_dispatch_thread = std::thread(&Dispatcher::DispatchThreadMain, this);
+  m_clientserver_thread = std::thread(&Dispatcher::ServerThreadMain, this);
+}
+
+void DispatcherBase::StartClient() {
+  {
+    std::lock_guard<wpi::mutex> lock(m_user_mutex);
+    if (m_active) return;
+    m_active = true;
+  }
+  m_networkMode = NT_NET_MODE_CLIENT | NT_NET_MODE_STARTING;
+  m_storage.SetDispatcher(this, false);
+
+  m_dispatch_thread = std::thread(&Dispatcher::DispatchThreadMain, this);
+  m_clientserver_thread = std::thread(&Dispatcher::ClientThreadMain, this);
+}
+
+void DispatcherBase::Stop() {
+  m_active = false;
+
+  // wake up dispatch thread with a flush
+  m_flush_cv.notify_one();
+
+  // wake up client thread with a reconnect
+  {
+    std::lock_guard<wpi::mutex> lock(m_user_mutex);
+    m_client_connector = nullptr;
+  }
+  ClientReconnect();
+
+  // wake up server thread by shutting down the socket
+  if (m_server_acceptor) m_server_acceptor->shutdown();
+
+  // join threads, with timeout
+  if (m_dispatch_thread.joinable()) m_dispatch_thread.join();
+  if (m_clientserver_thread.joinable()) m_clientserver_thread.join();
+
+  std::vector<std::shared_ptr<INetworkConnection>> conns;
+  {
+    std::lock_guard<wpi::mutex> lock(m_user_mutex);
+    conns.swap(m_connections);
+  }
+
+  // close all connections
+  conns.resize(0);
+}
+
+void DispatcherBase::SetUpdateRate(double interval) {
+  // don't allow update rates faster than 10 ms or slower than 1 second
+  if (interval < 0.01)
+    interval = 0.01;
+  else if (interval > 1.0)
+    interval = 1.0;
+  m_update_rate = static_cast<unsigned int>(interval * 1000);
+}
+
+void DispatcherBase::SetIdentity(const Twine& name) {
+  std::lock_guard<wpi::mutex> lock(m_user_mutex);
+  m_identity = name.str();
+}
+
+void DispatcherBase::Flush() {
+  auto now = std::chrono::steady_clock::now();
+  {
+    std::lock_guard<wpi::mutex> lock(m_flush_mutex);
+    // don't allow flushes more often than every 10 ms
+    if ((now - m_last_flush) < std::chrono::milliseconds(10)) return;
+    m_last_flush = now;
+    m_do_flush = true;
+  }
+  m_flush_cv.notify_one();
+}
+
+std::vector<ConnectionInfo> DispatcherBase::GetConnections() const {
+  std::vector<ConnectionInfo> conns;
+  if (!m_active) return conns;
+
+  std::lock_guard<wpi::mutex> lock(m_user_mutex);
+  for (auto& conn : m_connections) {
+    if (conn->state() != NetworkConnection::kActive) continue;
+    conns.emplace_back(conn->info());
+  }
+
+  return conns;
+}
+
+bool DispatcherBase::IsConnected() const {
+  if (!m_active) return false;
+
+  std::lock_guard<wpi::mutex> lock(m_user_mutex);
+  for (auto& conn : m_connections) {
+    if (conn->state() == NetworkConnection::kActive) return true;
+  }
+
+  return false;
+}
+
+unsigned int DispatcherBase::AddListener(
+    std::function<void(const ConnectionNotification& event)> callback,
+    bool immediate_notify) const {
+  std::lock_guard<wpi::mutex> lock(m_user_mutex);
+  unsigned int uid = m_notifier.Add(callback);
+  // perform immediate notifications
+  if (immediate_notify) {
+    for (auto& conn : m_connections) {
+      if (conn->state() != NetworkConnection::kActive) continue;
+      m_notifier.NotifyConnection(true, conn->info(), uid);
+    }
+  }
+  return uid;
+}
+
+unsigned int DispatcherBase::AddPolledListener(unsigned int poller_uid,
+                                               bool immediate_notify) const {
+  std::lock_guard<wpi::mutex> lock(m_user_mutex);
+  unsigned int uid = m_notifier.AddPolled(poller_uid);
+  // perform immediate notifications
+  if (immediate_notify) {
+    for (auto& conn : m_connections) {
+      if (conn->state() != NetworkConnection::kActive) continue;
+      m_notifier.NotifyConnection(true, conn->info(), uid);
+    }
+  }
+  return uid;
+}
+
+void DispatcherBase::SetConnector(Connector connector) {
+  std::lock_guard<wpi::mutex> lock(m_user_mutex);
+  m_client_connector = std::move(connector);
+}
+
+void DispatcherBase::SetConnectorOverride(Connector connector) {
+  std::lock_guard<wpi::mutex> lock(m_user_mutex);
+  m_client_connector_override = std::move(connector);
+}
+
+void DispatcherBase::ClearConnectorOverride() {
+  std::lock_guard<wpi::mutex> lock(m_user_mutex);
+  m_client_connector_override = nullptr;
+}
+
+void DispatcherBase::DispatchThreadMain() {
+  auto timeout_time = std::chrono::steady_clock::now();
+
+  static const auto save_delta_time = std::chrono::seconds(1);
+  auto next_save_time = timeout_time + save_delta_time;
+
+  int count = 0;
+
+  while (m_active) {
+    // handle loop taking too long
+    auto start = std::chrono::steady_clock::now();
+    if (start > timeout_time) timeout_time = start;
+
+    // wait for periodic or when flushed
+    timeout_time += std::chrono::milliseconds(m_update_rate);
+    std::unique_lock<wpi::mutex> flush_lock(m_flush_mutex);
+    m_flush_cv.wait_until(flush_lock, timeout_time,
+                          [&] { return !m_active || m_do_flush; });
+    m_do_flush = false;
+    flush_lock.unlock();
+    if (!m_active) break;  // in case we were woken up to terminate
+
+    // perform periodic persistent save
+    if ((m_networkMode & NT_NET_MODE_SERVER) != 0 &&
+        !m_persist_filename.empty() && start > next_save_time) {
+      next_save_time += save_delta_time;
+      // handle loop taking too long
+      if (start > next_save_time) next_save_time = start + save_delta_time;
+      const char* err = m_storage.SavePersistent(m_persist_filename, true);
+      if (err) WARNING("periodic persistent save: " << err);
+    }
+
+    {
+      std::lock_guard<wpi::mutex> user_lock(m_user_mutex);
+      bool reconnect = false;
+
+      if (++count > 10) {
+        DEBUG("dispatch running " << m_connections.size() << " connections");
+        count = 0;
+      }
+
+      for (auto& conn : m_connections) {
+        // post outgoing messages if connection is active
+        // only send keep-alives on client
+        if (conn->state() == NetworkConnection::kActive)
+          conn->PostOutgoing((m_networkMode & NT_NET_MODE_CLIENT) != 0);
+
+        // if client, reconnect if connection died
+        if ((m_networkMode & NT_NET_MODE_CLIENT) != 0 &&
+            conn->state() == NetworkConnection::kDead)
+          reconnect = true;
+      }
+      // reconnect if we disconnected (and a reconnect is not in progress)
+      if (reconnect && !m_do_reconnect) {
+        m_do_reconnect = true;
+        m_reconnect_cv.notify_one();
+      }
+    }
+  }
+}
+
+void DispatcherBase::QueueOutgoing(std::shared_ptr<Message> msg,
+                                   INetworkConnection* only,
+                                   INetworkConnection* except) {
+  std::lock_guard<wpi::mutex> user_lock(m_user_mutex);
+  for (auto& conn : m_connections) {
+    if (conn.get() == except) continue;
+    if (only && conn.get() != only) continue;
+    auto state = conn->state();
+    if (state != NetworkConnection::kSynchronized &&
+        state != NetworkConnection::kActive)
+      continue;
+    conn->QueueOutgoing(msg);
+  }
+}
+
+void DispatcherBase::ServerThreadMain() {
+  if (m_server_acceptor->start() != 0) {
+    m_active = false;
+    m_networkMode = NT_NET_MODE_SERVER | NT_NET_MODE_FAILURE;
+    return;
+  }
+  m_networkMode = NT_NET_MODE_SERVER;
+  while (m_active) {
+    auto stream = m_server_acceptor->accept();
+    if (!stream) {
+      m_active = false;
+      return;
+    }
+    if (!m_active) {
+      m_networkMode = NT_NET_MODE_NONE;
+      return;
+    }
+    DEBUG("server: client connection from " << stream->getPeerIP() << " port "
+                                            << stream->getPeerPort());
+
+    // add to connections list
+    using namespace std::placeholders;
+    auto conn = std::make_shared<NetworkConnection>(
+        ++m_connections_uid, std::move(stream), m_notifier, m_logger,
+        std::bind(&Dispatcher::ServerHandshake, this, _1, _2, _3),
+        std::bind(&IStorage::GetMessageEntryType, &m_storage, _1));
+    conn->set_process_incoming(
+        std::bind(&IStorage::ProcessIncoming, &m_storage, _1, _2,
+                  std::weak_ptr<NetworkConnection>(conn)));
+    {
+      std::lock_guard<wpi::mutex> lock(m_user_mutex);
+      // reuse dead connection slots
+      bool placed = false;
+      for (auto& c : m_connections) {
+        if (c->state() == NetworkConnection::kDead) {
+          c = conn;
+          placed = true;
+          break;
+        }
+      }
+      if (!placed) m_connections.emplace_back(conn);
+      conn->Start();
+    }
+  }
+  m_networkMode = NT_NET_MODE_NONE;
+}
+
+void DispatcherBase::ClientThreadMain() {
+  while (m_active) {
+    // sleep between retries
+    std::this_thread::sleep_for(std::chrono::milliseconds(250));
+    Connector connect;
+
+    // get next server to connect to
+    {
+      std::lock_guard<wpi::mutex> lock(m_user_mutex);
+      if (m_client_connector_override) {
+        connect = m_client_connector_override;
+      } else {
+        if (!m_client_connector) {
+          m_networkMode = NT_NET_MODE_CLIENT | NT_NET_MODE_FAILURE;
+          continue;
+        }
+        connect = m_client_connector;
+      }
+    }
+
+    // try to connect (with timeout)
+    DEBUG("client trying to connect");
+    auto stream = connect();
+    if (!stream) {
+      m_networkMode = NT_NET_MODE_CLIENT | NT_NET_MODE_FAILURE;
+      continue;  // keep retrying
+    }
+    DEBUG("client connected");
+    m_networkMode = NT_NET_MODE_CLIENT;
+
+    std::unique_lock<wpi::mutex> lock(m_user_mutex);
+    using namespace std::placeholders;
+    auto conn = std::make_shared<NetworkConnection>(
+        ++m_connections_uid, std::move(stream), m_notifier, m_logger,
+        std::bind(&Dispatcher::ClientHandshake, this, _1, _2, _3),
+        std::bind(&IStorage::GetMessageEntryType, &m_storage, _1));
+    conn->set_process_incoming(
+        std::bind(&IStorage::ProcessIncoming, &m_storage, _1, _2,
+                  std::weak_ptr<NetworkConnection>(conn)));
+    m_connections.resize(0);  // disconnect any current
+    m_connections.emplace_back(conn);
+    conn->set_proto_rev(m_reconnect_proto_rev);
+    conn->Start();
+
+    // reconnect the next time starting with latest protocol revision
+    m_reconnect_proto_rev = 0x0300;
+
+    // block until told to reconnect
+    m_do_reconnect = false;
+    m_reconnect_cv.wait(lock, [&] { return !m_active || m_do_reconnect; });
+  }
+  m_networkMode = NT_NET_MODE_NONE;
+}
+
+bool DispatcherBase::ClientHandshake(
+    NetworkConnection& conn, std::function<std::shared_ptr<Message>()> get_msg,
+    std::function<void(wpi::ArrayRef<std::shared_ptr<Message>>)> send_msgs) {
+  // get identity
+  std::string self_id;
+  {
+    std::lock_guard<wpi::mutex> lock(m_user_mutex);
+    self_id = m_identity;
+  }
+
+  // send client hello
+  DEBUG("client: sending hello");
+  send_msgs(Message::ClientHello(self_id));
+
+  // wait for response
+  auto msg = get_msg();
+  if (!msg) {
+    // disconnected, retry
+    DEBUG("client: server disconnected before first response");
+    return false;
+  }
+
+  if (msg->Is(Message::kProtoUnsup)) {
+    if (msg->id() == 0x0200) ClientReconnect(0x0200);
+    return false;
+  }
+
+  bool new_server = true;
+  if (conn.proto_rev() >= 0x0300) {
+    // should be server hello; if not, disconnect.
+    if (!msg->Is(Message::kServerHello)) return false;
+    conn.set_remote_id(msg->str());
+    if ((msg->flags() & 1) != 0) new_server = false;
+    // get the next message
+    msg = get_msg();
+  }
+
+  // receive initial assignments
+  std::vector<std::shared_ptr<Message>> incoming;
+  for (;;) {
+    if (!msg) {
+      // disconnected, retry
+      DEBUG("client: server disconnected during initial entries");
+      return false;
+    }
+    DEBUG4("received init str=" << msg->str() << " id=" << msg->id()
+                                << " seq_num=" << msg->seq_num_uid());
+    if (msg->Is(Message::kServerHelloDone)) break;
+    // shouldn't receive a keep alive, but handle gracefully
+    if (msg->Is(Message::kKeepAlive)) {
+      msg = get_msg();
+      continue;
+    }
+    if (!msg->Is(Message::kEntryAssign)) {
+      // unexpected message
+      DEBUG("client: received message ("
+            << msg->type()
+            << ") other than entry assignment during initial handshake");
+      return false;
+    }
+    incoming.emplace_back(std::move(msg));
+    // get the next message
+    msg = get_msg();
+  }
+
+  // generate outgoing assignments
+  NetworkConnection::Outgoing outgoing;
+
+  m_storage.ApplyInitialAssignments(conn, incoming, new_server, &outgoing);
+
+  if (conn.proto_rev() >= 0x0300)
+    outgoing.emplace_back(Message::ClientHelloDone());
+
+  if (!outgoing.empty()) send_msgs(outgoing);
+
+  INFO("client: CONNECTED to server " << conn.stream().getPeerIP() << " port "
+                                      << conn.stream().getPeerPort());
+  return true;
+}
+
+bool DispatcherBase::ServerHandshake(
+    NetworkConnection& conn, std::function<std::shared_ptr<Message>()> get_msg,
+    std::function<void(wpi::ArrayRef<std::shared_ptr<Message>>)> send_msgs) {
+  // Wait for the client to send us a hello.
+  auto msg = get_msg();
+  if (!msg) {
+    DEBUG("server: client disconnected before sending hello");
+    return false;
+  }
+  if (!msg->Is(Message::kClientHello)) {
+    DEBUG("server: client initial message was not client hello");
+    return false;
+  }
+
+  // Check that the client requested version is not too high.
+  unsigned int proto_rev = msg->id();
+  if (proto_rev > 0x0300) {
+    DEBUG("server: client requested proto > 0x0300");
+    send_msgs(Message::ProtoUnsup());
+    return false;
+  }
+
+  if (proto_rev >= 0x0300) conn.set_remote_id(msg->str());
+
+  // Set the proto version to the client requested version
+  DEBUG("server: client protocol " << proto_rev);
+  conn.set_proto_rev(proto_rev);
+
+  // Send initial set of assignments
+  NetworkConnection::Outgoing outgoing;
+
+  // Start with server hello.  TODO: initial connection flag
+  if (proto_rev >= 0x0300) {
+    std::lock_guard<wpi::mutex> lock(m_user_mutex);
+    outgoing.emplace_back(Message::ServerHello(0u, m_identity));
+  }
+
+  // Get snapshot of initial assignments
+  m_storage.GetInitialAssignments(conn, &outgoing);
+
+  // Finish with server hello done
+  outgoing.emplace_back(Message::ServerHelloDone());
+
+  // Batch transmit
+  DEBUG("server: sending initial assignments");
+  send_msgs(outgoing);
+
+  // In proto rev 3.0 and later, the handshake concludes with a client hello
+  // done message, so we can batch the assigns before marking the connection
+  // active.  In pre-3.0, we need to just immediately mark it active and hand
+  // off control to the dispatcher to assign them as they arrive.
+  if (proto_rev >= 0x0300) {
+    // receive client initial assignments
+    std::vector<std::shared_ptr<Message>> incoming;
+    msg = get_msg();
+    for (;;) {
+      if (!msg) {
+        // disconnected, retry
+        DEBUG("server: disconnected waiting for initial entries");
+        return false;
+      }
+      if (msg->Is(Message::kClientHelloDone)) break;
+      // shouldn't receive a keep alive, but handle gracefully
+      if (msg->Is(Message::kKeepAlive)) {
+        msg = get_msg();
+        continue;
+      }
+      if (!msg->Is(Message::kEntryAssign)) {
+        // unexpected message
+        DEBUG("server: received message ("
+              << msg->type()
+              << ") other than entry assignment during initial handshake");
+        return false;
+      }
+      incoming.push_back(msg);
+      // get the next message (blocks)
+      msg = get_msg();
+    }
+    for (auto& msg : incoming)
+      m_storage.ProcessIncoming(msg, &conn, std::weak_ptr<NetworkConnection>());
+  }
+
+  INFO("server: client CONNECTED: " << conn.stream().getPeerIP() << " port "
+                                    << conn.stream().getPeerPort());
+  return true;
+}
+
+void DispatcherBase::ClientReconnect(unsigned int proto_rev) {
+  if ((m_networkMode & NT_NET_MODE_SERVER) != 0) return;
+  {
+    std::lock_guard<wpi::mutex> lock(m_user_mutex);
+    m_reconnect_proto_rev = proto_rev;
+    m_do_reconnect = true;
+  }
+  m_reconnect_cv.notify_one();
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Dispatcher.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Dispatcher.h
new file mode 100644
index 0000000..dfaf4d5
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Dispatcher.h
@@ -0,0 +1,151 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_DISPATCHER_H_
+#define NTCORE_DISPATCHER_H_
+
+#include <atomic>
+#include <chrono>
+#include <functional>
+#include <memory>
+#include <string>
+#include <thread>
+#include <utility>
+#include <vector>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "IDispatcher.h"
+#include "INetworkConnection.h"
+
+namespace wpi {
+class Logger;
+class NetworkAcceptor;
+class NetworkStream;
+}  // namespace wpi
+
+namespace nt {
+
+class IConnectionNotifier;
+class IStorage;
+class NetworkConnection;
+
+class DispatcherBase : public IDispatcher {
+  friend class DispatcherTest;
+
+ public:
+  typedef std::function<std::unique_ptr<wpi::NetworkStream>()> Connector;
+
+  DispatcherBase(IStorage& storage, IConnectionNotifier& notifier,
+                 wpi::Logger& logger);
+  virtual ~DispatcherBase();
+
+  unsigned int GetNetworkMode() const;
+  void StartServer(const Twine& persist_filename,
+                   std::unique_ptr<wpi::NetworkAcceptor> acceptor);
+  void StartClient();
+  void Stop();
+  void SetUpdateRate(double interval);
+  void SetIdentity(const Twine& name);
+  void Flush();
+  std::vector<ConnectionInfo> GetConnections() const;
+  bool IsConnected() const;
+
+  unsigned int AddListener(
+      std::function<void(const ConnectionNotification& event)> callback,
+      bool immediate_notify) const;
+  unsigned int AddPolledListener(unsigned int poller_uid,
+                                 bool immediate_notify) const;
+
+  void SetConnector(Connector connector);
+  void SetConnectorOverride(Connector connector);
+  void ClearConnectorOverride();
+
+  bool active() const { return m_active; }
+
+  DispatcherBase(const DispatcherBase&) = delete;
+  DispatcherBase& operator=(const DispatcherBase&) = delete;
+
+ private:
+  void DispatchThreadMain();
+  void ServerThreadMain();
+  void ClientThreadMain();
+
+  bool ClientHandshake(
+      NetworkConnection& conn,
+      std::function<std::shared_ptr<Message>()> get_msg,
+      std::function<void(wpi::ArrayRef<std::shared_ptr<Message>>)> send_msgs);
+  bool ServerHandshake(
+      NetworkConnection& conn,
+      std::function<std::shared_ptr<Message>()> get_msg,
+      std::function<void(wpi::ArrayRef<std::shared_ptr<Message>>)> send_msgs);
+
+  void ClientReconnect(unsigned int proto_rev = 0x0300);
+
+  void QueueOutgoing(std::shared_ptr<Message> msg, INetworkConnection* only,
+                     INetworkConnection* except) override;
+
+  IStorage& m_storage;
+  IConnectionNotifier& m_notifier;
+  unsigned int m_networkMode = NT_NET_MODE_NONE;
+  std::string m_persist_filename;
+  std::thread m_dispatch_thread;
+  std::thread m_clientserver_thread;
+
+  std::unique_ptr<wpi::NetworkAcceptor> m_server_acceptor;
+  Connector m_client_connector_override;
+  Connector m_client_connector;
+  uint8_t m_connections_uid = 0;
+
+  // Mutex for user-accessible items
+  mutable wpi::mutex m_user_mutex;
+  std::vector<std::shared_ptr<INetworkConnection>> m_connections;
+  std::string m_identity;
+
+  std::atomic_bool m_active;       // set to false to terminate threads
+  std::atomic_uint m_update_rate;  // periodic dispatch update rate, in ms
+
+  // Condition variable for forced dispatch wakeup (flush)
+  wpi::mutex m_flush_mutex;
+  wpi::condition_variable m_flush_cv;
+  std::chrono::steady_clock::time_point m_last_flush;
+  bool m_do_flush = false;
+
+  // Condition variable for client reconnect (uses user mutex)
+  wpi::condition_variable m_reconnect_cv;
+  unsigned int m_reconnect_proto_rev = 0x0300;
+  bool m_do_reconnect = true;
+
+ protected:
+  wpi::Logger& m_logger;
+};
+
+class Dispatcher : public DispatcherBase {
+  friend class DispatcherTest;
+
+ public:
+  Dispatcher(IStorage& storage, IConnectionNotifier& notifier,
+             wpi::Logger& logger)
+      : DispatcherBase(storage, notifier, logger) {}
+
+  void StartServer(const Twine& persist_filename, const char* listen_address,
+                   unsigned int port);
+
+  void SetServer(const char* server_name, unsigned int port);
+  void SetServer(ArrayRef<std::pair<StringRef, unsigned int>> servers);
+  void SetServerTeam(unsigned int team, unsigned int port);
+
+  void SetServerOverride(const char* server_name, unsigned int port);
+  void ClearServerOverride();
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_DISPATCHER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/DsClient.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/DsClient.cpp
new file mode 100644
index 0000000..8b97be7
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/DsClient.cpp
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "DsClient.h"
+
+#include <wpi/SmallString.h>
+#include <wpi/TCPConnector.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/raw_socket_istream.h>
+
+#include "Dispatcher.h"
+#include "Log.h"
+
+using namespace nt;
+
+class DsClient::Thread : public wpi::SafeThread {
+ public:
+  Thread(Dispatcher& dispatcher, wpi::Logger& logger, unsigned int port)
+      : m_dispatcher(dispatcher), m_logger(logger), m_port(port) {}
+
+  void Main();
+
+  Dispatcher& m_dispatcher;
+  wpi::Logger& m_logger;
+  unsigned int m_port;
+  std::unique_ptr<wpi::NetworkStream> m_stream;
+};
+
+DsClient::DsClient(Dispatcher& dispatcher, wpi::Logger& logger)
+    : m_dispatcher(dispatcher), m_logger(logger) {}
+
+void DsClient::Start(unsigned int port) {
+  auto thr = m_owner.GetThread();
+  if (!thr)
+    m_owner.Start(m_dispatcher, m_logger, port);
+  else
+    thr->m_port = port;
+}
+
+void DsClient::Stop() {
+  {
+    // Close the stream so the read (if any) terminates.
+    auto thr = m_owner.GetThread();
+    if (thr) {
+      thr->m_active = false;
+      if (thr->m_stream) thr->m_stream->close();
+    }
+  }
+  m_owner.Stop();
+}
+
+void DsClient::Thread::Main() {
+  unsigned int oldip = 0;
+  wpi::Logger nolog;  // to silence log messages from TCPConnector
+
+  while (m_active) {
+    // wait for periodic reconnect or termination
+    auto timeout_time =
+        std::chrono::steady_clock::now() + std::chrono::milliseconds(500);
+    unsigned int port;
+    {
+      std::unique_lock<wpi::mutex> lock(m_mutex);
+      m_cond.wait_until(lock, timeout_time, [&] { return !m_active; });
+      port = m_port;
+    }
+    if (!m_active) goto done;
+
+    // Try to connect to DS on the local machine
+    m_stream = wpi::TCPConnector::connect("127.0.0.1", 1742, nolog, 1);
+    if (!m_active) goto done;
+    if (!m_stream) continue;
+
+    DEBUG3("connected to DS");
+    wpi::raw_socket_istream is(*m_stream);
+
+    while (m_active && !is.has_error()) {
+      // Read JSON "{...}".  This is very limited, does not handle quoted "}" or
+      // nested {}, but is sufficient for this purpose.
+      wpi::SmallString<128> json;
+      char ch;
+
+      // Throw away characters until {
+      do {
+        is.read(ch);
+        if (is.has_error()) break;
+        if (!m_active) goto done;
+      } while (ch != '{');
+      json += '{';
+
+      if (is.has_error()) {
+        m_stream = nullptr;
+        break;
+      }
+
+      // Read characters until }
+      do {
+        is.read(ch);
+        if (is.has_error()) break;
+        if (!m_active) goto done;
+        json += ch;
+      } while (ch != '}');
+
+      if (is.has_error()) {
+        m_stream = nullptr;
+        break;
+      }
+      DEBUG3("json=" << json);
+
+      // Look for "robotIP":12345, and get 12345 portion
+      size_t pos = json.find("\"robotIP\"");
+      if (pos == wpi::StringRef::npos) continue;  // could not find?
+      pos += 9;
+      pos = json.find(':', pos);
+      if (pos == wpi::StringRef::npos) continue;  // could not find?
+      size_t endpos = json.find_first_not_of("0123456789", pos + 1);
+      DEBUG3("found robotIP=" << json.slice(pos + 1, endpos));
+
+      // Parse into number
+      unsigned int ip = 0;
+      if (json.slice(pos + 1, endpos).getAsInteger(10, ip)) continue;  // error
+
+      // If zero, clear the server override
+      if (ip == 0) {
+        m_dispatcher.ClearServerOverride();
+        oldip = 0;
+        continue;
+      }
+
+      // If unchanged, don't reconnect
+      if (ip == oldip) continue;
+      oldip = ip;
+
+      // Convert number into dotted quad
+      json.clear();
+      wpi::raw_svector_ostream os{json};
+      os << ((ip >> 24) & 0xff) << "." << ((ip >> 16) & 0xff) << "."
+         << ((ip >> 8) & 0xff) << "." << (ip & 0xff);
+      INFO("client: DS overriding server IP to " << os.str());
+      m_dispatcher.SetServerOverride(json.c_str(), port);
+    }
+
+    // We disconnected from the DS, clear the server override
+    m_dispatcher.ClearServerOverride();
+    oldip = 0;
+  }
+
+done:
+  m_dispatcher.ClearServerOverride();
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/DsClient.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/DsClient.h
new file mode 100644
index 0000000..ad13d25
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/DsClient.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_DSCLIENT_H_
+#define NTCORE_DSCLIENT_H_
+
+#include <wpi/SafeThread.h>
+
+#include "Log.h"
+
+namespace nt {
+
+class Dispatcher;
+
+class DsClient {
+ public:
+  DsClient(Dispatcher& dispatcher, wpi::Logger& logger);
+  ~DsClient() = default;
+
+  void Start(unsigned int port);
+  void Stop();
+
+ private:
+  class Thread;
+  wpi::SafeThreadOwner<Thread> m_owner;
+  Dispatcher& m_dispatcher;
+  wpi::Logger& m_logger;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_DSCLIENT_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/EntryNotifier.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/EntryNotifier.cpp
new file mode 100644
index 0000000..5fde687
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/EntryNotifier.cpp
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "EntryNotifier.h"
+
+#include "Log.h"
+
+using namespace nt;
+
+EntryNotifier::EntryNotifier(int inst, wpi::Logger& logger)
+    : m_inst(inst), m_logger(logger) {
+  m_local_notifiers = false;
+}
+
+void EntryNotifier::Start() { DoStart(m_inst); }
+
+bool EntryNotifier::local_notifiers() const { return m_local_notifiers; }
+
+bool impl::EntryNotifierThread::Matches(const EntryListenerData& listener,
+                                        const EntryNotification& data) {
+  if (!data.value) return false;
+
+  // Flags must be within requested flag set for this listener.
+  // Because assign messages can result in both a value and flags update,
+  // we handle that case specially.
+  unsigned int listen_flags =
+      listener.flags & ~(NT_NOTIFY_IMMEDIATE | NT_NOTIFY_LOCAL);
+  unsigned int flags = data.flags & ~(NT_NOTIFY_IMMEDIATE | NT_NOTIFY_LOCAL);
+  unsigned int assign_both = NT_NOTIFY_UPDATE | NT_NOTIFY_FLAGS;
+  if ((flags & assign_both) == assign_both) {
+    if ((listen_flags & assign_both) == 0) return false;
+    listen_flags &= ~assign_both;
+    flags &= ~assign_both;
+  }
+  if ((flags & ~listen_flags) != 0) return false;
+
+  // must match local id or prefix
+  if (listener.entry != 0 && data.entry != listener.entry) return false;
+  if (listener.entry == 0 &&
+      !wpi::StringRef(data.name).startswith(listener.prefix))
+    return false;
+
+  return true;
+}
+
+unsigned int EntryNotifier::Add(
+    std::function<void(const EntryNotification& event)> callback,
+    StringRef prefix, unsigned int flags) {
+  if ((flags & NT_NOTIFY_LOCAL) != 0) m_local_notifiers = true;
+  return DoAdd(callback, prefix, flags);
+}
+
+unsigned int EntryNotifier::Add(
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int local_id, unsigned int flags) {
+  if ((flags & NT_NOTIFY_LOCAL) != 0) m_local_notifiers = true;
+  return DoAdd(callback, Handle(m_inst, local_id, Handle::kEntry), flags);
+}
+
+unsigned int EntryNotifier::AddPolled(unsigned int poller_uid,
+                                      wpi::StringRef prefix,
+                                      unsigned int flags) {
+  if ((flags & NT_NOTIFY_LOCAL) != 0) m_local_notifiers = true;
+  return DoAdd(poller_uid, prefix, flags);
+}
+
+unsigned int EntryNotifier::AddPolled(unsigned int poller_uid,
+                                      unsigned int local_id,
+                                      unsigned int flags) {
+  if ((flags & NT_NOTIFY_LOCAL) != 0) m_local_notifiers = true;
+  return DoAdd(poller_uid, Handle(m_inst, local_id, Handle::kEntry), flags);
+}
+
+void EntryNotifier::NotifyEntry(unsigned int local_id, StringRef name,
+                                std::shared_ptr<Value> value,
+                                unsigned int flags,
+                                unsigned int only_listener) {
+  // optimization: don't generate needless local queue entries if we have
+  // no local listeners (as this is a common case on the server side)
+  if ((flags & NT_NOTIFY_LOCAL) != 0 && !m_local_notifiers) return;
+  DEBUG("notifying '" << name << "' (local=" << local_id
+                      << "), flags=" << flags);
+  Send(only_listener, 0, Handle(m_inst, local_id, Handle::kEntry).handle(),
+       name, value, flags);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/EntryNotifier.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/EntryNotifier.h
new file mode 100644
index 0000000..3ccf9ff
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/EntryNotifier.h
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_ENTRYNOTIFIER_H_
+#define NTCORE_ENTRYNOTIFIER_H_
+
+#include <atomic>
+#include <memory>
+#include <string>
+
+#include "CallbackManager.h"
+#include "Handle.h"
+#include "IEntryNotifier.h"
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class Logger;
+}  // namespace wpi
+
+namespace nt {
+
+namespace impl {
+
+struct EntryListenerData
+    : public ListenerData<std::function<void(const EntryNotification& event)>> {
+  EntryListenerData() = default;
+  EntryListenerData(
+      std::function<void(const EntryNotification& event)> callback_,
+      StringRef prefix_, unsigned int flags_)
+      : ListenerData(callback_), prefix(prefix_), flags(flags_) {}
+  EntryListenerData(
+      std::function<void(const EntryNotification& event)> callback_,
+      NT_Entry entry_, unsigned int flags_)
+      : ListenerData(callback_), entry(entry_), flags(flags_) {}
+  EntryListenerData(unsigned int poller_uid_, StringRef prefix_,
+                    unsigned int flags_)
+      : ListenerData(poller_uid_), prefix(prefix_), flags(flags_) {}
+  EntryListenerData(unsigned int poller_uid_, NT_Entry entry_,
+                    unsigned int flags_)
+      : ListenerData(poller_uid_), entry(entry_), flags(flags_) {}
+
+  std::string prefix;
+  NT_Entry entry = 0;
+  unsigned int flags;
+};
+
+class EntryNotifierThread
+    : public CallbackThread<EntryNotifierThread, EntryNotification,
+                            EntryListenerData> {
+ public:
+  explicit EntryNotifierThread(int inst) : m_inst(inst) {}
+
+  bool Matches(const EntryListenerData& listener,
+               const EntryNotification& data);
+
+  void SetListener(EntryNotification* data, unsigned int listener_uid) {
+    data->listener =
+        Handle(m_inst, listener_uid, Handle::kEntryListener).handle();
+  }
+
+  void DoCallback(std::function<void(const EntryNotification& event)> callback,
+                  const EntryNotification& data) {
+    callback(data);
+  }
+
+  int m_inst;
+};
+
+}  // namespace impl
+
+class EntryNotifier
+    : public IEntryNotifier,
+      public CallbackManager<EntryNotifier, impl::EntryNotifierThread> {
+  friend class EntryNotifierTest;
+  friend class CallbackManager<EntryNotifier, impl::EntryNotifierThread>;
+
+ public:
+  explicit EntryNotifier(int inst, wpi::Logger& logger);
+
+  void Start();
+
+  bool local_notifiers() const override;
+
+  unsigned int Add(std::function<void(const EntryNotification& event)> callback,
+                   wpi::StringRef prefix, unsigned int flags) override;
+  unsigned int Add(std::function<void(const EntryNotification& event)> callback,
+                   unsigned int local_id, unsigned int flags) override;
+  unsigned int AddPolled(unsigned int poller_uid, wpi::StringRef prefix,
+                         unsigned int flags) override;
+  unsigned int AddPolled(unsigned int poller_uid, unsigned int local_id,
+                         unsigned int flags) override;
+
+  void NotifyEntry(unsigned int local_id, StringRef name,
+                   std::shared_ptr<Value> value, unsigned int flags,
+                   unsigned int only_listener = UINT_MAX) override;
+
+ private:
+  int m_inst;
+  wpi::Logger& m_logger;
+  std::atomic_bool m_local_notifiers;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_ENTRYNOTIFIER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Handle.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Handle.h
new file mode 100644
index 0000000..47b5edf
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Handle.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_HANDLE_H_
+#define NTCORE_HANDLE_H_
+
+#include "ntcore_c.h"
+
+namespace nt {
+
+// Handle data layout:
+// Bits 30-28: Type
+// Bits 27-20: Instance index
+// Bits 19-0:  Handle index (0/unused for instance handles)
+
+class Handle {
+ public:
+  enum Type {
+    kConnectionListener = 1,
+    kConnectionListenerPoller,
+    kEntry,
+    kEntryListener,
+    kEntryListenerPoller,
+    kInstance,
+    kLogger,
+    kLoggerPoller,
+    kRpcCall,
+    kRpcCallPoller
+  };
+  enum { kIndexMax = 0xfffff };
+
+  explicit Handle(NT_Handle handle) : m_handle(handle) {}
+  operator NT_Handle() const { return m_handle; }
+
+  NT_Handle handle() const { return m_handle; }
+
+  Handle(int inst, int index, Type type) {
+    if (inst < 0 || index < 0) {
+      m_handle = 0;
+      return;
+    }
+    m_handle = ((static_cast<int>(type) & 0xf) << 27) | ((inst & 0x7f) << 20) |
+               (index & 0xfffff);
+  }
+
+  int GetIndex() const { return static_cast<int>(m_handle) & 0xfffff; }
+  Type GetType() const {
+    return static_cast<Type>((static_cast<int>(m_handle) >> 27) & 0xf);
+  }
+  int GetInst() const { return (static_cast<int>(m_handle) >> 20) & 0x7f; }
+  bool IsType(Type type) const { return type == GetType(); }
+  int GetTypedIndex(Type type) const { return IsType(type) ? GetIndex() : -1; }
+  int GetTypedInst(Type type) const { return IsType(type) ? GetInst() : -1; }
+
+ private:
+  NT_Handle m_handle;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_HANDLE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IConnectionNotifier.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IConnectionNotifier.h
new file mode 100644
index 0000000..7a165f2
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IConnectionNotifier.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_ICONNECTIONNOTIFIER_H_
+#define NTCORE_ICONNECTIONNOTIFIER_H_
+
+#include <climits>
+
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class IConnectionNotifier {
+ public:
+  IConnectionNotifier() = default;
+  IConnectionNotifier(const IConnectionNotifier&) = delete;
+  IConnectionNotifier& operator=(const IConnectionNotifier&) = delete;
+  virtual ~IConnectionNotifier() = default;
+  virtual unsigned int Add(
+      std::function<void(const ConnectionNotification& event)> callback) = 0;
+  virtual unsigned int AddPolled(unsigned int poller_uid) = 0;
+  virtual void NotifyConnection(bool connected, const ConnectionInfo& conn_info,
+                                unsigned int only_listener = UINT_MAX) = 0;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_ICONNECTIONNOTIFIER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IDispatcher.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IDispatcher.h
new file mode 100644
index 0000000..aace766
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IDispatcher.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_IDISPATCHER_H_
+#define NTCORE_IDISPATCHER_H_
+
+#include <memory>
+
+#include "Message.h"
+
+namespace nt {
+
+class INetworkConnection;
+
+// Interface for generation of outgoing messages to break a dependency loop
+// between Storage and Dispatcher.
+class IDispatcher {
+ public:
+  IDispatcher() = default;
+  IDispatcher(const IDispatcher&) = delete;
+  IDispatcher& operator=(const IDispatcher&) = delete;
+  virtual ~IDispatcher() = default;
+  virtual void QueueOutgoing(std::shared_ptr<Message> msg,
+                             INetworkConnection* only,
+                             INetworkConnection* except) = 0;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_IDISPATCHER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IEntryNotifier.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IEntryNotifier.h
new file mode 100644
index 0000000..80ed97e
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IEntryNotifier.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_IENTRYNOTIFIER_H_
+#define NTCORE_IENTRYNOTIFIER_H_
+
+#include <climits>
+#include <memory>
+
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class IEntryNotifier {
+ public:
+  IEntryNotifier() = default;
+  IEntryNotifier(const IEntryNotifier&) = delete;
+  IEntryNotifier& operator=(const IEntryNotifier&) = delete;
+  virtual ~IEntryNotifier() = default;
+  virtual bool local_notifiers() const = 0;
+
+  virtual unsigned int Add(
+      std::function<void(const EntryNotification& event)> callback,
+      wpi::StringRef prefix, unsigned int flags) = 0;
+  virtual unsigned int Add(
+      std::function<void(const EntryNotification& event)> callback,
+      unsigned int local_id, unsigned int flags) = 0;
+  virtual unsigned int AddPolled(unsigned int poller_uid, wpi::StringRef prefix,
+                                 unsigned int flags) = 0;
+  virtual unsigned int AddPolled(unsigned int poller_uid, unsigned int local_id,
+                                 unsigned int flags) = 0;
+
+  virtual void NotifyEntry(unsigned int local_id, StringRef name,
+                           std::shared_ptr<Value> value, unsigned int flags,
+                           unsigned int only_listener = UINT_MAX) = 0;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_IENTRYNOTIFIER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/INetworkConnection.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/INetworkConnection.h
new file mode 100644
index 0000000..0387cc9
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/INetworkConnection.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_INETWORKCONNECTION_H_
+#define NTCORE_INETWORKCONNECTION_H_
+
+#include <memory>
+
+#include "Message.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class INetworkConnection {
+ public:
+  enum State { kCreated, kInit, kHandshake, kSynchronized, kActive, kDead };
+
+  INetworkConnection() = default;
+  INetworkConnection(const INetworkConnection&) = delete;
+  INetworkConnection& operator=(const INetworkConnection&) = delete;
+  virtual ~INetworkConnection() = default;
+
+  virtual ConnectionInfo info() const = 0;
+
+  virtual void QueueOutgoing(std::shared_ptr<Message> msg) = 0;
+  virtual void PostOutgoing(bool keep_alive) = 0;
+
+  virtual unsigned int proto_rev() const = 0;
+  virtual void set_proto_rev(unsigned int proto_rev) = 0;
+
+  virtual State state() const = 0;
+  virtual void set_state(State state) = 0;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_INETWORKCONNECTION_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IRpcServer.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IRpcServer.h
new file mode 100644
index 0000000..dc8b0a6
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IRpcServer.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_IRPCSERVER_H_
+#define NTCORE_IRPCSERVER_H_
+
+#include <memory>
+
+#include "Message.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class IRpcServer {
+ public:
+  typedef std::function<void(StringRef result)> SendResponseFunc;
+
+  IRpcServer() = default;
+  IRpcServer(const IRpcServer&) = delete;
+  IRpcServer& operator=(const IRpcServer&) = delete;
+  virtual ~IRpcServer() = default;
+
+  virtual void RemoveRpc(unsigned int rpc_uid) = 0;
+
+  virtual void ProcessRpc(unsigned int local_id, unsigned int call_uid,
+                          StringRef name, StringRef params,
+                          const ConnectionInfo& conn,
+                          SendResponseFunc send_response,
+                          unsigned int rpc_uid) = 0;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_IRPCSERVER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IStorage.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IStorage.h
new file mode 100644
index 0000000..0fb3a0b
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/IStorage.h
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_ISTORAGE_H_
+#define NTCORE_ISTORAGE_H_
+
+#include <functional>
+#include <memory>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/Twine.h>
+
+#include "Message.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+class IDispatcher;
+class INetworkConnection;
+
+class IStorage {
+ public:
+  IStorage() = default;
+  IStorage(const IStorage&) = delete;
+  IStorage& operator=(const IStorage&) = delete;
+  virtual ~IStorage() = default;
+
+  // Accessors required by Dispatcher.  An interface is used for
+  // generation of outgoing messages to break a dependency loop between
+  // Storage and Dispatcher.
+  virtual void SetDispatcher(IDispatcher* dispatcher, bool server) = 0;
+  virtual void ClearDispatcher() = 0;
+
+  // Required for wire protocol 2.0 to get the entry type of an entry when
+  // receiving entry updates (because the length/type is not provided in the
+  // message itself).  Not used in wire protocol 3.0.
+  virtual NT_Type GetMessageEntryType(unsigned int id) const = 0;
+
+  virtual void ProcessIncoming(std::shared_ptr<Message> msg,
+                               INetworkConnection* conn,
+                               std::weak_ptr<INetworkConnection> conn_weak) = 0;
+  virtual void GetInitialAssignments(
+      INetworkConnection& conn,
+      std::vector<std::shared_ptr<Message>>* msgs) = 0;
+  virtual void ApplyInitialAssignments(
+      INetworkConnection& conn, wpi::ArrayRef<std::shared_ptr<Message>> msgs,
+      bool new_server, std::vector<std::shared_ptr<Message>>* out_msgs) = 0;
+
+  // Filename-based save/load functions.  Used both by periodic saves and
+  // accessible directly via the user API.
+  virtual const char* SavePersistent(const Twine& filename,
+                                     bool periodic) const = 0;
+  virtual const char* LoadPersistent(
+      const Twine& filename,
+      std::function<void(size_t line, const char* msg)> warn) = 0;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_ISTORAGE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/InstanceImpl.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/InstanceImpl.cpp
new file mode 100644
index 0000000..3b34292
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/InstanceImpl.cpp
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "InstanceImpl.h"
+
+using namespace nt;
+
+std::atomic<int> InstanceImpl::s_default{-1};
+std::atomic<InstanceImpl*> InstanceImpl::s_fast_instances[10];
+wpi::UidVector<InstanceImpl*, 10> InstanceImpl::s_instances;
+wpi::mutex InstanceImpl::s_mutex;
+
+using namespace std::placeholders;
+
+InstanceImpl::InstanceImpl(int inst)
+    : logger_impl(inst),
+      logger(std::bind(&LoggerImpl::Log, &logger_impl, _1, _2, _3, _4)),
+      connection_notifier(inst),
+      entry_notifier(inst, logger),
+      rpc_server(inst, logger),
+      storage(entry_notifier, rpc_server, logger),
+      dispatcher(storage, connection_notifier, logger),
+      ds_client(dispatcher, logger) {
+  logger.set_min_level(logger_impl.GetMinLevel());
+}
+
+InstanceImpl::~InstanceImpl() { logger.SetLogger(nullptr); }
+
+InstanceImpl* InstanceImpl::GetDefault() { return Get(GetDefaultIndex()); }
+
+InstanceImpl* InstanceImpl::Get(int inst) {
+  if (inst < 0) return nullptr;
+
+  // fast path, just an atomic read
+  if (static_cast<unsigned int>(inst) <
+      (sizeof(s_fast_instances) / sizeof(s_fast_instances[0]))) {
+    InstanceImpl* ptr = s_fast_instances[inst];
+    if (ptr) return ptr;
+  }
+
+  // slow path
+  std::lock_guard<wpi::mutex> lock(s_mutex);
+
+  // static fast-path block
+  if (static_cast<unsigned int>(inst) <
+      (sizeof(s_fast_instances) / sizeof(s_fast_instances[0]))) {
+    // double-check
+    return s_fast_instances[inst];
+  }
+
+  // vector
+  if (static_cast<unsigned int>(inst) < s_instances.size()) {
+    return s_instances[inst];
+  }
+
+  // doesn't exist
+  return nullptr;
+}
+
+int InstanceImpl::GetDefaultIndex() {
+  int inst = s_default;
+  if (inst >= 0) return inst;
+
+  // slow path
+  std::lock_guard<wpi::mutex> lock(s_mutex);
+
+  // double-check
+  inst = s_default;
+  if (inst >= 0) return inst;
+
+  // alloc and save
+  inst = AllocImpl();
+  s_default = inst;
+  return inst;
+}
+
+int InstanceImpl::Alloc() {
+  std::lock_guard<wpi::mutex> lock(s_mutex);
+  return AllocImpl();
+}
+
+int InstanceImpl::AllocImpl() {
+  unsigned int inst = s_instances.emplace_back(nullptr);
+  InstanceImpl* ptr = new InstanceImpl(inst);
+  s_instances[inst] = ptr;
+
+  if (inst < (sizeof(s_fast_instances) / sizeof(s_fast_instances[0]))) {
+    s_fast_instances[inst] = ptr;
+  }
+
+  return static_cast<int>(inst);
+}
+
+void InstanceImpl::Destroy(int inst) {
+  std::lock_guard<wpi::mutex> lock(s_mutex);
+  if (inst < 0 || static_cast<unsigned int>(inst) >= s_instances.size()) return;
+
+  if (static_cast<unsigned int>(inst) <
+      (sizeof(s_fast_instances) / sizeof(s_fast_instances[0]))) {
+    s_fast_instances[inst] = nullptr;
+  }
+
+  delete s_instances[inst];
+  s_instances.erase(inst);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/InstanceImpl.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/InstanceImpl.h
new file mode 100644
index 0000000..6e732d8
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/InstanceImpl.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_INSTANCEIMPL_H_
+#define NTCORE_INSTANCEIMPL_H_
+
+#include <atomic>
+#include <memory>
+
+#include <wpi/UidVector.h>
+#include <wpi/mutex.h>
+
+#include "ConnectionNotifier.h"
+#include "Dispatcher.h"
+#include "DsClient.h"
+#include "EntryNotifier.h"
+#include "Log.h"
+#include "LoggerImpl.h"
+#include "RpcServer.h"
+#include "Storage.h"
+
+namespace nt {
+
+class InstanceImpl {
+ public:
+  explicit InstanceImpl(int inst);
+  ~InstanceImpl();
+
+  // Instance repository
+  static InstanceImpl* GetDefault();
+  static InstanceImpl* Get(int inst);
+  static int GetDefaultIndex();
+  static int Alloc();
+  static void Destroy(int inst);
+
+  LoggerImpl logger_impl;
+  wpi::Logger logger;
+  ConnectionNotifier connection_notifier;
+  EntryNotifier entry_notifier;
+  RpcServer rpc_server;
+  Storage storage;
+  Dispatcher dispatcher;
+  DsClient ds_client;
+
+ private:
+  static int AllocImpl();
+
+  static std::atomic<int> s_default;
+  static std::atomic<InstanceImpl*> s_fast_instances[10];
+  static wpi::UidVector<InstanceImpl*, 10> s_instances;
+  static wpi::mutex s_mutex;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_INSTANCEIMPL_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Log.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Log.h
new file mode 100644
index 0000000..b8a3daf
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Log.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_LOG_H_
+#define NTCORE_LOG_H_
+
+#include <wpi/Logger.h>
+
+#define LOG(level, x) WPI_LOG(m_logger, level, x)
+
+#undef ERROR
+#define ERROR(x) WPI_ERROR(m_logger, x)
+#define WARNING(x) WPI_WARNING(m_logger, x)
+#define INFO(x) WPI_INFO(m_logger, x)
+
+#define DEBUG(x) WPI_DEBUG(m_logger, x)
+#define DEBUG1(x) WPI_DEBUG1(m_logger, x)
+#define DEBUG2(x) WPI_DEBUG2(m_logger, x)
+#define DEBUG3(x) WPI_DEBUG3(m_logger, x)
+#define DEBUG4(x) WPI_DEBUG4(m_logger, x)
+
+#endif  // NTCORE_LOG_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/LoggerImpl.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/LoggerImpl.cpp
new file mode 100644
index 0000000..b2c6786
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/LoggerImpl.cpp
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "LoggerImpl.h"
+
+#include <wpi/Path.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringRef.h>
+#include <wpi/raw_ostream.h>
+
+using namespace nt;
+
+static void DefaultLogger(unsigned int level, const char* file,
+                          unsigned int line, const char* msg) {
+  wpi::SmallString<128> buf;
+  wpi::raw_svector_ostream oss(buf);
+  if (level == 20) {
+    oss << "NT: " << msg << '\n';
+    wpi::errs() << oss.str();
+    return;
+  }
+
+  wpi::StringRef levelmsg;
+  if (level >= 50)
+    levelmsg = "CRITICAL: ";
+  else if (level >= 40)
+    levelmsg = "ERROR: ";
+  else if (level >= 30)
+    levelmsg = "WARNING: ";
+  else
+    return;
+  oss << "NT: " << levelmsg << msg << " (" << file << ':' << line << ")\n";
+  wpi::errs() << oss.str();
+}
+
+LoggerImpl::LoggerImpl(int inst) : m_inst(inst) {}
+
+void LoggerImpl::Start() { DoStart(m_inst); }
+
+unsigned int LoggerImpl::Add(
+    std::function<void(const LogMessage& msg)> callback, unsigned int min_level,
+    unsigned int max_level) {
+  return DoAdd(callback, min_level, max_level);
+}
+
+unsigned int LoggerImpl::AddPolled(unsigned int poller_uid,
+                                   unsigned int min_level,
+                                   unsigned int max_level) {
+  return DoAdd(poller_uid, min_level, max_level);
+}
+
+unsigned int LoggerImpl::GetMinLevel() {
+  auto thr = GetThread();
+  if (!thr) return NT_LOG_INFO;
+  unsigned int level = NT_LOG_INFO;
+  for (size_t i = 0; i < thr->m_listeners.size(); ++i) {
+    const auto& listener = thr->m_listeners[i];
+    if (listener && listener.min_level < level) level = listener.min_level;
+  }
+  return level;
+}
+
+void LoggerImpl::Log(unsigned int level, const char* file, unsigned int line,
+                     const char* msg) {
+  // this is safe because it's null terminated and always the end
+  const char* filename = wpi::sys::path::filename(file).data();
+  {
+    auto thr = GetThread();
+    if (!thr || thr->m_listeners.empty())
+      DefaultLogger(level, filename, line, msg);
+  }
+  Send(UINT_MAX, 0, level, filename, line, msg);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/LoggerImpl.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/LoggerImpl.h
new file mode 100644
index 0000000..3ac0295
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/LoggerImpl.h
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_LOGGERIMPL_H_
+#define NTCORE_LOGGERIMPL_H_
+
+#include "CallbackManager.h"
+#include "Handle.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+namespace impl {
+
+struct LoggerListenerData
+    : public ListenerData<std::function<void(const LogMessage& msg)>> {
+  LoggerListenerData() = default;
+  LoggerListenerData(std::function<void(const LogMessage& msg)> callback_,
+                     unsigned int min_level_, unsigned int max_level_)
+      : ListenerData(callback_), min_level(min_level_), max_level(max_level_) {}
+  LoggerListenerData(unsigned int poller_uid_, unsigned int min_level_,
+                     unsigned int max_level_)
+      : ListenerData(poller_uid_),
+        min_level(min_level_),
+        max_level(max_level_) {}
+
+  unsigned int min_level;
+  unsigned int max_level;
+};
+
+class LoggerThread
+    : public CallbackThread<LoggerThread, LogMessage, LoggerListenerData> {
+ public:
+  explicit LoggerThread(int inst) : m_inst(inst) {}
+
+  bool Matches(const LoggerListenerData& listener, const LogMessage& data) {
+    return data.level >= listener.min_level && data.level <= listener.max_level;
+  }
+
+  void SetListener(LogMessage* data, unsigned int listener_uid) {
+    data->logger = Handle(m_inst, listener_uid, Handle::kLogger).handle();
+  }
+
+  void DoCallback(std::function<void(const LogMessage& msg)> callback,
+                  const LogMessage& data) {
+    callback(data);
+  }
+
+  int m_inst;
+};
+
+}  // namespace impl
+
+class LoggerImpl : public CallbackManager<LoggerImpl, impl::LoggerThread> {
+  friend class LoggerTest;
+  friend class CallbackManager<LoggerImpl, impl::LoggerThread>;
+
+ public:
+  explicit LoggerImpl(int inst);
+
+  void Start();
+
+  unsigned int Add(std::function<void(const LogMessage& msg)> callback,
+                   unsigned int min_level, unsigned int max_level);
+  unsigned int AddPolled(unsigned int poller_uid, unsigned int min_level,
+                         unsigned int max_level);
+
+  unsigned int GetMinLevel();
+
+  void Log(unsigned int level, const char* file, unsigned int line,
+           const char* msg);
+
+ private:
+  int m_inst;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_LOGGERIMPL_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Message.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Message.cpp
new file mode 100644
index 0000000..576e444
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Message.cpp
@@ -0,0 +1,301 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "Message.h"
+
+#include <stdint.h>
+
+#include "Log.h"
+#include "WireDecoder.h"
+#include "WireEncoder.h"
+
+#define kClearAllMagic 0xD06CB27Aul
+
+using namespace nt;
+
+std::shared_ptr<Message> Message::Read(WireDecoder& decoder,
+                                       GetEntryTypeFunc get_entry_type) {
+  unsigned int msg_type = 0;
+  if (!decoder.Read8(&msg_type)) return nullptr;
+  auto msg =
+      std::make_shared<Message>(static_cast<MsgType>(msg_type), private_init());
+  switch (msg_type) {
+    case kKeepAlive:
+      break;
+    case kClientHello: {
+      unsigned int proto_rev;
+      if (!decoder.Read16(&proto_rev)) return nullptr;
+      msg->m_id = proto_rev;
+      // This intentionally uses the provided proto_rev instead of
+      // decoder.proto_rev().
+      if (proto_rev >= 0x0300u) {
+        if (!decoder.ReadString(&msg->m_str)) return nullptr;
+      }
+      break;
+    }
+    case kProtoUnsup: {
+      if (!decoder.Read16(&msg->m_id)) return nullptr;  // proto rev
+      break;
+    }
+    case kServerHelloDone:
+      break;
+    case kServerHello:
+      if (decoder.proto_rev() < 0x0300u) {
+        decoder.set_error("received SERVER_HELLO in protocol < 3.0");
+        return nullptr;
+      }
+      if (!decoder.Read8(&msg->m_flags)) return nullptr;
+      if (!decoder.ReadString(&msg->m_str)) return nullptr;
+      break;
+    case kClientHelloDone:
+      if (decoder.proto_rev() < 0x0300u) {
+        decoder.set_error("received CLIENT_HELLO_DONE in protocol < 3.0");
+        return nullptr;
+      }
+      break;
+    case kEntryAssign: {
+      if (!decoder.ReadString(&msg->m_str)) return nullptr;  // name
+      NT_Type type;
+      if (!decoder.ReadType(&type)) return nullptr;              // entry type
+      if (!decoder.Read16(&msg->m_id)) return nullptr;           // id
+      if (!decoder.Read16(&msg->m_seq_num_uid)) return nullptr;  // seq num
+      if (decoder.proto_rev() >= 0x0300u) {
+        if (!decoder.Read8(&msg->m_flags)) return nullptr;  // flags
+      }
+      msg->m_value = decoder.ReadValue(type);
+      if (!msg->m_value) return nullptr;
+      break;
+    }
+    case kEntryUpdate: {
+      if (!decoder.Read16(&msg->m_id)) return nullptr;           // id
+      if (!decoder.Read16(&msg->m_seq_num_uid)) return nullptr;  // seq num
+      NT_Type type;
+      if (decoder.proto_rev() >= 0x0300u) {
+        if (!decoder.ReadType(&type)) return nullptr;
+      } else {
+        type = get_entry_type(msg->m_id);
+      }
+      WPI_DEBUG4(decoder.logger(), "update message data type: " << type);
+      msg->m_value = decoder.ReadValue(type);
+      if (!msg->m_value) return nullptr;
+      break;
+    }
+    case kFlagsUpdate: {
+      if (decoder.proto_rev() < 0x0300u) {
+        decoder.set_error("received FLAGS_UPDATE in protocol < 3.0");
+        return nullptr;
+      }
+      if (!decoder.Read16(&msg->m_id)) return nullptr;
+      if (!decoder.Read8(&msg->m_flags)) return nullptr;
+      break;
+    }
+    case kEntryDelete: {
+      if (decoder.proto_rev() < 0x0300u) {
+        decoder.set_error("received ENTRY_DELETE in protocol < 3.0");
+        return nullptr;
+      }
+      if (!decoder.Read16(&msg->m_id)) return nullptr;
+      break;
+    }
+    case kClearEntries: {
+      if (decoder.proto_rev() < 0x0300u) {
+        decoder.set_error("received CLEAR_ENTRIES in protocol < 3.0");
+        return nullptr;
+      }
+      uint32_t magic;
+      if (!decoder.Read32(&magic)) return nullptr;
+      if (magic != kClearAllMagic) {
+        decoder.set_error(
+            "received incorrect CLEAR_ENTRIES magic value, ignoring");
+        return nullptr;
+      }
+      break;
+    }
+    case kExecuteRpc: {
+      if (decoder.proto_rev() < 0x0300u) {
+        decoder.set_error("received EXECUTE_RPC in protocol < 3.0");
+        return nullptr;
+      }
+      if (!decoder.Read16(&msg->m_id)) return nullptr;
+      if (!decoder.Read16(&msg->m_seq_num_uid)) return nullptr;  // uid
+      uint64_t size;
+      if (!decoder.ReadUleb128(&size)) return nullptr;
+      const char* params;
+      if (!decoder.Read(&params, size)) return nullptr;
+      msg->m_str = wpi::StringRef(params, size);
+      break;
+    }
+    case kRpcResponse: {
+      if (decoder.proto_rev() < 0x0300u) {
+        decoder.set_error("received RPC_RESPONSE in protocol < 3.0");
+        return nullptr;
+      }
+      if (!decoder.Read16(&msg->m_id)) return nullptr;
+      if (!decoder.Read16(&msg->m_seq_num_uid)) return nullptr;  // uid
+      uint64_t size;
+      if (!decoder.ReadUleb128(&size)) return nullptr;
+      const char* results;
+      if (!decoder.Read(&results, size)) return nullptr;
+      msg->m_str = wpi::StringRef(results, size);
+      break;
+    }
+    default:
+      decoder.set_error("unrecognized message type");
+      WPI_INFO(decoder.logger(), "unrecognized message type: " << msg_type);
+      return nullptr;
+  }
+  return msg;
+}
+
+std::shared_ptr<Message> Message::ClientHello(wpi::StringRef self_id) {
+  auto msg = std::make_shared<Message>(kClientHello, private_init());
+  msg->m_str = self_id;
+  return msg;
+}
+
+std::shared_ptr<Message> Message::ServerHello(unsigned int flags,
+                                              wpi::StringRef self_id) {
+  auto msg = std::make_shared<Message>(kServerHello, private_init());
+  msg->m_str = self_id;
+  msg->m_flags = flags;
+  return msg;
+}
+
+std::shared_ptr<Message> Message::EntryAssign(wpi::StringRef name,
+                                              unsigned int id,
+                                              unsigned int seq_num,
+                                              std::shared_ptr<Value> value,
+                                              unsigned int flags) {
+  auto msg = std::make_shared<Message>(kEntryAssign, private_init());
+  msg->m_str = name;
+  msg->m_value = value;
+  msg->m_id = id;
+  msg->m_flags = flags;
+  msg->m_seq_num_uid = seq_num;
+  return msg;
+}
+
+std::shared_ptr<Message> Message::EntryUpdate(unsigned int id,
+                                              unsigned int seq_num,
+                                              std::shared_ptr<Value> value) {
+  auto msg = std::make_shared<Message>(kEntryUpdate, private_init());
+  msg->m_value = value;
+  msg->m_id = id;
+  msg->m_seq_num_uid = seq_num;
+  return msg;
+}
+
+std::shared_ptr<Message> Message::FlagsUpdate(unsigned int id,
+                                              unsigned int flags) {
+  auto msg = std::make_shared<Message>(kFlagsUpdate, private_init());
+  msg->m_id = id;
+  msg->m_flags = flags;
+  return msg;
+}
+
+std::shared_ptr<Message> Message::EntryDelete(unsigned int id) {
+  auto msg = std::make_shared<Message>(kEntryDelete, private_init());
+  msg->m_id = id;
+  return msg;
+}
+
+std::shared_ptr<Message> Message::ExecuteRpc(unsigned int id, unsigned int uid,
+                                             wpi::StringRef params) {
+  auto msg = std::make_shared<Message>(kExecuteRpc, private_init());
+  msg->m_str = params;
+  msg->m_id = id;
+  msg->m_seq_num_uid = uid;
+  return msg;
+}
+
+std::shared_ptr<Message> Message::RpcResponse(unsigned int id, unsigned int uid,
+                                              wpi::StringRef result) {
+  auto msg = std::make_shared<Message>(kRpcResponse, private_init());
+  msg->m_str = result;
+  msg->m_id = id;
+  msg->m_seq_num_uid = uid;
+  return msg;
+}
+
+void Message::Write(WireEncoder& encoder) const {
+  switch (m_type) {
+    case kKeepAlive:
+      encoder.Write8(kKeepAlive);
+      break;
+    case kClientHello:
+      encoder.Write8(kClientHello);
+      encoder.Write16(encoder.proto_rev());
+      if (encoder.proto_rev() < 0x0300u) return;
+      encoder.WriteString(m_str);
+      break;
+    case kProtoUnsup:
+      encoder.Write8(kProtoUnsup);
+      encoder.Write16(encoder.proto_rev());
+      break;
+    case kServerHelloDone:
+      encoder.Write8(kServerHelloDone);
+      break;
+    case kServerHello:
+      if (encoder.proto_rev() < 0x0300u) return;  // new message in version 3.0
+      encoder.Write8(kServerHello);
+      encoder.Write8(m_flags);
+      encoder.WriteString(m_str);
+      break;
+    case kClientHelloDone:
+      if (encoder.proto_rev() < 0x0300u) return;  // new message in version 3.0
+      encoder.Write8(kClientHelloDone);
+      break;
+    case kEntryAssign:
+      encoder.Write8(kEntryAssign);
+      encoder.WriteString(m_str);
+      encoder.WriteType(m_value->type());
+      encoder.Write16(m_id);
+      encoder.Write16(m_seq_num_uid);
+      if (encoder.proto_rev() >= 0x0300u) encoder.Write8(m_flags);
+      encoder.WriteValue(*m_value);
+      break;
+    case kEntryUpdate:
+      encoder.Write8(kEntryUpdate);
+      encoder.Write16(m_id);
+      encoder.Write16(m_seq_num_uid);
+      if (encoder.proto_rev() >= 0x0300u) encoder.WriteType(m_value->type());
+      encoder.WriteValue(*m_value);
+      break;
+    case kFlagsUpdate:
+      if (encoder.proto_rev() < 0x0300u) return;  // new message in version 3.0
+      encoder.Write8(kFlagsUpdate);
+      encoder.Write16(m_id);
+      encoder.Write8(m_flags);
+      break;
+    case kEntryDelete:
+      if (encoder.proto_rev() < 0x0300u) return;  // new message in version 3.0
+      encoder.Write8(kEntryDelete);
+      encoder.Write16(m_id);
+      break;
+    case kClearEntries:
+      if (encoder.proto_rev() < 0x0300u) return;  // new message in version 3.0
+      encoder.Write8(kClearEntries);
+      encoder.Write32(kClearAllMagic);
+      break;
+    case kExecuteRpc:
+      if (encoder.proto_rev() < 0x0300u) return;  // new message in version 3.0
+      encoder.Write8(kExecuteRpc);
+      encoder.Write16(m_id);
+      encoder.Write16(m_seq_num_uid);
+      encoder.WriteString(m_str);
+      break;
+    case kRpcResponse:
+      if (encoder.proto_rev() < 0x0300u) return;  // new message in version 3.0
+      encoder.Write8(kRpcResponse);
+      encoder.Write16(m_id);
+      encoder.Write16(m_seq_num_uid);
+      encoder.WriteString(m_str);
+      break;
+    default:
+      break;
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Message.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Message.h
new file mode 100644
index 0000000..9b25abf
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Message.h
@@ -0,0 +1,117 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_MESSAGE_H_
+#define NTCORE_MESSAGE_H_
+
+#include <functional>
+#include <memory>
+#include <string>
+
+#include "networktables/NetworkTableValue.h"
+
+namespace nt {
+
+class WireDecoder;
+class WireEncoder;
+
+class Message {
+  struct private_init {};
+
+ public:
+  enum MsgType {
+    kUnknown = -1,
+    kKeepAlive = 0x00,
+    kClientHello = 0x01,
+    kProtoUnsup = 0x02,
+    kServerHelloDone = 0x03,
+    kServerHello = 0x04,
+    kClientHelloDone = 0x05,
+    kEntryAssign = 0x10,
+    kEntryUpdate = 0x11,
+    kFlagsUpdate = 0x12,
+    kEntryDelete = 0x13,
+    kClearEntries = 0x14,
+    kExecuteRpc = 0x20,
+    kRpcResponse = 0x21
+  };
+  typedef std::function<NT_Type(unsigned int id)> GetEntryTypeFunc;
+
+  Message() : m_type(kUnknown), m_id(0), m_flags(0), m_seq_num_uid(0) {}
+  Message(MsgType type, const private_init&)
+      : m_type(type), m_id(0), m_flags(0), m_seq_num_uid(0) {}
+
+  MsgType type() const { return m_type; }
+  bool Is(MsgType type) const { return type == m_type; }
+
+  // Message data accessors.  Callers are responsible for knowing what data is
+  // actually provided for a particular message.
+  wpi::StringRef str() const { return m_str; }
+  std::shared_ptr<Value> value() const { return m_value; }
+  unsigned int id() const { return m_id; }
+  unsigned int flags() const { return m_flags; }
+  unsigned int seq_num_uid() const { return m_seq_num_uid; }
+
+  // Read and write from wire representation
+  void Write(WireEncoder& encoder) const;
+  static std::shared_ptr<Message> Read(WireDecoder& decoder,
+                                       GetEntryTypeFunc get_entry_type);
+
+  // Create messages without data
+  static std::shared_ptr<Message> KeepAlive() {
+    return std::make_shared<Message>(kKeepAlive, private_init());
+  }
+  static std::shared_ptr<Message> ProtoUnsup() {
+    return std::make_shared<Message>(kProtoUnsup, private_init());
+  }
+  static std::shared_ptr<Message> ServerHelloDone() {
+    return std::make_shared<Message>(kServerHelloDone, private_init());
+  }
+  static std::shared_ptr<Message> ClientHelloDone() {
+    return std::make_shared<Message>(kClientHelloDone, private_init());
+  }
+  static std::shared_ptr<Message> ClearEntries() {
+    return std::make_shared<Message>(kClearEntries, private_init());
+  }
+
+  // Create messages with data
+  static std::shared_ptr<Message> ClientHello(wpi::StringRef self_id);
+  static std::shared_ptr<Message> ServerHello(unsigned int flags,
+                                              wpi::StringRef self_id);
+  static std::shared_ptr<Message> EntryAssign(wpi::StringRef name,
+                                              unsigned int id,
+                                              unsigned int seq_num,
+                                              std::shared_ptr<Value> value,
+                                              unsigned int flags);
+  static std::shared_ptr<Message> EntryUpdate(unsigned int id,
+                                              unsigned int seq_num,
+                                              std::shared_ptr<Value> value);
+  static std::shared_ptr<Message> FlagsUpdate(unsigned int id,
+                                              unsigned int flags);
+  static std::shared_ptr<Message> EntryDelete(unsigned int id);
+  static std::shared_ptr<Message> ExecuteRpc(unsigned int id, unsigned int uid,
+                                             wpi::StringRef params);
+  static std::shared_ptr<Message> RpcResponse(unsigned int id, unsigned int uid,
+                                              wpi::StringRef result);
+
+  Message(const Message&) = delete;
+  Message& operator=(const Message&) = delete;
+
+ private:
+  MsgType m_type;
+
+  // Message data.  Use varies by message type.
+  std::string m_str;
+  std::shared_ptr<Value> m_value;
+  unsigned int m_id;  // also used for proto_rev
+  unsigned int m_flags;
+  unsigned int m_seq_num_uid;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_MESSAGE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/NetworkConnection.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/NetworkConnection.cpp
new file mode 100644
index 0000000..cb1e333
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/NetworkConnection.cpp
@@ -0,0 +1,333 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "NetworkConnection.h"
+
+#include <wpi/NetworkStream.h>
+#include <wpi/raw_socket_istream.h>
+#include <wpi/timestamp.h>
+
+#include "IConnectionNotifier.h"
+#include "Log.h"
+#include "WireDecoder.h"
+#include "WireEncoder.h"
+
+using namespace nt;
+
+NetworkConnection::NetworkConnection(unsigned int uid,
+                                     std::unique_ptr<wpi::NetworkStream> stream,
+                                     IConnectionNotifier& notifier,
+                                     wpi::Logger& logger,
+                                     HandshakeFunc handshake,
+                                     Message::GetEntryTypeFunc get_entry_type)
+    : m_uid(uid),
+      m_stream(std::move(stream)),
+      m_notifier(notifier),
+      m_logger(logger),
+      m_handshake(handshake),
+      m_get_entry_type(get_entry_type),
+      m_state(kCreated) {
+  m_active = false;
+  m_proto_rev = 0x0300;
+  m_last_update = 0;
+
+  // turn off Nagle algorithm; we bundle packets for transmission
+  m_stream->setNoDelay();
+}
+
+NetworkConnection::~NetworkConnection() { Stop(); }
+
+void NetworkConnection::Start() {
+  if (m_active) return;
+  m_active = true;
+  set_state(kInit);
+  // clear queue
+  while (!m_outgoing.empty()) m_outgoing.pop();
+  // reset shutdown flags
+  {
+    std::lock_guard<wpi::mutex> lock(m_shutdown_mutex);
+    m_read_shutdown = false;
+    m_write_shutdown = false;
+  }
+  // start threads
+  m_write_thread = std::thread(&NetworkConnection::WriteThreadMain, this);
+  m_read_thread = std::thread(&NetworkConnection::ReadThreadMain, this);
+}
+
+void NetworkConnection::Stop() {
+  DEBUG2("NetworkConnection stopping (" << this << ")");
+  set_state(kDead);
+  m_active = false;
+  // closing the stream so the read thread terminates
+  if (m_stream) m_stream->close();
+  // send an empty outgoing message set so the write thread terminates
+  m_outgoing.push(Outgoing());
+  // wait for threads to terminate, with timeout
+  if (m_write_thread.joinable()) {
+    std::unique_lock<wpi::mutex> lock(m_shutdown_mutex);
+    auto timeout_time =
+        std::chrono::steady_clock::now() + std::chrono::milliseconds(200);
+    if (m_write_shutdown_cv.wait_until(lock, timeout_time,
+                                       [&] { return m_write_shutdown; }))
+      m_write_thread.join();
+    else
+      m_write_thread.detach();  // timed out, detach it
+  }
+  if (m_read_thread.joinable()) {
+    std::unique_lock<wpi::mutex> lock(m_shutdown_mutex);
+    auto timeout_time =
+        std::chrono::steady_clock::now() + std::chrono::milliseconds(200);
+    if (m_read_shutdown_cv.wait_until(lock, timeout_time,
+                                      [&] { return m_read_shutdown; }))
+      m_read_thread.join();
+    else
+      m_read_thread.detach();  // timed out, detach it
+  }
+  // clear queue
+  while (!m_outgoing.empty()) m_outgoing.pop();
+}
+
+ConnectionInfo NetworkConnection::info() const {
+  return ConnectionInfo{remote_id(), m_stream->getPeerIP(),
+                        static_cast<unsigned int>(m_stream->getPeerPort()),
+                        m_last_update, m_proto_rev};
+}
+
+unsigned int NetworkConnection::proto_rev() const { return m_proto_rev; }
+
+void NetworkConnection::set_proto_rev(unsigned int proto_rev) {
+  m_proto_rev = proto_rev;
+}
+
+NetworkConnection::State NetworkConnection::state() const {
+  std::lock_guard<wpi::mutex> lock(m_state_mutex);
+  return m_state;
+}
+
+void NetworkConnection::set_state(State state) {
+  std::lock_guard<wpi::mutex> lock(m_state_mutex);
+  // Don't update state any more once we've died
+  if (m_state == kDead) return;
+  // One-shot notify state changes
+  if (m_state != kActive && state == kActive)
+    m_notifier.NotifyConnection(true, info());
+  if (m_state != kDead && state == kDead)
+    m_notifier.NotifyConnection(false, info());
+  m_state = state;
+}
+
+std::string NetworkConnection::remote_id() const {
+  std::lock_guard<wpi::mutex> lock(m_remote_id_mutex);
+  return m_remote_id;
+}
+
+void NetworkConnection::set_remote_id(StringRef remote_id) {
+  std::lock_guard<wpi::mutex> lock(m_remote_id_mutex);
+  m_remote_id = remote_id;
+}
+
+void NetworkConnection::ReadThreadMain() {
+  wpi::raw_socket_istream is(*m_stream);
+  WireDecoder decoder(is, m_proto_rev, m_logger);
+
+  set_state(kHandshake);
+  if (!m_handshake(*this,
+                   [&] {
+                     decoder.set_proto_rev(m_proto_rev);
+                     auto msg = Message::Read(decoder, m_get_entry_type);
+                     if (!msg && decoder.error())
+                       DEBUG("error reading in handshake: " << decoder.error());
+                     return msg;
+                   },
+                   [&](wpi::ArrayRef<std::shared_ptr<Message>> msgs) {
+                     m_outgoing.emplace(msgs);
+                   })) {
+    set_state(kDead);
+    m_active = false;
+    goto done;
+  }
+
+  set_state(kActive);
+  while (m_active) {
+    if (!m_stream) break;
+    decoder.set_proto_rev(m_proto_rev);
+    decoder.Reset();
+    auto msg = Message::Read(decoder, m_get_entry_type);
+    if (!msg) {
+      if (decoder.error()) INFO("read error: " << decoder.error());
+      // terminate connection on bad message
+      if (m_stream) m_stream->close();
+      break;
+    }
+    DEBUG3("received type=" << msg->type() << " with str=" << msg->str()
+                            << " id=" << msg->id()
+                            << " seq_num=" << msg->seq_num_uid());
+    m_last_update = Now();
+    m_process_incoming(std::move(msg), this);
+  }
+  DEBUG2("read thread died (" << this << ")");
+  set_state(kDead);
+  m_active = false;
+  m_outgoing.push(Outgoing());  // also kill write thread
+
+done:
+  // use condition variable to signal thread shutdown
+  {
+    std::lock_guard<wpi::mutex> lock(m_shutdown_mutex);
+    m_read_shutdown = true;
+    m_read_shutdown_cv.notify_one();
+  }
+}
+
+void NetworkConnection::WriteThreadMain() {
+  WireEncoder encoder(m_proto_rev);
+
+  while (m_active) {
+    auto msgs = m_outgoing.pop();
+    DEBUG4("write thread woke up");
+    if (msgs.empty()) continue;
+    encoder.set_proto_rev(m_proto_rev);
+    encoder.Reset();
+    DEBUG3("sending " << msgs.size() << " messages");
+    for (auto& msg : msgs) {
+      if (msg) {
+        DEBUG3("sending type=" << msg->type() << " with str=" << msg->str()
+                               << " id=" << msg->id()
+                               << " seq_num=" << msg->seq_num_uid());
+        msg->Write(encoder);
+      }
+    }
+    wpi::NetworkStream::Error err;
+    if (!m_stream) break;
+    if (encoder.size() == 0) continue;
+    if (m_stream->send(encoder.data(), encoder.size(), &err) == 0) break;
+    DEBUG4("sent " << encoder.size() << " bytes");
+  }
+  DEBUG2("write thread died (" << this << ")");
+  set_state(kDead);
+  m_active = false;
+  if (m_stream) m_stream->close();  // also kill read thread
+
+  // use condition variable to signal thread shutdown
+  {
+    std::lock_guard<wpi::mutex> lock(m_shutdown_mutex);
+    m_write_shutdown = true;
+    m_write_shutdown_cv.notify_one();
+  }
+}
+
+void NetworkConnection::QueueOutgoing(std::shared_ptr<Message> msg) {
+  std::lock_guard<wpi::mutex> lock(m_pending_mutex);
+
+  // Merge with previous.  One case we don't combine: delete/assign loop.
+  switch (msg->type()) {
+    case Message::kEntryAssign:
+    case Message::kEntryUpdate: {
+      // don't do this for unassigned id's
+      unsigned int id = msg->id();
+      if (id == 0xffff) {
+        m_pending_outgoing.push_back(msg);
+        break;
+      }
+      if (id < m_pending_update.size() && m_pending_update[id].first != 0) {
+        // overwrite the previous one for this id
+        auto& oldmsg = m_pending_outgoing[m_pending_update[id].first - 1];
+        if (oldmsg && oldmsg->Is(Message::kEntryAssign) &&
+            msg->Is(Message::kEntryUpdate)) {
+          // need to update assignment with new seq_num and value
+          oldmsg = Message::EntryAssign(oldmsg->str(), id, msg->seq_num_uid(),
+                                        msg->value(), oldmsg->flags());
+        } else {
+          oldmsg = msg;  // easy update
+        }
+      } else {
+        // new, but remember it
+        size_t pos = m_pending_outgoing.size();
+        m_pending_outgoing.push_back(msg);
+        if (id >= m_pending_update.size()) m_pending_update.resize(id + 1);
+        m_pending_update[id].first = pos + 1;
+      }
+      break;
+    }
+    case Message::kEntryDelete: {
+      // don't do this for unassigned id's
+      unsigned int id = msg->id();
+      if (id == 0xffff) {
+        m_pending_outgoing.push_back(msg);
+        break;
+      }
+
+      // clear previous updates
+      if (id < m_pending_update.size()) {
+        if (m_pending_update[id].first != 0) {
+          m_pending_outgoing[m_pending_update[id].first - 1].reset();
+          m_pending_update[id].first = 0;
+        }
+        if (m_pending_update[id].second != 0) {
+          m_pending_outgoing[m_pending_update[id].second - 1].reset();
+          m_pending_update[id].second = 0;
+        }
+      }
+
+      // add deletion
+      m_pending_outgoing.push_back(msg);
+      break;
+    }
+    case Message::kFlagsUpdate: {
+      // don't do this for unassigned id's
+      unsigned int id = msg->id();
+      if (id == 0xffff) {
+        m_pending_outgoing.push_back(msg);
+        break;
+      }
+      if (id < m_pending_update.size() && m_pending_update[id].second != 0) {
+        // overwrite the previous one for this id
+        m_pending_outgoing[m_pending_update[id].second - 1] = msg;
+      } else {
+        // new, but remember it
+        size_t pos = m_pending_outgoing.size();
+        m_pending_outgoing.push_back(msg);
+        if (id >= m_pending_update.size()) m_pending_update.resize(id + 1);
+        m_pending_update[id].second = pos + 1;
+      }
+      break;
+    }
+    case Message::kClearEntries: {
+      // knock out all previous assigns/updates!
+      for (auto& i : m_pending_outgoing) {
+        if (!i) continue;
+        auto t = i->type();
+        if (t == Message::kEntryAssign || t == Message::kEntryUpdate ||
+            t == Message::kFlagsUpdate || t == Message::kEntryDelete ||
+            t == Message::kClearEntries)
+          i.reset();
+      }
+      m_pending_update.resize(0);
+      m_pending_outgoing.push_back(msg);
+      break;
+    }
+    default:
+      m_pending_outgoing.push_back(msg);
+      break;
+  }
+}
+
+void NetworkConnection::PostOutgoing(bool keep_alive) {
+  std::lock_guard<wpi::mutex> lock(m_pending_mutex);
+  auto now = std::chrono::steady_clock::now();
+  if (m_pending_outgoing.empty()) {
+    if (!keep_alive) return;
+    // send keep-alives once a second (if no other messages have been sent)
+    if ((now - m_last_post) < std::chrono::seconds(1)) return;
+    m_outgoing.emplace(Outgoing{Message::KeepAlive()});
+  } else {
+    m_outgoing.emplace(std::move(m_pending_outgoing));
+    m_pending_outgoing.resize(0);
+    m_pending_update.resize(0);
+  }
+  m_last_post = now;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/NetworkConnection.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/NetworkConnection.h
new file mode 100644
index 0000000..91ad64e
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/NetworkConnection.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKCONNECTION_H_
+#define NTCORE_NETWORKCONNECTION_H_
+
+#include <stdint.h>
+
+#include <atomic>
+#include <chrono>
+#include <memory>
+#include <string>
+#include <thread>
+#include <utility>
+#include <vector>
+
+#include <wpi/ConcurrentQueue.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "INetworkConnection.h"
+#include "Message.h"
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class Logger;
+class NetworkStream;
+}  // namespace wpi
+
+namespace nt {
+
+class IConnectionNotifier;
+
+class NetworkConnection : public INetworkConnection {
+ public:
+  typedef std::function<bool(
+      NetworkConnection& conn,
+      std::function<std::shared_ptr<Message>()> get_msg,
+      std::function<void(wpi::ArrayRef<std::shared_ptr<Message>>)> send_msgs)>
+      HandshakeFunc;
+  typedef std::function<void(std::shared_ptr<Message> msg,
+                             NetworkConnection* conn)>
+      ProcessIncomingFunc;
+  typedef std::vector<std::shared_ptr<Message>> Outgoing;
+  typedef wpi::ConcurrentQueue<Outgoing> OutgoingQueue;
+
+  NetworkConnection(unsigned int uid,
+                    std::unique_ptr<wpi::NetworkStream> stream,
+                    IConnectionNotifier& notifier, wpi::Logger& logger,
+                    HandshakeFunc handshake,
+                    Message::GetEntryTypeFunc get_entry_type);
+  ~NetworkConnection();
+
+  // Set the input processor function.  This must be called before Start().
+  void set_process_incoming(ProcessIncomingFunc func) {
+    m_process_incoming = func;
+  }
+
+  void Start();
+  void Stop();
+
+  ConnectionInfo info() const override;
+
+  bool active() const { return m_active; }
+  wpi::NetworkStream& stream() { return *m_stream; }
+
+  void QueueOutgoing(std::shared_ptr<Message> msg) override;
+  void PostOutgoing(bool keep_alive) override;
+
+  unsigned int uid() const { return m_uid; }
+
+  unsigned int proto_rev() const override;
+  void set_proto_rev(unsigned int proto_rev) override;
+
+  State state() const override;
+  void set_state(State state) override;
+
+  std::string remote_id() const;
+  void set_remote_id(StringRef remote_id);
+
+  uint64_t last_update() const { return m_last_update; }
+
+  NetworkConnection(const NetworkConnection&) = delete;
+  NetworkConnection& operator=(const NetworkConnection&) = delete;
+
+ private:
+  void ReadThreadMain();
+  void WriteThreadMain();
+
+  unsigned int m_uid;
+  std::unique_ptr<wpi::NetworkStream> m_stream;
+  IConnectionNotifier& m_notifier;
+  wpi::Logger& m_logger;
+  OutgoingQueue m_outgoing;
+  HandshakeFunc m_handshake;
+  Message::GetEntryTypeFunc m_get_entry_type;
+  ProcessIncomingFunc m_process_incoming;
+  std::thread m_read_thread;
+  std::thread m_write_thread;
+  std::atomic_bool m_active;
+  std::atomic_uint m_proto_rev;
+  mutable wpi::mutex m_state_mutex;
+  State m_state;
+  mutable wpi::mutex m_remote_id_mutex;
+  std::string m_remote_id;
+  std::atomic_ullong m_last_update;
+  std::chrono::steady_clock::time_point m_last_post;
+
+  wpi::mutex m_pending_mutex;
+  Outgoing m_pending_outgoing;
+  std::vector<std::pair<size_t, size_t>> m_pending_update;
+
+  // Condition variables for shutdown
+  wpi::mutex m_shutdown_mutex;
+  wpi::condition_variable m_read_shutdown_cv;
+  wpi::condition_variable m_write_shutdown_cv;
+  bool m_read_shutdown = false;
+  bool m_write_shutdown = false;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_NETWORKCONNECTION_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/RpcServer.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/RpcServer.cpp
new file mode 100644
index 0000000..0c6811c
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/RpcServer.cpp
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "RpcServer.h"
+
+using namespace nt;
+
+RpcServer::RpcServer(int inst, wpi::Logger& logger)
+    : m_inst(inst), m_logger(logger) {}
+
+void RpcServer::Start() { DoStart(m_inst, m_logger); }
+
+unsigned int RpcServer::Add(
+    std::function<void(const RpcAnswer& answer)> callback) {
+  return DoAdd(callback);
+}
+
+unsigned int RpcServer::AddPolled(unsigned int poller_uid) {
+  return DoAdd(poller_uid);
+}
+
+void RpcServer::RemoveRpc(unsigned int rpc_uid) { Remove(rpc_uid); }
+
+void RpcServer::ProcessRpc(unsigned int local_id, unsigned int call_uid,
+                           StringRef name, StringRef params,
+                           const ConnectionInfo& conn,
+                           SendResponseFunc send_response,
+                           unsigned int rpc_uid) {
+  Send(rpc_uid, Handle(m_inst, local_id, Handle::kEntry).handle(),
+       Handle(m_inst, call_uid, Handle::kRpcCall).handle(), name, params, conn,
+       send_response);
+}
+
+bool RpcServer::PostRpcResponse(unsigned int local_id, unsigned int call_uid,
+                                wpi::StringRef result) {
+  auto thr = GetThread();
+  auto i = thr->m_response_map.find(impl::RpcIdPair{local_id, call_uid});
+  if (i == thr->m_response_map.end()) {
+    WARNING("posting RPC response to nonexistent call (or duplicate response)");
+    return false;
+  }
+  (i->getSecond())(result);
+  thr->m_response_map.erase(i);
+  return true;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/RpcServer.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/RpcServer.h
new file mode 100644
index 0000000..5afe62a
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/RpcServer.h
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_RPCSERVER_H_
+#define NTCORE_RPCSERVER_H_
+
+#include <utility>
+
+#include <wpi/DenseMap.h>
+#include <wpi/mutex.h>
+
+#include "CallbackManager.h"
+#include "Handle.h"
+#include "IRpcServer.h"
+#include "Log.h"
+
+namespace nt {
+
+namespace impl {
+
+typedef std::pair<unsigned int, unsigned int> RpcIdPair;
+
+struct RpcNotifierData : public RpcAnswer {
+  RpcNotifierData(NT_Entry entry_, NT_RpcCall call_, StringRef name_,
+                  StringRef params_, const ConnectionInfo& conn_,
+                  IRpcServer::SendResponseFunc send_response_)
+      : RpcAnswer{entry_, call_, name_, params_, conn_},
+        send_response{send_response_} {}
+
+  IRpcServer::SendResponseFunc send_response;
+};
+
+using RpcListenerData =
+    ListenerData<std::function<void(const RpcAnswer& answer)>>;
+
+class RpcServerThread
+    : public CallbackThread<RpcServerThread, RpcAnswer, RpcListenerData,
+                            RpcNotifierData> {
+ public:
+  RpcServerThread(int inst, wpi::Logger& logger)
+      : m_inst(inst), m_logger(logger) {}
+
+  bool Matches(const RpcListenerData& /*listener*/,
+               const RpcNotifierData& data) {
+    return !data.name.empty() && data.send_response;
+  }
+
+  void SetListener(RpcNotifierData* data, unsigned int /*listener_uid*/) {
+    unsigned int local_id = Handle{data->entry}.GetIndex();
+    unsigned int call_uid = Handle{data->call}.GetIndex();
+    RpcIdPair lookup_uid{local_id, call_uid};
+    m_response_map.insert(std::make_pair(lookup_uid, data->send_response));
+  }
+
+  void DoCallback(std::function<void(const RpcAnswer& call)> callback,
+                  const RpcNotifierData& data) {
+    DEBUG4("rpc calling " << data.name);
+    unsigned int local_id = Handle{data.entry}.GetIndex();
+    unsigned int call_uid = Handle{data.call}.GetIndex();
+    RpcIdPair lookup_uid{local_id, call_uid};
+    callback(data);
+    {
+      std::lock_guard<wpi::mutex> lock(m_mutex);
+      auto i = m_response_map.find(lookup_uid);
+      if (i != m_response_map.end()) {
+        // post an empty response and erase it
+        (i->getSecond())("");
+        m_response_map.erase(i);
+      }
+    }
+  }
+
+  int m_inst;
+  wpi::Logger& m_logger;
+  wpi::DenseMap<RpcIdPair, IRpcServer::SendResponseFunc> m_response_map;
+};
+
+}  // namespace impl
+
+class RpcServer : public IRpcServer,
+                  public CallbackManager<RpcServer, impl::RpcServerThread> {
+  friend class RpcServerTest;
+  friend class CallbackManager<RpcServer, impl::RpcServerThread>;
+
+ public:
+  RpcServer(int inst, wpi::Logger& logger);
+
+  void Start();
+
+  unsigned int Add(std::function<void(const RpcAnswer& answer)> callback);
+  unsigned int AddPolled(unsigned int poller_uid);
+  void RemoveRpc(unsigned int rpc_uid) override;
+
+  void ProcessRpc(unsigned int local_id, unsigned int call_uid, StringRef name,
+                  StringRef params, const ConnectionInfo& conn,
+                  SendResponseFunc send_response,
+                  unsigned int rpc_uid) override;
+
+  bool PostRpcResponse(unsigned int local_id, unsigned int call_uid,
+                       wpi::StringRef result);
+
+ private:
+  int m_inst;
+  wpi::Logger& m_logger;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_RPCSERVER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/SequenceNumber.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/SequenceNumber.cpp
new file mode 100644
index 0000000..6d61331
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/SequenceNumber.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "SequenceNumber.h"
+
+namespace nt {
+
+bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs) {
+  if (lhs.m_value < rhs.m_value)
+    return (rhs.m_value - lhs.m_value) < (1u << 15);
+  else if (lhs.m_value > rhs.m_value)
+    return (lhs.m_value - rhs.m_value) > (1u << 15);
+  else
+    return false;
+}
+
+bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs) {
+  if (lhs.m_value < rhs.m_value)
+    return (rhs.m_value - lhs.m_value) > (1u << 15);
+  else if (lhs.m_value > rhs.m_value)
+    return (lhs.m_value - rhs.m_value) < (1u << 15);
+  else
+    return false;
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/SequenceNumber.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/SequenceNumber.h
new file mode 100644
index 0000000..11d9953
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/SequenceNumber.h
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_SEQUENCENUMBER_H_
+#define NTCORE_SEQUENCENUMBER_H_
+
+namespace nt {
+
+/* A sequence number per RFC 1982 */
+class SequenceNumber {
+ public:
+  SequenceNumber() : m_value(0) {}
+  explicit SequenceNumber(unsigned int value) : m_value(value) {}
+  unsigned int value() const { return m_value; }
+
+  SequenceNumber& operator++() {
+    ++m_value;
+    if (m_value > 0xffff) m_value = 0;
+    return *this;
+  }
+  SequenceNumber operator++(int) {
+    SequenceNumber tmp(*this);
+    operator++();
+    return tmp;
+  }
+
+  friend bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs);
+  friend bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs);
+  friend bool operator<=(const SequenceNumber& lhs, const SequenceNumber& rhs);
+  friend bool operator>=(const SequenceNumber& lhs, const SequenceNumber& rhs);
+  friend bool operator==(const SequenceNumber& lhs, const SequenceNumber& rhs);
+  friend bool operator!=(const SequenceNumber& lhs, const SequenceNumber& rhs);
+
+ private:
+  unsigned int m_value;
+};
+
+bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs);
+bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs);
+
+inline bool operator<=(const SequenceNumber& lhs, const SequenceNumber& rhs) {
+  return lhs == rhs || lhs < rhs;
+}
+
+inline bool operator>=(const SequenceNumber& lhs, const SequenceNumber& rhs) {
+  return lhs == rhs || lhs > rhs;
+}
+
+inline bool operator==(const SequenceNumber& lhs, const SequenceNumber& rhs) {
+  return lhs.m_value == rhs.m_value;
+}
+
+inline bool operator!=(const SequenceNumber& lhs, const SequenceNumber& rhs) {
+  return lhs.m_value != rhs.m_value;
+}
+
+}  // namespace nt
+
+#endif  // NTCORE_SEQUENCENUMBER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage.cpp
new file mode 100644
index 0000000..0d8d467
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage.cpp
@@ -0,0 +1,1131 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "Storage.h"
+
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "IDispatcher.h"
+#include "IEntryNotifier.h"
+#include "INetworkConnection.h"
+#include "IRpcServer.h"
+#include "Log.h"
+
+using namespace nt;
+
+Storage::Storage(IEntryNotifier& notifier, IRpcServer& rpc_server,
+                 wpi::Logger& logger)
+    : m_notifier(notifier), m_rpc_server(rpc_server), m_logger(logger) {
+  m_terminating = false;
+}
+
+Storage::~Storage() {
+  m_terminating = true;
+  m_rpc_results_cond.notify_all();
+}
+
+void Storage::SetDispatcher(IDispatcher* dispatcher, bool server) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_dispatcher = dispatcher;
+  m_server = server;
+}
+
+void Storage::ClearDispatcher() { m_dispatcher = nullptr; }
+
+NT_Type Storage::GetMessageEntryType(unsigned int id) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (id >= m_idmap.size()) return NT_UNASSIGNED;
+  Entry* entry = m_idmap[id];
+  if (!entry || !entry->value) return NT_UNASSIGNED;
+  return entry->value->type();
+}
+
+void Storage::ProcessIncoming(std::shared_ptr<Message> msg,
+                              INetworkConnection* conn,
+                              std::weak_ptr<INetworkConnection> conn_weak) {
+  switch (msg->type()) {
+    case Message::kKeepAlive:
+      break;  // ignore
+    case Message::kClientHello:
+    case Message::kProtoUnsup:
+    case Message::kServerHelloDone:
+    case Message::kServerHello:
+    case Message::kClientHelloDone:
+      // shouldn't get these, but ignore if we do
+      break;
+    case Message::kEntryAssign:
+      ProcessIncomingEntryAssign(std::move(msg), conn);
+      break;
+    case Message::kEntryUpdate:
+      ProcessIncomingEntryUpdate(std::move(msg), conn);
+      break;
+    case Message::kFlagsUpdate:
+      ProcessIncomingFlagsUpdate(std::move(msg), conn);
+      break;
+    case Message::kEntryDelete:
+      ProcessIncomingEntryDelete(std::move(msg), conn);
+      break;
+    case Message::kClearEntries:
+      ProcessIncomingClearEntries(std::move(msg), conn);
+      break;
+    case Message::kExecuteRpc:
+      ProcessIncomingExecuteRpc(std::move(msg), conn, std::move(conn_weak));
+      break;
+    case Message::kRpcResponse:
+      ProcessIncomingRpcResponse(std::move(msg), conn);
+      break;
+    default:
+      break;
+  }
+}
+
+void Storage::ProcessIncomingEntryAssign(std::shared_ptr<Message> msg,
+                                         INetworkConnection* conn) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  unsigned int id = msg->id();
+  StringRef name = msg->str();
+  Entry* entry;
+  bool may_need_update = false;
+  SequenceNumber seq_num(msg->seq_num_uid());
+  if (m_server) {
+    // if we're a server, id=0xffff requests are requests for an id
+    // to be assigned, and we need to send the new assignment back to
+    // the sender as well as all other connections.
+    if (id == 0xffff) {
+      entry = GetOrNew(name);
+      // see if it was already assigned; ignore if so.
+      if (entry->id != 0xffff) return;
+
+      entry->flags = msg->flags();
+      entry->seq_num = seq_num;
+      SetEntryValueImpl(entry, msg->value(), lock, false);
+      return;
+    }
+    if (id >= m_idmap.size() || !m_idmap[id]) {
+      // ignore arbitrary entry assignments
+      // this can happen due to e.g. assignment to deleted entry
+      lock.unlock();
+      DEBUG("server: received assignment to unknown entry");
+      return;
+    }
+    entry = m_idmap[id];
+  } else {
+    // clients simply accept new assignments
+    if (id == 0xffff) {
+      lock.unlock();
+      DEBUG("client: received entry assignment request?");
+      return;
+    }
+    if (id >= m_idmap.size()) m_idmap.resize(id + 1);
+    entry = m_idmap[id];
+    if (!entry) {
+      // create local
+      entry = GetOrNew(name);
+      entry->id = id;
+      m_idmap[id] = entry;
+      if (!entry->value) {
+        // didn't exist at all (rather than just being a response to a
+        // id assignment request)
+        entry->value = msg->value();
+        entry->flags = msg->flags();
+        entry->seq_num = seq_num;
+
+        // notify
+        m_notifier.NotifyEntry(entry->local_id, name, entry->value,
+                               NT_NOTIFY_NEW);
+        return;
+      }
+      may_need_update = true;  // we may need to send an update message
+
+      // if the received flags don't match what we sent, we most likely
+      // updated flags locally in the interim; send flags update message.
+      if (msg->flags() != entry->flags) {
+        auto dispatcher = m_dispatcher;
+        auto outmsg = Message::FlagsUpdate(id, entry->flags);
+        lock.unlock();
+        dispatcher->QueueOutgoing(outmsg, nullptr, nullptr);
+        lock.lock();
+      }
+    }
+  }
+
+  // common client and server handling
+
+  // already exists; ignore if sequence number not higher than local
+  if (seq_num < entry->seq_num) {
+    if (may_need_update) {
+      auto dispatcher = m_dispatcher;
+      auto outmsg =
+          Message::EntryUpdate(entry->id, entry->seq_num.value(), entry->value);
+      lock.unlock();
+      dispatcher->QueueOutgoing(outmsg, nullptr, nullptr);
+    }
+    return;
+  }
+
+  // sanity check: name should match id
+  if (msg->str() != entry->name) {
+    lock.unlock();
+    DEBUG("entry assignment for same id with different name?");
+    return;
+  }
+
+  unsigned int notify_flags = NT_NOTIFY_UPDATE;
+
+  // don't update flags from a <3.0 remote (not part of message)
+  // don't update flags if this is a server response to a client id request
+  if (!may_need_update && conn->proto_rev() >= 0x0300) {
+    // update persistent dirty flag if persistent flag changed
+    if ((entry->flags & NT_PERSISTENT) != (msg->flags() & NT_PERSISTENT))
+      m_persistent_dirty = true;
+    if (entry->flags != msg->flags()) notify_flags |= NT_NOTIFY_FLAGS;
+    entry->flags = msg->flags();
+  }
+
+  // update persistent dirty flag if the value changed and it's persistent
+  if (entry->IsPersistent() && *entry->value != *msg->value())
+    m_persistent_dirty = true;
+
+  // update local
+  entry->value = msg->value();
+  entry->seq_num = seq_num;
+
+  // notify
+  m_notifier.NotifyEntry(entry->local_id, name, entry->value, notify_flags);
+
+  // broadcast to all other connections (note for client there won't
+  // be any other connections, so don't bother)
+  if (m_server && m_dispatcher) {
+    auto dispatcher = m_dispatcher;
+    auto outmsg = Message::EntryAssign(entry->name, id, msg->seq_num_uid(),
+                                       msg->value(), entry->flags);
+    lock.unlock();
+    dispatcher->QueueOutgoing(outmsg, nullptr, conn);
+  }
+}
+
+void Storage::ProcessIncomingEntryUpdate(std::shared_ptr<Message> msg,
+                                         INetworkConnection* conn) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  unsigned int id = msg->id();
+  if (id >= m_idmap.size() || !m_idmap[id]) {
+    // ignore arbitrary entry updates;
+    // this can happen due to deleted entries
+    lock.unlock();
+    DEBUG("received update to unknown entry");
+    return;
+  }
+  Entry* entry = m_idmap[id];
+
+  // ignore if sequence number not higher than local
+  SequenceNumber seq_num(msg->seq_num_uid());
+  if (seq_num <= entry->seq_num) return;
+
+  // update local
+  entry->value = msg->value();
+  entry->seq_num = seq_num;
+
+  // update persistent dirty flag if it's a persistent value
+  if (entry->IsPersistent()) m_persistent_dirty = true;
+
+  // notify
+  m_notifier.NotifyEntry(entry->local_id, entry->name, entry->value,
+                         NT_NOTIFY_UPDATE);
+
+  // broadcast to all other connections (note for client there won't
+  // be any other connections, so don't bother)
+  if (m_server && m_dispatcher) {
+    auto dispatcher = m_dispatcher;
+    lock.unlock();
+    dispatcher->QueueOutgoing(msg, nullptr, conn);
+  }
+}
+
+void Storage::ProcessIncomingFlagsUpdate(std::shared_ptr<Message> msg,
+                                         INetworkConnection* conn) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  unsigned int id = msg->id();
+  if (id >= m_idmap.size() || !m_idmap[id]) {
+    // ignore arbitrary entry updates;
+    // this can happen due to deleted entries
+    lock.unlock();
+    DEBUG("received flags update to unknown entry");
+    return;
+  }
+
+  // update local
+  SetEntryFlagsImpl(m_idmap[id], msg->flags(), lock, false);
+
+  // broadcast to all other connections (note for client there won't
+  // be any other connections, so don't bother)
+  if (m_server && m_dispatcher) {
+    auto dispatcher = m_dispatcher;
+    lock.unlock();
+    dispatcher->QueueOutgoing(msg, nullptr, conn);
+  }
+}
+
+void Storage::ProcessIncomingEntryDelete(std::shared_ptr<Message> msg,
+                                         INetworkConnection* conn) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  unsigned int id = msg->id();
+  if (id >= m_idmap.size() || !m_idmap[id]) {
+    // ignore arbitrary entry updates;
+    // this can happen due to deleted entries
+    lock.unlock();
+    DEBUG("received delete to unknown entry");
+    return;
+  }
+
+  // update local
+  DeleteEntryImpl(m_idmap[id], lock, false);
+
+  // broadcast to all other connections (note for client there won't
+  // be any other connections, so don't bother)
+  if (m_server && m_dispatcher) {
+    auto dispatcher = m_dispatcher;
+    lock.unlock();
+    dispatcher->QueueOutgoing(msg, nullptr, conn);
+  }
+}
+
+void Storage::ProcessIncomingClearEntries(std::shared_ptr<Message> msg,
+                                          INetworkConnection* conn) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  // update local
+  DeleteAllEntriesImpl(false);
+
+  // broadcast to all other connections (note for client there won't
+  // be any other connections, so don't bother)
+  if (m_server && m_dispatcher) {
+    auto dispatcher = m_dispatcher;
+    lock.unlock();
+    dispatcher->QueueOutgoing(msg, nullptr, conn);
+  }
+}
+
+void Storage::ProcessIncomingExecuteRpc(
+    std::shared_ptr<Message> msg, INetworkConnection* /*conn*/,
+    std::weak_ptr<INetworkConnection> conn_weak) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (!m_server) return;  // only process on server
+  unsigned int id = msg->id();
+  if (id >= m_idmap.size() || !m_idmap[id]) {
+    // ignore call to non-existent RPC
+    // this can happen due to deleted entries
+    lock.unlock();
+    DEBUG("received RPC call to unknown entry");
+    return;
+  }
+  Entry* entry = m_idmap[id];
+  if (!entry->value || !entry->value->IsRpc()) {
+    lock.unlock();
+    DEBUG("received RPC call to non-RPC entry");
+    return;
+  }
+  ConnectionInfo conn_info;
+  auto c = conn_weak.lock();
+  if (c) {
+    conn_info = c->info();
+  } else {
+    conn_info.remote_id = "";
+    conn_info.remote_ip = "";
+    conn_info.remote_port = 0;
+    conn_info.last_update = 0;
+    conn_info.protocol_version = 0;
+  }
+  unsigned int call_uid = msg->seq_num_uid();
+  m_rpc_server.ProcessRpc(
+      entry->local_id, call_uid, entry->name, msg->str(), conn_info,
+      [=](StringRef result) {
+        auto c = conn_weak.lock();
+        if (c) c->QueueOutgoing(Message::RpcResponse(id, call_uid, result));
+      },
+      entry->rpc_uid);
+}
+
+void Storage::ProcessIncomingRpcResponse(std::shared_ptr<Message> msg,
+                                         INetworkConnection* /*conn*/) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (m_server) return;  // only process on client
+  unsigned int id = msg->id();
+  if (id >= m_idmap.size() || !m_idmap[id]) {
+    // ignore response to non-existent RPC
+    // this can happen due to deleted entries
+    lock.unlock();
+    DEBUG("received rpc response to unknown entry");
+    return;
+  }
+  Entry* entry = m_idmap[id];
+  if (!entry->value || !entry->value->IsRpc()) {
+    lock.unlock();
+    DEBUG("received RPC response to non-RPC entry");
+    return;
+  }
+  m_rpc_results.insert(std::make_pair(
+      RpcIdPair{entry->local_id, msg->seq_num_uid()}, msg->str()));
+  m_rpc_results_cond.notify_all();
+}
+
+void Storage::GetInitialAssignments(
+    INetworkConnection& conn, std::vector<std::shared_ptr<Message>>* msgs) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  conn.set_state(INetworkConnection::kSynchronized);
+  for (auto& i : m_entries) {
+    Entry* entry = i.getValue();
+    if (!entry->value) continue;
+    msgs->emplace_back(Message::EntryAssign(i.getKey(), entry->id,
+                                            entry->seq_num.value(),
+                                            entry->value, entry->flags));
+  }
+}
+
+void Storage::ApplyInitialAssignments(
+    INetworkConnection& conn, wpi::ArrayRef<std::shared_ptr<Message>> msgs,
+    bool /*new_server*/, std::vector<std::shared_ptr<Message>>* out_msgs) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (m_server) return;  // should not do this on server
+
+  conn.set_state(INetworkConnection::kSynchronized);
+
+  std::vector<std::shared_ptr<Message>> update_msgs;
+
+  // clear existing id's
+  for (auto& i : m_entries) i.getValue()->id = 0xffff;
+
+  // clear existing idmap
+  m_idmap.resize(0);
+
+  // apply assignments
+  for (auto& msg : msgs) {
+    if (!msg->Is(Message::kEntryAssign)) {
+      DEBUG("client: received non-entry assignment request?");
+      continue;
+    }
+
+    unsigned int id = msg->id();
+    if (id == 0xffff) {
+      DEBUG("client: received entry assignment request?");
+      continue;
+    }
+
+    SequenceNumber seq_num(msg->seq_num_uid());
+    StringRef name = msg->str();
+
+    Entry* entry = GetOrNew(name);
+    entry->seq_num = seq_num;
+    entry->id = id;
+    if (!entry->value) {
+      // doesn't currently exist
+      entry->value = msg->value();
+      entry->flags = msg->flags();
+      // notify
+      m_notifier.NotifyEntry(entry->local_id, name, entry->value,
+                             NT_NOTIFY_NEW);
+    } else {
+      // if we have written the value locally and the value is not persistent,
+      // then we don't update the local value and instead send it back to the
+      // server as an update message
+      if (entry->local_write && !entry->IsPersistent()) {
+        ++entry->seq_num;
+        update_msgs.emplace_back(Message::EntryUpdate(
+            entry->id, entry->seq_num.value(), entry->value));
+      } else {
+        entry->value = msg->value();
+        unsigned int notify_flags = NT_NOTIFY_UPDATE;
+        // don't update flags from a <3.0 remote (not part of message)
+        if (conn.proto_rev() >= 0x0300) {
+          if (entry->flags != msg->flags()) notify_flags |= NT_NOTIFY_FLAGS;
+          entry->flags = msg->flags();
+        }
+        // notify
+        m_notifier.NotifyEntry(entry->local_id, name, entry->value,
+                               notify_flags);
+      }
+    }
+
+    // save to idmap
+    if (id >= m_idmap.size()) m_idmap.resize(id + 1);
+    m_idmap[id] = entry;
+  }
+
+  // delete or generate assign messages for unassigned local entries
+  DeleteAllEntriesImpl(false, [&](Entry* entry) -> bool {
+    // was assigned by the server, don't delete
+    if (entry->id != 0xffff) return false;
+    // if we have written the value locally, we send an assign message to the
+    // server instead of deleting
+    if (entry->local_write) {
+      out_msgs->emplace_back(Message::EntryAssign(entry->name, entry->id,
+                                                  entry->seq_num.value(),
+                                                  entry->value, entry->flags));
+      return false;
+    }
+    // otherwise delete
+    return true;
+  });
+  auto dispatcher = m_dispatcher;
+  lock.unlock();
+  for (auto& msg : update_msgs)
+    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
+}
+
+std::shared_ptr<Value> Storage::GetEntryValue(StringRef name) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto i = m_entries.find(name);
+  if (i == m_entries.end()) return nullptr;
+  return i->getValue()->value;
+}
+
+std::shared_ptr<Value> Storage::GetEntryValue(unsigned int local_id) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return nullptr;
+  return m_localmap[local_id]->value;
+}
+
+bool Storage::SetDefaultEntryValue(StringRef name,
+                                   std::shared_ptr<Value> value) {
+  if (name.empty()) return false;
+  if (!value) return false;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  Entry* entry = GetOrNew(name);
+
+  // we return early if value already exists; if types match return true
+  if (entry->value) return entry->value->type() == value->type();
+
+  SetEntryValueImpl(entry, value, lock, true);
+  return true;
+}
+
+bool Storage::SetDefaultEntryValue(unsigned int local_id,
+                                   std::shared_ptr<Value> value) {
+  if (!value) return false;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return false;
+  Entry* entry = m_localmap[local_id].get();
+
+  // we return early if value already exists; if types match return true
+  if (entry->value) return entry->value->type() == value->type();
+
+  SetEntryValueImpl(entry, value, lock, true);
+  return true;
+}
+
+bool Storage::SetEntryValue(StringRef name, std::shared_ptr<Value> value) {
+  if (name.empty()) return true;
+  if (!value) return true;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  Entry* entry = GetOrNew(name);
+
+  if (entry->value && entry->value->type() != value->type())
+    return false;  // error on type mismatch
+
+  SetEntryValueImpl(entry, value, lock, true);
+  return true;
+}
+
+bool Storage::SetEntryValue(unsigned int local_id,
+                            std::shared_ptr<Value> value) {
+  if (!value) return true;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return true;
+  Entry* entry = m_localmap[local_id].get();
+
+  if (entry->value && entry->value->type() != value->type())
+    return false;  // error on type mismatch
+
+  SetEntryValueImpl(entry, value, lock, true);
+  return true;
+}
+
+void Storage::SetEntryValueImpl(Entry* entry, std::shared_ptr<Value> value,
+                                std::unique_lock<wpi::mutex>& lock,
+                                bool local) {
+  if (!value) return;
+  auto old_value = entry->value;
+  entry->value = value;
+
+  // if we're the server, assign an id if it doesn't have one
+  if (m_server && entry->id == 0xffff) {
+    unsigned int id = m_idmap.size();
+    entry->id = id;
+    m_idmap.push_back(entry);
+  }
+
+  // update persistent dirty flag if value changed and it's persistent
+  if (entry->IsPersistent() && (!old_value || *old_value != *value))
+    m_persistent_dirty = true;
+
+  // notify
+  if (!old_value)
+    m_notifier.NotifyEntry(entry->local_id, entry->name, value,
+                           NT_NOTIFY_NEW | (local ? NT_NOTIFY_LOCAL : 0));
+  else if (*old_value != *value)
+    m_notifier.NotifyEntry(entry->local_id, entry->name, value,
+                           NT_NOTIFY_UPDATE | (local ? NT_NOTIFY_LOCAL : 0));
+
+  // remember local changes
+  if (local) entry->local_write = true;
+
+  // generate message
+  if (!m_dispatcher || (!local && !m_server)) return;
+  auto dispatcher = m_dispatcher;
+  if (!old_value || old_value->type() != value->type()) {
+    if (local) ++entry->seq_num;
+    auto msg = Message::EntryAssign(
+        entry->name, entry->id, entry->seq_num.value(), value, entry->flags);
+    lock.unlock();
+    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
+  } else if (*old_value != *value) {
+    if (local) ++entry->seq_num;
+    // don't send an update if we don't have an assigned id yet
+    if (entry->id != 0xffff) {
+      auto msg = Message::EntryUpdate(entry->id, entry->seq_num.value(), value);
+      lock.unlock();
+      dispatcher->QueueOutgoing(msg, nullptr, nullptr);
+    }
+  }
+}
+
+void Storage::SetEntryTypeValue(StringRef name, std::shared_ptr<Value> value) {
+  if (name.empty()) return;
+  if (!value) return;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  Entry* entry = GetOrNew(name);
+
+  SetEntryValueImpl(entry, value, lock, true);
+}
+
+void Storage::SetEntryTypeValue(unsigned int local_id,
+                                std::shared_ptr<Value> value) {
+  if (!value) return;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return;
+  Entry* entry = m_localmap[local_id].get();
+  if (!entry) return;
+
+  SetEntryValueImpl(entry, value, lock, true);
+}
+
+void Storage::SetEntryFlags(StringRef name, unsigned int flags) {
+  if (name.empty()) return;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  auto i = m_entries.find(name);
+  if (i == m_entries.end()) return;
+  SetEntryFlagsImpl(i->getValue(), flags, lock, true);
+}
+
+void Storage::SetEntryFlags(unsigned int id_local, unsigned int flags) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (id_local >= m_localmap.size()) return;
+  SetEntryFlagsImpl(m_localmap[id_local].get(), flags, lock, true);
+}
+
+void Storage::SetEntryFlagsImpl(Entry* entry, unsigned int flags,
+                                std::unique_lock<wpi::mutex>& lock,
+                                bool local) {
+  if (!entry->value || entry->flags == flags) return;
+
+  // update persistent dirty flag if persistent flag changed
+  if ((entry->flags & NT_PERSISTENT) != (flags & NT_PERSISTENT))
+    m_persistent_dirty = true;
+
+  entry->flags = flags;
+
+  // notify
+  m_notifier.NotifyEntry(entry->local_id, entry->name, entry->value,
+                         NT_NOTIFY_FLAGS | (local ? NT_NOTIFY_LOCAL : 0));
+
+  // generate message
+  if (!local || !m_dispatcher) return;
+  auto dispatcher = m_dispatcher;
+  unsigned int id = entry->id;
+  // don't send an update if we don't have an assigned id yet
+  if (id != 0xffff) {
+    lock.unlock();
+    dispatcher->QueueOutgoing(Message::FlagsUpdate(id, flags), nullptr,
+                              nullptr);
+  }
+}
+
+unsigned int Storage::GetEntryFlags(StringRef name) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto i = m_entries.find(name);
+  if (i == m_entries.end()) return 0;
+  return i->getValue()->flags;
+}
+
+unsigned int Storage::GetEntryFlags(unsigned int local_id) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return 0;
+  return m_localmap[local_id]->flags;
+}
+
+void Storage::DeleteEntry(StringRef name) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  auto i = m_entries.find(name);
+  if (i == m_entries.end()) return;
+  DeleteEntryImpl(i->getValue(), lock, true);
+}
+
+void Storage::DeleteEntry(unsigned int local_id) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return;
+  DeleteEntryImpl(m_localmap[local_id].get(), lock, true);
+}
+
+void Storage::DeleteEntryImpl(Entry* entry, std::unique_lock<wpi::mutex>& lock,
+                              bool local) {
+  unsigned int id = entry->id;
+
+  // Erase entry from id mapping.
+  if (id < m_idmap.size()) m_idmap[id] = nullptr;
+
+  // empty the value and reset id and local_write flag
+  std::shared_ptr<Value> old_value;
+  old_value.swap(entry->value);
+  entry->id = 0xffff;
+  entry->local_write = false;
+
+  // remove RPC if there was one
+  if (entry->rpc_uid != UINT_MAX) {
+    m_rpc_server.RemoveRpc(entry->rpc_uid);
+    entry->rpc_uid = UINT_MAX;
+  }
+
+  // update persistent dirty flag if it's a persistent value
+  if (entry->IsPersistent()) m_persistent_dirty = true;
+
+  // reset flags
+  entry->flags = 0;
+
+  if (!old_value) return;  // was not previously assigned
+
+  // notify
+  m_notifier.NotifyEntry(entry->local_id, entry->name, old_value,
+                         NT_NOTIFY_DELETE | (local ? NT_NOTIFY_LOCAL : 0));
+
+  // if it had a value, generate message
+  // don't send an update if we don't have an assigned id yet
+  if (local && id != 0xffff) {
+    if (!m_dispatcher) return;
+    auto dispatcher = m_dispatcher;
+    lock.unlock();
+    dispatcher->QueueOutgoing(Message::EntryDelete(id), nullptr, nullptr);
+  }
+}
+
+template <typename F>
+void Storage::DeleteAllEntriesImpl(bool local, F should_delete) {
+  for (auto& i : m_entries) {
+    Entry* entry = i.getValue();
+    if (entry->value && should_delete(entry)) {
+      // notify it's being deleted
+      m_notifier.NotifyEntry(entry->local_id, i.getKey(), entry->value,
+                             NT_NOTIFY_DELETE | (local ? NT_NOTIFY_LOCAL : 0));
+      // remove it from idmap
+      if (entry->id < m_idmap.size()) m_idmap[entry->id] = nullptr;
+      entry->id = 0xffff;
+      entry->local_write = false;
+      entry->value.reset();
+      continue;
+    }
+  }
+}
+
+void Storage::DeleteAllEntriesImpl(bool local) {
+  // only delete non-persistent values
+  DeleteAllEntriesImpl(local,
+                       [](Entry* entry) { return !entry->IsPersistent(); });
+}
+
+void Storage::DeleteAllEntries() {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (m_entries.empty()) return;
+
+  DeleteAllEntriesImpl(true);
+
+  // generate message
+  if (!m_dispatcher) return;
+  auto dispatcher = m_dispatcher;
+  lock.unlock();
+  dispatcher->QueueOutgoing(Message::ClearEntries(), nullptr, nullptr);
+}
+
+Storage::Entry* Storage::GetOrNew(const Twine& name) {
+  wpi::SmallString<128> nameBuf;
+  StringRef nameStr = name.toStringRef(nameBuf);
+  auto& entry = m_entries[nameStr];
+  if (!entry) {
+    m_localmap.emplace_back(new Entry(nameStr));
+    entry = m_localmap.back().get();
+    entry->local_id = m_localmap.size() - 1;
+  }
+  return entry;
+}
+
+unsigned int Storage::GetEntry(const Twine& name) {
+  if (name.isTriviallyEmpty() ||
+      (name.isSingleStringRef() && name.getSingleStringRef().empty()))
+    return UINT_MAX;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  return GetOrNew(name)->local_id;
+}
+
+std::vector<unsigned int> Storage::GetEntries(const Twine& prefix,
+                                              unsigned int types) {
+  wpi::SmallString<128> prefixBuf;
+  StringRef prefixStr = prefix.toStringRef(prefixBuf);
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  std::vector<unsigned int> ids;
+  for (auto& i : m_entries) {
+    Entry* entry = i.getValue();
+    auto value = entry->value.get();
+    if (!value || !i.getKey().startswith(prefixStr)) continue;
+    if (types != 0 && (types & value->type()) == 0) continue;
+    ids.push_back(entry->local_id);
+  }
+  return ids;
+}
+
+EntryInfo Storage::GetEntryInfo(int inst, unsigned int local_id) const {
+  EntryInfo info;
+  info.entry = 0;
+  info.type = NT_UNASSIGNED;
+  info.flags = 0;
+  info.last_change = 0;
+
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return info;
+  Entry* entry = m_localmap[local_id].get();
+  if (!entry->value) return info;
+
+  info.entry = Handle(inst, local_id, Handle::kEntry);
+  info.name = entry->name;
+  info.type = entry->value->type();
+  info.flags = entry->flags;
+  info.last_change = entry->value->last_change();
+  return info;
+}
+
+std::string Storage::GetEntryName(unsigned int local_id) const {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return std::string{};
+  return m_localmap[local_id]->name;
+}
+
+NT_Type Storage::GetEntryType(unsigned int local_id) const {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return NT_UNASSIGNED;
+  Entry* entry = m_localmap[local_id].get();
+  if (!entry->value) return NT_UNASSIGNED;
+  return entry->value->type();
+}
+
+uint64_t Storage::GetEntryLastChange(unsigned int local_id) const {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return 0;
+  Entry* entry = m_localmap[local_id].get();
+  if (!entry->value) return 0;
+  return entry->value->last_change();
+}
+
+std::vector<EntryInfo> Storage::GetEntryInfo(int inst, const Twine& prefix,
+                                             unsigned int types) {
+  wpi::SmallString<128> prefixBuf;
+  StringRef prefixStr = prefix.toStringRef(prefixBuf);
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  std::vector<EntryInfo> infos;
+  for (auto& i : m_entries) {
+    Entry* entry = i.getValue();
+    auto value = entry->value.get();
+    if (!value || !i.getKey().startswith(prefixStr)) continue;
+    if (types != 0 && (types & value->type()) == 0) continue;
+    EntryInfo info;
+    info.entry = Handle(inst, entry->local_id, Handle::kEntry);
+    info.name = i.getKey();
+    info.type = value->type();
+    info.flags = entry->flags;
+    info.last_change = value->last_change();
+    infos.push_back(std::move(info));
+  }
+  return infos;
+}
+
+unsigned int Storage::AddListener(
+    const Twine& prefix,
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int flags) const {
+  wpi::SmallString<128> prefixBuf;
+  StringRef prefixStr = prefix.toStringRef(prefixBuf);
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  unsigned int uid = m_notifier.Add(callback, prefixStr, flags);
+  // perform immediate notifications
+  if ((flags & NT_NOTIFY_IMMEDIATE) != 0 && (flags & NT_NOTIFY_NEW) != 0) {
+    for (auto& i : m_entries) {
+      Entry* entry = i.getValue();
+      if (!entry->value || !i.getKey().startswith(prefixStr)) continue;
+      m_notifier.NotifyEntry(entry->local_id, i.getKey(), entry->value,
+                             NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW, uid);
+    }
+  }
+  return uid;
+}
+
+unsigned int Storage::AddListener(
+    unsigned int local_id,
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int flags) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  unsigned int uid = m_notifier.Add(callback, local_id, flags);
+  // perform immediate notifications
+  if ((flags & NT_NOTIFY_IMMEDIATE) != 0 && (flags & NT_NOTIFY_NEW) != 0 &&
+      local_id < m_localmap.size()) {
+    Entry* entry = m_localmap[local_id].get();
+    if (entry->value) {
+      m_notifier.NotifyEntry(local_id, entry->name, entry->value,
+                             NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW, uid);
+    }
+  }
+  return uid;
+}
+
+unsigned int Storage::AddPolledListener(unsigned int poller,
+                                        const Twine& prefix,
+                                        unsigned int flags) const {
+  wpi::SmallString<128> prefixBuf;
+  StringRef prefixStr = prefix.toStringRef(prefixBuf);
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  unsigned int uid = m_notifier.AddPolled(poller, prefixStr, flags);
+  // perform immediate notifications
+  if ((flags & NT_NOTIFY_IMMEDIATE) != 0 && (flags & NT_NOTIFY_NEW) != 0) {
+    for (auto& i : m_entries) {
+      if (!i.getKey().startswith(prefixStr)) continue;
+      Entry* entry = i.getValue();
+      if (!entry->value) continue;
+      m_notifier.NotifyEntry(entry->local_id, i.getKey(), entry->value,
+                             NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW, uid);
+    }
+  }
+  return uid;
+}
+
+unsigned int Storage::AddPolledListener(unsigned int poller,
+                                        unsigned int local_id,
+                                        unsigned int flags) const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  unsigned int uid = m_notifier.AddPolled(poller, local_id, flags);
+  // perform immediate notifications
+  if ((flags & NT_NOTIFY_IMMEDIATE) != 0 && (flags & NT_NOTIFY_NEW) != 0 &&
+      local_id < m_localmap.size()) {
+    Entry* entry = m_localmap[local_id].get();
+    // if no value, don't notify
+    if (entry->value) {
+      m_notifier.NotifyEntry(local_id, entry->name, entry->value,
+                             NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW, uid);
+    }
+  }
+  return uid;
+}
+
+bool Storage::GetPersistentEntries(
+    bool periodic,
+    std::vector<std::pair<std::string, std::shared_ptr<Value>>>* entries)
+    const {
+  // copy values out of storage as quickly as possible so lock isn't held
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    // for periodic, don't re-save unless something has changed
+    if (periodic && !m_persistent_dirty) return false;
+    m_persistent_dirty = false;
+    entries->reserve(m_entries.size());
+    for (auto& i : m_entries) {
+      Entry* entry = i.getValue();
+      // only write persistent-flagged values
+      if (!entry->value || !entry->IsPersistent()) continue;
+      entries->emplace_back(i.getKey(), entry->value);
+    }
+  }
+
+  // sort in name order
+  std::sort(entries->begin(), entries->end(),
+            [](const std::pair<std::string, std::shared_ptr<Value>>& a,
+               const std::pair<std::string, std::shared_ptr<Value>>& b) {
+              return a.first < b.first;
+            });
+  return true;
+}
+
+bool Storage::GetEntries(
+    const Twine& prefix,
+    std::vector<std::pair<std::string, std::shared_ptr<Value>>>* entries)
+    const {
+  wpi::SmallString<128> prefixBuf;
+  StringRef prefixStr = prefix.toStringRef(prefixBuf);
+  // copy values out of storage as quickly as possible so lock isn't held
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    entries->reserve(m_entries.size());
+    for (auto& i : m_entries) {
+      Entry* entry = i.getValue();
+      // only write values with given prefix
+      if (!entry->value || !i.getKey().startswith(prefixStr)) continue;
+      entries->emplace_back(i.getKey(), entry->value);
+    }
+  }
+
+  // sort in name order
+  std::sort(entries->begin(), entries->end(),
+            [](const std::pair<std::string, std::shared_ptr<Value>>& a,
+               const std::pair<std::string, std::shared_ptr<Value>>& b) {
+              return a.first < b.first;
+            });
+  return true;
+}
+
+void Storage::CreateRpc(unsigned int local_id, StringRef def,
+                        unsigned int rpc_uid) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return;
+  Entry* entry = m_localmap[local_id].get();
+
+  auto old_value = entry->value;
+  auto value = Value::MakeRpc(def);
+  entry->value = value;
+
+  // set up the RPC info
+  entry->rpc_uid = rpc_uid;
+
+  if (old_value && *old_value == *value) return;
+
+  // assign an id if it doesn't have one
+  if (entry->id == 0xffff) {
+    unsigned int id = m_idmap.size();
+    entry->id = id;
+    m_idmap.push_back(entry);
+  }
+
+  // generate message
+  if (!m_dispatcher) return;
+  auto dispatcher = m_dispatcher;
+  if (!old_value || old_value->type() != value->type()) {
+    ++entry->seq_num;
+    auto msg = Message::EntryAssign(
+        entry->name, entry->id, entry->seq_num.value(), value, entry->flags);
+    lock.unlock();
+    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
+  } else {
+    ++entry->seq_num;
+    auto msg = Message::EntryUpdate(entry->id, entry->seq_num.value(), value);
+    lock.unlock();
+    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
+  }
+}
+
+unsigned int Storage::CallRpc(unsigned int local_id, StringRef params) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (local_id >= m_localmap.size()) return 0;
+  Entry* entry = m_localmap[local_id].get();
+
+  if (!entry->value || !entry->value->IsRpc()) return 0;
+
+  ++entry->rpc_call_uid;
+  if (entry->rpc_call_uid > 0xffff) entry->rpc_call_uid = 0;
+  unsigned int call_uid = entry->rpc_call_uid;
+
+  auto msg = Message::ExecuteRpc(entry->id, call_uid, params);
+  StringRef name{entry->name};
+
+  if (m_server) {
+    // RPCs are unlikely to be used locally on the server, but handle it
+    // gracefully anyway.
+    auto rpc_uid = entry->rpc_uid;
+    lock.unlock();
+    ConnectionInfo conn_info;
+    conn_info.remote_id = "Server";
+    conn_info.remote_ip = "localhost";
+    conn_info.remote_port = 0;
+    conn_info.last_update = wpi::Now();
+    conn_info.protocol_version = 0x0300;
+    unsigned int call_uid = msg->seq_num_uid();
+    m_rpc_server.ProcessRpc(local_id, call_uid, name, msg->str(), conn_info,
+                            [=](StringRef result) {
+                              std::lock_guard<wpi::mutex> lock(m_mutex);
+                              m_rpc_results.insert(std::make_pair(
+                                  RpcIdPair{local_id, call_uid}, result));
+                              m_rpc_results_cond.notify_all();
+                            },
+                            rpc_uid);
+  } else {
+    auto dispatcher = m_dispatcher;
+    lock.unlock();
+    dispatcher->QueueOutgoing(msg, nullptr, nullptr);
+  }
+  return call_uid;
+}
+
+bool Storage::GetRpcResult(unsigned int local_id, unsigned int call_uid,
+                           std::string* result) {
+  bool timed_out = false;
+  return GetRpcResult(local_id, call_uid, result, -1, &timed_out);
+}
+
+bool Storage::GetRpcResult(unsigned int local_id, unsigned int call_uid,
+                           std::string* result, double timeout,
+                           bool* timed_out) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+
+  RpcIdPair call_pair{local_id, call_uid};
+
+  // only allow one blocking call per rpc call uid
+  if (!m_rpc_blocking_calls.insert(call_pair).second) return false;
+
+  auto timeout_time =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+  *timed_out = false;
+  for (;;) {
+    auto i = m_rpc_results.find(call_pair);
+    if (i == m_rpc_results.end()) {
+      if (timeout == 0 || m_terminating) {
+        m_rpc_blocking_calls.erase(call_pair);
+        return false;
+      }
+      if (timeout < 0) {
+        m_rpc_results_cond.wait(lock);
+      } else {
+        auto cond_timed_out = m_rpc_results_cond.wait_until(lock, timeout_time);
+        if (cond_timed_out == std::cv_status::timeout) {
+          m_rpc_blocking_calls.erase(call_pair);
+          *timed_out = true;
+          return false;
+        }
+      }
+      // if element does not exist, we have been canceled
+      if (m_rpc_blocking_calls.count(call_pair) == 0) {
+        return false;
+      }
+      if (m_terminating) {
+        m_rpc_blocking_calls.erase(call_pair);
+        return false;
+      }
+      continue;
+    }
+    result->swap(i->getSecond());
+    // safe to erase even if id does not exist
+    m_rpc_blocking_calls.erase(call_pair);
+    m_rpc_results.erase(i);
+    return true;
+  }
+}
+
+void Storage::CancelRpcResult(unsigned int local_id, unsigned int call_uid) {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  // safe to erase even if id does not exist
+  m_rpc_blocking_calls.erase(RpcIdPair{local_id, call_uid});
+  m_rpc_results_cond.notify_all();
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage.h
new file mode 100644
index 0000000..fa9b2bf
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage.h
@@ -0,0 +1,262 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_STORAGE_H_
+#define NTCORE_STORAGE_H_
+
+#include <stdint.h>
+
+#include <atomic>
+#include <cstddef>
+#include <functional>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <wpi/DenseMap.h>
+#include <wpi/SmallSet.h>
+#include <wpi/StringMap.h>
+#include <wpi/condition_variable.h>
+#include <wpi/mutex.h>
+
+#include "IStorage.h"
+#include "Message.h"
+#include "SequenceNumber.h"
+#include "ntcore_cpp.h"
+
+namespace wpi {
+class Logger;
+class raw_istream;
+class raw_ostream;
+}  // namespace wpi
+
+namespace nt {
+
+class IEntryNotifier;
+class INetworkConnection;
+class IRpcServer;
+class IStorageTest;
+
+class Storage : public IStorage {
+  friend class StorageTest;
+
+ public:
+  Storage(IEntryNotifier& notifier, IRpcServer& rpcserver, wpi::Logger& logger);
+  Storage(const Storage&) = delete;
+  Storage& operator=(const Storage&) = delete;
+
+  ~Storage();
+
+  // Accessors required by Dispatcher.  An interface is used for
+  // generation of outgoing messages to break a dependency loop between
+  // Storage and Dispatcher.
+  void SetDispatcher(IDispatcher* dispatcher, bool server) override;
+  void ClearDispatcher() override;
+
+  // Required for wire protocol 2.0 to get the entry type of an entry when
+  // receiving entry updates (because the length/type is not provided in the
+  // message itself).  Not used in wire protocol 3.0.
+  NT_Type GetMessageEntryType(unsigned int id) const override;
+
+  void ProcessIncoming(std::shared_ptr<Message> msg, INetworkConnection* conn,
+                       std::weak_ptr<INetworkConnection> conn_weak) override;
+  void GetInitialAssignments(
+      INetworkConnection& conn,
+      std::vector<std::shared_ptr<Message>>* msgs) override;
+  void ApplyInitialAssignments(
+      INetworkConnection& conn, wpi::ArrayRef<std::shared_ptr<Message>> msgs,
+      bool new_server,
+      std::vector<std::shared_ptr<Message>>* out_msgs) override;
+
+  // User functions.  These are the actual implementations of the corresponding
+  // user API functions in ntcore_cpp.
+  std::shared_ptr<Value> GetEntryValue(StringRef name) const;
+  std::shared_ptr<Value> GetEntryValue(unsigned int local_id) const;
+
+  bool SetDefaultEntryValue(StringRef name, std::shared_ptr<Value> value);
+  bool SetDefaultEntryValue(unsigned int local_id,
+                            std::shared_ptr<Value> value);
+
+  bool SetEntryValue(StringRef name, std::shared_ptr<Value> value);
+  bool SetEntryValue(unsigned int local_id, std::shared_ptr<Value> value);
+
+  void SetEntryTypeValue(StringRef name, std::shared_ptr<Value> value);
+  void SetEntryTypeValue(unsigned int local_id, std::shared_ptr<Value> value);
+
+  void SetEntryFlags(StringRef name, unsigned int flags);
+  void SetEntryFlags(unsigned int local_id, unsigned int flags);
+
+  unsigned int GetEntryFlags(StringRef name) const;
+  unsigned int GetEntryFlags(unsigned int local_id) const;
+
+  void DeleteEntry(StringRef name);
+  void DeleteEntry(unsigned int local_id);
+
+  void DeleteAllEntries();
+
+  std::vector<EntryInfo> GetEntryInfo(int inst, const Twine& prefix,
+                                      unsigned int types);
+
+  unsigned int AddListener(
+      const Twine& prefix,
+      std::function<void(const EntryNotification& event)> callback,
+      unsigned int flags) const;
+  unsigned int AddListener(
+      unsigned int local_id,
+      std::function<void(const EntryNotification& event)> callback,
+      unsigned int flags) const;
+
+  unsigned int AddPolledListener(unsigned int poller_uid, const Twine& prefix,
+                                 unsigned int flags) const;
+  unsigned int AddPolledListener(unsigned int poller_uid, unsigned int local_id,
+                                 unsigned int flags) const;
+
+  // Index-only
+  unsigned int GetEntry(const Twine& name);
+  std::vector<unsigned int> GetEntries(const Twine& prefix, unsigned int types);
+  EntryInfo GetEntryInfo(int inst, unsigned int local_id) const;
+  std::string GetEntryName(unsigned int local_id) const;
+  NT_Type GetEntryType(unsigned int local_id) const;
+  uint64_t GetEntryLastChange(unsigned int local_id) const;
+
+  // Filename-based save/load functions.  Used both by periodic saves and
+  // accessible directly via the user API.
+  const char* SavePersistent(const Twine& filename,
+                             bool periodic) const override;
+  const char* LoadPersistent(
+      const Twine& filename,
+      std::function<void(size_t line, const char* msg)> warn) override;
+
+  const char* SaveEntries(const Twine& filename, const Twine& prefix) const;
+  const char* LoadEntries(
+      const Twine& filename, const Twine& prefix,
+      std::function<void(size_t line, const char* msg)> warn);
+
+  // Stream-based save/load functions (exposed for testing purposes).  These
+  // implement the guts of the filename-based functions.
+  void SavePersistent(wpi::raw_ostream& os, bool periodic) const;
+  bool LoadEntries(wpi::raw_istream& is, const Twine& prefix, bool persistent,
+                   std::function<void(size_t line, const char* msg)> warn);
+
+  void SaveEntries(wpi::raw_ostream& os, const Twine& prefix) const;
+
+  // RPC configuration needs to come through here as RPC definitions are
+  // actually special Storage value types.
+  void CreateRpc(unsigned int local_id, StringRef def, unsigned int rpc_uid);
+  unsigned int CallRpc(unsigned int local_id, StringRef params);
+  bool GetRpcResult(unsigned int local_id, unsigned int call_uid,
+                    std::string* result);
+  bool GetRpcResult(unsigned int local_id, unsigned int call_uid,
+                    std::string* result, double timeout, bool* timed_out);
+  void CancelRpcResult(unsigned int local_id, unsigned int call_uid);
+
+ private:
+  // Data for each table entry.
+  struct Entry {
+    explicit Entry(wpi::StringRef name_) : name(name_) {}
+    bool IsPersistent() const { return (flags & NT_PERSISTENT) != 0; }
+
+    // We redundantly store the name so that it's available when accessing the
+    // raw Entry* via the ID map.
+    std::string name;
+
+    // The current value and flags.
+    std::shared_ptr<Value> value;
+    unsigned int flags{0};
+
+    // Unique ID for this entry as used in network messages.  The value is
+    // assigned by the server, so on the client this is 0xffff until an
+    // entry assignment is received back from the server.
+    unsigned int id{0xffff};
+
+    // Local ID.
+    unsigned int local_id{UINT_MAX};
+
+    // Sequence number for update resolution.
+    SequenceNumber seq_num;
+
+    // If value has been written locally.  Used during initial handshake
+    // on client to determine whether or not to accept remote changes.
+    bool local_write{false};
+
+    // RPC handle.
+    unsigned int rpc_uid{UINT_MAX};
+
+    // Last UID used when calling this RPC (primarily for client use).  This
+    // is incremented for each call.
+    unsigned int rpc_call_uid{0};
+  };
+
+  typedef wpi::StringMap<Entry*> EntriesMap;
+  typedef std::vector<Entry*> IdMap;
+  typedef std::vector<std::unique_ptr<Entry>> LocalMap;
+  typedef std::pair<unsigned int, unsigned int> RpcIdPair;
+  typedef wpi::DenseMap<RpcIdPair, std::string> RpcResultMap;
+  typedef wpi::SmallSet<RpcIdPair, 12> RpcBlockingCallSet;
+
+  mutable wpi::mutex m_mutex;
+  EntriesMap m_entries;
+  IdMap m_idmap;
+  LocalMap m_localmap;
+  RpcResultMap m_rpc_results;
+  RpcBlockingCallSet m_rpc_blocking_calls;
+  // If any persistent values have changed
+  mutable bool m_persistent_dirty = false;
+
+  // condition variable and termination flag for blocking on a RPC result
+  std::atomic_bool m_terminating;
+  wpi::condition_variable m_rpc_results_cond;
+
+  // configured by dispatcher at startup
+  IDispatcher* m_dispatcher = nullptr;
+  bool m_server = true;
+
+  IEntryNotifier& m_notifier;
+  IRpcServer& m_rpc_server;
+  wpi::Logger& m_logger;
+
+  void ProcessIncomingEntryAssign(std::shared_ptr<Message> msg,
+                                  INetworkConnection* conn);
+  void ProcessIncomingEntryUpdate(std::shared_ptr<Message> msg,
+                                  INetworkConnection* conn);
+  void ProcessIncomingFlagsUpdate(std::shared_ptr<Message> msg,
+                                  INetworkConnection* conn);
+  void ProcessIncomingEntryDelete(std::shared_ptr<Message> msg,
+                                  INetworkConnection* conn);
+  void ProcessIncomingClearEntries(std::shared_ptr<Message> msg,
+                                   INetworkConnection* conn);
+  void ProcessIncomingExecuteRpc(std::shared_ptr<Message> msg,
+                                 INetworkConnection* conn,
+                                 std::weak_ptr<INetworkConnection> conn_weak);
+  void ProcessIncomingRpcResponse(std::shared_ptr<Message> msg,
+                                  INetworkConnection* conn);
+
+  bool GetPersistentEntries(
+      bool periodic,
+      std::vector<std::pair<std::string, std::shared_ptr<Value>>>* entries)
+      const;
+  bool GetEntries(const Twine& prefix,
+                  std::vector<std::pair<std::string, std::shared_ptr<Value>>>*
+                      entries) const;
+  void SetEntryValueImpl(Entry* entry, std::shared_ptr<Value> value,
+                         std::unique_lock<wpi::mutex>& lock, bool local);
+  void SetEntryFlagsImpl(Entry* entry, unsigned int flags,
+                         std::unique_lock<wpi::mutex>& lock, bool local);
+  void DeleteEntryImpl(Entry* entry, std::unique_lock<wpi::mutex>& lock,
+                       bool local);
+
+  // Must be called with m_mutex held
+  template <typename F>
+  void DeleteAllEntriesImpl(bool local, F should_delete);
+  void DeleteAllEntriesImpl(bool local);
+  Entry* GetOrNew(const Twine& name);
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_STORAGE_H_
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
new file mode 100644
index 0000000..c05e029
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage_load.cpp
@@ -0,0 +1,453 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <cctype>
+#include <string>
+
+#include <wpi/Base64.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringExtras.h>
+#include <wpi/raw_istream.h>
+
+#include "IDispatcher.h"
+#include "IEntryNotifier.h"
+#include "Storage.h"
+
+using namespace nt;
+
+namespace {
+
+class LoadPersistentImpl {
+ public:
+  typedef std::pair<std::string, std::shared_ptr<Value>> Entry;
+  typedef std::function<void(size_t line, const char* msg)> WarnFunc;
+
+  LoadPersistentImpl(wpi::raw_istream& is, WarnFunc warn)
+      : m_is(is), m_warn(warn) {}
+
+  bool Load(StringRef prefix, std::vector<Entry>* entries);
+
+ private:
+  bool ReadLine();
+  bool ReadHeader();
+  NT_Type ReadType();
+  wpi::StringRef ReadName(wpi::SmallVectorImpl<char>& buf);
+  std::shared_ptr<Value> ReadValue(NT_Type type);
+  std::shared_ptr<Value> ReadBooleanValue();
+  std::shared_ptr<Value> ReadDoubleValue();
+  std::shared_ptr<Value> ReadStringValue();
+  std::shared_ptr<Value> ReadRawValue();
+  std::shared_ptr<Value> ReadBooleanArrayValue();
+  std::shared_ptr<Value> ReadDoubleArrayValue();
+  std::shared_ptr<Value> ReadStringArrayValue();
+
+  void Warn(const char* msg) {
+    if (m_warn) m_warn(m_line_num, msg);
+  }
+
+  wpi::raw_istream& m_is;
+  WarnFunc m_warn;
+
+  wpi::StringRef m_line;
+  wpi::SmallString<128> m_line_buf;
+  size_t m_line_num = 0;
+
+  std::vector<int> m_buf_boolean_array;
+  std::vector<double> m_buf_double_array;
+  std::vector<std::string> m_buf_string_array;
+};
+
+}  // namespace
+
+/* Extracts an escaped string token.  Does not unescape the string.
+ * If a string cannot be matched, an empty string is returned.
+ * If the string is unterminated, an empty tail string is returned.
+ * The returned token includes the starting and trailing quotes (unless the
+ * string is unterminated).
+ * Returns a pair containing the extracted token (if any) and the remaining
+ * tail string.
+ */
+static std::pair<wpi::StringRef, wpi::StringRef> ReadStringToken(
+    wpi::StringRef source) {
+  // Match opening quote
+  if (source.empty() || source.front() != '"')
+    return std::make_pair(wpi::StringRef(), source);
+
+  // Scan for ending double quote, checking for escaped as we go.
+  size_t size = source.size();
+  size_t pos;
+  for (pos = 1; pos < size; ++pos) {
+    if (source[pos] == '"' && source[pos - 1] != '\\') {
+      ++pos;  // we want to include the trailing quote in the result
+      break;
+    }
+  }
+  return std::make_pair(source.slice(0, pos), source.substr(pos));
+}
+
+static int fromxdigit(char ch) {
+  if (ch >= 'a' && ch <= 'f')
+    return (ch - 'a' + 10);
+  else if (ch >= 'A' && ch <= 'F')
+    return (ch - 'A' + 10);
+  else
+    return ch - '0';
+}
+
+static wpi::StringRef UnescapeString(wpi::StringRef source,
+                                     wpi::SmallVectorImpl<char>& buf) {
+  assert(source.size() >= 2 && source.front() == '"' && source.back() == '"');
+  buf.clear();
+  buf.reserve(source.size() - 2);
+  for (auto s = source.begin() + 1, end = source.end() - 1; s != end; ++s) {
+    if (*s != '\\') {
+      buf.push_back(*s);
+      continue;
+    }
+    switch (*++s) {
+      case '\\':
+      case '"':
+        buf.push_back(s[-1]);
+        break;
+      case 't':
+        buf.push_back('\t');
+        break;
+      case 'n':
+        buf.push_back('\n');
+        break;
+      case 'x': {
+        if (!isxdigit(*(s + 1))) {
+          buf.push_back('x');  // treat it like a unknown escape
+          break;
+        }
+        int ch = fromxdigit(*++s);
+        if (std::isxdigit(*(s + 1))) {
+          ch <<= 4;
+          ch |= fromxdigit(*++s);
+        }
+        buf.push_back(static_cast<char>(ch));
+        break;
+      }
+      default:
+        buf.push_back(s[-1]);
+        break;
+    }
+  }
+  return wpi::StringRef{buf.data(), buf.size()};
+}
+
+bool LoadPersistentImpl::Load(StringRef prefix, std::vector<Entry>* entries) {
+  if (!ReadHeader()) return false;  // header
+
+  while (ReadLine()) {
+    // type
+    NT_Type type = ReadType();
+    if (type == NT_UNASSIGNED) {
+      Warn("unrecognized type");
+      continue;
+    }
+
+    // name
+    wpi::SmallString<128> buf;
+    wpi::StringRef name = ReadName(buf);
+    if (name.empty() || !name.startswith(prefix)) continue;
+
+    // =
+    m_line = m_line.ltrim(" \t");
+    if (m_line.empty() || m_line.front() != '=') {
+      Warn("expected = after name");
+      continue;
+    }
+    m_line = m_line.drop_front().ltrim(" \t");
+
+    // value
+    auto value = ReadValue(type);
+
+    // move to entries
+    if (value) entries->emplace_back(name, std::move(value));
+  }
+  return true;
+}
+
+bool LoadPersistentImpl::ReadLine() {
+  // ignore blank lines and lines that start with ; or # (comments)
+  while (!m_is.has_error()) {
+    ++m_line_num;
+    m_line = m_is.getline(m_line_buf, INT_MAX).trim();
+    if (!m_line.empty() && m_line.front() != ';' && m_line.front() != '#')
+      return true;
+  }
+  return false;
+}
+
+bool LoadPersistentImpl::ReadHeader() {
+  // header
+  if (!ReadLine() || m_line != "[NetworkTables Storage 3.0]") {
+    Warn("header line mismatch, ignoring rest of file");
+    return false;
+  }
+  return true;
+}
+
+NT_Type LoadPersistentImpl::ReadType() {
+  wpi::StringRef tok;
+  std::tie(tok, m_line) = m_line.split(' ');
+  if (tok == "boolean") {
+    return NT_BOOLEAN;
+  } else if (tok == "double") {
+    return NT_DOUBLE;
+  } else if (tok == "string") {
+    return NT_STRING;
+  } else if (tok == "raw") {
+    return NT_RAW;
+  } else if (tok == "array") {
+    wpi::StringRef array_tok;
+    std::tie(array_tok, m_line) = m_line.split(' ');
+    if (array_tok == "boolean")
+      return NT_BOOLEAN_ARRAY;
+    else if (array_tok == "double")
+      return NT_DOUBLE_ARRAY;
+    else if (array_tok == "string")
+      return NT_STRING_ARRAY;
+  }
+  return NT_UNASSIGNED;
+}
+
+wpi::StringRef LoadPersistentImpl::ReadName(wpi::SmallVectorImpl<char>& buf) {
+  wpi::StringRef tok;
+  std::tie(tok, m_line) = ReadStringToken(m_line);
+  if (tok.empty()) {
+    Warn("missing name");
+    return wpi::StringRef{};
+  }
+  if (tok.back() != '"') {
+    Warn("unterminated name string");
+    return wpi::StringRef{};
+  }
+  return UnescapeString(tok, buf);
+}
+
+std::shared_ptr<Value> LoadPersistentImpl::ReadValue(NT_Type type) {
+  switch (type) {
+    case NT_BOOLEAN:
+      return ReadBooleanValue();
+    case NT_DOUBLE:
+      return ReadDoubleValue();
+    case NT_STRING:
+      return ReadStringValue();
+    case NT_RAW:
+      return ReadRawValue();
+    case NT_BOOLEAN_ARRAY:
+      return ReadBooleanArrayValue();
+    case NT_DOUBLE_ARRAY:
+      return ReadDoubleArrayValue();
+    case NT_STRING_ARRAY:
+      return ReadStringArrayValue();
+    default:
+      return nullptr;
+  }
+}
+
+std::shared_ptr<Value> LoadPersistentImpl::ReadBooleanValue() {
+  // only true or false is accepted
+  if (m_line == "true") return Value::MakeBoolean(true);
+  if (m_line == "false") return Value::MakeBoolean(false);
+  Warn("unrecognized boolean value, not 'true' or 'false'");
+  return nullptr;
+}
+
+std::shared_ptr<Value> LoadPersistentImpl::ReadDoubleValue() {
+  // need to convert to null-terminated string for std::strtod()
+  wpi::SmallString<64> buf = m_line;
+  char* end;
+  double v = std::strtod(buf.c_str(), &end);
+  if (*end != '\0') {
+    Warn("invalid double value");
+    return nullptr;
+  }
+  return Value::MakeDouble(v);
+}
+
+std::shared_ptr<Value> LoadPersistentImpl::ReadStringValue() {
+  wpi::StringRef tok;
+  std::tie(tok, m_line) = ReadStringToken(m_line);
+  if (tok.empty()) {
+    Warn("missing string value");
+    return nullptr;
+  }
+  if (tok.back() != '"') {
+    Warn("unterminated string value");
+    return nullptr;
+  }
+  wpi::SmallString<128> buf;
+  return Value::MakeString(UnescapeString(tok, buf));
+}
+
+std::shared_ptr<Value> LoadPersistentImpl::ReadRawValue() {
+  wpi::SmallString<128> buf;
+  size_t nr;
+  return Value::MakeRaw(wpi::Base64Decode(m_line, &nr, buf));
+}
+
+std::shared_ptr<Value> LoadPersistentImpl::ReadBooleanArrayValue() {
+  m_buf_boolean_array.clear();
+  while (!m_line.empty()) {
+    wpi::StringRef tok;
+    std::tie(tok, m_line) = m_line.split(',');
+    tok = tok.trim(" \t");
+    if (tok == "true") {
+      m_buf_boolean_array.push_back(1);
+    } else if (tok == "false") {
+      m_buf_boolean_array.push_back(0);
+    } else {
+      Warn("unrecognized boolean value, not 'true' or 'false'");
+      return nullptr;
+    }
+  }
+  return Value::MakeBooleanArray(std::move(m_buf_boolean_array));
+}
+
+std::shared_ptr<Value> LoadPersistentImpl::ReadDoubleArrayValue() {
+  m_buf_double_array.clear();
+  while (!m_line.empty()) {
+    wpi::StringRef tok;
+    std::tie(tok, m_line) = m_line.split(',');
+    tok = tok.trim(" \t");
+    // need to convert to null-terminated string for std::strtod()
+    wpi::SmallString<64> buf = tok;
+    char* end;
+    double v = std::strtod(buf.c_str(), &end);
+    if (*end != '\0') {
+      Warn("invalid double value");
+      return nullptr;
+    }
+    m_buf_double_array.push_back(v);
+  }
+
+  return Value::MakeDoubleArray(std::move(m_buf_double_array));
+}
+
+std::shared_ptr<Value> LoadPersistentImpl::ReadStringArrayValue() {
+  m_buf_string_array.clear();
+  while (!m_line.empty()) {
+    wpi::StringRef tok;
+    std::tie(tok, m_line) = ReadStringToken(m_line);
+    if (tok.empty()) {
+      Warn("missing string value");
+      return nullptr;
+    }
+    if (tok.back() != '"') {
+      Warn("unterminated string value");
+      return nullptr;
+    }
+
+    wpi::SmallString<128> buf;
+    m_buf_string_array.push_back(UnescapeString(tok, buf));
+
+    m_line = m_line.ltrim(" \t");
+    if (m_line.empty()) break;
+    if (m_line.front() != ',') {
+      Warn("expected comma between strings");
+      return nullptr;
+    }
+    m_line = m_line.drop_front().ltrim(" \t");
+  }
+
+  return Value::MakeStringArray(std::move(m_buf_string_array));
+}
+
+bool Storage::LoadEntries(
+    wpi::raw_istream& is, const Twine& prefix, bool persistent,
+    std::function<void(size_t line, const char* msg)> warn) {
+  wpi::SmallString<128> prefixBuf;
+  StringRef prefixStr = prefix.toStringRef(prefixBuf);
+
+  // entries to add
+  std::vector<LoadPersistentImpl::Entry> entries;
+
+  // load file
+  if (!LoadPersistentImpl(is, warn).Load(prefixStr, &entries)) return false;
+
+  // copy values into storage as quickly as possible so lock isn't held
+  std::vector<std::shared_ptr<Message>> msgs;
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  for (auto& i : entries) {
+    Entry* entry = GetOrNew(i.first);
+    auto old_value = entry->value;
+    entry->value = i.second;
+    bool was_persist = entry->IsPersistent();
+    if (!was_persist && persistent) entry->flags |= NT_PERSISTENT;
+
+    // if we're the server, assign an id if it doesn't have one
+    if (m_server && entry->id == 0xffff) {
+      unsigned int id = m_idmap.size();
+      entry->id = id;
+      m_idmap.push_back(entry);
+    }
+
+    // notify (for local listeners)
+    if (m_notifier.local_notifiers()) {
+      if (!old_value) {
+        m_notifier.NotifyEntry(entry->local_id, i.first, i.second,
+                               NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
+      } else if (*old_value != *i.second) {
+        unsigned int notify_flags = NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL;
+        if (!was_persist && persistent) notify_flags |= NT_NOTIFY_FLAGS;
+        m_notifier.NotifyEntry(entry->local_id, i.first, i.second,
+                               notify_flags);
+      } else if (!was_persist && persistent) {
+        m_notifier.NotifyEntry(entry->local_id, i.first, i.second,
+                               NT_NOTIFY_FLAGS | NT_NOTIFY_LOCAL);
+      }
+    }
+
+    if (!m_dispatcher) continue;  // shortcut
+    ++entry->seq_num;
+
+    // put on update queue
+    if (!old_value || old_value->type() != i.second->type()) {
+      msgs.emplace_back(Message::EntryAssign(
+          i.first, entry->id, entry->seq_num.value(), i.second, entry->flags));
+    } else if (entry->id != 0xffff) {
+      // don't send an update if we don't have an assigned id yet
+      if (*old_value != *i.second)
+        msgs.emplace_back(
+            Message::EntryUpdate(entry->id, entry->seq_num.value(), i.second));
+      if (!was_persist)
+        msgs.emplace_back(Message::FlagsUpdate(entry->id, entry->flags));
+    }
+  }
+
+  if (m_dispatcher) {
+    auto dispatcher = m_dispatcher;
+    lock.unlock();
+    for (auto& msg : msgs)
+      dispatcher->QueueOutgoing(std::move(msg), nullptr, nullptr);
+  }
+
+  return true;
+}
+
+const char* Storage::LoadPersistent(
+    const Twine& filename,
+    std::function<void(size_t line, const char* msg)> warn) {
+  std::error_code ec;
+  wpi::raw_fd_istream is(filename, ec);
+  if (ec.value() != 0) return "could not open file";
+  if (!LoadEntries(is, "", true, warn)) return "error reading file";
+  return nullptr;
+}
+
+const char* Storage::LoadEntries(
+    const Twine& filename, const Twine& prefix,
+    std::function<void(size_t line, const char* msg)> warn) {
+  std::error_code ec;
+  wpi::raw_fd_istream is(filename, ec);
+  if (ec.value() != 0) return "could not open file";
+  if (!LoadEntries(is, prefix, false, warn)) return "error reading file";
+  return nullptr;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage_save.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage_save.cpp
new file mode 100644
index 0000000..3f352da
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Storage_save.cpp
@@ -0,0 +1,272 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <cctype>
+#include <string>
+
+#include <wpi/Base64.h>
+#include <wpi/FileSystem.h>
+#include <wpi/Format.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringExtras.h>
+#include <wpi/raw_ostream.h>
+
+#include "Log.h"
+#include "Storage.h"
+
+using namespace nt;
+
+namespace {
+
+class SavePersistentImpl {
+ public:
+  typedef std::pair<std::string, std::shared_ptr<Value>> Entry;
+
+  explicit SavePersistentImpl(wpi::raw_ostream& os) : m_os(os) {}
+
+  void Save(wpi::ArrayRef<Entry> entries);
+
+ private:
+  void WriteString(wpi::StringRef str);
+  void WriteHeader();
+  void WriteEntries(wpi::ArrayRef<Entry> entries);
+  void WriteEntry(wpi::StringRef name, const Value& value);
+  bool WriteType(NT_Type type);
+  void WriteValue(const Value& value);
+
+  wpi::raw_ostream& m_os;
+};
+
+}  // namespace
+
+/* Escapes and writes a string, including start and end double quotes */
+void SavePersistentImpl::WriteString(wpi::StringRef str) {
+  m_os << '"';
+  for (auto c : str) {
+    switch (c) {
+      case '\\':
+        m_os << "\\\\";
+        break;
+      case '\t':
+        m_os << "\\t";
+        break;
+      case '\n':
+        m_os << "\\n";
+        break;
+      case '"':
+        m_os << "\\\"";
+        break;
+      default:
+        if (std::isprint(c) && c != '=') {
+          m_os << c;
+          break;
+        }
+
+        // Write out the escaped representation.
+        m_os << "\\x";
+        m_os << wpi::hexdigit((c >> 4) & 0xF);
+        m_os << wpi::hexdigit((c >> 0) & 0xF);
+    }
+  }
+  m_os << '"';
+}
+
+void SavePersistentImpl::Save(wpi::ArrayRef<Entry> entries) {
+  WriteHeader();
+  WriteEntries(entries);
+}
+
+void SavePersistentImpl::WriteHeader() {
+  m_os << "[NetworkTables Storage 3.0]\n";
+}
+
+void SavePersistentImpl::WriteEntries(wpi::ArrayRef<Entry> entries) {
+  for (auto& i : entries) {
+    if (!i.second) continue;
+    WriteEntry(i.first, *i.second);
+  }
+}
+
+void SavePersistentImpl::WriteEntry(wpi::StringRef name, const Value& value) {
+  if (!WriteType(value.type())) return;  // type
+  WriteString(name);                     // name
+  m_os << '=';                           // '='
+  WriteValue(value);                     // value
+  m_os << '\n';                          // eol
+}
+
+bool SavePersistentImpl::WriteType(NT_Type type) {
+  switch (type) {
+    case NT_BOOLEAN:
+      m_os << "boolean ";
+      break;
+    case NT_DOUBLE:
+      m_os << "double ";
+      break;
+    case NT_STRING:
+      m_os << "string ";
+      break;
+    case NT_RAW:
+      m_os << "raw ";
+      break;
+    case NT_BOOLEAN_ARRAY:
+      m_os << "array boolean ";
+      break;
+    case NT_DOUBLE_ARRAY:
+      m_os << "array double ";
+      break;
+    case NT_STRING_ARRAY:
+      m_os << "array string ";
+      break;
+    default:
+      return false;
+  }
+  return true;
+}
+
+void SavePersistentImpl::WriteValue(const Value& value) {
+  switch (value.type()) {
+    case NT_BOOLEAN:
+      m_os << (value.GetBoolean() ? "true" : "false");
+      break;
+    case NT_DOUBLE:
+      m_os << wpi::format("%g", value.GetDouble());
+      break;
+    case NT_STRING:
+      WriteString(value.GetString());
+      break;
+    case NT_RAW: {
+      wpi::Base64Encode(m_os, value.GetRaw());
+      break;
+    }
+    case NT_BOOLEAN_ARRAY: {
+      bool first = true;
+      for (auto elem : value.GetBooleanArray()) {
+        if (!first) m_os << ',';
+        first = false;
+        m_os << (elem ? "true" : "false");
+      }
+      break;
+    }
+    case NT_DOUBLE_ARRAY: {
+      bool first = true;
+      for (auto elem : value.GetDoubleArray()) {
+        if (!first) m_os << ',';
+        first = false;
+        m_os << wpi::format("%g", elem);
+      }
+      break;
+    }
+    case NT_STRING_ARRAY: {
+      bool first = true;
+      for (auto& elem : value.GetStringArray()) {
+        if (!first) m_os << ',';
+        first = false;
+        WriteString(elem);
+      }
+      break;
+    }
+    default:
+      break;
+  }
+}
+
+void Storage::SavePersistent(wpi::raw_ostream& os, bool periodic) const {
+  std::vector<SavePersistentImpl::Entry> entries;
+  if (!GetPersistentEntries(periodic, &entries)) return;
+  SavePersistentImpl(os).Save(entries);
+}
+
+const char* Storage::SavePersistent(const Twine& filename,
+                                    bool periodic) const {
+  wpi::SmallString<128> fn;
+  filename.toVector(fn);
+  wpi::SmallString<128> tmp = fn;
+  tmp += ".tmp";
+  wpi::SmallString<128> bak = fn;
+  bak += ".bak";
+
+  // Get entries before creating file
+  std::vector<SavePersistentImpl::Entry> entries;
+  if (!GetPersistentEntries(periodic, &entries)) return nullptr;
+
+  const char* err = nullptr;
+
+  // start by writing to temporary file
+  std::error_code ec;
+  wpi::raw_fd_ostream os(tmp, ec, wpi::sys::fs::F_Text);
+  if (ec.value() != 0) {
+    err = "could not open file";
+    goto done;
+  }
+  DEBUG("saving persistent file '" << filename << "'");
+  SavePersistentImpl(os).Save(entries);
+  os.close();
+  if (os.has_error()) {
+    std::remove(tmp.c_str());
+    err = "error saving file";
+    goto done;
+  }
+
+  // Safely move to real file.  We ignore any failures related to the backup.
+  std::remove(bak.c_str());
+  std::rename(fn.c_str(), bak.c_str());
+  if (std::rename(tmp.c_str(), fn.c_str()) != 0) {
+    std::rename(bak.c_str(), fn.c_str());  // attempt to restore backup
+    err = "could not rename temp file to real file";
+    goto done;
+  }
+
+done:
+  // try again if there was an error
+  if (err && periodic) m_persistent_dirty = true;
+  return err;
+}
+
+void Storage::SaveEntries(wpi::raw_ostream& os, const Twine& prefix) const {
+  std::vector<SavePersistentImpl::Entry> entries;
+  if (!GetEntries(prefix, &entries)) return;
+  SavePersistentImpl(os).Save(entries);
+}
+
+const char* Storage::SaveEntries(const Twine& filename,
+                                 const Twine& prefix) const {
+  wpi::SmallString<128> fn;
+  filename.toVector(fn);
+  wpi::SmallString<128> tmp = fn;
+  tmp += ".tmp";
+  wpi::SmallString<128> bak = fn;
+  bak += ".bak";
+
+  // Get entries before creating file
+  std::vector<SavePersistentImpl::Entry> entries;
+  if (!GetEntries(prefix, &entries)) return nullptr;
+
+  // start by writing to temporary file
+  std::error_code ec;
+  wpi::raw_fd_ostream os(tmp, ec, wpi::sys::fs::F_Text);
+  if (ec.value() != 0) {
+    return "could not open file";
+  }
+  DEBUG("saving file '" << filename << "'");
+  SavePersistentImpl(os).Save(entries);
+  os.close();
+  if (os.has_error()) {
+    std::remove(tmp.c_str());
+    return "error saving file";
+  }
+
+  // Safely move to real file.  We ignore any failures related to the backup.
+  std::remove(bak.c_str());
+  std::rename(fn.c_str(), bak.c_str());
+  if (std::rename(tmp.c_str(), fn.c_str()) != 0) {
+    std::rename(bak.c_str(), fn.c_str());  // attempt to restore backup
+    return "could not rename temp file to real file";
+  }
+
+  return nullptr;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Value.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Value.cpp
new file mode 100644
index 0000000..61390f0
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Value.cpp
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <stdint.h>
+
+#include <wpi/memory.h>
+#include <wpi/timestamp.h>
+
+#include "Value_internal.h"
+#include "networktables/NetworkTableValue.h"
+
+using namespace nt;
+
+Value::Value() {
+  m_val.type = NT_UNASSIGNED;
+  m_val.last_change = wpi::Now();
+}
+
+Value::Value(NT_Type type, uint64_t time, const private_init&) {
+  m_val.type = type;
+  if (time == 0)
+    m_val.last_change = wpi::Now();
+  else
+    m_val.last_change = time;
+  if (m_val.type == NT_BOOLEAN_ARRAY)
+    m_val.data.arr_boolean.arr = nullptr;
+  else if (m_val.type == NT_DOUBLE_ARRAY)
+    m_val.data.arr_double.arr = nullptr;
+  else if (m_val.type == NT_STRING_ARRAY)
+    m_val.data.arr_string.arr = nullptr;
+}
+
+Value::~Value() {
+  if (m_val.type == NT_BOOLEAN_ARRAY)
+    delete[] m_val.data.arr_boolean.arr;
+  else if (m_val.type == NT_DOUBLE_ARRAY)
+    delete[] m_val.data.arr_double.arr;
+  else if (m_val.type == NT_STRING_ARRAY)
+    delete[] m_val.data.arr_string.arr;
+}
+
+std::shared_ptr<Value> Value::MakeBooleanArray(wpi::ArrayRef<bool> value,
+                                               uint64_t time) {
+  auto val = std::make_shared<Value>(NT_BOOLEAN_ARRAY, time, private_init());
+  val->m_val.data.arr_boolean.arr = new int[value.size()];
+  val->m_val.data.arr_boolean.size = value.size();
+  std::copy(value.begin(), value.end(), val->m_val.data.arr_boolean.arr);
+  return val;
+}
+
+std::shared_ptr<Value> Value::MakeBooleanArray(wpi::ArrayRef<int> value,
+                                               uint64_t time) {
+  auto val = std::make_shared<Value>(NT_BOOLEAN_ARRAY, time, private_init());
+  val->m_val.data.arr_boolean.arr = new int[value.size()];
+  val->m_val.data.arr_boolean.size = value.size();
+  std::copy(value.begin(), value.end(), val->m_val.data.arr_boolean.arr);
+  return val;
+}
+
+std::shared_ptr<Value> Value::MakeDoubleArray(wpi::ArrayRef<double> value,
+                                              uint64_t time) {
+  auto val = std::make_shared<Value>(NT_DOUBLE_ARRAY, time, private_init());
+  val->m_val.data.arr_double.arr = new double[value.size()];
+  val->m_val.data.arr_double.size = value.size();
+  std::copy(value.begin(), value.end(), val->m_val.data.arr_double.arr);
+  return val;
+}
+
+std::shared_ptr<Value> Value::MakeStringArray(wpi::ArrayRef<std::string> value,
+                                              uint64_t time) {
+  auto val = std::make_shared<Value>(NT_STRING_ARRAY, time, private_init());
+  val->m_string_array = value;
+  // point NT_Value to the contents in the vector.
+  val->m_val.data.arr_string.arr = new NT_String[value.size()];
+  val->m_val.data.arr_string.size = val->m_string_array.size();
+  for (size_t i = 0; i < value.size(); ++i) {
+    val->m_val.data.arr_string.arr[i].str = const_cast<char*>(value[i].c_str());
+    val->m_val.data.arr_string.arr[i].len = value[i].size();
+  }
+  return val;
+}
+
+std::shared_ptr<Value> Value::MakeStringArray(std::vector<std::string>&& value,
+                                              uint64_t time) {
+  auto val = std::make_shared<Value>(NT_STRING_ARRAY, time, private_init());
+  val->m_string_array = std::move(value);
+  value.clear();
+  // point NT_Value to the contents in the vector.
+  val->m_val.data.arr_string.arr = new NT_String[val->m_string_array.size()];
+  val->m_val.data.arr_string.size = val->m_string_array.size();
+  for (size_t i = 0; i < val->m_string_array.size(); ++i) {
+    val->m_val.data.arr_string.arr[i].str =
+        const_cast<char*>(val->m_string_array[i].c_str());
+    val->m_val.data.arr_string.arr[i].len = val->m_string_array[i].size();
+  }
+  return val;
+}
+
+void nt::ConvertToC(const Value& in, NT_Value* out) {
+  out->type = NT_UNASSIGNED;
+  switch (in.type()) {
+    case NT_UNASSIGNED:
+      return;
+    case NT_BOOLEAN:
+      out->data.v_boolean = in.GetBoolean() ? 1 : 0;
+      break;
+    case NT_DOUBLE:
+      out->data.v_double = in.GetDouble();
+      break;
+    case NT_STRING:
+      ConvertToC(in.GetString(), &out->data.v_string);
+      break;
+    case NT_RAW:
+      ConvertToC(in.GetRaw(), &out->data.v_raw);
+      break;
+    case NT_RPC:
+      ConvertToC(in.GetRpc(), &out->data.v_raw);
+      break;
+    case NT_BOOLEAN_ARRAY: {
+      auto v = in.GetBooleanArray();
+      out->data.arr_boolean.arr =
+          static_cast<int*>(wpi::CheckedMalloc(v.size() * sizeof(int)));
+      out->data.arr_boolean.size = v.size();
+      std::copy(v.begin(), v.end(), out->data.arr_boolean.arr);
+      break;
+    }
+    case NT_DOUBLE_ARRAY: {
+      auto v = in.GetDoubleArray();
+      out->data.arr_double.arr =
+          static_cast<double*>(wpi::CheckedMalloc(v.size() * sizeof(double)));
+      out->data.arr_double.size = v.size();
+      std::copy(v.begin(), v.end(), out->data.arr_double.arr);
+      break;
+    }
+    case NT_STRING_ARRAY: {
+      auto v = in.GetStringArray();
+      out->data.arr_string.arr = static_cast<NT_String*>(
+          wpi::CheckedMalloc(v.size() * sizeof(NT_String)));
+      for (size_t i = 0; i < v.size(); ++i)
+        ConvertToC(v[i], &out->data.arr_string.arr[i]);
+      out->data.arr_string.size = v.size();
+      break;
+    }
+    default:
+      // assert(false && "unknown value type");
+      return;
+  }
+  out->type = in.type();
+}
+
+void nt::ConvertToC(wpi::StringRef in, NT_String* out) {
+  out->len = in.size();
+  out->str = static_cast<char*>(wpi::CheckedMalloc(in.size() + 1));
+  std::memcpy(out->str, in.data(), in.size());
+  out->str[in.size()] = '\0';
+}
+
+std::shared_ptr<Value> nt::ConvertFromC(const NT_Value& value) {
+  switch (value.type) {
+    case NT_UNASSIGNED:
+      return nullptr;
+    case NT_BOOLEAN:
+      return Value::MakeBoolean(value.data.v_boolean != 0);
+    case NT_DOUBLE:
+      return Value::MakeDouble(value.data.v_double);
+    case NT_STRING:
+      return Value::MakeString(ConvertFromC(value.data.v_string));
+    case NT_RAW:
+      return Value::MakeRaw(ConvertFromC(value.data.v_raw));
+    case NT_RPC:
+      return Value::MakeRpc(ConvertFromC(value.data.v_raw));
+    case NT_BOOLEAN_ARRAY:
+      return Value::MakeBooleanArray(wpi::ArrayRef<int>(
+          value.data.arr_boolean.arr, value.data.arr_boolean.size));
+    case NT_DOUBLE_ARRAY:
+      return Value::MakeDoubleArray(wpi::ArrayRef<double>(
+          value.data.arr_double.arr, value.data.arr_double.size));
+    case NT_STRING_ARRAY: {
+      std::vector<std::string> v;
+      v.reserve(value.data.arr_string.size);
+      for (size_t i = 0; i < value.data.arr_string.size; ++i)
+        v.push_back(ConvertFromC(value.data.arr_string.arr[i]));
+      return Value::MakeStringArray(std::move(v));
+    }
+    default:
+      // assert(false && "unknown value type");
+      return nullptr;
+  }
+}
+
+bool nt::operator==(const Value& lhs, const Value& rhs) {
+  if (lhs.type() != rhs.type()) return false;
+  switch (lhs.type()) {
+    case NT_UNASSIGNED:
+      return true;  // XXX: is this better being false instead?
+    case NT_BOOLEAN:
+      return lhs.m_val.data.v_boolean == rhs.m_val.data.v_boolean;
+    case NT_DOUBLE:
+      return lhs.m_val.data.v_double == rhs.m_val.data.v_double;
+    case NT_STRING:
+    case NT_RAW:
+    case NT_RPC:
+      return lhs.m_string == rhs.m_string;
+    case NT_BOOLEAN_ARRAY:
+      if (lhs.m_val.data.arr_boolean.size != rhs.m_val.data.arr_boolean.size)
+        return false;
+      return std::memcmp(lhs.m_val.data.arr_boolean.arr,
+                         rhs.m_val.data.arr_boolean.arr,
+                         lhs.m_val.data.arr_boolean.size *
+                             sizeof(lhs.m_val.data.arr_boolean.arr[0])) == 0;
+    case NT_DOUBLE_ARRAY:
+      if (lhs.m_val.data.arr_double.size != rhs.m_val.data.arr_double.size)
+        return false;
+      return std::memcmp(lhs.m_val.data.arr_double.arr,
+                         rhs.m_val.data.arr_double.arr,
+                         lhs.m_val.data.arr_double.size *
+                             sizeof(lhs.m_val.data.arr_double.arr[0])) == 0;
+    case NT_STRING_ARRAY:
+      return lhs.m_string_array == rhs.m_string_array;
+    default:
+      // assert(false && "unknown value type");
+      return false;
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Value_internal.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Value_internal.h
new file mode 100644
index 0000000..ea25777
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/Value_internal.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_VALUE_INTERNAL_H_
+#define NTCORE_VALUE_INTERNAL_H_
+
+#include <memory>
+#include <string>
+
+#include <wpi/StringRef.h>
+
+#include "ntcore_c.h"
+
+namespace nt {
+
+class Value;
+
+void ConvertToC(const Value& in, NT_Value* out);
+std::shared_ptr<Value> ConvertFromC(const NT_Value& value);
+void ConvertToC(wpi::StringRef in, NT_String* out);
+inline wpi::StringRef ConvertFromC(const NT_String& str) {
+  return wpi::StringRef(str.str, str.len);
+}
+
+}  // namespace nt
+
+#endif  // NTCORE_VALUE_INTERNAL_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireDecoder.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireDecoder.cpp
new file mode 100644
index 0000000..132e8a2
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireDecoder.cpp
@@ -0,0 +1,208 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "WireDecoder.h"
+
+#include <stdint.h>
+
+#include <cassert>
+#include <cstdlib>
+#include <cstring>
+
+#include <wpi/MathExtras.h>
+#include <wpi/leb128.h>
+#include <wpi/memory.h>
+
+using namespace nt;
+
+static double ReadDouble(const char*& buf) {
+  // Fast but non-portable!
+  uint64_t val = (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+  ++buf;
+  val <<= 8;
+  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+  ++buf;
+  val <<= 8;
+  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+  ++buf;
+  val <<= 8;
+  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+  ++buf;
+  val <<= 8;
+  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+  ++buf;
+  val <<= 8;
+  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+  ++buf;
+  val <<= 8;
+  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+  ++buf;
+  val <<= 8;
+  val |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+  ++buf;
+  return wpi::BitsToDouble(val);
+}
+
+WireDecoder::WireDecoder(wpi::raw_istream& is, unsigned int proto_rev,
+                         wpi::Logger& logger)
+    : m_is(is), m_logger(logger) {
+  // Start with a 1K temporary buffer.  Use malloc instead of new so we can
+  // realloc.
+  m_allocated = 1024;
+  m_buf = static_cast<char*>(wpi::CheckedMalloc(m_allocated));
+  m_proto_rev = proto_rev;
+  m_error = nullptr;
+}
+
+WireDecoder::~WireDecoder() { std::free(m_buf); }
+
+bool WireDecoder::ReadDouble(double* val) {
+  const char* buf;
+  if (!Read(&buf, 8)) return false;
+  *val = ::ReadDouble(buf);
+  return true;
+}
+
+void WireDecoder::Realloc(size_t len) {
+  // Double current buffer size until we have enough space.
+  if (m_allocated >= len) return;
+  size_t newlen = m_allocated * 2;
+  while (newlen < len) newlen *= 2;
+  m_buf = static_cast<char*>(wpi::CheckedRealloc(m_buf, newlen));
+  m_allocated = newlen;
+}
+
+bool WireDecoder::ReadType(NT_Type* type) {
+  unsigned int itype;
+  if (!Read8(&itype)) return false;
+  // Convert from byte value to enum
+  switch (itype) {
+    case 0x00:
+      *type = NT_BOOLEAN;
+      break;
+    case 0x01:
+      *type = NT_DOUBLE;
+      break;
+    case 0x02:
+      *type = NT_STRING;
+      break;
+    case 0x03:
+      *type = NT_RAW;
+      break;
+    case 0x10:
+      *type = NT_BOOLEAN_ARRAY;
+      break;
+    case 0x11:
+      *type = NT_DOUBLE_ARRAY;
+      break;
+    case 0x12:
+      *type = NT_STRING_ARRAY;
+      break;
+    case 0x20:
+      *type = NT_RPC;
+      break;
+    default:
+      *type = NT_UNASSIGNED;
+      m_error = "unrecognized value type";
+      return false;
+  }
+  return true;
+}
+
+std::shared_ptr<Value> WireDecoder::ReadValue(NT_Type type) {
+  switch (type) {
+    case NT_BOOLEAN: {
+      unsigned int v;
+      if (!Read8(&v)) return nullptr;
+      return Value::MakeBoolean(v != 0);
+    }
+    case NT_DOUBLE: {
+      double v;
+      if (!ReadDouble(&v)) return nullptr;
+      return Value::MakeDouble(v);
+    }
+    case NT_STRING: {
+      std::string v;
+      if (!ReadString(&v)) return nullptr;
+      return Value::MakeString(std::move(v));
+    }
+    case NT_RAW: {
+      if (m_proto_rev < 0x0300u) {
+        m_error = "received raw value in protocol < 3.0";
+        return nullptr;
+      }
+      std::string v;
+      if (!ReadString(&v)) return nullptr;
+      return Value::MakeRaw(std::move(v));
+    }
+    case NT_RPC: {
+      if (m_proto_rev < 0x0300u) {
+        m_error = "received RPC value in protocol < 3.0";
+        return nullptr;
+      }
+      std::string v;
+      if (!ReadString(&v)) return nullptr;
+      return Value::MakeRpc(std::move(v));
+    }
+    case NT_BOOLEAN_ARRAY: {
+      // size
+      unsigned int size;
+      if (!Read8(&size)) return nullptr;
+
+      // array values
+      const char* buf;
+      if (!Read(&buf, size)) return nullptr;
+      std::vector<int> v(size);
+      for (unsigned int i = 0; i < size; ++i) v[i] = buf[i] ? 1 : 0;
+      return Value::MakeBooleanArray(std::move(v));
+    }
+    case NT_DOUBLE_ARRAY: {
+      // size
+      unsigned int size;
+      if (!Read8(&size)) return nullptr;
+
+      // array values
+      const char* buf;
+      if (!Read(&buf, size * 8)) return nullptr;
+      std::vector<double> v(size);
+      for (unsigned int i = 0; i < size; ++i) v[i] = ::ReadDouble(buf);
+      return Value::MakeDoubleArray(std::move(v));
+    }
+    case NT_STRING_ARRAY: {
+      // size
+      unsigned int size;
+      if (!Read8(&size)) return nullptr;
+
+      // array values
+      std::vector<std::string> v(size);
+      for (unsigned int i = 0; i < size; ++i) {
+        if (!ReadString(&v[i])) return nullptr;
+      }
+      return Value::MakeStringArray(std::move(v));
+    }
+    default:
+      m_error = "invalid type when trying to read value";
+      return nullptr;
+  }
+}
+
+bool WireDecoder::ReadString(std::string* str) {
+  size_t len;
+  if (m_proto_rev < 0x0300u) {
+    unsigned int v;
+    if (!Read16(&v)) return false;
+    len = v;
+  } else {
+    uint64_t v;
+    if (!ReadUleb128(&v)) return false;
+    len = v;
+  }
+  const char* buf;
+  if (!Read(&buf, len)) return false;
+  *str = wpi::StringRef(buf, len);
+  return true;
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireDecoder.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireDecoder.h
new file mode 100644
index 0000000..6b4483b
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireDecoder.h
@@ -0,0 +1,158 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_WIREDECODER_H_
+#define NTCORE_WIREDECODER_H_
+
+#include <stdint.h>
+
+#include <cstddef>
+#include <memory>
+#include <string>
+
+#include <wpi/leb128.h>
+#include <wpi/raw_istream.h>
+
+#include "Log.h"
+#include "networktables/NetworkTableValue.h"
+
+namespace nt {
+
+/* Decodes network data into native representation.
+ * This class is designed to read from a raw_istream, which provides a blocking
+ * read interface.  There are no provisions in this class for resuming a read
+ * that was interrupted partway.  Read functions return false if
+ * raw_istream.read() returned false (indicating the end of the input data
+ * stream).
+ */
+class WireDecoder {
+ public:
+  WireDecoder(wpi::raw_istream& is, unsigned int proto_rev,
+              wpi::Logger& logger);
+  ~WireDecoder();
+
+  void set_proto_rev(unsigned int proto_rev) { m_proto_rev = proto_rev; }
+
+  /* Get the active protocol revision. */
+  unsigned int proto_rev() const { return m_proto_rev; }
+
+  /* Get the logger. */
+  wpi::Logger& logger() const { return m_logger; }
+
+  /* Clears error indicator. */
+  void Reset() { m_error = nullptr; }
+
+  /* Returns error indicator (a string describing the error).  Returns nullptr
+   * if no error has occurred.
+   */
+  const char* error() const { return m_error; }
+
+  void set_error(const char* error) { m_error = error; }
+
+  /* Reads the specified number of bytes.
+   * @param buf pointer to read data (output parameter)
+   * @param len number of bytes to read
+   * Caution: the buffer is only temporarily valid.
+   */
+  bool Read(const char** buf, size_t len) {
+    if (len > m_allocated) Realloc(len);
+    *buf = m_buf;
+    m_is.read(m_buf, len);
+#if 0
+    if (m_logger.min_level() <= NT_LOG_DEBUG4 && m_logger.HasLogger()) {
+      std::ostringstream oss;
+      oss << "read " << len << " bytes:" << std::hex;
+      if (!rv) {
+        oss << "error";
+      } else {
+        for (size_t i = 0; i < len; ++i)
+          oss << ' ' << static_cast<unsigned int>((*buf)[i]);
+      }
+      m_logger.Log(NT_LOG_DEBUG4, __FILE__, __LINE__, oss.str().c_str());
+    }
+#endif
+    return !m_is.has_error();
+  }
+
+  /* Reads a single byte. */
+  bool Read8(unsigned int* val) {
+    const char* buf;
+    if (!Read(&buf, 1)) return false;
+    *val = (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+    return true;
+  }
+
+  /* Reads a 16-bit word. */
+  bool Read16(unsigned int* val) {
+    const char* buf;
+    if (!Read(&buf, 2)) return false;
+    unsigned int v = (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+    ++buf;
+    v <<= 8;
+    v |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+    *val = v;
+    return true;
+  }
+
+  /* Reads a 32-bit word. */
+  bool Read32(uint32_t* val) {
+    const char* buf;
+    if (!Read(&buf, 4)) return false;
+    unsigned int v = (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+    ++buf;
+    v <<= 8;
+    v |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+    ++buf;
+    v <<= 8;
+    v |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+    ++buf;
+    v <<= 8;
+    v |= (*reinterpret_cast<const unsigned char*>(buf)) & 0xff;
+    *val = v;
+    return true;
+  }
+
+  /* Reads a double. */
+  bool ReadDouble(double* val);
+
+  /* Reads an ULEB128-encoded unsigned integer. */
+  bool ReadUleb128(uint64_t* val) { return wpi::ReadUleb128(m_is, val); }
+
+  bool ReadType(NT_Type* type);
+  bool ReadString(std::string* str);
+  std::shared_ptr<Value> ReadValue(NT_Type type);
+
+  WireDecoder(const WireDecoder&) = delete;
+  WireDecoder& operator=(const WireDecoder&) = delete;
+
+ protected:
+  /* The protocol revision.  E.g. 0x0200 for version 2.0. */
+  unsigned int m_proto_rev;
+
+  /* Error indicator. */
+  const char* m_error;
+
+ private:
+  /* Reallocate temporary buffer to specified length. */
+  void Realloc(size_t len);
+
+  /* input stream */
+  wpi::raw_istream& m_is;
+
+  /* logger */
+  wpi::Logger& m_logger;
+
+  /* temporary buffer */
+  char* m_buf;
+
+  /* allocated size of temporary buffer */
+  size_t m_allocated;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_WIREDECODER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireEncoder.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireEncoder.cpp
new file mode 100644
index 0000000..6538349
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireEncoder.cpp
@@ -0,0 +1,199 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "WireEncoder.h"
+
+#include <stdint.h>
+
+#include <cassert>
+#include <cstdlib>
+#include <cstring>
+
+#include <wpi/MathExtras.h>
+#include <wpi/leb128.h>
+
+using namespace nt;
+
+WireEncoder::WireEncoder(unsigned int proto_rev) {
+  m_proto_rev = proto_rev;
+  m_error = nullptr;
+}
+
+void WireEncoder::WriteDouble(double val) {
+  // The highest performance way to do this, albeit non-portable.
+  uint64_t v = wpi::DoubleToBits(val);
+  m_data.append(
+      {static_cast<char>((v >> 56) & 0xff), static_cast<char>((v >> 48) & 0xff),
+       static_cast<char>((v >> 40) & 0xff), static_cast<char>((v >> 32) & 0xff),
+       static_cast<char>((v >> 24) & 0xff), static_cast<char>((v >> 16) & 0xff),
+       static_cast<char>((v >> 8) & 0xff), static_cast<char>(v & 0xff)});
+}
+
+void WireEncoder::WriteUleb128(uint32_t val) { wpi::WriteUleb128(m_data, val); }
+
+void WireEncoder::WriteType(NT_Type type) {
+  char ch;
+  // Convert from enum to actual byte value.
+  switch (type) {
+    case NT_BOOLEAN:
+      ch = 0x00;
+      break;
+    case NT_DOUBLE:
+      ch = 0x01;
+      break;
+    case NT_STRING:
+      ch = 0x02;
+      break;
+    case NT_RAW:
+      if (m_proto_rev < 0x0300u) {
+        m_error = "raw type not supported in protocol < 3.0";
+        return;
+      }
+      ch = 0x03;
+      break;
+    case NT_BOOLEAN_ARRAY:
+      ch = 0x10;
+      break;
+    case NT_DOUBLE_ARRAY:
+      ch = 0x11;
+      break;
+    case NT_STRING_ARRAY:
+      ch = 0x12;
+      break;
+    case NT_RPC:
+      if (m_proto_rev < 0x0300u) {
+        m_error = "RPC type not supported in protocol < 3.0";
+        return;
+      }
+      ch = 0x20;
+      break;
+    default:
+      m_error = "unrecognized type";
+      return;
+  }
+  m_data.push_back(ch);
+}
+
+size_t WireEncoder::GetValueSize(const Value& value) const {
+  switch (value.type()) {
+    case NT_BOOLEAN:
+      return 1;
+    case NT_DOUBLE:
+      return 8;
+    case NT_STRING:
+      return GetStringSize(value.GetString());
+    case NT_RAW:
+      if (m_proto_rev < 0x0300u) return 0;
+      return GetStringSize(value.GetRaw());
+    case NT_RPC:
+      if (m_proto_rev < 0x0300u) return 0;
+      return GetStringSize(value.GetRpc());
+    case NT_BOOLEAN_ARRAY: {
+      // 1-byte size, 1 byte per element
+      size_t size = value.GetBooleanArray().size();
+      if (size > 0xff) size = 0xff;  // size is only 1 byte, truncate
+      return 1 + size;
+    }
+    case NT_DOUBLE_ARRAY: {
+      // 1-byte size, 8 bytes per element
+      size_t size = value.GetDoubleArray().size();
+      if (size > 0xff) size = 0xff;  // size is only 1 byte, truncate
+      return 1 + size * 8;
+    }
+    case NT_STRING_ARRAY: {
+      auto v = value.GetStringArray();
+      size_t size = v.size();
+      if (size > 0xff) size = 0xff;  // size is only 1 byte, truncate
+      size_t len = 1;                // 1-byte size
+      for (size_t i = 0; i < size; ++i) len += GetStringSize(v[i]);
+      return len;
+    }
+    default:
+      return 0;
+  }
+}
+
+void WireEncoder::WriteValue(const Value& value) {
+  switch (value.type()) {
+    case NT_BOOLEAN:
+      Write8(value.GetBoolean() ? 1 : 0);
+      break;
+    case NT_DOUBLE:
+      WriteDouble(value.GetDouble());
+      break;
+    case NT_STRING:
+      WriteString(value.GetString());
+      break;
+    case NT_RAW:
+      if (m_proto_rev < 0x0300u) {
+        m_error = "raw values not supported in protocol < 3.0";
+        return;
+      }
+      WriteString(value.GetRaw());
+      break;
+    case NT_RPC:
+      if (m_proto_rev < 0x0300u) {
+        m_error = "RPC values not supported in protocol < 3.0";
+        return;
+      }
+      WriteString(value.GetRpc());
+      break;
+    case NT_BOOLEAN_ARRAY: {
+      auto v = value.GetBooleanArray();
+      size_t size = v.size();
+      if (size > 0xff) size = 0xff;  // size is only 1 byte, truncate
+      Write8(size);
+
+      for (size_t i = 0; i < size; ++i) Write8(v[i] ? 1 : 0);
+      break;
+    }
+    case NT_DOUBLE_ARRAY: {
+      auto v = value.GetDoubleArray();
+      size_t size = v.size();
+      if (size > 0xff) size = 0xff;  // size is only 1 byte, truncate
+      Write8(size);
+
+      for (size_t i = 0; i < size; ++i) WriteDouble(v[i]);
+      break;
+    }
+    case NT_STRING_ARRAY: {
+      auto v = value.GetStringArray();
+      size_t size = v.size();
+      if (size > 0xff) size = 0xff;  // size is only 1 byte, truncate
+      Write8(size);
+
+      for (size_t i = 0; i < size; ++i) WriteString(v[i]);
+      break;
+    }
+    default:
+      m_error = "unrecognized type when writing value";
+      return;
+  }
+}
+
+size_t WireEncoder::GetStringSize(wpi::StringRef str) const {
+  if (m_proto_rev < 0x0300u) {
+    size_t len = str.size();
+    if (len > 0xffff) len = 0xffff;  // Limited to 64K length; truncate
+    return 2 + len;
+  }
+  return wpi::SizeUleb128(str.size()) + str.size();
+}
+
+void WireEncoder::WriteString(wpi::StringRef str) {
+  // length
+  size_t len = str.size();
+  if (m_proto_rev < 0x0300u) {
+    if (len > 0xffff) len = 0xffff;  // Limited to 64K length; truncate
+    Write16(len);
+  } else {
+    WriteUleb128(len);
+  }
+
+  // contents
+  m_data.append(str.data(), str.data() + len);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireEncoder.h b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireEncoder.h
new file mode 100644
index 0000000..c4f769c
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/WireEncoder.h
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_WIREENCODER_H_
+#define NTCORE_WIREENCODER_H_
+
+#include <stdint.h>
+
+#include <cassert>
+#include <cstddef>
+
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+
+#include "networktables/NetworkTableValue.h"
+
+namespace nt {
+
+/* Encodes native data for network transmission.
+ * This class maintains an internal memory buffer for written data so that
+ * it can be efficiently bursted to the network after a number of writes
+ * have been performed.  For this reason, all operations are non-blocking.
+ */
+class WireEncoder {
+ public:
+  explicit WireEncoder(unsigned int proto_rev);
+
+  /* Change the protocol revision (mostly affects value encoding). */
+  void set_proto_rev(unsigned int proto_rev) { m_proto_rev = proto_rev; }
+
+  /* Get the active protocol revision. */
+  unsigned int proto_rev() const { return m_proto_rev; }
+
+  /* Clears buffer and error indicator. */
+  void Reset() {
+    m_data.clear();
+    m_error = nullptr;
+  }
+
+  /* Returns error indicator (a string describing the error).  Returns nullptr
+   * if no error has occurred.
+   */
+  const char* error() const { return m_error; }
+
+  /* Returns pointer to start of memory buffer with written data. */
+  const char* data() const { return m_data.data(); }
+
+  /* Returns number of bytes written to memory buffer. */
+  size_t size() const { return m_data.size(); }
+
+  wpi::StringRef ToStringRef() const {
+    return wpi::StringRef(m_data.data(), m_data.size());
+  }
+
+  /* Writes a single byte. */
+  void Write8(unsigned int val) {
+    m_data.push_back(static_cast<char>(val & 0xff));
+  }
+
+  /* Writes a 16-bit word. */
+  void Write16(unsigned int val) {
+    m_data.append(
+        {static_cast<char>((val >> 8) & 0xff), static_cast<char>(val & 0xff)});
+  }
+
+  /* Writes a 32-bit word. */
+  void Write32(uint32_t val) {
+    m_data.append({static_cast<char>((val >> 24) & 0xff),
+                   static_cast<char>((val >> 16) & 0xff),
+                   static_cast<char>((val >> 8) & 0xff),
+                   static_cast<char>(val & 0xff)});
+  }
+
+  /* Writes a double. */
+  void WriteDouble(double val);
+
+  /* Writes an ULEB128-encoded unsigned integer. */
+  void WriteUleb128(uint32_t val);
+
+  void WriteType(NT_Type type);
+  void WriteValue(const Value& value);
+  void WriteString(wpi::StringRef str);
+
+  /* Utility function to get the written size of a value (without actually
+   * writing it).
+   */
+  size_t GetValueSize(const Value& value) const;
+
+  /* Utility function to get the written size of a string (without actually
+   * writing it).
+   */
+  size_t GetStringSize(wpi::StringRef str) const;
+
+ protected:
+  /* The protocol revision.  E.g. 0x0200 for version 2.0. */
+  unsigned int m_proto_rev;
+
+  /* Error indicator. */
+  const char* m_error;
+
+ private:
+  wpi::SmallVector<char, 256> m_data;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_WIREENCODER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp
new file mode 100644
index 0000000..49f34f0
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp
@@ -0,0 +1,1874 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <jni.h>
+
+#include <cassert>
+
+#include <wpi/ConvertUTF.h>
+#include <wpi/SmallString.h>
+#include <wpi/jni_util.h>
+#include <wpi/raw_ostream.h>
+
+#include "edu_wpi_first_networktables_NetworkTablesJNI.h"
+#include "ntcore.h"
+
+using namespace wpi::java;
+
+#ifdef __GNUC__
+#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
+#endif
+
+//
+// Globals and load/unload
+//
+
+// Used for callback.
+static JavaVM* jvm = nullptr;
+static JClass booleanCls;
+static JClass connectionInfoCls;
+static JClass connectionNotificationCls;
+static JClass doubleCls;
+static JClass entryInfoCls;
+static JClass entryNotificationCls;
+static JClass logMessageCls;
+static JClass rpcAnswerCls;
+static JClass valueCls;
+static JException illegalArgEx;
+static JException interruptedEx;
+static JException nullPointerEx;
+static JException persistentEx;
+
+static const JClassInit classes[] = {
+    {"java/lang/Boolean", &booleanCls},
+    {"edu/wpi/first/networktables/ConnectionInfo", &connectionInfoCls},
+    {"edu/wpi/first/networktables/ConnectionNotification",
+     &connectionNotificationCls},
+    {"java/lang/Double", &doubleCls},
+    {"edu/wpi/first/networktables/EntryInfo", &entryInfoCls},
+    {"edu/wpi/first/networktables/EntryNotification", &entryNotificationCls},
+    {"edu/wpi/first/networktables/LogMessage", &logMessageCls},
+    {"edu/wpi/first/networktables/RpcAnswer", &rpcAnswerCls},
+    {"edu/wpi/first/networktables/NetworkTableValue", &valueCls}};
+
+static const JExceptionInit exceptions[] = {
+    {"java/lang/IllegalArgumentException", &illegalArgEx},
+    {"java/lang/InterruptedException", &interruptedEx},
+    {"java/lang/NullPointerException", &nullPointerEx},
+    {"edu/wpi/first/networktables/PersistentException", &persistentEx}};
+
+extern "C" {
+
+JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) {
+  jvm = vm;
+
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return JNI_ERR;
+
+  // Cache references to classes
+  for (auto& c : classes) {
+    *c.cls = JClass(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  for (auto& c : exceptions) {
+    *c.cls = JException(env, c.name);
+    if (!*c.cls) return JNI_ERR;
+  }
+
+  return JNI_VERSION_1_6;
+}
+
+JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) {
+  JNIEnv* env;
+  if (vm->GetEnv(reinterpret_cast<void**>(&env), JNI_VERSION_1_6) != JNI_OK)
+    return;
+  // Delete global references
+  for (auto& c : classes) {
+    c.cls->free(env);
+  }
+  for (auto& c : exceptions) {
+    c.cls->free(env);
+  }
+  jvm = nullptr;
+}
+
+}  // extern "C"
+
+//
+// Conversions from Java objects to C++
+//
+
+inline std::shared_ptr<nt::Value> FromJavaRaw(JNIEnv* env, jbyteArray jarr,
+                                              jlong time) {
+  CriticalJByteArrayRef ref{env, jarr};
+  if (!ref) return nullptr;
+  return nt::Value::MakeRaw(ref, time);
+}
+
+inline std::shared_ptr<nt::Value> FromJavaRawBB(JNIEnv* env, jobject jbb,
+                                                int len, jlong time) {
+  JByteArrayRef ref{env, jbb, len};
+  if (!ref) return nullptr;
+  return nt::Value::MakeRaw(ref.str(), time);
+}
+
+inline std::shared_ptr<nt::Value> FromJavaRpc(JNIEnv* env, jbyteArray jarr,
+                                              jlong time) {
+  CriticalJByteArrayRef ref{env, jarr};
+  if (!ref) return nullptr;
+  return nt::Value::MakeRpc(ref.str(), time);
+}
+
+std::shared_ptr<nt::Value> FromJavaBooleanArray(JNIEnv* env, jbooleanArray jarr,
+                                                jlong time) {
+  CriticalJBooleanArrayRef ref{env, jarr};
+  if (!ref) return nullptr;
+  wpi::ArrayRef<jboolean> elements{ref};
+  size_t len = elements.size();
+  std::vector<int> arr;
+  arr.reserve(len);
+  for (size_t i = 0; i < len; ++i) arr.push_back(elements[i]);
+  return nt::Value::MakeBooleanArray(arr, time);
+}
+
+std::shared_ptr<nt::Value> FromJavaDoubleArray(JNIEnv* env, jdoubleArray jarr,
+                                               jlong time) {
+  CriticalJDoubleArrayRef ref{env, jarr};
+  if (!ref) return nullptr;
+  return nt::Value::MakeDoubleArray(ref, time);
+}
+
+std::shared_ptr<nt::Value> FromJavaStringArray(JNIEnv* env, jobjectArray jarr,
+                                               jlong time) {
+  size_t len = env->GetArrayLength(jarr);
+  std::vector<std::string> arr;
+  arr.reserve(len);
+  for (size_t i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(jarr, i))};
+    if (!elem) return nullptr;
+    arr.push_back(JStringRef{env, elem}.str());
+  }
+  return nt::Value::MakeStringArray(std::move(arr), time);
+}
+
+//
+// Conversions from C++ to Java objects
+//
+
+static jobject MakeJObject(JNIEnv* env, const nt::Value& value) {
+  static jmethodID booleanConstructor = nullptr;
+  static jmethodID doubleConstructor = nullptr;
+  if (!booleanConstructor)
+    booleanConstructor = env->GetMethodID(booleanCls, "<init>", "(Z)V");
+  if (!doubleConstructor)
+    doubleConstructor = env->GetMethodID(doubleCls, "<init>", "(D)V");
+
+  switch (value.type()) {
+    case NT_BOOLEAN:
+      return env->NewObject(booleanCls, booleanConstructor,
+                            (jboolean)(value.GetBoolean() ? 1 : 0));
+    case NT_DOUBLE:
+      return env->NewObject(doubleCls, doubleConstructor,
+                            (jdouble)value.GetDouble());
+    case NT_STRING:
+      return MakeJString(env, value.GetString());
+    case NT_RAW:
+      return MakeJByteArray(env, value.GetRaw());
+    case NT_BOOLEAN_ARRAY:
+      return MakeJBooleanArray(env, value.GetBooleanArray());
+    case NT_DOUBLE_ARRAY:
+      return MakeJDoubleArray(env, value.GetDoubleArray());
+    case NT_STRING_ARRAY:
+      return MakeJStringArray(env, value.GetStringArray());
+    case NT_RPC:
+      return MakeJByteArray(env, value.GetRpc());
+    default:
+      return nullptr;
+  }
+}
+
+static jobject MakeJValue(JNIEnv* env, const nt::Value* value) {
+  static jmethodID constructor =
+      env->GetMethodID(valueCls, "<init>", "(ILjava/lang/Object;J)V");
+  if (!value)
+    return env->NewObject(valueCls, constructor, (jint)NT_UNASSIGNED, nullptr,
+                          (jlong)0);
+  return env->NewObject(valueCls, constructor, (jint)value->type(),
+                        MakeJObject(env, *value), (jlong)value->time());
+}
+
+static jobject MakeJObject(JNIEnv* env, const nt::ConnectionInfo& info) {
+  static jmethodID constructor =
+      env->GetMethodID(connectionInfoCls, "<init>",
+                       "(Ljava/lang/String;Ljava/lang/String;IJI)V");
+  JLocal<jstring> remote_id{env, MakeJString(env, info.remote_id)};
+  JLocal<jstring> remote_ip{env, MakeJString(env, info.remote_ip)};
+  return env->NewObject(connectionInfoCls, constructor, remote_id.obj(),
+                        remote_ip.obj(), (jint)info.remote_port,
+                        (jlong)info.last_update, (jint)info.protocol_version);
+}
+
+static jobject MakeJObject(JNIEnv* env, jobject inst,
+                           const nt::ConnectionNotification& notification) {
+  static jmethodID constructor = env->GetMethodID(
+      connectionNotificationCls, "<init>",
+      "(Ledu/wpi/first/networktables/NetworkTableInstance;IZLedu/wpi/first/"
+      "networktables/ConnectionInfo;)V");
+  JLocal<jobject> conn{env, MakeJObject(env, notification.conn)};
+  return env->NewObject(connectionNotificationCls, constructor, inst,
+                        (jint)notification.listener,
+                        (jboolean)notification.connected, conn.obj());
+}
+
+static jobject MakeJObject(JNIEnv* env, jobject inst,
+                           const nt::EntryInfo& info) {
+  static jmethodID constructor =
+      env->GetMethodID(entryInfoCls, "<init>",
+                       "(Ledu/wpi/first/networktables/"
+                       "NetworkTableInstance;ILjava/lang/String;IIJ)V");
+  JLocal<jstring> name{env, MakeJString(env, info.name)};
+  return env->NewObject(entryInfoCls, constructor, inst, (jint)info.entry,
+                        name.obj(), (jint)info.type, (jint)info.flags,
+                        (jlong)info.last_change);
+}
+
+static jobject MakeJObject(JNIEnv* env, jobject inst,
+                           const nt::EntryNotification& notification) {
+  static jmethodID constructor = env->GetMethodID(
+      entryNotificationCls, "<init>",
+      "(Ledu/wpi/first/networktables/NetworkTableInstance;IILjava/lang/"
+      "String;Ledu/wpi/first/networktables/NetworkTableValue;I)V");
+  JLocal<jstring> name{env, MakeJString(env, notification.name)};
+  JLocal<jobject> value{env, MakeJValue(env, notification.value.get())};
+  return env->NewObject(entryNotificationCls, constructor, inst,
+                        (jint)notification.listener, (jint)notification.entry,
+                        name.obj(), value.obj(), (jint)notification.flags);
+}
+
+static jobject MakeJObject(JNIEnv* env, jobject inst,
+                           const nt::LogMessage& msg) {
+  static jmethodID constructor = env->GetMethodID(
+      logMessageCls, "<init>",
+      "(Ledu/wpi/first/networktables/NetworkTableInstance;IILjava/lang/"
+      "String;ILjava/lang/String;)V");
+  JLocal<jstring> filename{env, MakeJString(env, msg.filename)};
+  JLocal<jstring> message{env, MakeJString(env, msg.message)};
+  return env->NewObject(logMessageCls, constructor, inst, (jint)msg.logger,
+                        (jint)msg.level, filename.obj(), (jint)msg.line,
+                        message.obj());
+}
+
+static jobject MakeJObject(JNIEnv* env, jobject inst,
+                           const nt::RpcAnswer& answer) {
+  static jmethodID constructor =
+      env->GetMethodID(rpcAnswerCls, "<init>",
+                       "(Ledu/wpi/first/networktables/"
+                       "NetworkTableInstance;IILjava/lang/String;[B"
+                       "Ledu/wpi/first/networktables/ConnectionInfo;)V");
+  JLocal<jstring> name{env, MakeJString(env, answer.name)};
+  JLocal<jbyteArray> params{env, MakeJByteArray(env, answer.params)};
+  JLocal<jobject> conn{env, MakeJObject(env, answer.conn)};
+  return env->NewObject(rpcAnswerCls, constructor, inst, (jint)answer.entry,
+                        (jint)answer.call, name.obj(), params.obj(),
+                        conn.obj());
+}
+
+static jobjectArray MakeJObject(JNIEnv* env, jobject inst,
+                                wpi::ArrayRef<nt::ConnectionNotification> arr) {
+  jobjectArray jarr =
+      env->NewObjectArray(arr.size(), connectionNotificationCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> elem{env, MakeJObject(env, inst, arr[i])};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+static jobjectArray MakeJObject(JNIEnv* env, jobject inst,
+                                wpi::ArrayRef<nt::EntryNotification> arr) {
+  jobjectArray jarr =
+      env->NewObjectArray(arr.size(), entryNotificationCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> elem{env, MakeJObject(env, inst, arr[i])};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+static jobjectArray MakeJObject(JNIEnv* env, jobject inst,
+                                wpi::ArrayRef<nt::LogMessage> arr) {
+  jobjectArray jarr = env->NewObjectArray(arr.size(), logMessageCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> elem{env, MakeJObject(env, inst, arr[i])};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+static jobjectArray MakeJObject(JNIEnv* env, jobject inst,
+                                wpi::ArrayRef<nt::RpcAnswer> arr) {
+  jobjectArray jarr = env->NewObjectArray(arr.size(), rpcAnswerCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> elem{env, MakeJObject(env, inst, arr[i])};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+extern "C" {
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getDefaultInstance
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getDefaultInstance
+  (JNIEnv*, jclass)
+{
+  return nt::GetDefaultInstance();
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    createInstance
+ * Signature: ()I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_createInstance
+  (JNIEnv*, jclass)
+{
+  return nt::CreateInstance();
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    destroyInstance
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyInstance
+  (JNIEnv*, jclass, jint inst)
+{
+  nt::DestroyInstance(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getInstanceFromHandle
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getInstanceFromHandle
+  (JNIEnv*, jclass, jint handle)
+{
+  return nt::GetInstanceFromHandle(handle);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getEntry
+ * Signature: (ILjava/lang/String;)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntry
+  (JNIEnv* env, jclass, jint inst, jstring key)
+{
+  if (!key) {
+    nullPointerEx.Throw(env, "key cannot be null");
+    return false;
+  }
+  return nt::GetEntry(inst, JStringRef{env, key}.str());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getEntries
+ * Signature: (ILjava/lang/String;I)[I
+ */
+JNIEXPORT jintArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntries
+  (JNIEnv* env, jclass, jint inst, jstring prefix, jint types)
+{
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return nullptr;
+  }
+  return MakeJIntArray(
+      env, nt::GetEntries(inst, JStringRef{env, prefix}.str(), types));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getEntryName
+ * Signature: (I)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntryName
+  (JNIEnv* env, jclass, jint entry)
+{
+  return MakeJString(env, nt::GetEntryName(entry));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getEntryLastChange
+ * Signature: (I)J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntryLastChange
+  (JNIEnv*, jclass, jint entry)
+{
+  return nt::GetEntryLastChange(entry);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getType
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getType
+  (JNIEnv*, jclass, jint entry)
+{
+  return nt::GetEntryType(entry);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setBoolean
+ * Signature: (IJZZ)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setBoolean
+  (JNIEnv*, jclass, jint entry, jlong time, jboolean value, jboolean force)
+{
+  if (force) {
+    nt::SetEntryTypeValue(entry,
+                          nt::Value::MakeBoolean(value != JNI_FALSE, time));
+    return JNI_TRUE;
+  }
+  return nt::SetEntryValue(entry,
+                           nt::Value::MakeBoolean(value != JNI_FALSE, time));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDouble
+ * Signature: (IJDZ)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDouble
+  (JNIEnv*, jclass, jint entry, jlong time, jdouble value, jboolean force)
+{
+  if (force) {
+    nt::SetEntryTypeValue(entry, nt::Value::MakeDouble(value, time));
+    return JNI_TRUE;
+  }
+  return nt::SetEntryValue(entry, nt::Value::MakeDouble(value, time));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setString
+ * Signature: (IJLjava/lang/String;Z)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setString
+  (JNIEnv* env, jclass, jint entry, jlong time, jstring value, jboolean force)
+{
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return false;
+  }
+  if (force) {
+    nt::SetEntryTypeValue(
+        entry, nt::Value::MakeString(JStringRef{env, value}.str(), time));
+    return JNI_TRUE;
+  }
+  return nt::SetEntryValue(
+      entry, nt::Value::MakeString(JStringRef{env, value}.str(), time));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setRaw
+ * Signature: (IJ[BZ)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setRaw__IJ_3BZ
+  (JNIEnv* env, jclass, jint entry, jlong time, jbyteArray value,
+   jboolean force)
+{
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return false;
+  }
+  auto v = FromJavaRaw(env, value, time);
+  if (!v) return false;
+  if (force) {
+    nt::SetEntryTypeValue(entry, v);
+    return JNI_TRUE;
+  }
+  return nt::SetEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setRaw
+ * Signature: (IJLjava/lang/Object;IZ)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setRaw__IJLjava_nio_ByteBuffer_2IZ
+  (JNIEnv* env, jclass, jint entry, jlong time, jobject value, jint len,
+   jboolean force)
+{
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return false;
+  }
+  auto v = FromJavaRawBB(env, value, len, time);
+  if (!v) return false;
+  if (force) {
+    nt::SetEntryTypeValue(entry, v);
+    return JNI_TRUE;
+  }
+  return nt::SetEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setBooleanArray
+ * Signature: (IJ[ZZ)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setBooleanArray
+  (JNIEnv* env, jclass, jint entry, jlong time, jbooleanArray value,
+   jboolean force)
+{
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return false;
+  }
+  auto v = FromJavaBooleanArray(env, value, time);
+  if (!v) return false;
+  if (force) {
+    nt::SetEntryTypeValue(entry, v);
+    return JNI_TRUE;
+  }
+  return nt::SetEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDoubleArray
+ * Signature: (IJ[DZ)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDoubleArray
+  (JNIEnv* env, jclass, jint entry, jlong time, jdoubleArray value,
+   jboolean force)
+{
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return false;
+  }
+  auto v = FromJavaDoubleArray(env, value, time);
+  if (!v) return false;
+  if (force) {
+    nt::SetEntryTypeValue(entry, v);
+    return JNI_TRUE;
+  }
+  return nt::SetEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setStringArray
+ * Signature: (IJ[Ljava/lang/Object;Z)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setStringArray
+  (JNIEnv* env, jclass, jint entry, jlong time, jobjectArray value,
+   jboolean force)
+{
+  if (!value) {
+    nullPointerEx.Throw(env, "value cannot be null");
+    return false;
+  }
+  auto v = FromJavaStringArray(env, value, time);
+  if (!v) return false;
+  if (force) {
+    nt::SetEntryTypeValue(entry, v);
+    return JNI_TRUE;
+  }
+  return nt::SetEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getValue
+ * Signature: (I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getValue
+  (JNIEnv* env, jclass, jint entry)
+{
+  auto val = nt::GetEntryValue(entry);
+  return MakeJValue(env, val.get());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getBoolean
+ * Signature: (IZ)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getBoolean
+  (JNIEnv*, jclass, jint entry, jboolean defaultValue)
+{
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val->IsBoolean()) return defaultValue;
+  return val->GetBoolean();
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getDouble
+ * Signature: (ID)D
+ */
+JNIEXPORT jdouble JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getDouble
+  (JNIEnv*, jclass, jint entry, jdouble defaultValue)
+{
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val->IsDouble()) return defaultValue;
+  return val->GetDouble();
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getString
+ * Signature: (ILjava/lang/String;)Ljava/lang/String;
+ */
+JNIEXPORT jstring JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getString
+  (JNIEnv* env, jclass, jint entry, jstring defaultValue)
+{
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val->IsString()) return defaultValue;
+  return MakeJString(env, val->GetString());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getRaw
+ * Signature: (I[B)[B
+ */
+JNIEXPORT jbyteArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getRaw
+  (JNIEnv* env, jclass, jint entry, jbyteArray defaultValue)
+{
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val->IsRaw()) return defaultValue;
+  return MakeJByteArray(env, val->GetRaw());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getBooleanArray
+ * Signature: (I[Z)[Z
+ */
+JNIEXPORT jbooleanArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getBooleanArray
+  (JNIEnv* env, jclass, jint entry, jbooleanArray defaultValue)
+{
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val->IsBooleanArray()) return defaultValue;
+  return MakeJBooleanArray(env, val->GetBooleanArray());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getDoubleArray
+ * Signature: (I[D)[D
+ */
+JNIEXPORT jdoubleArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getDoubleArray
+  (JNIEnv* env, jclass, jint entry, jdoubleArray defaultValue)
+{
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val->IsDoubleArray()) return defaultValue;
+  return MakeJDoubleArray(env, val->GetDoubleArray());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getStringArray
+ * Signature: (I[Ljava/lang/Object;)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getStringArray
+  (JNIEnv* env, jclass, jint entry, jobjectArray defaultValue)
+{
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val->IsStringArray()) return defaultValue;
+  return MakeJStringArray(env, val->GetStringArray());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDefaultBoolean
+ * Signature: (IJZ)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultBoolean
+  (JNIEnv*, jclass, jint entry, jlong time, jboolean defaultValue)
+{
+  return nt::SetDefaultEntryValue(
+      entry, nt::Value::MakeBoolean(defaultValue != JNI_FALSE, time));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDefaultDouble
+ * Signature: (IJD)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultDouble
+  (JNIEnv*, jclass, jint entry, jlong time, jdouble defaultValue)
+{
+  return nt::SetDefaultEntryValue(entry,
+                                  nt::Value::MakeDouble(defaultValue, time));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDefaultString
+ * Signature: (IJLjava/lang/String;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultString
+  (JNIEnv* env, jclass, jint entry, jlong time, jstring defaultValue)
+{
+  if (!defaultValue) {
+    nullPointerEx.Throw(env, "defaultValue cannot be null");
+    return false;
+  }
+  return nt::SetDefaultEntryValue(
+      entry, nt::Value::MakeString(JStringRef{env, defaultValue}.str(), time));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDefaultRaw
+ * Signature: (IJ[B)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultRaw
+  (JNIEnv* env, jclass, jint entry, jlong time, jbyteArray defaultValue)
+{
+  if (!defaultValue) {
+    nullPointerEx.Throw(env, "defaultValue cannot be null");
+    return false;
+  }
+  auto v = FromJavaRaw(env, defaultValue, time);
+  return nt::SetDefaultEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDefaultBooleanArray
+ * Signature: (IJ[Z)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultBooleanArray
+  (JNIEnv* env, jclass, jint entry, jlong time, jbooleanArray defaultValue)
+{
+  if (!defaultValue) {
+    nullPointerEx.Throw(env, "defaultValue cannot be null");
+    return false;
+  }
+  auto v = FromJavaBooleanArray(env, defaultValue, time);
+  return nt::SetDefaultEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDefaultDoubleArray
+ * Signature: (IJ[D)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultDoubleArray
+  (JNIEnv* env, jclass, jint entry, jlong time, jdoubleArray defaultValue)
+{
+  if (!defaultValue) {
+    nullPointerEx.Throw(env, "defaultValue cannot be null");
+    return false;
+  }
+  auto v = FromJavaDoubleArray(env, defaultValue, time);
+  return nt::SetDefaultEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setDefaultStringArray
+ * Signature: (IJ[Ljava/lang/Object;)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setDefaultStringArray
+  (JNIEnv* env, jclass, jint entry, jlong time, jobjectArray defaultValue)
+{
+  if (!defaultValue) {
+    nullPointerEx.Throw(env, "defaultValue cannot be null");
+    return false;
+  }
+  auto v = FromJavaStringArray(env, defaultValue, time);
+  return nt::SetDefaultEntryValue(entry, v);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setEntryFlags
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setEntryFlags
+  (JNIEnv*, jclass, jint entry, jint flags)
+{
+  nt::SetEntryFlags(entry, flags);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getEntryFlags
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntryFlags
+  (JNIEnv*, jclass, jint entry)
+{
+  return nt::GetEntryFlags(entry);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    deleteEntry
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_deleteEntry
+  (JNIEnv*, jclass, jint entry)
+{
+  nt::DeleteEntry(entry);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    deleteAllEntries
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_deleteAllEntries
+  (JNIEnv*, jclass, jint inst)
+{
+  nt::DeleteAllEntries(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getEntryInfoHandle
+ * Signature: (Ljava/lang/Object;I)Ljava/lang/Object;
+ */
+JNIEXPORT jobject JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntryInfoHandle
+  (JNIEnv* env, jclass, jobject inst, jint entry)
+{
+  return MakeJObject(env, inst, nt::GetEntryInfo(entry));
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getEntryInfo
+ * Signature: (Ljava/lang/Object;ILjava/lang/String;I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getEntryInfo
+  (JNIEnv* env, jclass, jobject instObject, jint inst, jstring prefix,
+   jint types)
+{
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return nullptr;
+  }
+  auto arr = nt::GetEntryInfo(inst, JStringRef{env, prefix}.str(), types);
+  jobjectArray jarr = env->NewObjectArray(arr.size(), entryInfoCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> jelem{env, MakeJObject(env, instObject, arr[i])};
+    env->SetObjectArrayElement(jarr, i, jelem);
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    createEntryListenerPoller
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_createEntryListenerPoller
+  (JNIEnv*, jclass, jint inst)
+{
+  return nt::CreateEntryListenerPoller(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    destroyEntryListenerPoller
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyEntryListenerPoller
+  (JNIEnv*, jclass, jint poller)
+{
+  nt::DestroyEntryListenerPoller(poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    addPolledEntryListener
+ * Signature: (ILjava/lang/String;I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_addPolledEntryListener__ILjava_lang_String_2I
+  (JNIEnv* env, jclass, jint poller, jstring prefix, jint flags)
+{
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return 0;
+  }
+  return nt::AddPolledEntryListener(poller, JStringRef{env, prefix}.str(),
+                                    flags);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    addPolledEntryListener
+ * Signature: (III)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_addPolledEntryListener__III
+  (JNIEnv* env, jclass, jint poller, jint entry, jint flags)
+{
+  return nt::AddPolledEntryListener(poller, entry, flags);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    pollEntryListener
+ * Signature: (Ljava/lang/Object;I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_pollEntryListener
+  (JNIEnv* env, jclass, jobject inst, jint poller)
+{
+  auto events = nt::PollEntryListener(poller);
+  if (events.empty()) {
+    interruptedEx.Throw(env, "PollEntryListener interrupted");
+    return nullptr;
+  }
+  return MakeJObject(env, inst, events);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    pollEntryListenerTimeout
+ * Signature: (Ljava/lang/Object;ID)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_pollEntryListenerTimeout
+  (JNIEnv* env, jclass, jobject inst, jint poller, jdouble timeout)
+{
+  bool timed_out = false;
+  auto events = nt::PollEntryListener(poller, timeout, &timed_out);
+  if (events.empty() && !timed_out) {
+    interruptedEx.Throw(env, "PollEntryListener interrupted");
+    return nullptr;
+  }
+  return MakeJObject(env, inst, events);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    cancelPollEntryListener
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelPollEntryListener
+  (JNIEnv*, jclass, jint poller)
+{
+  nt::CancelPollEntryListener(poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    removeEntryListener
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_removeEntryListener
+  (JNIEnv*, jclass, jint entryListenerUid)
+{
+  nt::RemoveEntryListener(entryListenerUid);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    waitForEntryListenerQueue
+ * Signature: (ID)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_waitForEntryListenerQueue
+  (JNIEnv*, jclass, jint inst, jdouble timeout)
+{
+  return nt::WaitForEntryListenerQueue(inst, timeout);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    createConnectionListenerPoller
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_createConnectionListenerPoller
+  (JNIEnv*, jclass, jint inst)
+{
+  return nt::CreateConnectionListenerPoller(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    destroyConnectionListenerPoller
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyConnectionListenerPoller
+  (JNIEnv*, jclass, jint poller)
+{
+  nt::DestroyConnectionListenerPoller(poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    addPolledConnectionListener
+ * Signature: (IZ)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_addPolledConnectionListener
+  (JNIEnv* env, jclass, jint poller, jboolean immediateNotify)
+{
+  return nt::AddPolledConnectionListener(poller, immediateNotify);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    pollConnectionListener
+ * Signature: (Ljava/lang/Object;I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_pollConnectionListener
+  (JNIEnv* env, jclass, jobject inst, jint poller)
+{
+  auto events = nt::PollConnectionListener(poller);
+  if (events.empty()) {
+    interruptedEx.Throw(env, "PollConnectionListener interrupted");
+    return nullptr;
+  }
+  return MakeJObject(env, inst, events);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    pollConnectionListenerTimeout
+ * Signature: (Ljava/lang/Object;ID)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_pollConnectionListenerTimeout
+  (JNIEnv* env, jclass, jobject inst, jint poller, jdouble timeout)
+{
+  bool timed_out = false;
+  auto events = nt::PollConnectionListener(poller, timeout, &timed_out);
+  if (events.empty() && !timed_out) {
+    interruptedEx.Throw(env, "PollConnectionListener interrupted");
+    return nullptr;
+  }
+  return MakeJObject(env, inst, events);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    cancelPollConnectionListener
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelPollConnectionListener
+  (JNIEnv*, jclass, jint poller)
+{
+  nt::CancelPollConnectionListener(poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    removeConnectionListener
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_removeConnectionListener
+  (JNIEnv*, jclass, jint connListenerUid)
+{
+  nt::RemoveConnectionListener(connListenerUid);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    waitForConnectionListenerQueue
+ * Signature: (ID)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_waitForConnectionListenerQueue
+  (JNIEnv*, jclass, jint inst, jdouble timeout)
+{
+  return nt::WaitForConnectionListenerQueue(inst, timeout);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    createRpcCallPoller
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_createRpcCallPoller
+  (JNIEnv*, jclass, jint inst)
+{
+  return nt::CreateRpcCallPoller(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    destroyRpcCallPoller
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyRpcCallPoller
+  (JNIEnv*, jclass, jint poller)
+{
+  nt::DestroyRpcCallPoller(poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    createPolledRpc
+ * Signature: (I[BI)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_createPolledRpc
+  (JNIEnv* env, jclass, jint entry, jbyteArray def, jint poller)
+{
+  if (!def) {
+    nullPointerEx.Throw(env, "def cannot be null");
+    return;
+  }
+  nt::CreatePolledRpc(entry, JByteArrayRef{env, def}, poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    pollRpc
+ * Signature: (Ljava/lang/Object;I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_pollRpc
+  (JNIEnv* env, jclass, jobject inst, jint poller)
+{
+  auto infos = nt::PollRpc(poller);
+  if (infos.empty()) {
+    interruptedEx.Throw(env, "PollRpc interrupted");
+    return nullptr;
+  }
+  return MakeJObject(env, inst, infos);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    pollRpcTimeout
+ * Signature: (Ljava/lang/Object;ID)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_pollRpcTimeout
+  (JNIEnv* env, jclass, jobject inst, jint poller, jdouble timeout)
+{
+  bool timed_out = false;
+  auto infos = nt::PollRpc(poller, timeout, &timed_out);
+  if (infos.empty() && !timed_out) {
+    interruptedEx.Throw(env, "PollRpc interrupted");
+    return nullptr;
+  }
+  return MakeJObject(env, inst, infos);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    cancelPollRpc
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelPollRpc
+  (JNIEnv*, jclass, jint poller)
+{
+  nt::CancelPollRpc(poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    waitForRpcCallQueue
+ * Signature: (ID)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_waitForRpcCallQueue
+  (JNIEnv*, jclass, jint inst, jdouble timeout)
+{
+  return nt::WaitForRpcCallQueue(inst, timeout);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    postRpcResponse
+ * Signature: (II[B)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_postRpcResponse
+  (JNIEnv* env, jclass, jint entry, jint call, jbyteArray result)
+{
+  if (!result) {
+    nullPointerEx.Throw(env, "result cannot be null");
+    return false;
+  }
+  return nt::PostRpcResponse(entry, call, JByteArrayRef{env, result});
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    callRpc
+ * Signature: (I[B)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_callRpc
+  (JNIEnv* env, jclass, jint entry, jbyteArray params)
+{
+  if (!params) {
+    nullPointerEx.Throw(env, "params cannot be null");
+    return 0;
+  }
+  return nt::CallRpc(entry, JByteArrayRef{env, params});
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getRpcResult
+ * Signature: (II)[B
+ */
+JNIEXPORT jbyteArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getRpcResult__II
+  (JNIEnv* env, jclass, jint entry, jint call)
+{
+  std::string result;
+  if (!nt::GetRpcResult(entry, call, &result)) return nullptr;
+  return MakeJByteArray(env, result);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getRpcResult
+ * Signature: (IID)[B
+ */
+JNIEXPORT jbyteArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getRpcResult__IID
+  (JNIEnv* env, jclass, jint entry, jint call, jdouble timeout)
+{
+  std::string result;
+  bool timed_out = false;
+  if (!nt::GetRpcResult(entry, call, &result, timeout, &timed_out))
+    return nullptr;
+  return MakeJByteArray(env, result);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    cancelRpcResult
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelRpcResult
+  (JNIEnv*, jclass, jint entry, jint call)
+{
+  nt::CancelRpcResult(entry, call);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getRpc
+ * Signature: (I[B)[B
+ */
+JNIEXPORT jbyteArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getRpc
+  (JNIEnv* env, jclass, jint entry, jbyteArray defaultValue)
+{
+  auto val = nt::GetEntryValue(entry);
+  if (!val || !val->IsRpc()) return defaultValue;
+  return MakeJByteArray(env, val->GetRpc());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setNetworkIdentity
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setNetworkIdentity
+  (JNIEnv* env, jclass, jint inst, jstring name)
+{
+  if (!name) {
+    nullPointerEx.Throw(env, "name cannot be null");
+    return;
+  }
+  nt::SetNetworkIdentity(inst, JStringRef{env, name}.str());
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getNetworkMode
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getNetworkMode
+  (JNIEnv*, jclass, jint inst)
+{
+  return nt::GetNetworkMode(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    startServer
+ * Signature: (ILjava/lang/String;Ljava/lang/String;I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startServer
+  (JNIEnv* env, jclass, jint inst, jstring persistFilename,
+   jstring listenAddress, jint port)
+{
+  if (!persistFilename) {
+    nullPointerEx.Throw(env, "persistFilename cannot be null");
+    return;
+  }
+  if (!listenAddress) {
+    nullPointerEx.Throw(env, "listenAddress cannot be null");
+    return;
+  }
+  nt::StartServer(inst, JStringRef{env, persistFilename}.str(),
+                  JStringRef{env, listenAddress}.c_str(), port);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    stopServer
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_stopServer
+  (JNIEnv*, jclass, jint inst)
+{
+  nt::StopServer(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    startClient
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startClient__I
+  (JNIEnv*, jclass, jint inst)
+{
+  nt::StartClient(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    startClient
+ * Signature: (ILjava/lang/String;I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startClient__ILjava_lang_String_2I
+  (JNIEnv* env, jclass, jint inst, jstring serverName, jint port)
+{
+  if (!serverName) {
+    nullPointerEx.Throw(env, "serverName cannot be null");
+    return;
+  }
+  nt::StartClient(inst, JStringRef{env, serverName}.c_str(), port);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    startClient
+ * Signature: (I[Ljava/lang/Object;[I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startClient__I_3Ljava_lang_String_2_3I
+  (JNIEnv* env, jclass, jint inst, jobjectArray serverNames, jintArray ports)
+{
+  if (!serverNames) {
+    nullPointerEx.Throw(env, "serverNames cannot be null");
+    return;
+  }
+  if (!ports) {
+    nullPointerEx.Throw(env, "ports cannot be null");
+    return;
+  }
+  int len = env->GetArrayLength(serverNames);
+  if (len != env->GetArrayLength(ports)) {
+    illegalArgEx.Throw(env,
+                       "serverNames and ports arrays must be the same size");
+    return;
+  }
+  jint* portInts = env->GetIntArrayElements(ports, nullptr);
+  if (!portInts) return;
+
+  std::vector<std::string> names;
+  std::vector<std::pair<nt::StringRef, unsigned int>> servers;
+  names.reserve(len);
+  servers.reserve(len);
+  for (int i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(serverNames, i))};
+    if (!elem) {
+      nullPointerEx.Throw(env, "null string in serverNames");
+      return;
+    }
+    names.emplace_back(JStringRef{env, elem}.str());
+    servers.emplace_back(
+        std::make_pair(nt::StringRef(names.back()), portInts[i]));
+  }
+  env->ReleaseIntArrayElements(ports, portInts, JNI_ABORT);
+  nt::StartClient(inst, servers);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    startClientTeam
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startClientTeam
+  (JNIEnv* env, jclass cls, jint inst, jint team, jint port)
+{
+  nt::StartClientTeam(inst, team, port);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    stopClient
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_stopClient
+  (JNIEnv*, jclass, jint inst)
+{
+  nt::StopClient(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setServer
+ * Signature: (ILjava/lang/String;I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setServer__ILjava_lang_String_2I
+  (JNIEnv* env, jclass, jint inst, jstring serverName, jint port)
+{
+  if (!serverName) {
+    nullPointerEx.Throw(env, "serverName cannot be null");
+    return;
+  }
+  nt::SetServer(inst, JStringRef{env, serverName}.c_str(), port);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setServer
+ * Signature: (I[Ljava/lang/Object;[I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setServer__I_3Ljava_lang_String_2_3I
+  (JNIEnv* env, jclass, jint inst, jobjectArray serverNames, jintArray ports)
+{
+  if (!serverNames) {
+    nullPointerEx.Throw(env, "serverNames cannot be null");
+    return;
+  }
+  if (!ports) {
+    nullPointerEx.Throw(env, "ports cannot be null");
+    return;
+  }
+  int len = env->GetArrayLength(serverNames);
+  if (len != env->GetArrayLength(ports)) {
+    illegalArgEx.Throw(env,
+                       "serverNames and ports arrays must be the same size");
+    return;
+  }
+  jint* portInts = env->GetIntArrayElements(ports, nullptr);
+  if (!portInts) return;
+
+  std::vector<std::string> names;
+  std::vector<std::pair<nt::StringRef, unsigned int>> servers;
+  names.reserve(len);
+  servers.reserve(len);
+  for (int i = 0; i < len; ++i) {
+    JLocal<jstring> elem{
+        env, static_cast<jstring>(env->GetObjectArrayElement(serverNames, i))};
+    if (!elem) {
+      nullPointerEx.Throw(env, "null string in serverNames");
+      return;
+    }
+    names.emplace_back(JStringRef{env, elem}.str());
+    servers.emplace_back(
+        std::make_pair(nt::StringRef(names.back()), portInts[i]));
+  }
+  env->ReleaseIntArrayElements(ports, portInts, JNI_ABORT);
+  nt::SetServer(inst, servers);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setServerTeam
+ * Signature: (III)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setServerTeam
+  (JNIEnv* env, jclass, jint inst, jint team, jint port)
+{
+  nt::SetServerTeam(inst, team, port);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    startDSClient
+ * Signature: (II)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_startDSClient
+  (JNIEnv*, jclass, jint inst, jint port)
+{
+  nt::StartDSClient(inst, port);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    stopDSClient
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_stopDSClient
+  (JNIEnv*, jclass, jint inst)
+{
+  nt::StopDSClient(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    setUpdateRate
+ * Signature: (ID)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_setUpdateRate
+  (JNIEnv*, jclass, jint inst, jdouble interval)
+{
+  nt::SetUpdateRate(inst, interval);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    flush
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_flush
+  (JNIEnv*, jclass, jint inst)
+{
+  nt::Flush(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    getConnections
+ * Signature: (I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_getConnections
+  (JNIEnv* env, jclass, jint inst)
+{
+  auto arr = nt::GetConnections(inst);
+  jobjectArray jarr =
+      env->NewObjectArray(arr.size(), connectionInfoCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jobject> jelem{env, MakeJObject(env, arr[i])};
+    env->SetObjectArrayElement(jarr, i, jelem);
+  }
+  return jarr;
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    isConnected
+ * Signature: (I)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_isConnected
+  (JNIEnv*, jclass, jint inst)
+{
+  return nt::IsConnected(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    savePersistent
+ * Signature: (ILjava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_savePersistent
+  (JNIEnv* env, jclass, jint inst, jstring filename)
+{
+  if (!filename) {
+    nullPointerEx.Throw(env, "filename cannot be null");
+    return;
+  }
+  const char* err = nt::SavePersistent(inst, JStringRef{env, filename}.str());
+  if (err) persistentEx.Throw(env, err);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    loadPersistent
+ * Signature: (ILjava/lang/String;)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_loadPersistent
+  (JNIEnv* env, jclass, jint inst, jstring filename)
+{
+  if (!filename) {
+    nullPointerEx.Throw(env, "filename cannot be null");
+    return nullptr;
+  }
+  std::vector<std::string> warns;
+  const char* err = nt::LoadPersistent(inst, JStringRef{env, filename}.str(),
+                                       [&](size_t line, const char* msg) {
+                                         wpi::SmallString<128> warn;
+                                         wpi::raw_svector_ostream oss(warn);
+                                         oss << line << ": " << msg;
+                                         warns.emplace_back(oss.str());
+                                       });
+  if (err) {
+    persistentEx.Throw(env, err);
+    return nullptr;
+  }
+  return MakeJStringArray(env, warns);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    saveEntries
+ * Signature: (ILjava/lang/String;Ljava/lang/String;)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_saveEntries
+  (JNIEnv* env, jclass, jint inst, jstring filename, jstring prefix)
+{
+  if (!filename) {
+    nullPointerEx.Throw(env, "filename cannot be null");
+    return;
+  }
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return;
+  }
+  const char* err = nt::SaveEntries(inst, JStringRef{env, filename}.str(),
+                                    JStringRef{env, prefix}.str());
+  if (err) persistentEx.Throw(env, err);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    loadEntries
+ * Signature: (ILjava/lang/String;Ljava/lang/String;)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_loadEntries
+  (JNIEnv* env, jclass, jint inst, jstring filename, jstring prefix)
+{
+  if (!filename) {
+    nullPointerEx.Throw(env, "filename cannot be null");
+    return nullptr;
+  }
+  if (!prefix) {
+    nullPointerEx.Throw(env, "prefix cannot be null");
+    return nullptr;
+  }
+  std::vector<std::string> warns;
+  const char* err = nt::LoadEntries(inst, JStringRef{env, filename}.str(),
+                                    JStringRef{env, prefix}.str(),
+                                    [&](size_t line, const char* msg) {
+                                      wpi::SmallString<128> warn;
+                                      wpi::raw_svector_ostream oss(warn);
+                                      oss << line << ": " << msg;
+                                      warns.emplace_back(oss.str());
+                                    });
+  if (err) {
+    persistentEx.Throw(env, err);
+    return nullptr;
+  }
+  return MakeJStringArray(env, warns);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    now
+ * Signature: ()J
+ */
+JNIEXPORT jlong JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_now
+  (JNIEnv*, jclass)
+{
+  return nt::Now();
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    createLoggerPoller
+ * Signature: (I)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_createLoggerPoller
+  (JNIEnv*, jclass, jint inst)
+{
+  return nt::CreateLoggerPoller(inst);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    destroyLoggerPoller
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_destroyLoggerPoller
+  (JNIEnv*, jclass, jint poller)
+{
+  nt::DestroyLoggerPoller(poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    addPolledLogger
+ * Signature: (III)I
+ */
+JNIEXPORT jint JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_addPolledLogger
+  (JNIEnv*, jclass, jint poller, jint minLevel, jint maxLevel)
+{
+  return nt::AddPolledLogger(poller, minLevel, maxLevel);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    pollLogger
+ * Signature: (Ljava/lang/Object;I)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_pollLogger
+  (JNIEnv* env, jclass, jobject inst, jint poller)
+{
+  auto events = nt::PollLogger(poller);
+  if (events.empty()) {
+    interruptedEx.Throw(env, "PollLogger interrupted");
+    return nullptr;
+  }
+  return MakeJObject(env, inst, events);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    pollLoggerTimeout
+ * Signature: (Ljava/lang/Object;ID)[Ljava/lang/Object;
+ */
+JNIEXPORT jobjectArray JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_pollLoggerTimeout
+  (JNIEnv* env, jclass, jobject inst, jint poller, jdouble timeout)
+{
+  bool timed_out = false;
+  auto events = nt::PollLogger(poller, timeout, &timed_out);
+  if (events.empty() && !timed_out) {
+    interruptedEx.Throw(env, "PollLogger interrupted");
+    return nullptr;
+  }
+  return MakeJObject(env, inst, events);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    cancelPollLogger
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_cancelPollLogger
+  (JNIEnv*, jclass, jint poller)
+{
+  nt::CancelPollLogger(poller);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    removeLogger
+ * Signature: (I)V
+ */
+JNIEXPORT void JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_removeLogger
+  (JNIEnv*, jclass, jint logger)
+{
+  nt::RemoveLogger(logger);
+}
+
+/*
+ * Class:     edu_wpi_first_networktables_NetworkTablesJNI
+ * Method:    waitForLoggerQueue
+ * Signature: (ID)Z
+ */
+JNIEXPORT jboolean JNICALL
+Java_edu_wpi_first_networktables_NetworkTablesJNI_waitForLoggerQueue
+  (JNIEnv*, jclass, jint inst, jdouble timeout)
+{
+  return nt::WaitForLoggerQueue(inst, timeout);
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp
new file mode 100644
index 0000000..1ec0942
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp
@@ -0,0 +1,562 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "networktables/NetworkTable.h"
+
+#include <algorithm>
+
+#include <wpi/SmallString.h>
+#include <wpi/StringMap.h>
+#include <wpi/raw_ostream.h>
+
+#include "networktables/NetworkTableInstance.h"
+#include "ntcore.h"
+#include "tables/ITableListener.h"
+
+using namespace nt;
+
+#ifdef __GNUC__
+#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
+#endif
+
+const char NetworkTable::PATH_SEPARATOR_CHAR = '/';
+std::string NetworkTable::s_persistent_filename = "networktables.ini";
+bool NetworkTable::s_client = false;
+bool NetworkTable::s_enable_ds = true;
+bool NetworkTable::s_running = false;
+unsigned int NetworkTable::s_port = NT_DEFAULT_PORT;
+
+StringRef NetworkTable::BasenameKey(StringRef key) {
+  size_t slash = key.rfind(PATH_SEPARATOR_CHAR);
+  if (slash == StringRef::npos) return key;
+  return key.substr(slash + 1);
+}
+
+std::string NetworkTable::NormalizeKey(const Twine& key,
+                                       bool withLeadingSlash) {
+  wpi::SmallString<128> buf;
+  return NormalizeKey(key, buf, withLeadingSlash);
+}
+
+StringRef NetworkTable::NormalizeKey(const Twine& key,
+                                     wpi::SmallVectorImpl<char>& buf,
+                                     bool withLeadingSlash) {
+  buf.clear();
+  if (withLeadingSlash) buf.push_back(PATH_SEPARATOR_CHAR);
+  // for each path element, add it with a slash following
+  wpi::SmallString<128> keyBuf;
+  StringRef keyStr = key.toStringRef(keyBuf);
+  wpi::SmallVector<StringRef, 16> parts;
+  keyStr.split(parts, PATH_SEPARATOR_CHAR, -1, false);
+  for (auto i = parts.begin(); i != parts.end(); ++i) {
+    buf.append(i->begin(), i->end());
+    buf.push_back(PATH_SEPARATOR_CHAR);
+  }
+  // remove trailing slash if the input key didn't have one
+  if (!keyStr.empty() && keyStr.back() != PATH_SEPARATOR_CHAR) buf.pop_back();
+  return StringRef(buf.data(), buf.size());
+}
+
+std::vector<std::string> NetworkTable::GetHierarchy(const Twine& key) {
+  std::vector<std::string> hierarchy;
+  hierarchy.emplace_back(1, PATH_SEPARATOR_CHAR);
+  // for each path element, add it to the end of what we built previously
+  wpi::SmallString<128> keyBuf;
+  StringRef keyStr = key.toStringRef(keyBuf);
+  wpi::SmallString<128> path;
+  wpi::SmallVector<StringRef, 16> parts;
+  keyStr.split(parts, PATH_SEPARATOR_CHAR, -1, false);
+  if (!parts.empty()) {
+    for (auto i = parts.begin(); i != parts.end(); ++i) {
+      path += PATH_SEPARATOR_CHAR;
+      path += *i;
+      hierarchy.emplace_back(path.str());
+    }
+    // handle trailing slash
+    if (keyStr.back() == PATH_SEPARATOR_CHAR) {
+      path += PATH_SEPARATOR_CHAR;
+      hierarchy.emplace_back(path.str());
+    }
+  }
+  return hierarchy;
+}
+
+void NetworkTable::Initialize() {
+  if (s_running) Shutdown();
+  auto inst = NetworkTableInstance::GetDefault();
+  if (s_client) {
+    inst.StartClient();
+    if (s_enable_ds) inst.StartDSClient(s_port);
+  } else {
+    inst.StartServer(s_persistent_filename, "", s_port);
+  }
+  s_running = true;
+}
+
+void NetworkTable::Shutdown() {
+  if (!s_running) return;
+  auto inst = NetworkTableInstance::GetDefault();
+  if (s_client) {
+    inst.StopDSClient();
+    inst.StopClient();
+  } else {
+    inst.StopServer();
+  }
+  s_running = false;
+}
+
+void NetworkTable::SetClientMode() { s_client = true; }
+
+void NetworkTable::SetServerMode() { s_client = false; }
+
+void NetworkTable::SetTeam(int team) {
+  auto inst = NetworkTableInstance::GetDefault();
+  inst.SetServerTeam(team, s_port);
+  if (s_enable_ds) inst.StartDSClient(s_port);
+}
+
+void NetworkTable::SetIPAddress(StringRef address) {
+  auto inst = NetworkTableInstance::GetDefault();
+  wpi::SmallString<32> addr_copy{address};
+  inst.SetServer(addr_copy.c_str(), s_port);
+
+  // Stop the DS client if we're explicitly connecting to localhost
+  if (address == "localhost" || address == "127.0.0.1")
+    inst.StopDSClient();
+  else if (s_enable_ds)
+    inst.StartDSClient(s_port);
+}
+
+void NetworkTable::SetIPAddress(ArrayRef<std::string> addresses) {
+  auto inst = NetworkTableInstance::GetDefault();
+  wpi::SmallVector<StringRef, 8> servers;
+  for (const auto& ip_address : addresses) servers.emplace_back(ip_address);
+  inst.SetServer(servers, s_port);
+
+  // Stop the DS client if we're explicitly connecting to localhost
+  if (!addresses.empty() &&
+      (addresses[0] == "localhost" || addresses[0] == "127.0.0.1"))
+    inst.StopDSClient();
+  else if (s_enable_ds)
+    inst.StartDSClient(s_port);
+}
+
+void NetworkTable::SetPort(unsigned int port) { s_port = port; }
+
+void NetworkTable::SetDSClientEnabled(bool enabled) {
+  auto inst = NetworkTableInstance::GetDefault();
+  s_enable_ds = enabled;
+  if (s_enable_ds)
+    inst.StartDSClient(s_port);
+  else
+    inst.StopDSClient();
+}
+
+void NetworkTable::SetPersistentFilename(StringRef filename) {
+  s_persistent_filename = filename;
+}
+
+void NetworkTable::SetNetworkIdentity(StringRef name) {
+  NetworkTableInstance::GetDefault().SetNetworkIdentity(name);
+}
+
+void NetworkTable::GlobalDeleteAll() {
+  NetworkTableInstance::GetDefault().DeleteAllEntries();
+}
+
+void NetworkTable::Flush() { NetworkTableInstance::GetDefault().Flush(); }
+
+void NetworkTable::SetUpdateRate(double interval) {
+  NetworkTableInstance::GetDefault().SetUpdateRate(interval);
+}
+
+const char* NetworkTable::SavePersistent(StringRef filename) {
+  return NetworkTableInstance::GetDefault().SavePersistent(filename);
+}
+
+const char* NetworkTable::LoadPersistent(
+    StringRef filename,
+    std::function<void(size_t line, const char* msg)> warn) {
+  return NetworkTableInstance::GetDefault().LoadPersistent(filename, warn);
+}
+
+std::shared_ptr<NetworkTable> NetworkTable::GetTable(StringRef key) {
+  if (!s_running) Initialize();
+  return NetworkTableInstance::GetDefault().GetTable(key);
+}
+
+NetworkTable::NetworkTable(NT_Inst inst, const Twine& path, const private_init&)
+    : m_inst(inst), m_path(path.str()) {}
+
+NetworkTable::~NetworkTable() {
+  for (auto& i : m_listeners) RemoveEntryListener(i.second);
+  for (auto i : m_lambdaListeners) RemoveEntryListener(i);
+}
+
+NetworkTableInstance NetworkTable::GetInstance() const {
+  return NetworkTableInstance{m_inst};
+}
+
+NetworkTableEntry NetworkTable::GetEntry(const Twine& key) const {
+  wpi::SmallString<128> keyBuf;
+  StringRef keyStr = key.toStringRef(keyBuf);
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  NT_Entry& entry = m_entries[keyStr];
+  if (entry == 0) {
+    entry = nt::GetEntry(m_inst, m_path + Twine(PATH_SEPARATOR_CHAR) + keyStr);
+  }
+  return NetworkTableEntry{entry};
+}
+
+NT_EntryListener NetworkTable::AddEntryListener(TableEntryListener listener,
+                                                unsigned int flags) const {
+  size_t prefix_len = m_path.size() + 1;
+  return nt::AddEntryListener(
+      m_inst, m_path + Twine(PATH_SEPARATOR_CHAR),
+      [=](const EntryNotification& event) {
+        StringRef relative_key = event.name.substr(prefix_len);
+        if (relative_key.find(PATH_SEPARATOR_CHAR) != StringRef::npos) return;
+        listener(const_cast<NetworkTable*>(this), relative_key,
+                 NetworkTableEntry{event.entry}, event.value, event.flags);
+      },
+      flags);
+}
+
+NT_EntryListener NetworkTable::AddEntryListener(const Twine& key,
+                                                TableEntryListener listener,
+                                                unsigned int flags) const {
+  size_t prefix_len = m_path.size() + 1;
+  auto entry = GetEntry(key);
+  return nt::AddEntryListener(entry.GetHandle(),
+                              [=](const EntryNotification& event) {
+                                listener(const_cast<NetworkTable*>(this),
+                                         event.name.substr(prefix_len), entry,
+                                         event.value, event.flags);
+                              },
+                              flags);
+}
+
+void NetworkTable::RemoveEntryListener(NT_EntryListener listener) const {
+  nt::RemoveEntryListener(listener);
+}
+
+void NetworkTable::AddTableListener(ITableListener* listener) {
+  AddTableListenerEx(listener, NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+}
+
+void NetworkTable::AddTableListener(ITableListener* listener,
+                                    bool immediateNotify) {
+  unsigned int flags = NT_NOTIFY_NEW | NT_NOTIFY_UPDATE;
+  if (immediateNotify) flags |= NT_NOTIFY_IMMEDIATE;
+  AddTableListenerEx(listener, flags);
+}
+
+void NetworkTable::AddTableListenerEx(ITableListener* listener,
+                                      unsigned int flags) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  wpi::SmallString<128> path(m_path);
+  path += PATH_SEPARATOR_CHAR;
+  size_t prefix_len = path.size();
+  NT_EntryListener id = nt::AddEntryListener(
+      m_inst, path,
+      [=](const EntryNotification& event) {
+        StringRef relative_key = event.name.substr(prefix_len);
+        if (relative_key.find(PATH_SEPARATOR_CHAR) != StringRef::npos) return;
+        listener->ValueChangedEx(this, relative_key, event.value, event.flags);
+      },
+      flags);
+  m_listeners.emplace_back(listener, id);
+}
+
+void NetworkTable::AddTableListener(StringRef key, ITableListener* listener,
+                                    bool immediateNotify) {
+  unsigned int flags = NT_NOTIFY_NEW | NT_NOTIFY_UPDATE;
+  if (immediateNotify) flags |= NT_NOTIFY_IMMEDIATE;
+  AddTableListenerEx(key, listener, flags);
+}
+
+void NetworkTable::AddTableListenerEx(StringRef key, ITableListener* listener,
+                                      unsigned int flags) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  size_t prefix_len = m_path.size() + 1;
+  auto entry = GetEntry(key);
+  NT_EntryListener id = nt::AddEntryListener(
+      entry.GetHandle(),
+      [=](const EntryNotification& event) {
+        listener->ValueChangedEx(this, event.name.substr(prefix_len),
+                                 event.value, event.flags);
+      },
+      flags);
+  m_listeners.emplace_back(listener, id);
+}
+
+void NetworkTable::AddSubTableListener(ITableListener* listener) {
+  AddSubTableListener(listener, false);
+}
+
+NT_EntryListener NetworkTable::AddSubTableListener(TableListener listener,
+                                                   bool localNotify) {
+  size_t prefix_len = m_path.size() + 1;
+
+  // The lambda needs to be copyable, but StringMap is not, so use
+  // a shared_ptr to it.
+  auto notified_tables = std::make_shared<wpi::StringMap<char>>();
+
+  unsigned int flags = NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE;
+  if (localNotify) flags |= NT_NOTIFY_LOCAL;
+  NT_EntryListener id = nt::AddEntryListener(
+      m_inst, m_path + Twine(PATH_SEPARATOR_CHAR),
+      [=](const EntryNotification& event) {
+        StringRef relative_key = event.name.substr(prefix_len);
+        auto end_sub_table = relative_key.find(PATH_SEPARATOR_CHAR);
+        if (end_sub_table == StringRef::npos) return;
+        StringRef sub_table_key = relative_key.substr(0, end_sub_table);
+        if (notified_tables->find(sub_table_key) == notified_tables->end())
+          return;
+        notified_tables->insert(std::make_pair(sub_table_key, '\0'));
+        listener(this, sub_table_key, this->GetSubTable(sub_table_key));
+      },
+      flags);
+  m_lambdaListeners.emplace_back(id);
+  return id;
+}
+
+void NetworkTable::RemoveTableListener(NT_EntryListener listener) {
+  nt::RemoveEntryListener(listener);
+  auto matches_begin =
+      std::remove(m_lambdaListeners.begin(), m_lambdaListeners.end(), listener);
+  m_lambdaListeners.erase(matches_begin, m_lambdaListeners.end());
+}
+
+void NetworkTable::AddSubTableListener(ITableListener* listener,
+                                       bool localNotify) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  size_t prefix_len = m_path.size() + 1;
+
+  // The lambda needs to be copyable, but StringMap is not, so use
+  // a shared_ptr to it.
+  auto notified_tables = std::make_shared<wpi::StringMap<char>>();
+
+  unsigned int flags = NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE;
+  if (localNotify) flags |= NT_NOTIFY_LOCAL;
+  NT_EntryListener id = nt::AddEntryListener(
+      m_inst, m_path + Twine(PATH_SEPARATOR_CHAR),
+      [=](const EntryNotification& event) {
+        StringRef relative_key = event.name.substr(prefix_len);
+        auto end_sub_table = relative_key.find(PATH_SEPARATOR_CHAR);
+        if (end_sub_table == StringRef::npos) return;
+        StringRef sub_table_key = relative_key.substr(0, end_sub_table);
+        if (notified_tables->find(sub_table_key) == notified_tables->end())
+          return;
+        notified_tables->insert(std::make_pair(sub_table_key, '\0'));
+        listener->ValueChangedEx(this, sub_table_key, nullptr, event.flags);
+      },
+      flags);
+  m_listeners.emplace_back(listener, id);
+}
+
+void NetworkTable::RemoveTableListener(ITableListener* listener) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto matches_begin =
+      std::remove_if(m_listeners.begin(), m_listeners.end(),
+                     [=](const Listener& x) { return x.first == listener; });
+
+  for (auto i = matches_begin; i != m_listeners.end(); ++i)
+    RemoveEntryListener(i->second);
+  m_listeners.erase(matches_begin, m_listeners.end());
+}
+
+std::shared_ptr<NetworkTable> NetworkTable::GetSubTable(
+    const Twine& key) const {
+  return std::make_shared<NetworkTable>(
+      m_inst, m_path + Twine(PATH_SEPARATOR_CHAR) + key, private_init{});
+}
+
+bool NetworkTable::ContainsKey(const Twine& key) const {
+  if (key.isTriviallyEmpty() ||
+      (key.isSingleStringRef() && key.getSingleStringRef().empty()))
+    return false;
+  return GetEntry(key).Exists();
+}
+
+bool NetworkTable::ContainsSubTable(const Twine& key) const {
+  return !GetEntryInfo(m_inst,
+                       m_path + Twine(PATH_SEPARATOR_CHAR) + key +
+                           Twine(PATH_SEPARATOR_CHAR),
+                       0)
+              .empty();
+}
+
+std::vector<std::string> NetworkTable::GetKeys(int types) const {
+  std::vector<std::string> keys;
+  size_t prefix_len = m_path.size() + 1;
+  auto infos = GetEntryInfo(m_inst, m_path + Twine(PATH_SEPARATOR_CHAR), types);
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  for (auto& info : infos) {
+    auto relative_key = StringRef(info.name).substr(prefix_len);
+    if (relative_key.find(PATH_SEPARATOR_CHAR) != StringRef::npos) continue;
+    keys.push_back(relative_key);
+    m_entries[relative_key] = info.entry;
+  }
+  return keys;
+}
+
+std::vector<std::string> NetworkTable::GetSubTables() const {
+  std::vector<std::string> keys;
+  size_t prefix_len = m_path.size() + 1;
+  for (auto& entry :
+       GetEntryInfo(m_inst, m_path + Twine(PATH_SEPARATOR_CHAR), 0)) {
+    auto relative_key = StringRef(entry.name).substr(prefix_len);
+    size_t end_subtable = relative_key.find(PATH_SEPARATOR_CHAR);
+    if (end_subtable == StringRef::npos) continue;
+    keys.push_back(relative_key.substr(0, end_subtable));
+  }
+  return keys;
+}
+
+void NetworkTable::SetPersistent(StringRef key) {
+  GetEntry(key).SetPersistent();
+}
+
+void NetworkTable::ClearPersistent(StringRef key) {
+  GetEntry(key).ClearPersistent();
+}
+
+bool NetworkTable::IsPersistent(StringRef key) const {
+  return GetEntry(key).IsPersistent();
+}
+
+void NetworkTable::SetFlags(StringRef key, unsigned int flags) {
+  GetEntry(key).SetFlags(flags);
+}
+
+void NetworkTable::ClearFlags(StringRef key, unsigned int flags) {
+  GetEntry(key).ClearFlags(flags);
+}
+
+unsigned int NetworkTable::GetFlags(StringRef key) const {
+  return GetEntry(key).GetFlags();
+}
+
+void NetworkTable::Delete(const Twine& key) { GetEntry(key).Delete(); }
+
+bool NetworkTable::PutNumber(StringRef key, double value) {
+  return GetEntry(key).SetDouble(value);
+}
+
+bool NetworkTable::SetDefaultNumber(StringRef key, double defaultValue) {
+  return GetEntry(key).SetDefaultDouble(defaultValue);
+}
+
+double NetworkTable::GetNumber(StringRef key, double defaultValue) const {
+  return GetEntry(key).GetDouble(defaultValue);
+}
+
+bool NetworkTable::PutString(StringRef key, StringRef value) {
+  return GetEntry(key).SetString(value);
+}
+
+bool NetworkTable::SetDefaultString(StringRef key, StringRef defaultValue) {
+  return GetEntry(key).SetDefaultString(defaultValue);
+}
+
+std::string NetworkTable::GetString(StringRef key,
+                                    StringRef defaultValue) const {
+  return GetEntry(key).GetString(defaultValue);
+}
+
+bool NetworkTable::PutBoolean(StringRef key, bool value) {
+  return GetEntry(key).SetBoolean(value);
+}
+
+bool NetworkTable::SetDefaultBoolean(StringRef key, bool defaultValue) {
+  return GetEntry(key).SetDefaultBoolean(defaultValue);
+}
+
+bool NetworkTable::GetBoolean(StringRef key, bool defaultValue) const {
+  return GetEntry(key).GetBoolean(defaultValue);
+}
+
+bool NetworkTable::PutBooleanArray(StringRef key, ArrayRef<int> value) {
+  return GetEntry(key).SetBooleanArray(value);
+}
+
+bool NetworkTable::SetDefaultBooleanArray(StringRef key,
+                                          ArrayRef<int> defaultValue) {
+  return GetEntry(key).SetDefaultBooleanArray(defaultValue);
+}
+
+std::vector<int> NetworkTable::GetBooleanArray(
+    StringRef key, ArrayRef<int> defaultValue) const {
+  return GetEntry(key).GetBooleanArray(defaultValue);
+}
+
+bool NetworkTable::PutNumberArray(StringRef key, ArrayRef<double> value) {
+  return GetEntry(key).SetDoubleArray(value);
+}
+
+bool NetworkTable::SetDefaultNumberArray(StringRef key,
+                                         ArrayRef<double> defaultValue) {
+  return GetEntry(key).SetDefaultDoubleArray(defaultValue);
+}
+
+std::vector<double> NetworkTable::GetNumberArray(
+    StringRef key, ArrayRef<double> defaultValue) const {
+  return GetEntry(key).GetDoubleArray(defaultValue);
+}
+
+bool NetworkTable::PutStringArray(StringRef key, ArrayRef<std::string> value) {
+  return GetEntry(key).SetStringArray(value);
+}
+
+bool NetworkTable::SetDefaultStringArray(StringRef key,
+                                         ArrayRef<std::string> defaultValue) {
+  return GetEntry(key).SetDefaultStringArray(defaultValue);
+}
+
+std::vector<std::string> NetworkTable::GetStringArray(
+    StringRef key, ArrayRef<std::string> defaultValue) const {
+  return GetEntry(key).GetStringArray(defaultValue);
+}
+
+bool NetworkTable::PutRaw(StringRef key, StringRef value) {
+  return GetEntry(key).SetRaw(value);
+}
+
+bool NetworkTable::SetDefaultRaw(StringRef key, StringRef defaultValue) {
+  return GetEntry(key).SetDefaultRaw(defaultValue);
+}
+
+std::string NetworkTable::GetRaw(StringRef key, StringRef defaultValue) const {
+  return GetEntry(key).GetRaw(defaultValue);
+}
+
+bool NetworkTable::PutValue(const Twine& key, std::shared_ptr<Value> value) {
+  return GetEntry(key).SetValue(value);
+}
+
+bool NetworkTable::SetDefaultValue(const Twine& key,
+                                   std::shared_ptr<Value> defaultValue) {
+  return GetEntry(key).SetDefaultValue(defaultValue);
+}
+
+std::shared_ptr<Value> NetworkTable::GetValue(const Twine& key) const {
+  return GetEntry(key).GetValue();
+}
+
+StringRef NetworkTable::GetPath() const { return m_path; }
+
+const char* NetworkTable::SaveEntries(const Twine& filename) const {
+  return nt::SaveEntries(m_inst, filename, m_path + Twine(PATH_SEPARATOR_CHAR));
+}
+
+const char* NetworkTable::LoadEntries(
+    const Twine& filename,
+    std::function<void(size_t line, const char* msg)> warn) {
+  return nt::LoadEntries(m_inst, filename, m_path + Twine(PATH_SEPARATOR_CHAR),
+                         warn);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp
new file mode 100644
index 0000000..5507ac0
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "networktables/NetworkTableEntry.h"
+
+#include "networktables/NetworkTableInstance.h"
+
+using namespace nt;
+
+NetworkTableInstance NetworkTableEntry::GetInstance() const {
+  return NetworkTableInstance{GetInstanceFromHandle(m_handle)};
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp
new file mode 100644
index 0000000..018572e
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "networktables/NetworkTableInstance.h"
+
+#include <wpi/SmallString.h>
+
+using namespace nt;
+
+std::shared_ptr<NetworkTable> NetworkTableInstance::GetTable(
+    const Twine& key) const {
+  StringRef simple;
+  bool isSimple = key.isSingleStringRef();
+  if (isSimple) simple = key.getSingleStringRef();
+  if (isSimple && (simple.empty() || simple == "/")) {
+    return std::make_shared<NetworkTable>(m_handle, "",
+                                          NetworkTable::private_init{});
+  } else if (isSimple && simple[0] == NetworkTable::PATH_SEPARATOR_CHAR) {
+    return std::make_shared<NetworkTable>(m_handle, key,
+                                          NetworkTable::private_init{});
+  } else {
+    return std::make_shared<NetworkTable>(
+        m_handle, Twine(NetworkTable::PATH_SEPARATOR_CHAR) + key,
+        NetworkTable::private_init{});
+  }
+}
+
+void NetworkTableInstance::StartClient(ArrayRef<StringRef> servers,
+                                       unsigned int port) {
+  wpi::SmallVector<std::pair<StringRef, unsigned int>, 8> server_ports;
+  for (const auto& server : servers)
+    server_ports.emplace_back(std::make_pair(server, port));
+  StartClient(server_ports);
+}
+
+void NetworkTableInstance::SetServer(ArrayRef<StringRef> servers,
+                                     unsigned int port) {
+  wpi::SmallVector<std::pair<StringRef, unsigned int>, 8> server_ports;
+  for (const auto& server : servers)
+    server_ports.emplace_back(std::make_pair(server, port));
+  SetServer(server_ports);
+}
+
+NT_EntryListener NetworkTableInstance::AddEntryListener(
+    const Twine& prefix,
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int flags) const {
+  return ::nt::AddEntryListener(m_handle, prefix, callback, flags);
+}
+
+NT_ConnectionListener NetworkTableInstance::AddConnectionListener(
+    std::function<void(const ConnectionNotification& event)> callback,
+    bool immediate_notify) const {
+  return ::nt::AddConnectionListener(m_handle, callback, immediate_notify);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/RpcCall.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/RpcCall.cpp
new file mode 100644
index 0000000..1149681
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/networktables/RpcCall.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "networktables/RpcCall.h"
+
+#include "networktables/NetworkTableEntry.h"
+
+using namespace nt;
+
+NetworkTableEntry RpcCall::GetEntry() const {
+  return NetworkTableEntry{m_entry};
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_c.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_c.cpp
new file mode 100644
index 0000000..6c71e55
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_c.cpp
@@ -0,0 +1,1136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <stdint.h>
+
+#include <cassert>
+#include <cstdlib>
+
+#include <wpi/memory.h>
+#include <wpi/timestamp.h>
+
+#include "Value_internal.h"
+#include "ntcore.h"
+
+using namespace nt;
+
+// Conversion helpers
+
+static void ConvertToC(wpi::StringRef in, char** out) {
+  *out = static_cast<char*>(wpi::CheckedMalloc(in.size() + 1));
+  std::memmove(*out, in.data(), in.size());
+  (*out)[in.size()] = '\0';
+}
+
+static void ConvertToC(const EntryInfo& in, NT_EntryInfo* out) {
+  out->entry = in.entry;
+  ConvertToC(in.name, &out->name);
+  out->type = in.type;
+  out->flags = in.flags;
+  out->last_change = in.last_change;
+}
+
+static void ConvertToC(const ConnectionInfo& in, NT_ConnectionInfo* out) {
+  ConvertToC(in.remote_id, &out->remote_id);
+  ConvertToC(in.remote_ip, &out->remote_ip);
+  out->remote_port = in.remote_port;
+  out->last_update = in.last_update;
+  out->protocol_version = in.protocol_version;
+}
+
+static void ConvertToC(const RpcParamDef& in, NT_RpcParamDef* out) {
+  ConvertToC(in.name, &out->name);
+  ConvertToC(*in.def_value, &out->def_value);
+}
+
+static void ConvertToC(const RpcResultDef& in, NT_RpcResultDef* out) {
+  ConvertToC(in.name, &out->name);
+  out->type = in.type;
+}
+
+static void ConvertToC(const RpcDefinition& in, NT_RpcDefinition* out) {
+  out->version = in.version;
+  ConvertToC(in.name, &out->name);
+
+  out->num_params = in.params.size();
+  out->params = static_cast<NT_RpcParamDef*>(
+      wpi::CheckedMalloc(in.params.size() * sizeof(NT_RpcParamDef)));
+  for (size_t i = 0; i < in.params.size(); ++i)
+    ConvertToC(in.params[i], &out->params[i]);
+
+  out->num_results = in.results.size();
+  out->results = static_cast<NT_RpcResultDef*>(
+      wpi::CheckedMalloc(in.results.size() * sizeof(NT_RpcResultDef)));
+  for (size_t i = 0; i < in.results.size(); ++i)
+    ConvertToC(in.results[i], &out->results[i]);
+}
+
+static void ConvertToC(const RpcAnswer& in, NT_RpcAnswer* out) {
+  out->entry = in.entry;
+  out->call = in.call;
+  ConvertToC(in.name, &out->name);
+  ConvertToC(in.params, &out->params);
+  ConvertToC(in.conn, &out->conn);
+}
+
+static void ConvertToC(const EntryNotification& in, NT_EntryNotification* out) {
+  out->listener = in.listener;
+  out->entry = in.entry;
+  ConvertToC(in.name, &out->name);
+  ConvertToC(*in.value, &out->value);
+  out->flags = in.flags;
+}
+
+static void ConvertToC(const ConnectionNotification& in,
+                       NT_ConnectionNotification* out) {
+  out->listener = in.listener;
+  out->connected = in.connected;
+  ConvertToC(in.conn, &out->conn);
+}
+
+static void ConvertToC(const LogMessage& in, NT_LogMessage* out) {
+  out->logger = in.logger;
+  out->level = in.level;
+  out->filename = in.filename;
+  out->line = in.line;
+  ConvertToC(in.message, &out->message);
+}
+
+template <typename O, typename I>
+static O* ConvertToC(const std::vector<I>& in, size_t* out_len) {
+  if (!out_len) return nullptr;
+  *out_len = in.size();
+  if (in.empty()) return nullptr;
+  O* out = static_cast<O*>(wpi::CheckedMalloc(sizeof(O) * in.size()));
+  for (size_t i = 0; i < in.size(); ++i) ConvertToC(in[i], &out[i]);
+  return out;
+}
+
+static void DisposeConnectionInfo(NT_ConnectionInfo* info) {
+  std::free(info->remote_id.str);
+  std::free(info->remote_ip.str);
+}
+
+static void DisposeEntryInfo(NT_EntryInfo* info) { std::free(info->name.str); }
+
+static void DisposeEntryNotification(NT_EntryNotification* info) {
+  std::free(info->name.str);
+  NT_DisposeValue(&info->value);
+}
+
+static void DisposeConnectionNotification(NT_ConnectionNotification* info) {
+  DisposeConnectionInfo(&info->conn);
+}
+
+static RpcParamDef ConvertFromC(const NT_RpcParamDef& in) {
+  RpcParamDef out;
+  out.name = ConvertFromC(in.name);
+  out.def_value = ConvertFromC(in.def_value);
+  return out;
+}
+
+static RpcResultDef ConvertFromC(const NT_RpcResultDef& in) {
+  RpcResultDef out;
+  out.name = ConvertFromC(in.name);
+  out.type = in.type;
+  return out;
+}
+
+static RpcDefinition ConvertFromC(const NT_RpcDefinition& in) {
+  RpcDefinition out;
+  out.version = in.version;
+  out.name = ConvertFromC(in.name);
+
+  out.params.reserve(in.num_params);
+  for (size_t i = 0; i < in.num_params; ++i)
+    out.params.push_back(ConvertFromC(in.params[i]));
+
+  out.results.reserve(in.num_results);
+  for (size_t i = 0; i < in.num_results; ++i)
+    out.results.push_back(ConvertFromC(in.results[i]));
+
+  return out;
+}
+
+extern "C" {
+
+/*
+ * Instance Functions
+ */
+
+NT_Inst NT_GetDefaultInstance(void) { return nt::GetDefaultInstance(); }
+
+NT_Inst NT_CreateInstance(void) { return nt::CreateInstance(); }
+
+void NT_DestroyInstance(NT_Inst inst) { return nt::DestroyInstance(inst); }
+
+NT_Inst NT_GetInstanceFromHandle(NT_Handle handle) {
+  return nt::GetInstanceFromHandle(handle);
+}
+
+/*
+ * Table Functions
+ */
+
+NT_Entry NT_GetEntry(NT_Inst inst, const char* name, size_t name_len) {
+  return nt::GetEntry(inst, StringRef(name, name_len));
+}
+
+NT_Entry* NT_GetEntries(NT_Inst inst, const char* prefix, size_t prefix_len,
+                        unsigned int types, size_t* count) {
+  auto info_v = nt::GetEntries(inst, StringRef(prefix, prefix_len), types);
+  *count = info_v.size();
+  if (info_v.size() == 0) return nullptr;
+
+  // create array and copy into it
+  NT_Entry* info = static_cast<NT_Entry*>(
+      wpi::CheckedMalloc(info_v.size() * sizeof(NT_Entry)));
+  std::memcpy(info, info_v.data(), info_v.size() * sizeof(NT_Entry));
+  return info;
+}
+
+char* NT_GetEntryName(NT_Entry entry, size_t* name_len) {
+  struct NT_String v_name;
+  nt::ConvertToC(nt::GetEntryName(entry), &v_name);
+  *name_len = v_name.len;
+  return v_name.str;
+}
+
+enum NT_Type NT_GetEntryType(NT_Entry entry) { return nt::GetEntryType(entry); }
+
+uint64_t NT_GetEntryLastChange(NT_Entry entry) {
+  return nt::GetEntryLastChange(entry);
+}
+
+void NT_GetEntryValue(NT_Entry entry, struct NT_Value* value) {
+  NT_InitValue(value);
+  auto v = nt::GetEntryValue(entry);
+  if (!v) return;
+  ConvertToC(*v, value);
+}
+
+int NT_SetDefaultEntryValue(NT_Entry entry,
+                            const struct NT_Value* default_value) {
+  return nt::SetDefaultEntryValue(entry, ConvertFromC(*default_value));
+}
+
+int NT_SetEntryValue(NT_Entry entry, const struct NT_Value* value) {
+  return nt::SetEntryValue(entry, ConvertFromC(*value));
+}
+
+void NT_SetEntryTypeValue(NT_Entry entry, const struct NT_Value* value) {
+  nt::SetEntryTypeValue(entry, ConvertFromC(*value));
+}
+
+void NT_SetEntryFlags(NT_Entry entry, unsigned int flags) {
+  nt::SetEntryFlags(entry, flags);
+}
+
+unsigned int NT_GetEntryFlags(NT_Entry entry) {
+  return nt::GetEntryFlags(entry);
+}
+
+void NT_DeleteEntry(NT_Entry entry) { nt::DeleteEntry(entry); }
+
+void NT_DeleteAllEntries(NT_Inst inst) { nt::DeleteAllEntries(inst); }
+
+struct NT_EntryInfo* NT_GetEntryInfo(NT_Inst inst, const char* prefix,
+                                     size_t prefix_len, unsigned int types,
+                                     size_t* count) {
+  auto info_v = nt::GetEntryInfo(inst, StringRef(prefix, prefix_len), types);
+  return ConvertToC<NT_EntryInfo>(info_v, count);
+}
+
+NT_Bool NT_GetEntryInfoHandle(NT_Entry entry, struct NT_EntryInfo* info) {
+  auto info_v = nt::GetEntryInfo(entry);
+  if (info_v.name.empty()) return false;
+  ConvertToC(info_v, info);
+  return true;
+}
+
+/*
+ * Callback Creation Functions
+ */
+
+NT_EntryListener NT_AddEntryListener(NT_Inst inst, const char* prefix,
+                                     size_t prefix_len, void* data,
+                                     NT_EntryListenerCallback callback,
+                                     unsigned int flags) {
+  return nt::AddEntryListener(inst, StringRef(prefix, prefix_len),
+                              [=](const EntryNotification& event) {
+                                NT_EntryNotification c_event;
+                                ConvertToC(event, &c_event);
+                                callback(data, &c_event);
+                                DisposeEntryNotification(&c_event);
+                              },
+                              flags);
+}
+
+NT_EntryListener NT_AddEntryListenerSingle(NT_Entry entry, void* data,
+                                           NT_EntryListenerCallback callback,
+                                           unsigned int flags) {
+  return nt::AddEntryListener(entry,
+                              [=](const EntryNotification& event) {
+                                NT_EntryNotification c_event;
+                                ConvertToC(event, &c_event);
+                                callback(data, &c_event);
+                                DisposeEntryNotification(&c_event);
+                              },
+                              flags);
+}
+
+NT_EntryListenerPoller NT_CreateEntryListenerPoller(NT_Inst inst) {
+  return nt::CreateEntryListenerPoller(inst);
+}
+
+void NT_DestroyEntryListenerPoller(NT_EntryListenerPoller poller) {
+  nt::DestroyEntryListenerPoller(poller);
+}
+
+NT_EntryListener NT_AddPolledEntryListener(NT_EntryListenerPoller poller,
+                                           const char* prefix,
+                                           size_t prefix_len,
+                                           unsigned int flags) {
+  return nt::AddPolledEntryListener(poller, StringRef(prefix, prefix_len),
+                                    flags);
+}
+
+NT_EntryListener NT_AddPolledEntryListenerSingle(NT_EntryListenerPoller poller,
+                                                 NT_Entry entry,
+                                                 unsigned int flags) {
+  return nt::AddPolledEntryListener(poller, entry, flags);
+}
+
+struct NT_EntryNotification* NT_PollEntryListener(NT_EntryListenerPoller poller,
+                                                  size_t* len) {
+  auto arr_cpp = nt::PollEntryListener(poller);
+  return ConvertToC<NT_EntryNotification>(arr_cpp, len);
+}
+
+struct NT_EntryNotification* NT_PollEntryListenerTimeout(
+    NT_EntryListenerPoller poller, size_t* len, double timeout,
+    NT_Bool* timed_out) {
+  bool cpp_timed_out = false;
+  auto arr_cpp = nt::PollEntryListener(poller, timeout, &cpp_timed_out);
+  *timed_out = cpp_timed_out;
+  return ConvertToC<NT_EntryNotification>(arr_cpp, len);
+}
+
+void NT_CancelPollEntryListener(NT_EntryListenerPoller poller) {
+  nt::CancelPollEntryListener(poller);
+}
+
+void NT_RemoveEntryListener(NT_EntryListener entry_listener) {
+  nt::RemoveEntryListener(entry_listener);
+}
+
+NT_Bool NT_WaitForEntryListenerQueue(NT_Inst inst, double timeout) {
+  return nt::WaitForEntryListenerQueue(inst, timeout);
+}
+
+NT_ConnectionListener NT_AddConnectionListener(
+    NT_Inst inst, void* data, NT_ConnectionListenerCallback callback,
+    NT_Bool immediate_notify) {
+  return nt::AddConnectionListener(inst,
+                                   [=](const ConnectionNotification& event) {
+                                     NT_ConnectionNotification event_c;
+                                     ConvertToC(event, &event_c);
+                                     callback(data, &event_c);
+                                     DisposeConnectionNotification(&event_c);
+                                   },
+                                   immediate_notify != 0);
+}
+
+NT_ConnectionListenerPoller NT_CreateConnectionListenerPoller(NT_Inst inst) {
+  return nt::CreateConnectionListenerPoller(inst);
+}
+
+void NT_DestroyConnectionListenerPoller(NT_ConnectionListenerPoller poller) {
+  nt::DestroyConnectionListenerPoller(poller);
+}
+
+NT_ConnectionListener NT_AddPolledConnectionListener(
+    NT_ConnectionListenerPoller poller, NT_Bool immediate_notify) {
+  return nt::AddPolledConnectionListener(poller, immediate_notify);
+}
+
+struct NT_ConnectionNotification* NT_PollConnectionListener(
+    NT_ConnectionListenerPoller poller, size_t* len) {
+  auto arr_cpp = nt::PollConnectionListener(poller);
+  return ConvertToC<NT_ConnectionNotification>(arr_cpp, len);
+}
+
+struct NT_ConnectionNotification* NT_PollConnectionListenerTimeout(
+    NT_ConnectionListenerPoller poller, size_t* len, double timeout,
+    NT_Bool* timed_out) {
+  bool cpp_timed_out = false;
+  auto arr_cpp = nt::PollConnectionListener(poller, timeout, &cpp_timed_out);
+  *timed_out = cpp_timed_out;
+  return ConvertToC<NT_ConnectionNotification>(arr_cpp, len);
+}
+
+void NT_CancelPollConnectionListener(NT_ConnectionListenerPoller poller) {
+  nt::CancelPollConnectionListener(poller);
+}
+
+void NT_RemoveConnectionListener(NT_ConnectionListener conn_listener) {
+  nt::RemoveConnectionListener(conn_listener);
+}
+
+NT_Bool NT_WaitForConnectionListenerQueue(NT_Inst inst, double timeout) {
+  return nt::WaitForConnectionListenerQueue(inst, timeout);
+}
+
+/*
+ * Remote Procedure Call Functions
+ */
+
+void NT_CreateRpc(NT_Entry entry, const char* def, size_t def_len, void* data,
+                  NT_RpcCallback callback) {
+  nt::CreateRpc(entry, StringRef(def, def_len), [=](const RpcAnswer& answer) {
+    NT_RpcAnswer answer_c;
+    ConvertToC(answer, &answer_c);
+    callback(data, &answer_c);
+    NT_DisposeRpcAnswer(&answer_c);
+  });
+}
+
+NT_RpcCallPoller NT_CreateRpcCallPoller(NT_Inst inst) {
+  return nt::CreateRpcCallPoller(inst);
+}
+
+void NT_DestroyRpcCallPoller(NT_RpcCallPoller poller) {
+  nt::DestroyRpcCallPoller(poller);
+}
+
+void NT_CreatePolledRpc(NT_Entry entry, const char* def, size_t def_len,
+                        NT_RpcCallPoller poller) {
+  nt::CreatePolledRpc(entry, StringRef(def, def_len), poller);
+}
+
+NT_RpcAnswer* NT_PollRpc(NT_RpcCallPoller poller, size_t* len) {
+  auto arr_cpp = nt::PollRpc(poller);
+  return ConvertToC<NT_RpcAnswer>(arr_cpp, len);
+}
+
+NT_RpcAnswer* NT_PollRpcTimeout(NT_RpcCallPoller poller, size_t* len,
+                                double timeout, NT_Bool* timed_out) {
+  bool cpp_timed_out = false;
+  auto arr_cpp = nt::PollRpc(poller, timeout, &cpp_timed_out);
+  *timed_out = cpp_timed_out;
+  return ConvertToC<NT_RpcAnswer>(arr_cpp, len);
+}
+
+void NT_CancelPollRpc(NT_RpcCallPoller poller) { nt::CancelPollRpc(poller); }
+
+NT_Bool NT_WaitForRpcCallQueue(NT_Inst inst, double timeout) {
+  return nt::WaitForRpcCallQueue(inst, timeout);
+}
+
+NT_Bool NT_PostRpcResponse(NT_Entry entry, NT_RpcCall call, const char* result,
+                           size_t result_len) {
+  return nt::PostRpcResponse(entry, call, StringRef(result, result_len));
+}
+
+NT_RpcCall NT_CallRpc(NT_Entry entry, const char* params, size_t params_len) {
+  return nt::CallRpc(entry, StringRef(params, params_len));
+}
+
+char* NT_GetRpcResult(NT_Entry entry, NT_RpcCall call, size_t* result_len) {
+  std::string result;
+  if (!nt::GetRpcResult(entry, call, &result)) return nullptr;
+
+  // convert result
+  *result_len = result.size();
+  char* result_cstr;
+  ConvertToC(result, &result_cstr);
+  return result_cstr;
+}
+
+char* NT_GetRpcResultTimeout(NT_Entry entry, NT_RpcCall call,
+                             size_t* result_len, double timeout,
+                             NT_Bool* timed_out) {
+  std::string result;
+  bool cpp_timed_out = false;
+  if (!nt::GetRpcResult(entry, call, &result, timeout, &cpp_timed_out)) {
+    *timed_out = cpp_timed_out;
+    return nullptr;
+  }
+
+  *timed_out = cpp_timed_out;
+  // convert result
+  *result_len = result.size();
+  char* result_cstr;
+  ConvertToC(result, &result_cstr);
+  return result_cstr;
+}
+
+void NT_CancelRpcResult(NT_Entry entry, NT_RpcCall call) {
+  nt::CancelRpcResult(entry, call);
+}
+
+char* NT_PackRpcDefinition(const NT_RpcDefinition* def, size_t* packed_len) {
+  auto packed = nt::PackRpcDefinition(ConvertFromC(*def));
+
+  // convert result
+  *packed_len = packed.size();
+  char* packed_cstr;
+  ConvertToC(packed, &packed_cstr);
+  return packed_cstr;
+}
+
+NT_Bool NT_UnpackRpcDefinition(const char* packed, size_t packed_len,
+                               NT_RpcDefinition* def) {
+  nt::RpcDefinition def_v;
+  if (!nt::UnpackRpcDefinition(StringRef(packed, packed_len), &def_v)) return 0;
+
+  // convert result
+  ConvertToC(def_v, def);
+  return 1;
+}
+
+char* NT_PackRpcValues(const NT_Value** values, size_t values_len,
+                       size_t* packed_len) {
+  // create input vector
+  std::vector<std::shared_ptr<Value>> values_v;
+  values_v.reserve(values_len);
+  for (size_t i = 0; i < values_len; ++i)
+    values_v.push_back(ConvertFromC(*values[i]));
+
+  // make the call
+  auto packed = nt::PackRpcValues(values_v);
+
+  // convert result
+  *packed_len = packed.size();
+  char* packed_cstr;
+  ConvertToC(packed, &packed_cstr);
+  return packed_cstr;
+}
+
+NT_Value** NT_UnpackRpcValues(const char* packed, size_t packed_len,
+                              const NT_Type* types, size_t types_len) {
+  auto values_v = nt::UnpackRpcValues(StringRef(packed, packed_len),
+                                      ArrayRef<NT_Type>(types, types_len));
+  if (values_v.size() == 0) return nullptr;
+
+  // create array and copy into it
+  NT_Value** values = static_cast<NT_Value**>(
+      wpi::CheckedMalloc(values_v.size() * sizeof(NT_Value*)));
+  for (size_t i = 0; i < values_v.size(); ++i) {
+    values[i] = static_cast<NT_Value*>(wpi::CheckedMalloc(sizeof(NT_Value)));
+    ConvertToC(*values_v[i], values[i]);
+  }
+  return values;
+}
+
+/*
+ * Client/Server Functions
+ */
+
+void NT_SetNetworkIdentity(NT_Inst inst, const char* name, size_t name_len) {
+  nt::SetNetworkIdentity(inst, StringRef(name, name_len));
+}
+
+unsigned int NT_GetNetworkMode(NT_Inst inst) {
+  return nt::GetNetworkMode(inst);
+}
+
+void NT_StartServer(NT_Inst inst, const char* persist_filename,
+                    const char* listen_address, unsigned int port) {
+  nt::StartServer(inst, persist_filename, listen_address, port);
+}
+
+void NT_StopServer(NT_Inst inst) { nt::StopServer(inst); }
+
+void NT_StartClientNone(NT_Inst inst) { nt::StartClient(inst); }
+
+void NT_StartClient(NT_Inst inst, const char* server_name, unsigned int port) {
+  nt::StartClient(inst, server_name, port);
+}
+
+void NT_StartClientMulti(NT_Inst inst, size_t count, const char** server_names,
+                         const unsigned int* ports) {
+  std::vector<std::pair<StringRef, unsigned int>> servers;
+  servers.reserve(count);
+  for (size_t i = 0; i < count; ++i)
+    servers.emplace_back(std::make_pair(server_names[i], ports[i]));
+  nt::StartClient(inst, servers);
+}
+
+void NT_StartClientTeam(NT_Inst inst, unsigned int team, unsigned int port) {
+  nt::StartClientTeam(inst, team, port);
+}
+
+void NT_StopClient(NT_Inst inst) { nt::StopClient(inst); }
+
+void NT_SetServer(NT_Inst inst, const char* server_name, unsigned int port) {
+  nt::SetServer(inst, server_name, port);
+}
+
+void NT_SetServerMulti(NT_Inst inst, size_t count, const char** server_names,
+                       const unsigned int* ports) {
+  std::vector<std::pair<StringRef, unsigned int>> servers;
+  servers.reserve(count);
+  for (size_t i = 0; i < count; ++i)
+    servers.emplace_back(std::make_pair(server_names[i], ports[i]));
+  nt::SetServer(inst, servers);
+}
+
+void NT_SetServerTeam(NT_Inst inst, unsigned int team, unsigned int port) {
+  nt::SetServerTeam(inst, team, port);
+}
+
+void NT_StartDSClient(NT_Inst inst, unsigned int port) {
+  nt::StartDSClient(inst, port);
+}
+
+void NT_StopDSClient(NT_Inst inst) { nt::StopDSClient(inst); }
+
+void NT_SetUpdateRate(NT_Inst inst, double interval) {
+  nt::SetUpdateRate(inst, interval);
+}
+
+void NT_Flush(NT_Inst inst) { nt::Flush(inst); }
+
+NT_Bool NT_IsConnected(NT_Inst inst) { return nt::IsConnected(inst); }
+
+struct NT_ConnectionInfo* NT_GetConnections(NT_Inst inst, size_t* count) {
+  auto conn_v = nt::GetConnections(inst);
+  return ConvertToC<NT_ConnectionInfo>(conn_v, count);
+}
+
+/*
+ * File Save/Load Functions
+ */
+
+const char* NT_SavePersistent(NT_Inst inst, const char* filename) {
+  return nt::SavePersistent(inst, filename);
+}
+
+const char* NT_LoadPersistent(NT_Inst inst, const char* filename,
+                              void (*warn)(size_t line, const char* msg)) {
+  return nt::LoadPersistent(inst, filename, warn);
+}
+
+const char* NT_SaveEntries(NT_Inst inst, const char* filename,
+                           const char* prefix, size_t prefix_len) {
+  return nt::SaveEntries(inst, filename, StringRef(prefix, prefix_len));
+}
+
+const char* NT_LoadEntries(NT_Inst inst, const char* filename,
+                           const char* prefix, size_t prefix_len,
+                           void (*warn)(size_t line, const char* msg)) {
+  return nt::LoadEntries(inst, filename, StringRef(prefix, prefix_len), warn);
+}
+
+/*
+ * Utility Functions
+ */
+
+uint64_t NT_Now(void) { return wpi::Now(); }
+
+NT_Logger NT_AddLogger(NT_Inst inst, void* data, NT_LogFunc func,
+                       unsigned int min_level, unsigned int max_level) {
+  return nt::AddLogger(inst,
+                       [=](const LogMessage& msg) {
+                         NT_LogMessage msg_c;
+                         ConvertToC(msg, &msg_c);
+                         func(data, &msg_c);
+                         NT_DisposeLogMessage(&msg_c);
+                       },
+                       min_level, max_level);
+}
+
+NT_LoggerPoller NT_CreateLoggerPoller(NT_Inst inst) {
+  return nt::CreateLoggerPoller(inst);
+}
+
+void NT_DestroyLoggerPoller(NT_LoggerPoller poller) {
+  nt::DestroyLoggerPoller(poller);
+}
+
+NT_Logger NT_AddPolledLogger(NT_LoggerPoller poller, unsigned int min_level,
+                             unsigned int max_level) {
+  return nt::AddPolledLogger(poller, min_level, max_level);
+}
+
+struct NT_LogMessage* NT_PollLogger(NT_LoggerPoller poller, size_t* len) {
+  auto arr_cpp = nt::PollLogger(poller);
+  return ConvertToC<NT_LogMessage>(arr_cpp, len);
+}
+
+struct NT_LogMessage* NT_PollLoggerTimeout(NT_LoggerPoller poller, size_t* len,
+                                           double timeout, NT_Bool* timed_out) {
+  bool cpp_timed_out = false;
+  auto arr_cpp = nt::PollLogger(poller, timeout, &cpp_timed_out);
+  *timed_out = cpp_timed_out;
+  return ConvertToC<NT_LogMessage>(arr_cpp, len);
+}
+
+void NT_CancelPollLogger(NT_LoggerPoller poller) {
+  nt::CancelPollLogger(poller);
+}
+
+void NT_RemoveLogger(NT_Logger logger) { nt::RemoveLogger(logger); }
+
+NT_Bool NT_WaitForLoggerQueue(NT_Inst inst, double timeout) {
+  return nt::WaitForLoggerQueue(inst, timeout);
+}
+
+void NT_DisposeValue(NT_Value* value) {
+  switch (value->type) {
+    case NT_UNASSIGNED:
+    case NT_BOOLEAN:
+    case NT_DOUBLE:
+      break;
+    case NT_STRING:
+    case NT_RAW:
+    case NT_RPC:
+      std::free(value->data.v_string.str);
+      break;
+    case NT_BOOLEAN_ARRAY:
+      std::free(value->data.arr_boolean.arr);
+      break;
+    case NT_DOUBLE_ARRAY:
+      std::free(value->data.arr_double.arr);
+      break;
+    case NT_STRING_ARRAY: {
+      for (size_t i = 0; i < value->data.arr_string.size; i++)
+        std::free(value->data.arr_string.arr[i].str);
+      std::free(value->data.arr_string.arr);
+      break;
+    }
+    default:
+      assert(false && "unknown value type");
+  }
+  value->type = NT_UNASSIGNED;
+  value->last_change = 0;
+}
+
+void NT_InitValue(NT_Value* value) {
+  value->type = NT_UNASSIGNED;
+  value->last_change = 0;
+}
+
+void NT_DisposeString(NT_String* str) {
+  std::free(str->str);
+  str->str = nullptr;
+  str->len = 0;
+}
+
+void NT_InitString(NT_String* str) {
+  str->str = nullptr;
+  str->len = 0;
+}
+
+void NT_DisposeEntryArray(NT_Entry* arr, size_t /*count*/) { std::free(arr); }
+
+void NT_DisposeConnectionInfoArray(NT_ConnectionInfo* arr, size_t count) {
+  for (size_t i = 0; i < count; i++) DisposeConnectionInfo(&arr[i]);
+  std::free(arr);
+}
+
+void NT_DisposeEntryInfoArray(NT_EntryInfo* arr, size_t count) {
+  for (size_t i = 0; i < count; i++) DisposeEntryInfo(&arr[i]);
+  std::free(arr);
+}
+
+void NT_DisposeEntryInfo(NT_EntryInfo* info) { DisposeEntryInfo(info); }
+
+void NT_DisposeEntryNotificationArray(NT_EntryNotification* arr, size_t count) {
+  for (size_t i = 0; i < count; i++) DisposeEntryNotification(&arr[i]);
+  std::free(arr);
+}
+
+void NT_DisposeEntryNotification(NT_EntryNotification* info) {
+  DisposeEntryNotification(info);
+}
+
+void NT_DisposeConnectionNotificationArray(NT_ConnectionNotification* arr,
+                                           size_t count) {
+  for (size_t i = 0; i < count; i++) DisposeConnectionNotification(&arr[i]);
+  std::free(arr);
+}
+
+void NT_DisposeConnectionNotification(NT_ConnectionNotification* info) {
+  DisposeConnectionNotification(info);
+}
+
+void NT_DisposeLogMessageArray(NT_LogMessage* arr, size_t count) {
+  for (size_t i = 0; i < count; i++) NT_DisposeLogMessage(&arr[i]);
+  std::free(arr);
+}
+
+void NT_DisposeLogMessage(NT_LogMessage* info) { std::free(info->message); }
+
+void NT_DisposeRpcDefinition(NT_RpcDefinition* def) {
+  NT_DisposeString(&def->name);
+
+  for (size_t i = 0; i < def->num_params; ++i) {
+    NT_DisposeString(&def->params[i].name);
+    NT_DisposeValue(&def->params[i].def_value);
+  }
+  std::free(def->params);
+  def->params = nullptr;
+  def->num_params = 0;
+
+  for (size_t i = 0; i < def->num_results; ++i)
+    NT_DisposeString(&def->results[i].name);
+  std::free(def->results);
+  def->results = nullptr;
+  def->num_results = 0;
+}
+
+void NT_DisposeRpcAnswerArray(NT_RpcAnswer* arr, size_t count) {
+  for (size_t i = 0; i < count; i++) NT_DisposeRpcAnswer(&arr[i]);
+  std::free(arr);
+}
+
+void NT_DisposeRpcAnswer(NT_RpcAnswer* call_info) {
+  NT_DisposeString(&call_info->name);
+  NT_DisposeString(&call_info->params);
+  DisposeConnectionInfo(&call_info->conn);
+}
+
+/* Interop Utility Functions */
+
+/* Array and Struct Allocations */
+
+/* Allocates a char array of the specified size.*/
+char* NT_AllocateCharArray(size_t size) {
+  char* retVal = static_cast<char*>(wpi::CheckedMalloc(size * sizeof(char)));
+  return retVal;
+}
+
+/* Allocates an integer or boolean array of the specified size. */
+int* NT_AllocateBooleanArray(size_t size) {
+  int* retVal = static_cast<int*>(wpi::CheckedMalloc(size * sizeof(int)));
+  return retVal;
+}
+
+/* Allocates a double array of the specified size. */
+double* NT_AllocateDoubleArray(size_t size) {
+  double* retVal =
+      static_cast<double*>(wpi::CheckedMalloc(size * sizeof(double)));
+  return retVal;
+}
+
+/* Allocates an NT_String array of the specified size. */
+struct NT_String* NT_AllocateStringArray(size_t size) {
+  NT_String* retVal =
+      static_cast<NT_String*>(wpi::CheckedMalloc(size * sizeof(NT_String)));
+  return retVal;
+}
+
+void NT_FreeCharArray(char* v_char) { std::free(v_char); }
+void NT_FreeDoubleArray(double* v_double) { std::free(v_double); }
+void NT_FreeBooleanArray(int* v_boolean) { std::free(v_boolean); }
+void NT_FreeStringArray(struct NT_String* v_string, size_t arr_size) {
+  for (size_t i = 0; i < arr_size; i++) std::free(v_string[i].str);
+  std::free(v_string);
+}
+
+NT_Bool NT_SetEntryDouble(NT_Entry entry, uint64_t time, double v_double,
+                          NT_Bool force) {
+  if (force != 0) {
+    nt::SetEntryTypeValue(entry, Value::MakeDouble(v_double, time));
+    return 1;
+  } else {
+    return nt::SetEntryValue(entry, Value::MakeDouble(v_double, time));
+  }
+}
+
+NT_Bool NT_SetEntryBoolean(NT_Entry entry, uint64_t time, NT_Bool v_boolean,
+                           NT_Bool force) {
+  if (force != 0) {
+    nt::SetEntryTypeValue(entry, Value::MakeBoolean(v_boolean != 0, time));
+    return 1;
+  } else {
+    return nt::SetEntryValue(entry, Value::MakeBoolean(v_boolean != 0, time));
+  }
+}
+
+NT_Bool NT_SetEntryString(NT_Entry entry, uint64_t time, const char* str,
+                          size_t str_len, NT_Bool force) {
+  if (force != 0) {
+    nt::SetEntryTypeValue(entry,
+                          Value::MakeString(StringRef(str, str_len), time));
+    return 1;
+  } else {
+    return nt::SetEntryValue(entry,
+                             Value::MakeString(StringRef(str, str_len), time));
+  }
+}
+
+NT_Bool NT_SetEntryRaw(NT_Entry entry, uint64_t time, const char* raw,
+                       size_t raw_len, NT_Bool force) {
+  if (force != 0) {
+    nt::SetEntryTypeValue(entry, Value::MakeRaw(StringRef(raw, raw_len), time));
+    return 1;
+  } else {
+    return nt::SetEntryValue(entry,
+                             Value::MakeRaw(StringRef(raw, raw_len), time));
+  }
+}
+
+NT_Bool NT_SetEntryBooleanArray(NT_Entry entry, uint64_t time,
+                                const NT_Bool* arr, size_t size,
+                                NT_Bool force) {
+  if (force != 0) {
+    nt::SetEntryTypeValue(
+        entry, Value::MakeBooleanArray(wpi::makeArrayRef(arr, size), time));
+    return 1;
+  } else {
+    return nt::SetEntryValue(
+        entry, Value::MakeBooleanArray(wpi::makeArrayRef(arr, size), time));
+  }
+}
+
+NT_Bool NT_SetEntryDoubleArray(NT_Entry entry, uint64_t time, const double* arr,
+                               size_t size, NT_Bool force) {
+  if (force != 0) {
+    nt::SetEntryTypeValue(
+        entry, Value::MakeDoubleArray(wpi::makeArrayRef(arr, size), time));
+    return 1;
+  } else {
+    return nt::SetEntryValue(
+        entry, Value::MakeDoubleArray(wpi::makeArrayRef(arr, size), time));
+  }
+}
+
+NT_Bool NT_SetEntryStringArray(NT_Entry entry, uint64_t time,
+                               const struct NT_String* arr, size_t size,
+                               NT_Bool force) {
+  std::vector<std::string> v;
+  v.reserve(size);
+  for (size_t i = 0; i < size; ++i) v.push_back(ConvertFromC(arr[i]));
+
+  if (force != 0) {
+    nt::SetEntryTypeValue(entry, Value::MakeStringArray(std::move(v), time));
+    return 1;
+  } else {
+    return nt::SetEntryValue(entry, Value::MakeStringArray(std::move(v), time));
+  }
+}
+
+enum NT_Type NT_GetValueType(const struct NT_Value* value) {
+  if (!value) return NT_Type::NT_UNASSIGNED;
+  return value->type;
+}
+
+NT_Bool NT_GetValueBoolean(const struct NT_Value* value, uint64_t* last_change,
+                           NT_Bool* v_boolean) {
+  if (!value || value->type != NT_Type::NT_BOOLEAN) return 0;
+  *v_boolean = value->data.v_boolean;
+  *last_change = value->last_change;
+  return 1;
+}
+
+NT_Bool NT_GetValueDouble(const struct NT_Value* value, uint64_t* last_change,
+                          double* v_double) {
+  if (!value || value->type != NT_Type::NT_DOUBLE) return 0;
+  *last_change = value->last_change;
+  *v_double = value->data.v_double;
+  return 1;
+}
+
+char* NT_GetValueString(const struct NT_Value* value, uint64_t* last_change,
+                        size_t* str_len) {
+  if (!value || value->type != NT_Type::NT_STRING) return nullptr;
+  *last_change = value->last_change;
+  *str_len = value->data.v_string.len;
+  char* str =
+      static_cast<char*>(wpi::CheckedMalloc(value->data.v_string.len + 1));
+  std::memcpy(str, value->data.v_string.str, value->data.v_string.len + 1);
+  return str;
+}
+
+char* NT_GetValueRaw(const struct NT_Value* value, uint64_t* last_change,
+                     size_t* raw_len) {
+  if (!value || value->type != NT_Type::NT_RAW) return nullptr;
+  *last_change = value->last_change;
+  *raw_len = value->data.v_string.len;
+  char* raw =
+      static_cast<char*>(wpi::CheckedMalloc(value->data.v_string.len + 1));
+  std::memcpy(raw, value->data.v_string.str, value->data.v_string.len + 1);
+  return raw;
+}
+
+NT_Bool* NT_GetValueBooleanArray(const struct NT_Value* value,
+                                 uint64_t* last_change, size_t* arr_size) {
+  if (!value || value->type != NT_Type::NT_BOOLEAN_ARRAY) return nullptr;
+  *last_change = value->last_change;
+  *arr_size = value->data.arr_boolean.size;
+  NT_Bool* arr = static_cast<int*>(
+      wpi::CheckedMalloc(value->data.arr_boolean.size * sizeof(NT_Bool)));
+  std::memcpy(arr, value->data.arr_boolean.arr,
+              value->data.arr_boolean.size * sizeof(NT_Bool));
+  return arr;
+}
+
+double* NT_GetValueDoubleArray(const struct NT_Value* value,
+                               uint64_t* last_change, size_t* arr_size) {
+  if (!value || value->type != NT_Type::NT_DOUBLE_ARRAY) return nullptr;
+  *last_change = value->last_change;
+  *arr_size = value->data.arr_double.size;
+  double* arr = static_cast<double*>(
+      wpi::CheckedMalloc(value->data.arr_double.size * sizeof(double)));
+  std::memcpy(arr, value->data.arr_double.arr,
+              value->data.arr_double.size * sizeof(double));
+  return arr;
+}
+
+NT_String* NT_GetValueStringArray(const struct NT_Value* value,
+                                  uint64_t* last_change, size_t* arr_size) {
+  if (!value || value->type != NT_Type::NT_STRING_ARRAY) return nullptr;
+  *last_change = value->last_change;
+  *arr_size = value->data.arr_string.size;
+  NT_String* arr = static_cast<NT_String*>(
+      wpi::CheckedMalloc(value->data.arr_string.size * sizeof(NT_String)));
+  for (size_t i = 0; i < value->data.arr_string.size; ++i) {
+    size_t len = value->data.arr_string.arr[i].len;
+    arr[i].len = len;
+    arr[i].str = static_cast<char*>(wpi::CheckedMalloc(len + 1));
+    std::memcpy(arr[i].str, value->data.arr_string.arr[i].str, len + 1);
+  }
+  return arr;
+}
+
+NT_Bool NT_SetDefaultEntryBoolean(NT_Entry entry, uint64_t time,
+                                  NT_Bool default_boolean) {
+  return nt::SetDefaultEntryValue(
+      entry, Value::MakeBoolean(default_boolean != 0, time));
+}
+
+NT_Bool NT_SetDefaultEntryDouble(NT_Entry entry, uint64_t time,
+                                 double default_double) {
+  return nt::SetDefaultEntryValue(entry,
+                                  Value::MakeDouble(default_double, time));
+}
+
+NT_Bool NT_SetDefaultEntryString(NT_Entry entry, uint64_t time,
+                                 const char* default_value,
+                                 size_t default_len) {
+  return nt::SetDefaultEntryValue(
+      entry, Value::MakeString(StringRef(default_value, default_len), time));
+}
+
+NT_Bool NT_SetDefaultEntryRaw(NT_Entry entry, uint64_t time,
+                              const char* default_value, size_t default_len) {
+  return nt::SetDefaultEntryValue(
+      entry, Value::MakeRaw(StringRef(default_value, default_len), time));
+}
+
+NT_Bool NT_SetDefaultEntryBooleanArray(NT_Entry entry, uint64_t time,
+                                       const NT_Bool* default_value,
+                                       size_t default_size) {
+  return nt::SetDefaultEntryValue(
+      entry, Value::MakeBooleanArray(
+                 wpi::makeArrayRef(default_value, default_size), time));
+}
+
+NT_Bool NT_SetDefaultEntryDoubleArray(NT_Entry entry, uint64_t time,
+                                      const double* default_value,
+                                      size_t default_size) {
+  return nt::SetDefaultEntryValue(
+      entry, Value::MakeDoubleArray(
+                 wpi::makeArrayRef(default_value, default_size), time));
+}
+
+NT_Bool NT_SetDefaultEntryStringArray(NT_Entry entry, uint64_t time,
+                                      const struct NT_String* default_value,
+                                      size_t default_size) {
+  std::vector<std::string> vec;
+  vec.reserve(default_size);
+  for (size_t i = 0; i < default_size; ++i)
+    vec.push_back(ConvertFromC(default_value[i]));
+
+  return nt::SetDefaultEntryValue(entry,
+                                  Value::MakeStringArray(std::move(vec), time));
+}
+
+NT_Bool NT_GetEntryBoolean(NT_Entry entry, uint64_t* last_change,
+                           NT_Bool* v_boolean) {
+  auto v = nt::GetEntryValue(entry);
+  if (!v || !v->IsBoolean()) return 0;
+  *v_boolean = v->GetBoolean();
+  *last_change = v->last_change();
+  return 1;
+}
+
+NT_Bool NT_GetEntryDouble(NT_Entry entry, uint64_t* last_change,
+                          double* v_double) {
+  auto v = nt::GetEntryValue(entry);
+  if (!v || !v->IsDouble()) return 0;
+  *last_change = v->last_change();
+  *v_double = v->GetDouble();
+  return 1;
+}
+
+char* NT_GetEntryString(NT_Entry entry, uint64_t* last_change,
+                        size_t* str_len) {
+  auto v = nt::GetEntryValue(entry);
+  if (!v || !v->IsString()) return nullptr;
+  *last_change = v->last_change();
+  struct NT_String v_string;
+  nt::ConvertToC(v->GetString(), &v_string);
+  *str_len = v_string.len;
+  return v_string.str;
+}
+
+char* NT_GetEntryRaw(NT_Entry entry, uint64_t* last_change, size_t* raw_len) {
+  auto v = nt::GetEntryValue(entry);
+  if (!v || !v->IsRaw()) return nullptr;
+  *last_change = v->last_change();
+  struct NT_String v_raw;
+  nt::ConvertToC(v->GetRaw(), &v_raw);
+  *raw_len = v_raw.len;
+  return v_raw.str;
+}
+
+NT_Bool* NT_GetEntryBooleanArray(NT_Entry entry, uint64_t* last_change,
+                                 size_t* arr_size) {
+  auto v = nt::GetEntryValue(entry);
+  if (!v || !v->IsBooleanArray()) return nullptr;
+  *last_change = v->last_change();
+  auto vArr = v->GetBooleanArray();
+  NT_Bool* arr =
+      static_cast<int*>(wpi::CheckedMalloc(vArr.size() * sizeof(NT_Bool)));
+  *arr_size = vArr.size();
+  std::copy(vArr.begin(), vArr.end(), arr);
+  return arr;
+}
+
+double* NT_GetEntryDoubleArray(NT_Entry entry, uint64_t* last_change,
+                               size_t* arr_size) {
+  auto v = nt::GetEntryValue(entry);
+  if (!v || !v->IsDoubleArray()) return nullptr;
+  *last_change = v->last_change();
+  auto vArr = v->GetDoubleArray();
+  double* arr =
+      static_cast<double*>(wpi::CheckedMalloc(vArr.size() * sizeof(double)));
+  *arr_size = vArr.size();
+  std::copy(vArr.begin(), vArr.end(), arr);
+  return arr;
+}
+
+NT_String* NT_GetEntryStringArray(NT_Entry entry, uint64_t* last_change,
+                                  size_t* arr_size) {
+  auto v = nt::GetEntryValue(entry);
+  if (!v || !v->IsStringArray()) return nullptr;
+  *last_change = v->last_change();
+  auto vArr = v->GetStringArray();
+  NT_String* arr = static_cast<NT_String*>(
+      wpi::CheckedMalloc(vArr.size() * sizeof(NT_String)));
+  for (size_t i = 0; i < vArr.size(); ++i) {
+    ConvertToC(vArr[i], &arr[i]);
+  }
+  *arr_size = vArr.size();
+  return arr;
+}
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_cpp.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_cpp.cpp
new file mode 100644
index 0000000..18256f5
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_cpp.cpp
@@ -0,0 +1,1062 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <stdint.h>
+
+#include <cassert>
+#include <cstdio>
+#include <cstdlib>
+
+#include <wpi/timestamp.h>
+
+#include "Handle.h"
+#include "InstanceImpl.h"
+#include "Log.h"
+#include "WireDecoder.h"
+#include "WireEncoder.h"
+#include "ntcore.h"
+
+namespace nt {
+
+/*
+ * Instance Functions
+ */
+
+NT_Inst GetDefaultInstance() {
+  return Handle{InstanceImpl::GetDefaultIndex(), 0, Handle::kInstance};
+}
+
+NT_Inst CreateInstance() {
+  return Handle{InstanceImpl::Alloc(), 0, Handle::kInstance};
+}
+
+void DestroyInstance(NT_Inst inst) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  if (i < 0) return;
+  InstanceImpl::Destroy(i);
+}
+
+NT_Inst GetInstanceFromHandle(NT_Handle handle) {
+  Handle h{handle};
+  auto type = h.GetType();
+  if (type >= Handle::kConnectionListener && type <= Handle::kRpcCallPoller)
+    return Handle(h.GetInst(), 0, Handle::kInstance);
+
+  return 0;
+}
+
+/*
+ * Table Functions
+ */
+
+NT_Entry GetEntry(NT_Inst inst, const Twine& name) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return 0;
+
+  unsigned int id = ii->storage.GetEntry(name);
+  if (id == UINT_MAX) return 0;
+  return Handle(i, id, Handle::kEntry);
+}
+
+std::vector<NT_Entry> GetEntries(NT_Inst inst, const Twine& prefix,
+                                 unsigned int types) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return std::vector<NT_Entry>{};
+
+  auto arr = ii->storage.GetEntries(prefix, types);
+  // convert indices to handles
+  for (auto& val : arr) val = Handle(i, val, Handle::kEntry);
+  return arr;
+}
+
+std::string GetEntryName(NT_Entry entry) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::string{};
+
+  return ii->storage.GetEntryName(id);
+}
+
+NT_Type GetEntryType(NT_Entry entry) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return NT_UNASSIGNED;
+
+  return ii->storage.GetEntryType(id);
+}
+
+uint64_t GetEntryLastChange(NT_Entry entry) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return 0;
+
+  return ii->storage.GetEntryLastChange(id);
+}
+
+std::shared_ptr<Value> GetEntryValue(StringRef name) {
+  return InstanceImpl::GetDefault()->storage.GetEntryValue(name);
+}
+
+std::shared_ptr<Value> GetEntryValue(NT_Entry entry) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return nullptr;
+
+  return ii->storage.GetEntryValue(id);
+}
+
+bool SetDefaultEntryValue(StringRef name, std::shared_ptr<Value> value) {
+  return InstanceImpl::GetDefault()->storage.SetDefaultEntryValue(name, value);
+}
+
+bool SetDefaultEntryValue(NT_Entry entry, std::shared_ptr<Value> value) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return false;
+
+  return ii->storage.SetDefaultEntryValue(id, value);
+}
+
+bool SetEntryValue(StringRef name, std::shared_ptr<Value> value) {
+  return InstanceImpl::GetDefault()->storage.SetEntryValue(name, value);
+}
+
+bool SetEntryValue(NT_Entry entry, std::shared_ptr<Value> value) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return false;
+
+  return ii->storage.SetEntryValue(id, value);
+}
+
+void SetEntryTypeValue(StringRef name, std::shared_ptr<Value> value) {
+  InstanceImpl::GetDefault()->storage.SetEntryTypeValue(name, value);
+}
+
+void SetEntryTypeValue(NT_Entry entry, std::shared_ptr<Value> value) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->storage.SetEntryTypeValue(id, value);
+}
+
+void SetEntryFlags(StringRef name, unsigned int flags) {
+  InstanceImpl::GetDefault()->storage.SetEntryFlags(name, flags);
+}
+
+void SetEntryFlags(NT_Entry entry, unsigned int flags) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->storage.SetEntryFlags(id, flags);
+}
+
+unsigned int GetEntryFlags(StringRef name) {
+  return InstanceImpl::GetDefault()->storage.GetEntryFlags(name);
+}
+
+unsigned int GetEntryFlags(NT_Entry entry) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return 0;
+
+  return ii->storage.GetEntryFlags(id);
+}
+
+void DeleteEntry(StringRef name) {
+  InstanceImpl::GetDefault()->storage.DeleteEntry(name);
+}
+
+void DeleteEntry(NT_Entry entry) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->storage.DeleteEntry(id);
+}
+
+void DeleteAllEntries() {
+  InstanceImpl::GetDefault()->storage.DeleteAllEntries();
+}
+
+void DeleteAllEntries(NT_Inst inst) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (i < 0 || !ii) return;
+
+  ii->storage.DeleteAllEntries();
+}
+
+std::vector<EntryInfo> GetEntryInfo(StringRef prefix, unsigned int types) {
+  return InstanceImpl::GetDefault()->storage.GetEntryInfo(0, prefix, types);
+}
+
+std::vector<EntryInfo> GetEntryInfo(NT_Inst inst, const Twine& prefix,
+                                    unsigned int types) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return std::vector<EntryInfo>{};
+
+  return ii->storage.GetEntryInfo(i, prefix, types);
+}
+
+EntryInfo GetEntryInfo(NT_Entry entry) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  int i = handle.GetInst();
+  auto ii = InstanceImpl::Get(i);
+  if (id < 0 || !ii) {
+    EntryInfo info;
+    info.entry = 0;
+    info.type = NT_UNASSIGNED;
+    info.flags = 0;
+    info.last_change = 0;
+    return info;
+  }
+
+  return ii->storage.GetEntryInfo(i, id);
+}
+
+/*
+ * Callback Creation Functions
+ */
+
+NT_EntryListener AddEntryListener(StringRef prefix,
+                                  EntryListenerCallback callback,
+                                  unsigned int flags) {
+  return AddEntryListener(
+      Handle(InstanceImpl::GetDefaultIndex(), 0, Handle::kInstance), prefix,
+      [=](const EntryNotification& event) {
+        callback(event.listener, event.name, event.value, event.flags);
+      },
+      flags);
+}
+
+NT_EntryListener AddEntryListener(
+    NT_Inst inst, const Twine& prefix,
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int flags) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (i < 0 || !ii) return 0;
+
+  unsigned int uid = ii->storage.AddListener(prefix, callback, flags);
+  return Handle(i, uid, Handle::kEntryListener);
+}
+
+NT_EntryListener AddEntryListener(
+    NT_Entry entry,
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int flags) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  int i = handle.GetInst();
+  auto ii = InstanceImpl::Get(i);
+  if (id < 0 || !ii) return 0;
+
+  unsigned int uid = ii->storage.AddListener(id, callback, flags);
+  return Handle(i, uid, Handle::kEntryListener);
+}
+
+NT_EntryListenerPoller CreateEntryListenerPoller(NT_Inst inst) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return 0;
+
+  return Handle(i, ii->entry_notifier.CreatePoller(),
+                Handle::kEntryListenerPoller);
+}
+
+void DestroyEntryListenerPoller(NT_EntryListenerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->entry_notifier.RemovePoller(id);
+}
+
+NT_EntryListener AddPolledEntryListener(NT_EntryListenerPoller poller,
+                                        const Twine& prefix,
+                                        unsigned int flags) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
+  int i = handle.GetInst();
+  auto ii = InstanceImpl::Get(i);
+  if (id < 0 || !ii) return 0;
+
+  unsigned int uid = ii->storage.AddPolledListener(id, prefix, flags);
+  return Handle(i, uid, Handle::kEntryListener);
+}
+
+NT_EntryListener AddPolledEntryListener(NT_EntryListenerPoller poller,
+                                        NT_Entry entry, unsigned int flags) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  int i = handle.GetInst();
+  auto ii = InstanceImpl::Get(i);
+  if (id < 0 || !ii) return 0;
+
+  Handle phandle{poller};
+  int p_id = phandle.GetTypedIndex(Handle::kEntryListenerPoller);
+  if (p_id < 0) return 0;
+  if (handle.GetInst() != phandle.GetInst()) return 0;
+
+  unsigned int uid = ii->storage.AddPolledListener(p_id, id, flags);
+  return Handle(i, uid, Handle::kEntryListener);
+}
+
+std::vector<EntryNotification> PollEntryListener(
+    NT_EntryListenerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::vector<EntryNotification>{};
+
+  return ii->entry_notifier.Poll(static_cast<unsigned int>(id));
+}
+
+std::vector<EntryNotification> PollEntryListener(NT_EntryListenerPoller poller,
+                                                 double timeout,
+                                                 bool* timed_out) {
+  *timed_out = false;
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::vector<EntryNotification>{};
+
+  return ii->entry_notifier.Poll(static_cast<unsigned int>(id), timeout,
+                                 timed_out);
+}
+
+void CancelPollEntryListener(NT_EntryListenerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kEntryListenerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->entry_notifier.CancelPoll(id);
+}
+
+void RemoveEntryListener(NT_EntryListener entry_listener) {
+  Handle handle{entry_listener};
+  int uid = handle.GetTypedIndex(Handle::kEntryListener);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (uid < 0 || !ii) return;
+
+  ii->entry_notifier.Remove(uid);
+}
+
+bool WaitForEntryListenerQueue(NT_Inst inst, double timeout) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return true;
+  return ii->entry_notifier.WaitForQueue(timeout);
+}
+
+NT_ConnectionListener AddConnectionListener(ConnectionListenerCallback callback,
+                                            bool immediate_notify) {
+  return AddConnectionListener(
+      Handle(InstanceImpl::GetDefaultIndex(), 0, Handle::kInstance),
+      [=](const ConnectionNotification& event) {
+        callback(event.listener, event.connected, event.conn);
+      },
+      immediate_notify);
+}
+
+NT_ConnectionListener AddConnectionListener(
+    NT_Inst inst,
+    std::function<void(const ConnectionNotification& event)> callback,
+    bool immediate_notify) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return 0;
+
+  unsigned int uid = ii->dispatcher.AddListener(callback, immediate_notify);
+  return Handle(i, uid, Handle::kConnectionListener);
+}
+
+NT_ConnectionListenerPoller CreateConnectionListenerPoller(NT_Inst inst) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return 0;
+
+  return Handle(i, ii->connection_notifier.CreatePoller(),
+                Handle::kConnectionListenerPoller);
+}
+
+void DestroyConnectionListenerPoller(NT_ConnectionListenerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->connection_notifier.RemovePoller(id);
+}
+
+NT_ConnectionListener AddPolledConnectionListener(
+    NT_ConnectionListenerPoller poller, bool immediate_notify) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
+  int i = handle.GetInst();
+  auto ii = InstanceImpl::Get(i);
+  if (id < 0 || !ii) return 0;
+
+  unsigned int uid = ii->dispatcher.AddPolledListener(id, immediate_notify);
+  return Handle(i, uid, Handle::kConnectionListener);
+}
+
+std::vector<ConnectionNotification> PollConnectionListener(
+    NT_ConnectionListenerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::vector<ConnectionNotification>{};
+
+  return ii->connection_notifier.Poll(static_cast<unsigned int>(id));
+}
+
+std::vector<ConnectionNotification> PollConnectionListener(
+    NT_ConnectionListenerPoller poller, double timeout, bool* timed_out) {
+  *timed_out = false;
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::vector<ConnectionNotification>{};
+
+  return ii->connection_notifier.Poll(static_cast<unsigned int>(id), timeout,
+                                      timed_out);
+}
+
+void CancelPollConnectionListener(NT_ConnectionListenerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kConnectionListenerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->connection_notifier.CancelPoll(id);
+}
+
+void RemoveConnectionListener(NT_ConnectionListener conn_listener) {
+  Handle handle{conn_listener};
+  int uid = handle.GetTypedIndex(Handle::kConnectionListener);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (uid < 0 || !ii) return;
+
+  ii->connection_notifier.Remove(uid);
+}
+
+bool WaitForConnectionListenerQueue(NT_Inst inst, double timeout) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return true;
+  return ii->connection_notifier.WaitForQueue(timeout);
+}
+
+/*
+ * Remote Procedure Call Functions
+ */
+
+void CreateRpc(NT_Entry entry, StringRef def,
+               std::function<void(const RpcAnswer& answer)> callback) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  // only server can create RPCs
+  if ((ii->dispatcher.GetNetworkMode() & NT_NET_MODE_SERVER) == 0) return;
+  if (def.empty() || !callback) return;
+
+  ii->storage.CreateRpc(id, def, ii->rpc_server.Add(callback));
+}
+
+NT_RpcCallPoller CreateRpcCallPoller(NT_Inst inst) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return 0;
+
+  return Handle(i, ii->rpc_server.CreatePoller(), Handle::kRpcCallPoller);
+}
+
+void DestroyRpcCallPoller(NT_RpcCallPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kRpcCallPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->rpc_server.RemovePoller(id);
+}
+
+void CreatePolledRpc(NT_Entry entry, StringRef def, NT_RpcCallPoller poller) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  Handle phandle{poller};
+  int p_id = phandle.GetTypedIndex(Handle::kRpcCallPoller);
+  if (p_id < 0) return;
+  if (handle.GetInst() != phandle.GetInst()) return;
+
+  // only server can create RPCs
+  if ((ii->dispatcher.GetNetworkMode() & NT_NET_MODE_SERVER) == 0) return;
+  if (def.empty()) return;
+
+  ii->storage.CreateRpc(id, def, ii->rpc_server.AddPolled(p_id));
+}
+
+std::vector<RpcAnswer> PollRpc(NT_RpcCallPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kRpcCallPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::vector<RpcAnswer>{};
+
+  return ii->rpc_server.Poll(static_cast<unsigned int>(id));
+}
+
+std::vector<RpcAnswer> PollRpc(NT_RpcCallPoller poller, double timeout,
+                               bool* timed_out) {
+  *timed_out = false;
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kRpcCallPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::vector<RpcAnswer>{};
+
+  return ii->rpc_server.Poll(static_cast<unsigned int>(id), timeout, timed_out);
+}
+
+void CancelPollRpc(NT_RpcCallPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kRpcCallPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->rpc_server.CancelPoll(id);
+}
+
+bool WaitForRpcCallQueue(NT_Inst inst, double timeout) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return true;
+  return ii->rpc_server.WaitForQueue(timeout);
+}
+
+bool PostRpcResponse(NT_Entry entry, NT_RpcCall call, StringRef result) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return false;
+
+  Handle chandle{call};
+  int call_uid = chandle.GetTypedIndex(Handle::kRpcCall);
+  if (call_uid < 0) return false;
+  if (handle.GetInst() != chandle.GetInst()) return false;
+
+  return ii->rpc_server.PostRpcResponse(id, call_uid, result);
+}
+
+NT_RpcCall CallRpc(NT_Entry entry, StringRef params) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  int i = handle.GetInst();
+  auto ii = InstanceImpl::Get(i);
+  if (id < 0 || !ii) return 0;
+
+  unsigned int call_uid = ii->storage.CallRpc(id, params);
+  if (call_uid == 0) return 0;
+  return Handle(i, call_uid, Handle::kRpcCall);
+}
+
+bool GetRpcResult(NT_Entry entry, NT_RpcCall call, std::string* result) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return false;
+
+  Handle chandle{call};
+  int call_uid = chandle.GetTypedIndex(Handle::kRpcCall);
+  if (call_uid < 0) return false;
+  if (handle.GetInst() != chandle.GetInst()) return false;
+
+  return ii->storage.GetRpcResult(id, call_uid, result);
+}
+
+bool GetRpcResult(NT_Entry entry, NT_RpcCall call, std::string* result,
+                  double timeout, bool* timed_out) {
+  *timed_out = false;
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return false;
+
+  Handle chandle{call};
+  int call_uid = chandle.GetTypedIndex(Handle::kRpcCall);
+  if (call_uid < 0) return false;
+  if (handle.GetInst() != chandle.GetInst()) return false;
+
+  return ii->storage.GetRpcResult(id, call_uid, result, timeout, timed_out);
+}
+
+void CancelRpcResult(NT_Entry entry, NT_RpcCall call) {
+  Handle handle{entry};
+  int id = handle.GetTypedIndex(Handle::kEntry);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  Handle chandle{call};
+  int call_uid = chandle.GetTypedIndex(Handle::kRpcCall);
+  if (call_uid < 0) return;
+  if (handle.GetInst() != chandle.GetInst()) return;
+
+  ii->storage.CancelRpcResult(id, call_uid);
+}
+
+std::string PackRpcDefinition(const RpcDefinition& def) {
+  WireEncoder enc(0x0300);
+  enc.Write8(def.version);
+  enc.WriteString(def.name);
+
+  // parameters
+  unsigned int params_size = def.params.size();
+  if (params_size > 0xff) params_size = 0xff;
+  enc.Write8(params_size);
+  for (size_t i = 0; i < params_size; ++i) {
+    enc.WriteType(def.params[i].def_value->type());
+    enc.WriteString(def.params[i].name);
+    enc.WriteValue(*def.params[i].def_value);
+  }
+
+  // results
+  unsigned int results_size = def.results.size();
+  if (results_size > 0xff) results_size = 0xff;
+  enc.Write8(results_size);
+  for (size_t i = 0; i < results_size; ++i) {
+    enc.WriteType(def.results[i].type);
+    enc.WriteString(def.results[i].name);
+  }
+
+  return enc.ToStringRef();
+}
+
+bool UnpackRpcDefinition(StringRef packed, RpcDefinition* def) {
+  wpi::raw_mem_istream is(packed.data(), packed.size());
+  wpi::Logger logger;
+  WireDecoder dec(is, 0x0300, logger);
+  if (!dec.Read8(&def->version)) return false;
+  if (!dec.ReadString(&def->name)) return false;
+
+  // parameters
+  unsigned int params_size;
+  if (!dec.Read8(&params_size)) return false;
+  def->params.resize(0);
+  def->params.reserve(params_size);
+  for (size_t i = 0; i < params_size; ++i) {
+    RpcParamDef pdef;
+    NT_Type type;
+    if (!dec.ReadType(&type)) return false;
+    if (!dec.ReadString(&pdef.name)) return false;
+    pdef.def_value = dec.ReadValue(type);
+    if (!pdef.def_value) return false;
+    def->params.emplace_back(std::move(pdef));
+  }
+
+  // results
+  unsigned int results_size;
+  if (!dec.Read8(&results_size)) return false;
+  def->results.resize(0);
+  def->results.reserve(results_size);
+  for (size_t i = 0; i < results_size; ++i) {
+    RpcResultDef rdef;
+    if (!dec.ReadType(&rdef.type)) return false;
+    if (!dec.ReadString(&rdef.name)) return false;
+    def->results.emplace_back(std::move(rdef));
+  }
+
+  return true;
+}
+
+std::string PackRpcValues(ArrayRef<std::shared_ptr<Value>> values) {
+  WireEncoder enc(0x0300);
+  for (auto& value : values) enc.WriteValue(*value);
+  return enc.ToStringRef();
+}
+
+std::vector<std::shared_ptr<Value>> UnpackRpcValues(StringRef packed,
+                                                    ArrayRef<NT_Type> types) {
+  wpi::raw_mem_istream is(packed.data(), packed.size());
+  wpi::Logger logger;
+  WireDecoder dec(is, 0x0300, logger);
+  std::vector<std::shared_ptr<Value>> vec;
+  for (auto type : types) {
+    auto item = dec.ReadValue(type);
+    if (!item) return std::vector<std::shared_ptr<Value>>();
+    vec.emplace_back(std::move(item));
+  }
+  return vec;
+}
+
+uint64_t Now() { return wpi::Now(); }
+
+/*
+ * Client/Server Functions
+ */
+
+void SetNetworkIdentity(StringRef name) {
+  InstanceImpl::GetDefault()->dispatcher.SetIdentity(name);
+}
+
+void SetNetworkIdentity(NT_Inst inst, const Twine& name) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.SetIdentity(name);
+}
+
+unsigned int GetNetworkMode() {
+  return InstanceImpl::GetDefault()->dispatcher.GetNetworkMode();
+}
+
+unsigned int GetNetworkMode(NT_Inst inst) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return 0;
+
+  return ii->dispatcher.GetNetworkMode();
+}
+
+void StartServer(StringRef persist_filename, const char* listen_address,
+                 unsigned int port) {
+  auto ii = InstanceImpl::GetDefault();
+  ii->dispatcher.StartServer(persist_filename, listen_address, port);
+}
+
+void StartServer(NT_Inst inst, const Twine& persist_filename,
+                 const char* listen_address, unsigned int port) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.StartServer(persist_filename, listen_address, port);
+}
+
+void StopServer() { InstanceImpl::GetDefault()->dispatcher.Stop(); }
+
+void StopServer(NT_Inst inst) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.Stop();
+}
+
+void StartClient() { InstanceImpl::GetDefault()->dispatcher.StartClient(); }
+
+void StartClient(NT_Inst inst) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.StartClient();
+}
+
+void StartClient(const char* server_name, unsigned int port) {
+  auto ii = InstanceImpl::GetDefault();
+  ii->dispatcher.SetServer(server_name, port);
+  ii->dispatcher.StartClient();
+}
+
+void StartClient(NT_Inst inst, const char* server_name, unsigned int port) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.SetServer(server_name, port);
+  ii->dispatcher.StartClient();
+}
+
+void StartClient(ArrayRef<std::pair<StringRef, unsigned int>> servers) {
+  auto ii = InstanceImpl::GetDefault();
+  ii->dispatcher.SetServer(servers);
+  ii->dispatcher.StartClient();
+}
+
+void StartClient(NT_Inst inst,
+                 ArrayRef<std::pair<StringRef, unsigned int>> servers) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.SetServer(servers);
+  ii->dispatcher.StartClient();
+}
+
+void StartClientTeam(NT_Inst inst, unsigned int team, unsigned int port) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.SetServerTeam(team, port);
+  ii->dispatcher.StartClient();
+}
+
+void StopClient() { InstanceImpl::GetDefault()->dispatcher.Stop(); }
+
+void StopClient(NT_Inst inst) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.Stop();
+}
+
+void SetServer(const char* server_name, unsigned int port) {
+  InstanceImpl::GetDefault()->dispatcher.SetServer(server_name, port);
+}
+
+void SetServer(NT_Inst inst, const char* server_name, unsigned int port) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.SetServer(server_name, port);
+}
+
+void SetServer(ArrayRef<std::pair<StringRef, unsigned int>> servers) {
+  InstanceImpl::GetDefault()->dispatcher.SetServer(servers);
+}
+
+void SetServer(NT_Inst inst,
+               ArrayRef<std::pair<StringRef, unsigned int>> servers) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.SetServer(servers);
+}
+
+void SetServerTeam(NT_Inst inst, unsigned int team, unsigned int port) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.SetServerTeam(team, port);
+}
+
+void StartDSClient(unsigned int port) {
+  InstanceImpl::GetDefault()->ds_client.Start(port);
+}
+
+void StartDSClient(NT_Inst inst, unsigned int port) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->ds_client.Start(port);
+}
+
+void StopDSClient() { InstanceImpl::GetDefault()->ds_client.Stop(); }
+
+void StopDSClient(NT_Inst inst) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->ds_client.Stop();
+}
+
+void SetUpdateRate(double interval) {
+  InstanceImpl::GetDefault()->dispatcher.SetUpdateRate(interval);
+}
+
+void SetUpdateRate(NT_Inst inst, double interval) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.SetUpdateRate(interval);
+}
+
+void Flush() { InstanceImpl::GetDefault()->dispatcher.Flush(); }
+
+void Flush(NT_Inst inst) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return;
+
+  ii->dispatcher.Flush();
+}
+
+std::vector<ConnectionInfo> GetConnections() {
+  return InstanceImpl::GetDefault()->dispatcher.GetConnections();
+}
+
+std::vector<ConnectionInfo> GetConnections(NT_Inst inst) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return std::vector<ConnectionInfo>{};
+
+  return ii->dispatcher.GetConnections();
+}
+
+bool IsConnected(NT_Inst inst) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return false;
+
+  return ii->dispatcher.IsConnected();
+}
+
+/*
+ * Persistent Functions
+ */
+
+const char* SavePersistent(StringRef filename) {
+  return InstanceImpl::GetDefault()->storage.SavePersistent(filename, false);
+}
+
+const char* SavePersistent(NT_Inst inst, const Twine& filename) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return "invalid instance handle";
+
+  return ii->storage.SavePersistent(filename, false);
+}
+
+const char* LoadPersistent(
+    StringRef filename,
+    std::function<void(size_t line, const char* msg)> warn) {
+  return InstanceImpl::GetDefault()->storage.LoadPersistent(filename, warn);
+}
+
+const char* LoadPersistent(
+    NT_Inst inst, const Twine& filename,
+    std::function<void(size_t line, const char* msg)> warn) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return "invalid instance handle";
+
+  return ii->storage.LoadPersistent(filename, warn);
+}
+
+const char* SaveEntries(NT_Inst inst, const Twine& filename,
+                        const Twine& prefix) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return "invalid instance handle";
+
+  return ii->storage.SaveEntries(filename, prefix);
+}
+
+const char* LoadEntries(
+    NT_Inst inst, const Twine& filename, const Twine& prefix,
+    std::function<void(size_t line, const char* msg)> warn) {
+  auto ii = InstanceImpl::Get(Handle{inst}.GetTypedInst(Handle::kInstance));
+  if (!ii) return "invalid instance handle";
+
+  return ii->storage.LoadEntries(filename, prefix, warn);
+}
+
+void SetLogger(LogFunc func, unsigned int min_level) {
+  auto ii = InstanceImpl::GetDefault();
+  static wpi::mutex mutex;
+  static unsigned int logger = 0;
+  std::lock_guard<wpi::mutex> lock(mutex);
+  if (logger != 0) ii->logger_impl.Remove(logger);
+  logger = ii->logger_impl.Add(
+      [=](const LogMessage& msg) {
+        func(msg.level, msg.filename, msg.line, msg.message.c_str());
+      },
+      min_level, UINT_MAX);
+}
+
+NT_Logger AddLogger(NT_Inst inst,
+                    std::function<void(const LogMessage& msg)> func,
+                    unsigned int min_level, unsigned int max_level) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return 0;
+
+  if (min_level < ii->logger.min_level()) ii->logger.set_min_level(min_level);
+
+  return Handle(i, ii->logger_impl.Add(func, min_level, max_level),
+                Handle::kLogger);
+}
+
+NT_LoggerPoller CreateLoggerPoller(NT_Inst inst) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return 0;
+
+  return Handle(i, ii->logger_impl.CreatePoller(), Handle::kLoggerPoller);
+}
+
+void DestroyLoggerPoller(NT_LoggerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->logger_impl.RemovePoller(id);
+}
+
+NT_Logger AddPolledLogger(NT_LoggerPoller poller, unsigned int min_level,
+                          unsigned int max_level) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
+  int i = handle.GetInst();
+  auto ii = InstanceImpl::Get(i);
+  if (id < 0 || !ii) return 0;
+
+  if (min_level < ii->logger.min_level()) ii->logger.set_min_level(min_level);
+
+  return Handle(i, ii->logger_impl.AddPolled(id, min_level, max_level),
+                Handle::kLogger);
+}
+
+std::vector<LogMessage> PollLogger(NT_LoggerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::vector<LogMessage>{};
+
+  return ii->logger_impl.Poll(static_cast<unsigned int>(id));
+}
+
+std::vector<LogMessage> PollLogger(NT_LoggerPoller poller, double timeout,
+                                   bool* timed_out) {
+  *timed_out = false;
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return std::vector<LogMessage>{};
+
+  return ii->logger_impl.Poll(static_cast<unsigned int>(id), timeout,
+                              timed_out);
+}
+
+void CancelPollLogger(NT_LoggerPoller poller) {
+  Handle handle{poller};
+  int id = handle.GetTypedIndex(Handle::kLoggerPoller);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (id < 0 || !ii) return;
+
+  ii->logger_impl.CancelPoll(id);
+}
+
+void RemoveLogger(NT_Logger logger) {
+  Handle handle{logger};
+  int uid = handle.GetTypedIndex(Handle::kLogger);
+  auto ii = InstanceImpl::Get(handle.GetInst());
+  if (uid < 0 || !ii) return;
+
+  ii->logger_impl.Remove(uid);
+  ii->logger.set_min_level(ii->logger_impl.GetMinLevel());
+}
+
+bool WaitForLoggerQueue(NT_Inst inst, double timeout) {
+  int i = Handle{inst}.GetTypedInst(Handle::kInstance);
+  auto ii = InstanceImpl::Get(i);
+  if (!ii) return true;
+  return ii->logger_impl.WaitForQueue(timeout);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_test.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_test.cpp
new file mode 100644
index 0000000..f74172e
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/ntcore_test.cpp
@@ -0,0 +1,246 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "ntcore_test.h"
+
+#include <wpi/memory.h>
+
+#include "Value_internal.h"
+
+extern "C" {
+struct NT_String* NT_GetStringForTesting(const char* string, int* struct_size) {
+  struct NT_String* str =
+      static_cast<NT_String*>(wpi::CheckedCalloc(1, sizeof(NT_String)));
+  nt::ConvertToC(wpi::StringRef(string), str);
+  *struct_size = sizeof(NT_String);
+  return str;
+}
+
+struct NT_EntryInfo* NT_GetEntryInfoForTesting(const char* name,
+                                               enum NT_Type type,
+                                               unsigned int flags,
+                                               uint64_t last_change,
+                                               int* struct_size) {
+  struct NT_EntryInfo* entry_info =
+      static_cast<NT_EntryInfo*>(wpi::CheckedCalloc(1, sizeof(NT_EntryInfo)));
+  nt::ConvertToC(wpi::StringRef(name), &entry_info->name);
+  entry_info->type = type;
+  entry_info->flags = flags;
+  entry_info->last_change = last_change;
+  *struct_size = sizeof(NT_EntryInfo);
+  return entry_info;
+}
+
+void NT_FreeEntryInfoForTesting(struct NT_EntryInfo* info) {
+  std::free(info->name.str);
+  std::free(info);
+}
+
+struct NT_ConnectionInfo* NT_GetConnectionInfoForTesting(
+    const char* remote_id, const char* remote_ip, unsigned int remote_port,
+    uint64_t last_update, unsigned int protocol_version, int* struct_size) {
+  struct NT_ConnectionInfo* conn_info = static_cast<NT_ConnectionInfo*>(
+      wpi::CheckedCalloc(1, sizeof(NT_ConnectionInfo)));
+  nt::ConvertToC(wpi::StringRef(remote_id), &conn_info->remote_id);
+  nt::ConvertToC(wpi::StringRef(remote_ip), &conn_info->remote_ip);
+  conn_info->remote_port = remote_port;
+  conn_info->last_update = last_update;
+  conn_info->protocol_version = protocol_version;
+  *struct_size = sizeof(NT_ConnectionInfo);
+  return conn_info;
+}
+
+void NT_FreeConnectionInfoForTesting(struct NT_ConnectionInfo* info) {
+  std::free(info->remote_id.str);
+  std::free(info->remote_ip.str);
+  std::free(info);
+}
+
+struct NT_Value* NT_GetValueBooleanForTesting(uint64_t last_change, int val,
+                                              int* struct_size) {
+  struct NT_Value* value =
+      static_cast<NT_Value*>(wpi::CheckedCalloc(1, sizeof(NT_Value)));
+  value->type = NT_BOOLEAN;
+  value->last_change = last_change;
+  value->data.v_boolean = val;
+  *struct_size = sizeof(NT_Value);
+  return value;
+}
+
+struct NT_Value* NT_GetValueDoubleForTesting(uint64_t last_change, double val,
+                                             int* struct_size) {
+  struct NT_Value* value =
+      static_cast<NT_Value*>(wpi::CheckedCalloc(1, sizeof(NT_Value)));
+  value->type = NT_DOUBLE;
+  value->last_change = last_change;
+  value->data.v_double = val;
+  *struct_size = sizeof(NT_Value);
+  return value;
+}
+
+struct NT_Value* NT_GetValueStringForTesting(uint64_t last_change,
+                                             const char* str,
+                                             int* struct_size) {
+  struct NT_Value* value =
+      static_cast<NT_Value*>(wpi::CheckedCalloc(1, sizeof(NT_Value)));
+  value->type = NT_STRING;
+  value->last_change = last_change;
+  nt::ConvertToC(wpi::StringRef(str), &value->data.v_string);
+  *struct_size = sizeof(NT_Value);
+  return value;
+}
+
+struct NT_Value* NT_GetValueRawForTesting(uint64_t last_change, const char* raw,
+                                          int raw_len, int* struct_size) {
+  struct NT_Value* value =
+      static_cast<NT_Value*>(wpi::CheckedCalloc(1, sizeof(NT_Value)));
+  value->type = NT_RAW;
+  value->last_change = last_change;
+  nt::ConvertToC(wpi::StringRef(raw, raw_len), &value->data.v_string);
+  *struct_size = sizeof(NT_Value);
+  return value;
+}
+
+struct NT_Value* NT_GetValueBooleanArrayForTesting(uint64_t last_change,
+                                                   const int* arr,
+                                                   size_t array_len,
+                                                   int* struct_size) {
+  struct NT_Value* value =
+      static_cast<NT_Value*>(wpi::CheckedCalloc(1, sizeof(NT_Value)));
+  value->type = NT_BOOLEAN_ARRAY;
+  value->last_change = last_change;
+  value->data.arr_boolean.arr = NT_AllocateBooleanArray(array_len);
+  value->data.arr_boolean.size = array_len;
+  std::memcpy(value->data.arr_boolean.arr, arr,
+              value->data.arr_boolean.size * sizeof(int));
+  *struct_size = sizeof(NT_Value);
+  return value;
+}
+
+struct NT_Value* NT_GetValueDoubleArrayForTesting(uint64_t last_change,
+                                                  const double* arr,
+                                                  size_t array_len,
+                                                  int* struct_size) {
+  struct NT_Value* value =
+      static_cast<NT_Value*>(wpi::CheckedCalloc(1, sizeof(NT_Value)));
+  value->type = NT_BOOLEAN;
+  value->last_change = last_change;
+  value->data.arr_double.arr = NT_AllocateDoubleArray(array_len);
+  value->data.arr_double.size = array_len;
+  std::memcpy(value->data.arr_double.arr, arr,
+              value->data.arr_double.size * sizeof(int));
+  *struct_size = sizeof(NT_Value);
+  return value;
+}
+
+struct NT_Value* NT_GetValueStringArrayForTesting(uint64_t last_change,
+                                                  const struct NT_String* arr,
+                                                  size_t array_len,
+                                                  int* struct_size) {
+  struct NT_Value* value =
+      static_cast<NT_Value*>(wpi::CheckedCalloc(1, sizeof(NT_Value)));
+  value->type = NT_BOOLEAN;
+  value->last_change = last_change;
+  value->data.arr_string.arr = NT_AllocateStringArray(array_len);
+  value->data.arr_string.size = array_len;
+  for (size_t i = 0; i < value->data.arr_string.size; ++i) {
+    size_t len = arr[i].len;
+    value->data.arr_string.arr[i].len = len;
+    value->data.arr_string.arr[i].str =
+        static_cast<char*>(wpi::CheckedMalloc(len + 1));
+    std::memcpy(value->data.arr_string.arr[i].str, arr[i].str, len + 1);
+  }
+  *struct_size = sizeof(NT_Value);
+  return value;
+}
+// No need for free as one already exists in the main library
+
+static void CopyNtValue(const struct NT_Value* copy_from,
+                        struct NT_Value* copy_to) {
+  auto cpp_value = nt::ConvertFromC(*copy_from);
+  nt::ConvertToC(*cpp_value, copy_to);
+}
+
+static void CopyNtString(const struct NT_String* copy_from,
+                         struct NT_String* copy_to) {
+  nt::ConvertToC(wpi::StringRef(copy_from->str, copy_from->len), copy_to);
+}
+
+struct NT_RpcParamDef* NT_GetRpcParamDefForTesting(const char* name,
+                                                   const struct NT_Value* val,
+                                                   int* struct_size) {
+  struct NT_RpcParamDef* def = static_cast<NT_RpcParamDef*>(
+      wpi::CheckedCalloc(1, sizeof(NT_RpcParamDef)));
+  nt::ConvertToC(wpi::StringRef(name), &def->name);
+  CopyNtValue(val, &def->def_value);
+  *struct_size = sizeof(NT_RpcParamDef);
+  return def;
+}
+
+void NT_FreeRpcParamDefForTesting(struct NT_RpcParamDef* def) {
+  NT_DisposeValue(&def->def_value);
+  NT_DisposeString(&def->name);
+  std::free(def);
+}
+
+struct NT_RpcResultDef* NT_GetRpcResultsDefForTesting(const char* name,
+                                                      enum NT_Type type,
+                                                      int* struct_size) {
+  struct NT_RpcResultDef* def = static_cast<NT_RpcResultDef*>(
+      wpi::CheckedCalloc(1, sizeof(NT_RpcResultDef)));
+  nt::ConvertToC(wpi::StringRef(name), &def->name);
+  def->type = type;
+  *struct_size = sizeof(NT_RpcResultDef);
+  return def;
+}
+
+void NT_FreeRpcResultsDefForTesting(struct NT_RpcResultDef* def) {
+  NT_DisposeString(&def->name);
+  std::free(def);
+}
+
+struct NT_RpcDefinition* NT_GetRpcDefinitionForTesting(
+    unsigned int version, const char* name, size_t num_params,
+    const struct NT_RpcParamDef* params, size_t num_results,
+    const struct NT_RpcResultDef* results, int* struct_size) {
+  struct NT_RpcDefinition* def = static_cast<NT_RpcDefinition*>(
+      wpi::CheckedCalloc(1, sizeof(NT_RpcDefinition)));
+  def->version = version;
+  nt::ConvertToC(wpi::StringRef(name), &def->name);
+  def->num_params = num_params;
+  def->params = static_cast<NT_RpcParamDef*>(
+      wpi::CheckedMalloc(num_params * sizeof(NT_RpcParamDef)));
+  for (size_t i = 0; i < num_params; ++i) {
+    CopyNtString(&params[i].name, &def->params[i].name);
+    CopyNtValue(&params[i].def_value, &def->params[i].def_value);
+  }
+  def->num_results = num_results;
+  def->results = static_cast<NT_RpcResultDef*>(
+      wpi::CheckedMalloc(num_results * sizeof(NT_RpcResultDef)));
+  for (size_t i = 0; i < num_results; ++i) {
+    CopyNtString(&results[i].name, &def->results[i].name);
+    def->results[i].type = results[i].type;
+  }
+  *struct_size = sizeof(NT_RpcDefinition);
+  return def;
+}
+// No need for free as one already exists in the main library
+
+struct NT_RpcAnswer* NT_GetRpcAnswerForTesting(
+    unsigned int rpc_id, unsigned int call_uid, const char* name,
+    const char* params, size_t params_len, int* struct_size) {
+  struct NT_RpcAnswer* info =
+      static_cast<NT_RpcAnswer*>(wpi::CheckedCalloc(1, sizeof(NT_RpcAnswer)));
+  info->entry = rpc_id;
+  info->call = call_uid;
+  nt::ConvertToC(wpi::StringRef(name), &info->name);
+  nt::ConvertToC(wpi::StringRef(params, params_len), &info->params);
+  *struct_size = sizeof(NT_RpcAnswer);
+  return info;
+}
+// No need for free as one already exists in the main library
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/cpp/tables/ITableListener.cpp b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/tables/ITableListener.cpp
new file mode 100644
index 0000000..6abd3bb
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/cpp/tables/ITableListener.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "tables/ITableListener.h"
+
+#include "ntcore_c.h"
+
+void ITableListener::ValueChangedEx(ITable* source, wpi::StringRef key,
+                                    std::shared_ptr<nt::Value> value,
+                                    unsigned int flags) {
+  ValueChanged(source, key, value, (flags & NT_NOTIFY_NEW) != 0);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/EntryListenerFlags.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/EntryListenerFlags.h
new file mode 100644
index 0000000..c5cc620
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/EntryListenerFlags.h
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_ENTRYLISTENERFLAGS_H_
+#define NTCORE_NETWORKTABLES_ENTRYLISTENERFLAGS_H_
+
+#include "ntcore_c.h"
+
+namespace nt {
+
+/** Entry listener flags */
+namespace EntryListenerFlags {
+
+/**
+ * Flag values for use with entry listeners.
+ *
+ * The flags are a bitmask and must be OR'ed together to indicate the
+ * combination of events desired to be received.
+ *
+ * The constants kNew, kDelete, kUpdate, and kFlags represent different events
+ * that can occur to entries.
+ *
+ * By default, notifications are only generated for remote changes occurring
+ * after the listener is created.  The constants kImmediate and kLocal are
+ * modifiers that cause notifications to be generated at other times.
+ *
+ * @ingroup ntcore_cpp_api
+ */
+enum {
+  /**
+   * Initial listener addition.
+   * Set this flag to receive immediate notification of entries matching the
+   * flag criteria (generally only useful when combined with kNew).
+   */
+  kImmediate = NT_NOTIFY_IMMEDIATE,
+
+  /**
+   * Changed locally.
+   * Set this flag to receive notification of both local changes and changes
+   * coming from remote nodes.  By default, notifications are only generated
+   * for remote changes.  Must be combined with some combination of kNew,
+   * kDelete, kUpdate, and kFlags to receive notifications of those respective
+   * events.
+   */
+  kLocal = NT_NOTIFY_LOCAL,
+
+  /**
+   * Newly created entry.
+   * Set this flag to receive a notification when an entry is created.
+   */
+  kNew = NT_NOTIFY_NEW,
+
+  /**
+   * Entry was deleted.
+   * Set this flag to receive a notification when an entry is deleted.
+   */
+  kDelete = NT_NOTIFY_DELETE,
+
+  /**
+   * Entry's value changed.
+   * Set this flag to receive a notification when an entry's value (or type)
+   * changes.
+   */
+  kUpdate = NT_NOTIFY_UPDATE,
+
+  /**
+   * Entry's flags changed.
+   * Set this flag to receive a notification when an entry's flags value
+   * changes.
+   */
+  kFlags = NT_NOTIFY_FLAGS
+};
+
+}  // namespace EntryListenerFlags
+
+}  // namespace nt
+
+#endif  // NTCORE_NETWORKTABLES_ENTRYLISTENERFLAGS_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTable.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTable.h
new file mode 100644
index 0000000..6bc2af6
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTable.h
@@ -0,0 +1,777 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_NETWORKTABLE_H_
+#define NTCORE_NETWORKTABLES_NETWORKTABLE_H_
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "networktables/NetworkTableEntry.h"
+#include "networktables/TableEntryListener.h"
+#include "networktables/TableListener.h"
+#include "ntcore_c.h"
+#include "tables/ITable.h"
+
+namespace nt {
+
+using wpi::ArrayRef;
+using wpi::StringRef;
+using wpi::Twine;
+
+class NetworkTableInstance;
+
+#ifdef __GNUC__
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
+#endif
+
+/**
+ * @defgroup ntcore_cpp_api ntcore C++ object-oriented API
+ *
+ * Recommended interface for C++, identical to Java API.
+ */
+
+/**
+ * A network table that knows its subtable path.
+ * @ingroup ntcore_cpp_api
+ */
+class NetworkTable final : public ITable {
+ private:
+  NT_Inst m_inst;
+  std::string m_path;
+  mutable wpi::mutex m_mutex;
+  mutable wpi::StringMap<NT_Entry> m_entries;
+  typedef std::pair<ITableListener*, NT_EntryListener> Listener;
+  std::vector<Listener> m_listeners;
+  std::vector<NT_EntryListener> m_lambdaListeners;
+
+  static std::vector<std::string> s_ip_addresses;
+  static std::string s_persistent_filename;
+  static bool s_client;
+  static bool s_enable_ds;
+  static bool s_running;
+  static unsigned int s_port;
+
+  struct private_init {};
+  friend class NetworkTableInstance;
+
+ public:
+  /**
+   * Gets the "base name" of a key. For example, "/foo/bar" becomes "bar".
+   * If the key has a trailing slash, returns an empty string.
+   *
+   * @param key key
+   * @return base name
+   */
+  static StringRef BasenameKey(StringRef key);
+
+  /**
+   * Normalizes an network table key to contain no consecutive slashes and
+   * optionally start with a leading slash. For example:
+   *
+   * <pre><code>
+   * normalizeKey("/foo/bar", true)  == "/foo/bar"
+   * normalizeKey("foo/bar", true)   == "/foo/bar"
+   * normalizeKey("/foo/bar", false) == "foo/bar"
+   * normalizeKey("foo//bar", false) == "foo/bar"
+   * </code></pre>
+   *
+   * @param key              the key to normalize
+   * @param withLeadingSlash whether or not the normalized key should begin
+   *                         with a leading slash
+   * @return normalized key
+   */
+  static std::string NormalizeKey(const Twine& key,
+                                  bool withLeadingSlash = true);
+
+  static StringRef NormalizeKey(const Twine& key,
+                                wpi::SmallVectorImpl<char>& buf,
+                                bool withLeadingSlash = true);
+
+  /**
+   * Gets a list of the names of all the super tables of a given key. For
+   * example, the key "/foo/bar/baz" has a hierarchy of "/", "/foo",
+   * "/foo/bar", and "/foo/bar/baz".
+   *
+   * @param key the key
+   * @return List of super tables
+   */
+  static std::vector<std::string> GetHierarchy(const Twine& key);
+
+  /**
+   * Constructor.  Use NetworkTableInstance::GetTable() or GetSubTable()
+   * instead.
+   */
+  NetworkTable(NT_Inst inst, const Twine& path, const private_init&);
+  virtual ~NetworkTable();
+
+  /**
+   * Gets the instance for the table.
+   *
+   * @return Instance
+   */
+  NetworkTableInstance GetInstance() const;
+
+  /**
+   * The path separator for sub-tables and keys
+   */
+  static const char PATH_SEPARATOR_CHAR;
+
+  /**
+   * Initializes network tables
+   */
+  WPI_DEPRECATED(
+      "use NetworkTableInstance::StartServer() or "
+      "NetworkTableInstance::StartClient() instead")
+  static void Initialize();
+
+  /**
+   * Shuts down network tables
+   */
+  WPI_DEPRECATED(
+      "use NetworkTableInstance::StopServer() or "
+      "NetworkTableInstance::StopClient() instead")
+  static void Shutdown();
+
+  /**
+   * set that network tables should be a client
+   * This must be called before initialize or GetTable
+   */
+  WPI_DEPRECATED("use NetworkTableInstance::StartClient() instead")
+  static void SetClientMode();
+
+  /**
+   * set that network tables should be a server
+   * This must be called before initialize or GetTable
+   */
+  WPI_DEPRECATED("use NetworkTableInstance::StartServer() instead")
+  static void SetServerMode();
+
+  /**
+   * set the team the robot is configured for (this will set the mdns address
+   * that network tables will connect to in client mode)
+   * This must be called before initialize or GetTable
+   *
+   * @param team the team number
+   */
+  WPI_DEPRECATED(
+      "use NetworkTableInstance::SetServerTeam() or "
+      "NetworkTableInstance::StartClientTeam() instead")
+  static void SetTeam(int team);
+
+  /**
+   * @param address the adress that network tables will connect to in client
+   * mode
+   */
+  WPI_DEPRECATED(
+      "use NetworkTableInstance::SetServer() or "
+      "NetworkTableInstance::StartClient() instead")
+  static void SetIPAddress(StringRef address);
+
+  /**
+   * @param addresses the addresses that network tables will connect to in
+   * client mode (in round robin order)
+   */
+  WPI_DEPRECATED(
+      "use NetworkTableInstance::SetServer() or "
+      "NetworkTableInstance::StartClient() instead")
+  static void SetIPAddress(ArrayRef<std::string> addresses);
+
+  /**
+   * Set the port number that network tables will connect to in client
+   * mode or listen to in server mode.
+   *
+   * @param port the port number
+   */
+  WPI_DEPRECATED(
+      "use the appropriate parameters to NetworkTableInstance::SetServer(), "
+      "NetworkTableInstance::StartClient(), "
+      "NetworkTableInstance::StartServer(), and "
+      "NetworkTableInstance::StartDSClient() instead")
+  static void SetPort(unsigned int port);
+
+  /**
+   * Enable requesting the server address from the Driver Station.
+   *
+   * @param enabled whether to enable the connection to the local DS
+   */
+  WPI_DEPRECATED(
+      "use NetworkTableInstance::StartDSClient() and "
+      "NetworkTableInstance::StopDSClient() instead")
+  static void SetDSClientEnabled(bool enabled);
+
+  /**
+   * Sets the persistent filename.
+   *
+   * @param filename the filename that the network tables server uses for
+   * automatic loading and saving of persistent values
+   */
+  WPI_DEPRECATED(
+      "use the appropriate parameter to NetworkTableInstance::StartServer() "
+      "instead")
+  static void SetPersistentFilename(StringRef filename);
+
+  /**
+   * Sets the network identity.
+   * This is provided in the connection info on the remote end.
+   *
+   * @param name identity
+   */
+  WPI_DEPRECATED("use NetworkTableInstance::SetNetworkIdentity() instead")
+  static void SetNetworkIdentity(StringRef name);
+
+  /**
+   * Deletes ALL keys in ALL subtables.  Use with caution!
+   */
+  WPI_DEPRECATED("use NetworkTableInstance::DeleteAllEntries() instead")
+  static void GlobalDeleteAll();
+
+  /**
+   * Flushes all updated values immediately to the network.
+   * Note: This is rate-limited to protect the network from flooding.
+   * This is primarily useful for synchronizing network updates with
+   * user code.
+   */
+  WPI_DEPRECATED("use NetworkTableInstance::Flush() instead")
+  static void Flush();
+
+  /**
+   * Set the periodic update rate.
+   * Sets how frequently updates are sent to other nodes over the network.
+   *
+   * @param interval update interval in seconds (range 0.01 to 1.0)
+   */
+  WPI_DEPRECATED("use NetworkTableInstance::SetUpdateRate() instead")
+  static void SetUpdateRate(double interval);
+
+  /**
+   * Saves persistent keys to a file.  The server does this automatically.
+   *
+   * @param filename file name
+   * @return Error (or nullptr).
+   */
+  WPI_DEPRECATED("use NetworkTableInstance::SavePersistent() instead")
+  static const char* SavePersistent(StringRef filename);
+
+  /**
+   * Loads persistent keys from a file.  The server does this automatically.
+   *
+   * @param filename file name
+   * @param warn callback function called for warnings
+   * @return Error (or nullptr).
+   */
+  WPI_DEPRECATED("use NetworkTableInstance::LoadPersistent() instead")
+  static const char* LoadPersistent(
+      StringRef filename,
+      std::function<void(size_t line, const char* msg)> warn);
+
+  /**
+   * Gets the table with the specified key. If the table does not exist, a new
+   * table will be created.<br>
+   * This will automatically initialize network tables if it has not been
+   * already.
+   *
+   * @param key  the key name
+   * @return the network table requested
+   */
+  WPI_DEPRECATED(
+      "use NetworkTableInstance::GetTable() or "
+      "NetworkTableInstance::GetEntry() instead")
+  static std::shared_ptr<NetworkTable> GetTable(StringRef key);
+
+  /**
+   * Gets the entry for a subkey.
+   *
+   * @param key the key name
+   * @return Network table entry.
+   */
+  NetworkTableEntry GetEntry(const Twine& key) const;
+
+  /**
+   * Listen to keys only within this table.
+   *
+   * @param listener    listener to add
+   * @param flags       EntryListenerFlags bitmask
+   * @return Listener handle
+   */
+  NT_EntryListener AddEntryListener(TableEntryListener listener,
+                                    unsigned int flags) const;
+
+  /**
+   * Listen to a single key.
+   *
+   * @param key         the key name
+   * @param listener    listener to add
+   * @param flags       EntryListenerFlags bitmask
+   * @return Listener handle
+   */
+  NT_EntryListener AddEntryListener(const Twine& key,
+                                    TableEntryListener listener,
+                                    unsigned int flags) const;
+
+  /**
+   * Remove an entry listener.
+   *
+   * @param listener    listener handle
+   */
+  void RemoveEntryListener(NT_EntryListener listener) const;
+
+  /**
+   * Listen for sub-table creation.
+   * This calls the listener once for each newly created sub-table.
+   * It immediately calls the listener for any existing sub-tables.
+   *
+   * @param listener        listener to add
+   * @param localNotify     notify local changes as well as remote
+   * @return Listener handle
+   */
+  NT_EntryListener AddSubTableListener(TableListener listener,
+                                       bool localNotify = false);
+
+  /**
+   * Remove a sub-table listener.
+   *
+   * @param listener    listener handle
+   */
+  void RemoveTableListener(NT_EntryListener listener);
+
+  WPI_DEPRECATED(
+      "use AddEntryListener() instead with flags value of NT_NOTIFY_NEW | "
+      "NT_NOTIFY_UPDATE")
+  void AddTableListener(ITableListener* listener) override;
+
+  WPI_DEPRECATED(
+      "use AddEntryListener() instead with flags value of NT_NOTIFY_NEW | "
+      "NT_NOTIFY_UPDATE | NT_NOTIFY_IMMEDIATE")
+  void AddTableListener(ITableListener* listener,
+                        bool immediateNotify) override;
+
+  WPI_DEPRECATED("use AddEntryListener() instead")
+  void AddTableListenerEx(ITableListener* listener,
+                          unsigned int flags) override;
+
+  WPI_DEPRECATED("use AddEntryListener() instead")
+  void AddTableListener(StringRef key, ITableListener* listener,
+                        bool immediateNotify) override;
+
+  WPI_DEPRECATED("use AddEntryListener() instead")
+  void AddTableListenerEx(StringRef key, ITableListener* listener,
+                          unsigned int flags) override;
+
+  WPI_DEPRECATED("use AddSubTableListener(TableListener, bool) instead")
+  void AddSubTableListener(ITableListener* listener) override;
+
+  WPI_DEPRECATED("use AddSubTableListener(TableListener, bool) instead")
+  void AddSubTableListener(ITableListener* listener, bool localNotify) override;
+
+  WPI_DEPRECATED("use RemoveTableListener(NT_EntryListener) instead")
+  void RemoveTableListener(ITableListener* listener) override;
+
+  /**
+   * Returns the table at the specified key. If there is no table at the
+   * specified key, it will create a new table
+   *
+   * @param key the key name
+   * @return the networktable to be returned
+   */
+  std::shared_ptr<NetworkTable> GetSubTable(const Twine& key) const override;
+
+  /**
+   * Determines whether the given key is in this table.
+   *
+   * @param key the key to search for
+   * @return true if the table as a value assigned to the given key
+   */
+  bool ContainsKey(const Twine& key) const override;
+
+  /**
+   * Determines whether there exists a non-empty subtable for this key
+   * in this table.
+   *
+   * @param key the key to search for
+   * @return true if there is a subtable with the key which contains at least
+   * one key/subtable of its own
+   */
+  bool ContainsSubTable(const Twine& key) const override;
+
+  /**
+   * Gets all keys in the table (not including sub-tables).
+   *
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return keys currently in the table
+   */
+  std::vector<std::string> GetKeys(int types = 0) const override;
+
+  /**
+   * Gets the names of all subtables in the table.
+   *
+   * @return subtables currently in the table
+   */
+  std::vector<std::string> GetSubTables() const override;
+
+  /**
+   * Makes a key's value persistent through program restarts.
+   *
+   * @param key the key to make persistent
+   */
+  void SetPersistent(StringRef key) override;
+
+  /**
+   * Stop making a key's value persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  void ClearPersistent(StringRef key) override;
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  bool IsPersistent(StringRef key) const override;
+
+  /**
+   * Sets flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to set (bitmask)
+   */
+  void SetFlags(StringRef key, unsigned int flags) override;
+
+  /**
+   * Clears flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to clear (bitmask)
+   */
+  void ClearFlags(StringRef key, unsigned int flags) override;
+
+  /**
+   * Returns the flags for the specified key.
+   *
+   * @param key the key name
+   * @return the flags, or 0 if the key is not defined
+   */
+  unsigned int GetFlags(StringRef key) const override;
+
+  /**
+   * Deletes the specified key in this table.
+   *
+   * @param key the key name
+   */
+  void Delete(const Twine& key) override;
+
+  /**
+   * Put a number in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  bool PutNumber(StringRef key, double value) override;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  bool SetDefaultNumber(StringRef key, double defaultValue) override;
+
+  /**
+   * Gets the number associated with the given name.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  double GetNumber(StringRef key, double defaultValue) const override;
+
+  /**
+   * Put a string in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  bool PutString(StringRef key, StringRef value) override;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  bool SetDefaultString(StringRef key, StringRef defaultValue) override;
+
+  /**
+   * Gets the string associated with the given name. If the key does not
+   * exist or is of different type, it will return the default value.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  std::string GetString(StringRef key, StringRef defaultValue) const override;
+
+  /**
+   * Put a boolean in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  bool PutBoolean(StringRef key, bool value) override;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  bool SetDefaultBoolean(StringRef key, bool defaultValue) override;
+
+  /**
+   * Gets the boolean associated with the given name. If the key does not
+   * exist or is of different type, it will return the default value.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  bool GetBoolean(StringRef key, bool defaultValue) const override;
+
+  /**
+   * Put a boolean array in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   *
+   * @note The array must be of int's rather than of bool's because
+   *       std::vector<bool> is special-cased in C++.  0 is false, any
+   *       non-zero value is true.
+   */
+  bool PutBooleanArray(StringRef key, ArrayRef<int> value) override;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @return False if the table key exists with a different type
+   */
+  bool SetDefaultBooleanArray(StringRef key,
+                              ArrayRef<int> defaultValue) override;
+
+  /**
+   * Returns the boolean array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   *
+   * @note The returned array is std::vector<int> instead of std::vector<bool>
+   *       because std::vector<bool> is special-cased in C++.  0 is false, any
+   *       non-zero value is true.
+   */
+  std::vector<int> GetBooleanArray(StringRef key,
+                                   ArrayRef<int> defaultValue) const override;
+
+  /**
+   * Put a number array in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  bool PutNumberArray(StringRef key, ArrayRef<double> value) override;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  bool SetDefaultNumberArray(StringRef key,
+                             ArrayRef<double> defaultValue) override;
+
+  /**
+   * Returns the number array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<double> GetNumberArray(
+      StringRef key, ArrayRef<double> defaultValue) const override;
+
+  /**
+   * Put a string array in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  bool PutStringArray(StringRef key, ArrayRef<std::string> value) override;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  bool SetDefaultStringArray(StringRef key,
+                             ArrayRef<std::string> defaultValue) override;
+
+  /**
+   * Returns the string array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<std::string> GetStringArray(
+      StringRef key, ArrayRef<std::string> defaultValue) const override;
+
+  /**
+   * Put a raw value (byte array) in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  bool PutRaw(StringRef key, StringRef value) override;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @return False if the table key exists with a different type
+   */
+  bool SetDefaultRaw(StringRef key, StringRef defaultValue) override;
+
+  /**
+   * Returns the raw value (byte array) the key maps to. If the key does not
+   * exist or is of different type, it will return the default value.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the raw contents.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::string GetRaw(StringRef key, StringRef defaultValue) const override;
+
+  /**
+   * Put a value in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  bool PutValue(const Twine& key, std::shared_ptr<Value> value) override;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @return False if the table key exists with a different type
+   */
+  bool SetDefaultValue(const Twine& key,
+                       std::shared_ptr<Value> defaultValue) override;
+
+  /**
+   * Gets the value associated with a key as an object
+   *
+   * @param key the key of the value to look up
+   * @return the value associated with the given key, or nullptr if the key
+   * does not exist
+   */
+  std::shared_ptr<Value> GetValue(const Twine& key) const override;
+
+  /**
+   * Gets the full path of this table.  Does not include the trailing "/".
+   *
+   * @return The path (e.g "", "/foo").
+   */
+  StringRef GetPath() const override;
+
+  /**
+   * Save table values to a file.  The file format used is identical to
+   * that used for SavePersistent.
+   *
+   * @param filename  filename
+   * @return error string, or nullptr if successful
+   */
+  const char* SaveEntries(const Twine& filename) const;
+
+  /**
+   * Load table values from a file.  The file format used is identical to
+   * that used for SavePersistent / LoadPersistent.
+   *
+   * @param filename  filename
+   * @param warn      callback function for warnings
+   * @return error string, or nullptr if successful
+   */
+  const char* LoadEntries(
+      const Twine& filename,
+      std::function<void(size_t line, const char* msg)> warn);
+};
+
+#ifdef __GNUC__
+#pragma GCC diagnostic pop
+#endif
+
+}  // namespace nt
+
+// For backwards compatability
+#ifndef NAMESPACED_NT
+using nt::NetworkTable;  // NOLINT
+#endif
+
+#endif  // NTCORE_NETWORKTABLES_NETWORKTABLE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableEntry.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableEntry.h
new file mode 100644
index 0000000..16b5c61
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableEntry.h
@@ -0,0 +1,500 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_H_
+#define NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_H_
+
+#include <stdint.h>
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "networktables/NetworkTableType.h"
+#include "networktables/NetworkTableValue.h"
+#include "networktables/RpcCall.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+using wpi::ArrayRef;
+using wpi::StringRef;
+using wpi::Twine;
+
+class NetworkTableInstance;
+
+/**
+ * NetworkTables Entry
+ * @ingroup ntcore_cpp_api
+ */
+class NetworkTableEntry final {
+ public:
+  /**
+   * Flag values (as returned by GetFlags()).
+   */
+  enum Flags { kPersistent = NT_PERSISTENT };
+
+  /**
+   * Construct invalid instance.
+   */
+  NetworkTableEntry();
+
+  /**
+   * Construct from native handle.
+   *
+   * @param handle Native handle
+   */
+  explicit NetworkTableEntry(NT_Entry handle);
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_handle != 0; }
+
+  /**
+   * Gets the native handle for the entry.
+   *
+   * @return Native handle
+   */
+  NT_Entry GetHandle() const;
+
+  /**
+   * Gets the instance for the entry.
+   *
+   * @return Instance
+   */
+  NetworkTableInstance GetInstance() const;
+
+  /**
+   * Determines if the entry currently exists.
+   *
+   * @return True if the entry exists, false otherwise.
+   */
+  bool Exists() const;
+
+  /**
+   * Gets the name of the entry (the key).
+   *
+   * @return the entry's name
+   */
+  std::string GetName() const;
+
+  /**
+   * Gets the type of the entry.
+   *
+   * @return the entry's type
+   */
+  NetworkTableType GetType() const;
+
+  /**
+   * Returns the flags.
+   *
+   * @return the flags (bitmask)
+   */
+  unsigned int GetFlags() const;
+
+  /**
+   * Gets the last time the entry's value was changed.
+   *
+   * @return Entry last change time
+   */
+  uint64_t GetLastChange() const;
+
+  /**
+   * Gets combined information about the entry.
+   *
+   * @return Entry information
+   */
+  EntryInfo GetInfo() const;
+
+  /**
+   * Gets the entry's value. If the entry does not exist, returns nullptr.
+   *
+   * @return the entry's value or nullptr if it does not exist.
+   */
+  std::shared_ptr<Value> GetValue() const;
+
+  /**
+   * Gets the entry's value as a boolean. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  bool GetBoolean(bool defaultValue) const;
+
+  /**
+   * Gets the entry's value as a double. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  double GetDouble(double defaultValue) const;
+
+  /**
+   * Gets the entry's value as a string. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  std::string GetString(StringRef defaultValue) const;
+
+  /**
+   * Gets the entry's value as a raw. If the entry does not exist or is of
+   * different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   */
+  std::string GetRaw(StringRef defaultValue) const;
+
+  /**
+   * Gets the entry's value as a boolean array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   *
+   * @note The returned array is std::vector<int> instead of std::vector<bool>
+   *       because std::vector<bool> is special-cased in C++.  0 is false, any
+   *       non-zero value is true.
+   */
+  std::vector<int> GetBooleanArray(ArrayRef<int> defaultValue) const;
+
+  /**
+   * Gets the entry's value as a double array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<double> GetDoubleArray(ArrayRef<double> defaultValue) const;
+
+  /**
+   * Gets the entry's value as a string array. If the entry does not exist
+   * or is of different type, it will return the default value.
+   *
+   * @param defaultValue the value to be returned if no value is found
+   * @return the entry's value or the given default value
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  std::vector<std::string> GetStringArray(
+      ArrayRef<std::string> defaultValue) const;
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultValue(std::shared_ptr<Value> value);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultBoolean(bool defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultDouble(double defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultString(const Twine& defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultRaw(StringRef defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultBooleanArray(ArrayRef<int> defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultDoubleArray(ArrayRef<double> defaultValue);
+
+  /**
+   * Sets the entry's value if it does not exist.
+   *
+   * @param defaultValue the default value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDefaultStringArray(ArrayRef<std::string> defaultValue);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetValue(std::shared_ptr<Value> value);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetBoolean(bool value);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDouble(double value);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetString(const Twine& value);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetRaw(StringRef value);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetBooleanArray(ArrayRef<int> value);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetDoubleArray(ArrayRef<double> value);
+
+  /**
+   * Sets the entry's value.
+   *
+   * @param value the value to set
+   * @return False if the entry exists with a different type
+   */
+  bool SetStringArray(ArrayRef<std::string> value);
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  void ForceSetValue(std::shared_ptr<Value> value);
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  void ForceSetBoolean(bool value);
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  void ForceSetDouble(double value);
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  void ForceSetString(const Twine& value);
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  void ForceSetRaw(StringRef value);
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  void ForceSetBooleanArray(ArrayRef<int> value);
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  void ForceSetDoubleArray(ArrayRef<double> value);
+
+  /**
+   * Sets the entry's value.  If the value is of different type, the type is
+   * changed to match the new value.
+   *
+   * @param value the value to set
+   */
+  void ForceSetStringArray(ArrayRef<std::string> value);
+
+  /**
+   * Sets flags.
+   *
+   * @param flags the flags to set (bitmask)
+   */
+  void SetFlags(unsigned int flags);
+
+  /**
+   * Clears flags.
+   *
+   * @param flags the flags to clear (bitmask)
+   */
+  void ClearFlags(unsigned int flags);
+
+  /**
+   * Make value persistent through program restarts.
+   */
+  void SetPersistent();
+
+  /**
+   * Stop making value persistent through program restarts.
+   */
+  void ClearPersistent();
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   *
+   * @return True if the value is persistent.
+   */
+  bool IsPersistent() const;
+
+  /**
+   * Deletes the entry.
+   */
+  void Delete();
+
+  /**
+   * Create a callback-based RPC entry point.  Only valid to use on the server.
+   * The callback function will be called when the RPC is called.
+   * This function creates RPC version 0 definitions (raw data in and out).
+   *
+   * @param callback  callback function
+   */
+  void CreateRpc(std::function<void(const RpcAnswer& answer)> callback);
+
+  /**
+   * Create a polled RPC entry point.  Only valid to use on the server.
+   * The caller is responsible for calling NetworkTableInstance::PollRpc()
+   * to poll for servicing incoming RPC calls.
+   * This function creates RPC version 0 definitions (raw data in and out).
+   */
+  void CreatePolledRpc();
+
+  /**
+   * Call a RPC function.  May be used on either the client or server.
+   * This function is non-blocking.  Either RpcCall::GetResult() or
+   * RpcCall::CancelResult() must be called on the return value to either
+   * get or ignore the result of the call.
+   *
+   * @param params      parameter
+   * @return RPC call object.
+   */
+  RpcCall CallRpc(StringRef params);
+
+  /**
+   * Add a listener for changes to this entry.
+   *
+   * @param callback          listener to add
+   * @param flags             NotifyKind bitmask
+   * @return Listener handle
+   */
+  NT_EntryListener AddListener(
+      std::function<void(const EntryNotification& event)> callback,
+      unsigned int flags) const;
+
+  /**
+   * Remove an entry listener.
+   *
+   * @param entry_listener Listener handle to remove
+   */
+  void RemoveListener(NT_EntryListener entry_listener);
+
+  /**
+   * Equality operator.  Returns true if both instances refer to the same
+   * native handle.
+   */
+  bool operator==(const NetworkTableEntry& oth) const {
+    return m_handle == oth.m_handle;
+  }
+
+  /** Inequality operator. */
+  bool operator!=(const NetworkTableEntry& oth) const {
+    return !(*this == oth);
+  }
+
+ protected:
+  /* Native handle */
+  NT_Entry m_handle;
+};
+
+}  // namespace nt
+
+#include "networktables/NetworkTableEntry.inl"
+
+#endif  // NTCORE_NETWORKTABLES_NETWORKTABLEENTRY_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableEntry.inl b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableEntry.inl
new file mode 100644
index 0000000..f95b1a8
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableEntry.inl
@@ -0,0 +1,232 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NT_ENTRY_INL_
+#define NT_ENTRY_INL_
+
+namespace nt {
+
+inline NetworkTableEntry::NetworkTableEntry() : m_handle{0} {}
+
+inline NetworkTableEntry::NetworkTableEntry(NT_Entry handle)
+    : m_handle{handle} {}
+
+inline NT_Entry NetworkTableEntry::GetHandle() const { return m_handle; }
+
+inline bool NetworkTableEntry::Exists() const {
+  return GetEntryType(m_handle) != NT_UNASSIGNED;
+}
+
+inline std::string NetworkTableEntry::GetName() const {
+  return GetEntryName(m_handle);
+}
+
+inline NetworkTableType NetworkTableEntry::GetType() const {
+  return static_cast<NetworkTableType>(GetEntryType(m_handle));
+}
+
+inline unsigned int NetworkTableEntry::GetFlags() const {
+  return GetEntryFlags(m_handle);
+}
+
+inline uint64_t NetworkTableEntry::GetLastChange() const {
+  return GetEntryLastChange(m_handle);
+}
+
+inline EntryInfo NetworkTableEntry::GetInfo() const {
+  return GetEntryInfo(m_handle);
+}
+
+inline std::shared_ptr<Value> NetworkTableEntry::GetValue() const {
+  return GetEntryValue(m_handle);
+}
+
+inline bool NetworkTableEntry::GetBoolean(bool defaultValue) const {
+  auto value = GetEntryValue(m_handle);
+  if (!value || value->type() != NT_BOOLEAN) return defaultValue;
+  return value->GetBoolean();
+}
+
+inline double NetworkTableEntry::GetDouble(double defaultValue) const {
+  auto value = GetEntryValue(m_handle);
+  if (!value || value->type() != NT_DOUBLE) return defaultValue;
+  return value->GetDouble();
+}
+
+inline std::string NetworkTableEntry::GetString(StringRef defaultValue) const {
+  auto value = GetEntryValue(m_handle);
+  if (!value || value->type() != NT_STRING) return defaultValue;
+  return value->GetString();
+}
+
+inline std::string NetworkTableEntry::GetRaw(StringRef defaultValue) const {
+  auto value = GetEntryValue(m_handle);
+  if (!value || value->type() != NT_RAW) return defaultValue;
+  return value->GetString();
+}
+
+inline std::vector<int> NetworkTableEntry::GetBooleanArray(
+    ArrayRef<int> defaultValue) const {
+  auto value = GetEntryValue(m_handle);
+  if (!value || value->type() != NT_BOOLEAN_ARRAY) return defaultValue;
+  return value->GetBooleanArray();
+}
+
+inline std::vector<double> NetworkTableEntry::GetDoubleArray(
+    ArrayRef<double> defaultValue) const {
+  auto value = GetEntryValue(m_handle);
+  if (!value || value->type() != NT_DOUBLE_ARRAY) return defaultValue;
+  return value->GetDoubleArray();
+}
+
+inline std::vector<std::string> NetworkTableEntry::GetStringArray(
+    ArrayRef<std::string> defaultValue) const {
+  auto value = GetEntryValue(m_handle);
+  if (!value || value->type() != NT_STRING_ARRAY) return defaultValue;
+  return value->GetStringArray();
+}
+
+inline bool NetworkTableEntry::SetDefaultValue(std::shared_ptr<Value> value) {
+  return SetDefaultEntryValue(m_handle, value);
+}
+
+inline bool NetworkTableEntry::SetDefaultBoolean(bool defaultValue) {
+  return SetDefaultEntryValue(m_handle, Value::MakeBoolean(defaultValue));
+}
+
+inline bool NetworkTableEntry::SetDefaultDouble(double defaultValue) {
+  return SetDefaultEntryValue(m_handle, Value::MakeDouble(defaultValue));
+}
+
+inline bool NetworkTableEntry::SetDefaultString(const Twine& defaultValue) {
+  return SetDefaultEntryValue(m_handle, Value::MakeString(defaultValue));
+}
+
+inline bool NetworkTableEntry::SetDefaultRaw(StringRef defaultValue) {
+  return SetDefaultEntryValue(m_handle, Value::MakeRaw(defaultValue));
+}
+
+inline bool NetworkTableEntry::SetDefaultBooleanArray(
+    ArrayRef<int> defaultValue) {
+  return SetDefaultEntryValue(m_handle, Value::MakeBooleanArray(defaultValue));
+}
+
+inline bool NetworkTableEntry::SetDefaultDoubleArray(
+    ArrayRef<double> defaultValue) {
+  return SetDefaultEntryValue(m_handle, Value::MakeDoubleArray(defaultValue));
+}
+
+inline bool NetworkTableEntry::SetDefaultStringArray(
+    ArrayRef<std::string> defaultValue) {
+  return SetDefaultEntryValue(m_handle, Value::MakeStringArray(defaultValue));
+}
+
+inline bool NetworkTableEntry::SetValue(std::shared_ptr<Value> value) {
+  return SetEntryValue(m_handle, value);
+}
+
+inline bool NetworkTableEntry::SetBoolean(bool value) {
+  return SetEntryValue(m_handle, Value::MakeBoolean(value));
+}
+
+inline bool NetworkTableEntry::SetDouble(double value) {
+  return SetEntryValue(m_handle, Value::MakeDouble(value));
+}
+
+inline bool NetworkTableEntry::SetString(const Twine& value) {
+  return SetEntryValue(m_handle, Value::MakeString(value));
+}
+
+inline bool NetworkTableEntry::SetRaw(StringRef value) {
+  return SetEntryValue(m_handle, Value::MakeRaw(value));
+}
+
+inline bool NetworkTableEntry::SetBooleanArray(ArrayRef<int> value) {
+  return SetEntryValue(m_handle, Value::MakeBooleanArray(value));
+}
+
+inline bool NetworkTableEntry::SetDoubleArray(ArrayRef<double> value) {
+  return SetEntryValue(m_handle, Value::MakeDoubleArray(value));
+}
+
+inline bool NetworkTableEntry::SetStringArray(ArrayRef<std::string> value) {
+  return SetEntryValue(m_handle, Value::MakeStringArray(value));
+}
+
+inline void NetworkTableEntry::ForceSetValue(std::shared_ptr<Value> value) {
+  SetEntryTypeValue(m_handle, value);
+}
+
+inline void NetworkTableEntry::ForceSetBoolean(bool value) {
+  SetEntryTypeValue(m_handle, Value::MakeBoolean(value));
+}
+
+inline void NetworkTableEntry::ForceSetDouble(double value) {
+  SetEntryTypeValue(m_handle, Value::MakeDouble(value));
+}
+
+inline void NetworkTableEntry::ForceSetString(const Twine& value) {
+  SetEntryTypeValue(m_handle, Value::MakeString(value));
+}
+
+inline void NetworkTableEntry::ForceSetRaw(StringRef value) {
+  SetEntryTypeValue(m_handle, Value::MakeRaw(value));
+}
+
+inline void NetworkTableEntry::ForceSetBooleanArray(ArrayRef<int> value) {
+  SetEntryTypeValue(m_handle, Value::MakeBooleanArray(value));
+}
+
+inline void NetworkTableEntry::ForceSetDoubleArray(ArrayRef<double> value) {
+  SetEntryTypeValue(m_handle, Value::MakeDoubleArray(value));
+}
+
+inline void NetworkTableEntry::ForceSetStringArray(
+    ArrayRef<std::string> value) {
+  SetEntryTypeValue(m_handle, Value::MakeStringArray(value));
+}
+
+inline void NetworkTableEntry::SetFlags(unsigned int flags) {
+  SetEntryFlags(m_handle, GetFlags() | flags);
+}
+
+inline void NetworkTableEntry::ClearFlags(unsigned int flags) {
+  SetEntryFlags(m_handle, GetFlags() & ~flags);
+}
+
+inline void NetworkTableEntry::SetPersistent() { SetFlags(kPersistent); }
+
+inline void NetworkTableEntry::ClearPersistent() { ClearFlags(kPersistent); }
+
+inline bool NetworkTableEntry::IsPersistent() const {
+  return (GetFlags() & kPersistent) != 0;
+}
+
+inline void NetworkTableEntry::Delete() { DeleteEntry(m_handle); }
+
+inline void NetworkTableEntry::CreateRpc(
+    std::function<void(const RpcAnswer& answer)> callback) {
+  ::nt::CreateRpc(m_handle, StringRef("\0", 1), callback);
+}
+
+inline RpcCall NetworkTableEntry::CallRpc(StringRef params) {
+  return RpcCall{m_handle, ::nt::CallRpc(m_handle, params)};
+}
+
+inline NT_EntryListener NetworkTableEntry::AddListener(
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int flags) const {
+  return AddEntryListener(m_handle, callback, flags);
+}
+
+inline void NetworkTableEntry::RemoveListener(NT_EntryListener entry_listener) {
+  RemoveEntryListener(entry_listener);
+}
+
+}  // namespace nt
+
+#endif  // NT_ENTRY_INL_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableInstance.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableInstance.h
new file mode 100644
index 0000000..ee08745
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableInstance.h
@@ -0,0 +1,561 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_H_
+#define NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_H_
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "networktables/NetworkTable.h"
+#include "networktables/NetworkTableEntry.h"
+#include "ntcore_c.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+using wpi::ArrayRef;
+using wpi::StringRef;
+using wpi::Twine;
+
+/**
+ * NetworkTables Instance.
+ *
+ * Instances are completely independent from each other.  Table operations on
+ * one instance will not be visible to other instances unless the instances are
+ * connected via the network.  The main limitation on instances is that you
+ * cannot have two servers on the same network port.  The main utility of
+ * instances is for unit testing, but they can also enable one program to
+ * connect to two different NetworkTables networks.
+ *
+ * The global "default" instance (as returned by GetDefault()) is
+ * always available, and is intended for the common case when there is only
+ * a single NetworkTables instance being used in the program.  The
+ * default instance cannot be destroyed.
+ *
+ * Additional instances can be created with the Create() function.
+ * Instances are not reference counted or RAII.  Instead, they must be
+ * explicitly destroyed (with Destroy()).
+ *
+ * @ingroup ntcore_cpp_api
+ */
+class NetworkTableInstance final {
+ public:
+  /**
+   * Client/server mode flag values (as returned by GetNetworkMode()).
+   * This is a bitmask.
+   */
+  enum NetworkMode {
+    kNetModeNone = NT_NET_MODE_NONE,
+    kNetModeServer = NT_NET_MODE_SERVER,
+    kNetModeClient = NT_NET_MODE_CLIENT,
+    kNetModeStarting = NT_NET_MODE_STARTING,
+    kNetModeFailure = NT_NET_MODE_FAILURE
+  };
+
+  /**
+   * Logging levels (as used by SetLogger()).
+   */
+  enum LogLevel {
+    kLogCritical = NT_LOG_CRITICAL,
+    kLogError = NT_LOG_ERROR,
+    kLogWarning = NT_LOG_WARNING,
+    kLogInfo = NT_LOG_INFO,
+    kLogDebug = NT_LOG_DEBUG,
+    kLogDebug1 = NT_LOG_DEBUG1,
+    kLogDebug2 = NT_LOG_DEBUG2,
+    kLogDebug3 = NT_LOG_DEBUG3,
+    kLogDebug4 = NT_LOG_DEBUG4
+  };
+
+  /**
+   * The default port that network tables operates on.
+   */
+  enum { kDefaultPort = NT_DEFAULT_PORT };
+
+  /**
+   * Construct invalid instance.
+   */
+  NetworkTableInstance() noexcept;
+
+  /**
+   * Construct from native handle.
+   *
+   * @param handle Native handle
+   */
+  explicit NetworkTableInstance(NT_Inst inst) noexcept;
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_handle != 0; }
+
+  /**
+   * Get global default instance.
+   *
+   * @return Global default instance
+   */
+  static NetworkTableInstance GetDefault();
+
+  /**
+   * Create an instance.
+   *
+   * @return Newly created instance
+   */
+  static NetworkTableInstance Create();
+
+  /**
+   * Destroys an instance (note: this has global effect).
+   *
+   * @param inst Instance
+   */
+  static void Destroy(NetworkTableInstance inst);
+
+  /**
+   * Gets the native handle for the entry.
+   *
+   * @return Native handle
+   */
+  NT_Inst GetHandle() const;
+
+  /**
+   * Gets the entry for a key.
+   *
+   * @param name Key
+   * @return Network table entry.
+   */
+  NetworkTableEntry GetEntry(const Twine& name);
+
+  /**
+   * Get entries starting with the given prefix.
+   *
+   * The results are optionally filtered by string prefix and entry type to
+   * only return a subset of all entries.
+   *
+   * @param prefix entry name required prefix; only entries whose name
+   * starts with this string are returned
+   * @param types bitmask of types; 0 is treated as a "don't care"
+   * @return Array of entries.
+   */
+  std::vector<NetworkTableEntry> GetEntries(const Twine& prefix,
+                                            unsigned int types);
+
+  /**
+   * Get information about entries starting with the given prefix.
+   *
+   * The results are optionally filtered by string prefix and entry type to
+   * only return a subset of all entries.
+   *
+   * @param prefix entry name required prefix; only entries whose name
+   * starts with this string are returned
+   * @param types bitmask of types; 0 is treated as a "don't care"
+   * @return Array of entry information.
+   */
+  std::vector<EntryInfo> GetEntryInfo(const Twine& prefix,
+                                      unsigned int types) const;
+
+  /**
+   * Gets the table with the specified key.
+   *
+   * @param key the key name
+   * @return The network table
+   */
+  std::shared_ptr<NetworkTable> GetTable(const Twine& key) const;
+
+  /**
+   * Deletes ALL keys in ALL subtables (except persistent values).
+   * Use with caution!
+   */
+  void DeleteAllEntries();
+
+  /**
+   * @{
+   * @name Entry Listener Functions
+   */
+
+  /**
+   * Add a listener for all entries starting with a certain prefix.
+   *
+   * @param prefix            UTF-8 string prefix
+   * @param callback          listener to add
+   * @param flags             EntryListenerFlags bitmask
+   * @return Listener handle
+   */
+  NT_EntryListener AddEntryListener(
+      const Twine& prefix,
+      std::function<void(const EntryNotification& event)> callback,
+      unsigned int flags) const;
+
+  /**
+   * Remove an entry listener.
+   *
+   * @param entry_listener Listener handle to remove
+   */
+  static void RemoveEntryListener(NT_EntryListener entry_listener);
+
+  /**
+   * Wait for the entry listener queue to be empty.  This is primarily useful
+   * for deterministic testing.  This blocks until either the entry listener
+   * queue is empty (e.g. there are no more events that need to be passed along
+   * to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+   *                  or a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  bool WaitForEntryListenerQueue(double timeout);
+
+  /** @} */
+
+  /**
+   * @{
+   * @name Connection Listener Functions
+   */
+
+  /**
+   * Add a connection listener.
+   *
+   * @param callback          listener to add
+   * @param immediate_notify  notify listener of all existing connections
+   * @return Listener handle
+   */
+  NT_ConnectionListener AddConnectionListener(
+      std::function<void(const ConnectionNotification& event)> callback,
+      bool immediate_notify) const;
+
+  /**
+   * Remove a connection listener.
+   *
+   * @param conn_listener Listener handle to remove
+   */
+  static void RemoveConnectionListener(NT_ConnectionListener conn_listener);
+
+  /**
+   * Wait for the connection listener queue to be empty.  This is primarily
+   * useful for deterministic testing.  This blocks until either the connection
+   * listener queue is empty (e.g. there are no more events that need to be
+   * passed along to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+   *                  or a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  bool WaitForConnectionListenerQueue(double timeout);
+
+  /** @} */
+
+  /**
+   * @{
+   * @name Remote Procedure Call Functions
+   */
+
+  /**
+   * Wait for the incoming RPC call queue to be empty.  This is primarily useful
+   * for deterministic testing.  This blocks until either the RPC call
+   * queue is empty (e.g. there are no more events that need to be passed along
+   * to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+   *                  or a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  bool WaitForRpcCallQueue(double timeout);
+
+  /** @} */
+
+  /**
+   * @{
+   * @name Client/Server Functions
+   */
+
+  /**
+   * Set the network identity of this node.
+   *
+   * This is the name used during the initial connection handshake, and is
+   * visible through ConnectionInfo on the remote node.
+   *
+   * @param name      identity to advertise
+   */
+  void SetNetworkIdentity(const Twine& name);
+
+  /**
+   * Get the current network mode.
+   *
+   * @return Bitmask of NetworkMode.
+   */
+  unsigned int GetNetworkMode() const;
+
+  /**
+   * Starts a server using the specified filename, listening address, and port.
+   *
+   * @param persist_filename  the name of the persist file to use (UTF-8 string,
+   *                          null terminated)
+   * @param listen_address    the address to listen on, or null to listen on any
+   *                          address (UTF-8 string, null terminated)
+   * @param port              port to communicate over
+   */
+  void StartServer(const Twine& persist_filename = "networktables.ini",
+                   const char* listen_address = "",
+                   unsigned int port = kDefaultPort);
+
+  /**
+   * Stops the server if it is running.
+   */
+  void StopServer();
+
+  /**
+   * Starts a client.  Use SetServer to set the server name and port.
+   */
+  void StartClient();
+
+  /**
+   * Starts a client using the specified server and port
+   *
+   * @param server_name server name (UTF-8 string, null terminated)
+   * @param port        port to communicate over
+   */
+  void StartClient(const char* server_name, unsigned int port = kDefaultPort);
+
+  /**
+   * Starts a client using the specified (server, port) combinations.  The
+   * client will attempt to connect to each server in round robin fashion.
+   *
+   * @param servers   array of server name and port pairs
+   */
+  void StartClient(ArrayRef<std::pair<StringRef, unsigned int>> servers);
+
+  /**
+   * Starts a client using the specified servers and port.  The
+   * client will attempt to connect to each server in round robin fashion.
+   *
+   * @param servers   array of server names
+   * @param port      port to communicate over
+   */
+  void StartClient(ArrayRef<StringRef> servers,
+                   unsigned int port = kDefaultPort);
+
+  /**
+   * Starts a client using commonly known robot addresses for the specified
+   * team.
+   *
+   * @param team        team number
+   * @param port        port to communicate over
+   */
+  void StartClientTeam(unsigned int team, unsigned int port = kDefaultPort);
+
+  /**
+   * Stops the client if it is running.
+   */
+  void StopClient();
+
+  /**
+   * Sets server address and port for client (without restarting client).
+   *
+   * @param server_name server name (UTF-8 string, null terminated)
+   * @param port        port to communicate over
+   */
+  void SetServer(const char* server_name, unsigned int port = kDefaultPort);
+
+  /**
+   * Sets server addresses and ports for client (without restarting client).
+   * The client will attempt to connect to each server in round robin fashion.
+   *
+   * @param servers   array of server name and port pairs
+   */
+  void SetServer(ArrayRef<std::pair<StringRef, unsigned int>> servers);
+
+  /**
+   * Sets server addresses and port for client (without restarting client).
+   * The client will attempt to connect to each server in round robin fashion.
+   *
+   * @param servers   array of server names
+   * @param port      port to communicate over
+   */
+  void SetServer(ArrayRef<StringRef> servers, unsigned int port = kDefaultPort);
+
+  /**
+   * Sets server addresses and port for client (without restarting client).
+   * Connects using commonly known robot addresses for the specified team.
+   *
+   * @param team        team number
+   * @param port        port to communicate over
+   */
+  void SetServerTeam(unsigned int team, unsigned int port = kDefaultPort);
+
+  /**
+   * Starts requesting server address from Driver Station.
+   * This connects to the Driver Station running on localhost to obtain the
+   * server IP address.
+   *
+   * @param port server port to use in combination with IP from DS
+   */
+  void StartDSClient(unsigned int port = kDefaultPort);
+
+  /**
+   * Stops requesting server address from Driver Station.
+   */
+  void StopDSClient();
+
+  /**
+   * Set the periodic update rate.
+   * Sets how frequently updates are sent to other nodes over the network.
+   *
+   * @param interval update interval in seconds (range 0.01 to 1.0)
+   */
+  void SetUpdateRate(double interval);
+
+  /**
+   * Flushes all updated values immediately to the network.
+   * @note This is rate-limited to protect the network from flooding.
+   * This is primarily useful for synchronizing network updates with
+   * user code.
+   */
+  void Flush() const;
+
+  /**
+   * Get information on the currently established network connections.
+   * If operating as a client, this will return either zero or one values.
+   *
+   * @return array of connection information
+   */
+  std::vector<ConnectionInfo> GetConnections() const;
+
+  /**
+   * Return whether or not the instance is connected to another node.
+   *
+   * @return True if connected.
+   */
+  bool IsConnected() const;
+
+  /** @} */
+
+  /**
+   * @{
+   * @name File Save/Load Functions
+   */
+
+  /**
+   * Save persistent values to a file.  The server automatically does this,
+   * but this function provides a way to save persistent values in the same
+   * format to a file on either a client or a server.
+   *
+   * @param filename  filename
+   * @return error string, or nullptr if successful
+   */
+  const char* SavePersistent(const Twine& filename) const;
+
+  /**
+   * Load persistent values from a file.  The server automatically does this
+   * at startup, but this function provides a way to restore persistent values
+   * in the same format from a file at any time on either a client or a server.
+   *
+   * @param filename  filename
+   * @param warn      callback function for warnings
+   * @return error string, or nullptr if successful
+   */
+  const char* LoadPersistent(
+      const Twine& filename,
+      std::function<void(size_t line, const char* msg)> warn);
+
+  /**
+   * Save table values to a file.  The file format used is identical to
+   * that used for SavePersistent.
+   *
+   * @param filename  filename
+   * @param prefix    save only keys starting with this prefix
+   * @return error string, or nullptr if successful
+   */
+  const char* SaveEntries(const Twine& filename, const Twine& prefix) const;
+
+  /**
+   * Load table values from a file.  The file format used is identical to
+   * that used for SavePersistent / LoadPersistent.
+   *
+   * @param filename  filename
+   * @param prefix    load only keys starting with this prefix
+   * @param warn      callback function for warnings
+   * @return error string, or nullptr if successful
+   */
+  const char* LoadEntries(
+      const Twine& filename, const Twine& prefix,
+      std::function<void(size_t line, const char* msg)> warn);
+
+  /** @} */
+
+  /**
+   * @{
+   * @name Logger Functions
+   */
+
+  /**
+   * Add logger callback function.  By default, log messages are sent to stderr;
+   * this function sends log messages with the specified levels to the provided
+   * callback function instead.  The callback function will only be called for
+   * log messages with level greater than or equal to minLevel and less than or
+   * equal to maxLevel; messages outside this range will be silently ignored.
+   *
+   * @param func        log callback function
+   * @param minLevel    minimum log level
+   * @param maxLevel    maximum log level
+   * @return Logger handle
+   */
+  NT_Logger AddLogger(std::function<void(const LogMessage& msg)> func,
+                      unsigned int min_level, unsigned int max_level);
+
+  /**
+   * Remove a logger.
+   *
+   * @param logger Logger handle to remove
+   */
+  static void RemoveLogger(NT_Logger logger);
+
+  /**
+   * Wait for the incoming log event queue to be empty.  This is primarily
+   * useful for deterministic testing.  This blocks until either the log event
+   * queue is empty (e.g. there are no more events that need to be passed along
+   * to callbacks or poll queues) or the timeout expires.
+   *
+   * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+   *                  or a negative value to block indefinitely
+   * @return False if timed out, otherwise true.
+   */
+  bool WaitForLoggerQueue(double timeout);
+
+  /** @} */
+
+  /**
+   * Equality operator.  Returns true if both instances refer to the same
+   * native handle.
+   */
+  bool operator==(const NetworkTableInstance& other) const {
+    return m_handle == other.m_handle;
+  }
+
+  /** Inequality operator. */
+  bool operator!=(const NetworkTableInstance& other) const {
+    return !(*this == other);
+  }
+
+ private:
+  /* Native handle */
+  NT_Inst m_handle;
+};
+
+}  // namespace nt
+
+#include "networktables/NetworkTableInstance.inl"
+
+#endif  // NTCORE_NETWORKTABLES_NETWORKTABLEINSTANCE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableInstance.inl b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableInstance.inl
new file mode 100644
index 0000000..83616d9
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableInstance.inl
@@ -0,0 +1,187 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NT_INSTANCE_INL_
+#define NT_INSTANCE_INL_
+
+namespace nt {
+
+inline NetworkTableInstance::NetworkTableInstance() noexcept : m_handle{0} {}
+
+inline NetworkTableInstance::NetworkTableInstance(NT_Inst handle) noexcept
+    : m_handle{handle} {}
+
+inline NetworkTableInstance NetworkTableInstance::GetDefault() {
+  return NetworkTableInstance{GetDefaultInstance()};
+}
+
+inline NetworkTableInstance NetworkTableInstance::Create() {
+  return NetworkTableInstance{CreateInstance()};
+}
+
+inline void NetworkTableInstance::Destroy(NetworkTableInstance inst) {
+  if (inst.m_handle != 0) DestroyInstance(inst.m_handle);
+}
+
+inline NT_Inst NetworkTableInstance::GetHandle() const { return m_handle; }
+
+inline NetworkTableEntry NetworkTableInstance::GetEntry(const Twine& name) {
+  return NetworkTableEntry{::nt::GetEntry(m_handle, name)};
+}
+
+inline std::vector<NetworkTableEntry> NetworkTableInstance::GetEntries(
+    const Twine& prefix, unsigned int types) {
+  std::vector<NetworkTableEntry> entries;
+  for (auto entry : ::nt::GetEntries(m_handle, prefix, types))
+    entries.emplace_back(entry);
+  return entries;
+}
+
+inline std::vector<EntryInfo> NetworkTableInstance::GetEntryInfo(
+    const Twine& prefix, unsigned int types) const {
+  return ::nt::GetEntryInfo(m_handle, prefix, types);
+}
+
+inline void NetworkTableInstance::DeleteAllEntries() {
+  ::nt::DeleteAllEntries(m_handle);
+}
+
+inline void NetworkTableInstance::RemoveEntryListener(
+    NT_EntryListener entry_listener) {
+  ::nt::RemoveEntryListener(entry_listener);
+}
+
+inline bool NetworkTableInstance::WaitForEntryListenerQueue(double timeout) {
+  return ::nt::WaitForEntryListenerQueue(m_handle, timeout);
+}
+
+inline void NetworkTableInstance::RemoveConnectionListener(
+    NT_ConnectionListener conn_listener) {
+  ::nt::RemoveConnectionListener(conn_listener);
+}
+
+inline bool NetworkTableInstance::WaitForConnectionListenerQueue(
+    double timeout) {
+  return ::nt::WaitForConnectionListenerQueue(m_handle, timeout);
+}
+
+inline bool NetworkTableInstance::WaitForRpcCallQueue(double timeout) {
+  return ::nt::WaitForRpcCallQueue(m_handle, timeout);
+}
+
+inline void NetworkTableInstance::SetNetworkIdentity(const Twine& name) {
+  ::nt::SetNetworkIdentity(m_handle, name);
+}
+
+inline unsigned int NetworkTableInstance::GetNetworkMode() const {
+  return ::nt::GetNetworkMode(m_handle);
+}
+
+inline void NetworkTableInstance::StartServer(const Twine& persist_filename,
+                                              const char* listen_address,
+                                              unsigned int port) {
+  ::nt::StartServer(m_handle, persist_filename, listen_address, port);
+}
+
+inline void NetworkTableInstance::StopServer() { ::nt::StopServer(m_handle); }
+
+inline void NetworkTableInstance::StartClient() { ::nt::StartClient(m_handle); }
+
+inline void NetworkTableInstance::StartClient(const char* server_name,
+                                              unsigned int port) {
+  ::nt::StartClient(m_handle, server_name, port);
+}
+
+inline void NetworkTableInstance::StartClient(
+    ArrayRef<std::pair<StringRef, unsigned int>> servers) {
+  ::nt::StartClient(m_handle, servers);
+}
+
+inline void NetworkTableInstance::StartClientTeam(unsigned int team,
+                                                  unsigned int port) {
+  ::nt::StartClientTeam(m_handle, team, port);
+}
+
+inline void NetworkTableInstance::StopClient() { ::nt::StopClient(m_handle); }
+
+inline void NetworkTableInstance::SetServer(const char* server_name,
+                                            unsigned int port) {
+  ::nt::SetServer(m_handle, server_name, port);
+}
+
+inline void NetworkTableInstance::SetServer(
+    ArrayRef<std::pair<StringRef, unsigned int>> servers) {
+  ::nt::SetServer(m_handle, servers);
+}
+
+inline void NetworkTableInstance::SetServerTeam(unsigned int team,
+                                                unsigned int port) {
+  ::nt::SetServerTeam(m_handle, team, port);
+}
+
+inline void NetworkTableInstance::StartDSClient(unsigned int port) {
+  ::nt::StartDSClient(m_handle, port);
+}
+
+inline void NetworkTableInstance::StopDSClient() {
+  ::nt::StopDSClient(m_handle);
+}
+
+inline void NetworkTableInstance::SetUpdateRate(double interval) {
+  ::nt::SetUpdateRate(m_handle, interval);
+}
+
+inline void NetworkTableInstance::Flush() const { ::nt::Flush(m_handle); }
+
+inline std::vector<ConnectionInfo> NetworkTableInstance::GetConnections()
+    const {
+  return ::nt::GetConnections(m_handle);
+}
+
+inline bool NetworkTableInstance::IsConnected() const {
+  return ::nt::IsConnected(m_handle);
+}
+
+inline const char* NetworkTableInstance::SavePersistent(
+    const Twine& filename) const {
+  return ::nt::SavePersistent(m_handle, filename);
+}
+
+inline const char* NetworkTableInstance::LoadPersistent(
+    const Twine& filename,
+    std::function<void(size_t line, const char* msg)> warn) {
+  return ::nt::LoadPersistent(m_handle, filename, warn);
+}
+
+inline const char* NetworkTableInstance::SaveEntries(
+    const Twine& filename, const Twine& prefix) const {
+  return ::nt::SaveEntries(m_handle, filename, prefix);
+}
+
+inline const char* NetworkTableInstance::LoadEntries(
+    const Twine& filename, const Twine& prefix,
+    std::function<void(size_t line, const char* msg)> warn) {
+  return ::nt::LoadEntries(m_handle, filename, prefix, warn);
+}
+
+inline NT_Logger NetworkTableInstance::AddLogger(
+    std::function<void(const LogMessage& msg)> func, unsigned int min_level,
+    unsigned int max_level) {
+  return ::nt::AddLogger(m_handle, func, min_level, max_level);
+}
+
+inline void NetworkTableInstance::RemoveLogger(NT_Logger logger) {
+  ::nt::RemoveLogger(logger);
+}
+
+inline bool NetworkTableInstance::WaitForLoggerQueue(double timeout) {
+  return ::nt::WaitForLoggerQueue(m_handle, timeout);
+}
+
+}  // namespace nt
+
+#endif  // NT_INSTANCE_INL_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableType.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableType.h
new file mode 100644
index 0000000..7ac3d9a
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableType.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_NETWORKTABLETYPE_H_
+#define NTCORE_NETWORKTABLES_NETWORKTABLETYPE_H_
+
+#include "ntcore_c.h"
+
+namespace nt {
+
+/**
+ * NetworkTable entry type.
+ * @ingroup ntcore_cpp_api
+ */
+enum class NetworkTableType {
+  kUnassigned = NT_UNASSIGNED,
+  kBoolean = NT_BOOLEAN,
+  kDouble = NT_DOUBLE,
+  kString = NT_STRING,
+  kRaw = NT_RAW,
+  kBooleanArray = NT_BOOLEAN_ARRAY,
+  kDoubleArray = NT_DOUBLE_ARRAY,
+  kStringArray = NT_STRING_ARRAY,
+  kRpc = NT_RPC
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_NETWORKTABLES_NETWORKTABLETYPE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableValue.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableValue.h
new file mode 100644
index 0000000..3aa0c01
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/NetworkTableValue.h
@@ -0,0 +1,458 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_NETWORKTABLEVALUE_H_
+#define NTCORE_NETWORKTABLES_NETWORKTABLEVALUE_H_
+
+#include <stdint.h>
+
+#include <cassert>
+#include <memory>
+#include <string>
+#include <type_traits>
+#include <utility>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "ntcore_c.h"
+
+namespace nt {
+
+using wpi::ArrayRef;
+using wpi::StringRef;
+using wpi::Twine;
+
+/**
+ * A network table entry value.
+ * @ingroup ntcore_cpp_api
+ */
+class Value final {
+  struct private_init {};
+
+ public:
+  Value();
+  Value(NT_Type type, uint64_t time, const private_init&);
+  ~Value();
+
+  /**
+   * Get the data type.
+   *
+   * @return The type.
+   */
+  NT_Type type() const { return m_val.type; }
+
+  /**
+   * Get the data value stored.
+   *
+   * @return The type.
+   */
+  const NT_Value& value() const { return m_val; }
+
+  /**
+   * Get the creation time of the value.
+   *
+   * @return The time, in the units returned by nt::Now().
+   */
+  uint64_t last_change() const { return m_val.last_change; }
+
+  /**
+   * Get the creation time of the value.
+   *
+   * @return The time, in the units returned by nt::Now().
+   */
+  uint64_t time() const { return m_val.last_change; }
+
+  /**
+   * @{
+   * @name Type Checkers
+   */
+
+  /**
+   * Determine if entry value contains a value or is unassigned.
+   *
+   * @return True if the entry value contains a value.
+   */
+  bool IsValid() const { return m_val.type != NT_UNASSIGNED; }
+
+  /**
+   * Determine if entry value contains a boolean.
+   *
+   * @return True if the entry value is of boolean type.
+   */
+  bool IsBoolean() const { return m_val.type == NT_BOOLEAN; }
+
+  /**
+   * Determine if entry value contains a double.
+   *
+   * @return True if the entry value is of double type.
+   */
+  bool IsDouble() const { return m_val.type == NT_DOUBLE; }
+
+  /**
+   * Determine if entry value contains a string.
+   *
+   * @return True if the entry value is of string type.
+   */
+  bool IsString() const { return m_val.type == NT_STRING; }
+
+  /**
+   * Determine if entry value contains a raw.
+   *
+   * @return True if the entry value is of raw type.
+   */
+  bool IsRaw() const { return m_val.type == NT_RAW; }
+
+  /**
+   * Determine if entry value contains a rpc definition.
+   *
+   * @return True if the entry value is of rpc definition type.
+   */
+  bool IsRpc() const { return m_val.type == NT_RPC; }
+
+  /**
+   * Determine if entry value contains a boolean array.
+   *
+   * @return True if the entry value is of boolean array type.
+   */
+  bool IsBooleanArray() const { return m_val.type == NT_BOOLEAN_ARRAY; }
+
+  /**
+   * Determine if entry value contains a double array.
+   *
+   * @return True if the entry value is of double array type.
+   */
+  bool IsDoubleArray() const { return m_val.type == NT_DOUBLE_ARRAY; }
+
+  /**
+   * Determine if entry value contains a string array.
+   *
+   * @return True if the entry value is of string array type.
+   */
+  bool IsStringArray() const { return m_val.type == NT_STRING_ARRAY; }
+
+  /** @} */
+
+  /**
+   * @{
+   * @name Type-Safe Getters
+   */
+
+  /**
+   * Get the entry's boolean value.
+   *
+   * @return The boolean value.
+   */
+  bool GetBoolean() const {
+    assert(m_val.type == NT_BOOLEAN);
+    return m_val.data.v_boolean != 0;
+  }
+
+  /**
+   * Get the entry's double value.
+   *
+   * @return The double value.
+   */
+  double GetDouble() const {
+    assert(m_val.type == NT_DOUBLE);
+    return m_val.data.v_double;
+  }
+
+  /**
+   * Get the entry's string value.
+   *
+   * @return The string value.
+   */
+  StringRef GetString() const {
+    assert(m_val.type == NT_STRING);
+    return m_string;
+  }
+
+  /**
+   * Get the entry's raw value.
+   *
+   * @return The raw value.
+   */
+  StringRef GetRaw() const {
+    assert(m_val.type == NT_RAW);
+    return m_string;
+  }
+
+  /**
+   * Get the entry's rpc definition value.
+   *
+   * @return The rpc definition value.
+   */
+  StringRef GetRpc() const {
+    assert(m_val.type == NT_RPC);
+    return m_string;
+  }
+
+  /**
+   * Get the entry's boolean array value.
+   *
+   * @return The boolean array value.
+   */
+  ArrayRef<int> GetBooleanArray() const {
+    assert(m_val.type == NT_BOOLEAN_ARRAY);
+    return ArrayRef<int>(m_val.data.arr_boolean.arr,
+                         m_val.data.arr_boolean.size);
+  }
+
+  /**
+   * Get the entry's double array value.
+   *
+   * @return The double array value.
+   */
+  ArrayRef<double> GetDoubleArray() const {
+    assert(m_val.type == NT_DOUBLE_ARRAY);
+    return ArrayRef<double>(m_val.data.arr_double.arr,
+                            m_val.data.arr_double.size);
+  }
+
+  /**
+   * Get the entry's string array value.
+   *
+   * @return The string array value.
+   */
+  ArrayRef<std::string> GetStringArray() const {
+    assert(m_val.type == NT_STRING_ARRAY);
+    return m_string_array;
+  }
+
+  /** @} */
+
+  /**
+   * @{
+   * @name Factory functions
+   */
+
+  /**
+   * Creates a boolean entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeBoolean(bool value, uint64_t time = 0) {
+    auto val = std::make_shared<Value>(NT_BOOLEAN, time, private_init());
+    val->m_val.data.v_boolean = value;
+    return val;
+  }
+
+  /**
+   * Creates a double entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeDouble(double value, uint64_t time = 0) {
+    auto val = std::make_shared<Value>(NT_DOUBLE, time, private_init());
+    val->m_val.data.v_double = value;
+    return val;
+  }
+
+  /**
+   * Creates a string entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeString(const Twine& value,
+                                           uint64_t time = 0) {
+    auto val = std::make_shared<Value>(NT_STRING, time, private_init());
+    val->m_string = value.str();
+    val->m_val.data.v_string.str = const_cast<char*>(val->m_string.c_str());
+    val->m_val.data.v_string.len = val->m_string.size();
+    return val;
+  }
+
+/**
+ * Creates a string entry value.
+ *
+ * @param value the value
+ * @param time if nonzero, the creation time to use (instead of the current
+ *             time)
+ * @return The entry value
+ */
+#ifdef _MSC_VER
+  template <typename T,
+            typename = std::enable_if_t<std::is_same<T, std::string>>>
+#else
+  template <typename T,
+            typename std::enable_if<std::is_same<T, std::string>::value>::type>
+#endif
+  static std::shared_ptr<Value> MakeString(T&& value, uint64_t time = 0) {
+    auto val = std::make_shared<Value>(NT_STRING, time, private_init());
+    val->m_string = std::move(value);
+    val->m_val.data.v_string.str = const_cast<char*>(val->m_string.c_str());
+    val->m_val.data.v_string.len = val->m_string.size();
+    return val;
+  }
+
+  /**
+   * Creates a raw entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeRaw(StringRef value, uint64_t time = 0) {
+    auto val = std::make_shared<Value>(NT_RAW, time, private_init());
+    val->m_string = value;
+    val->m_val.data.v_raw.str = const_cast<char*>(val->m_string.c_str());
+    val->m_val.data.v_raw.len = val->m_string.size();
+    return val;
+  }
+
+/**
+ * Creates a raw entry value.
+ *
+ * @param value the value
+ * @param time if nonzero, the creation time to use (instead of the current
+ *             time)
+ * @return The entry value
+ */
+#ifdef _MSC_VER
+  template <typename T,
+            typename = std::enable_if_t<std::is_same<T, std::string>>>
+#else
+  template <typename T,
+            typename std::enable_if<std::is_same<T, std::string>::value>::type>
+#endif
+  static std::shared_ptr<Value> MakeRaw(T&& value, uint64_t time = 0) {
+    auto val = std::make_shared<Value>(NT_RAW, time, private_init());
+    val->m_string = std::move(value);
+    val->m_val.data.v_raw.str = const_cast<char*>(val->m_string.c_str());
+    val->m_val.data.v_raw.len = val->m_string.size();
+    return val;
+  }
+
+  /**
+   * Creates a rpc entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeRpc(StringRef value, uint64_t time = 0) {
+    auto val = std::make_shared<Value>(NT_RPC, time, private_init());
+    val->m_string = value;
+    val->m_val.data.v_raw.str = const_cast<char*>(val->m_string.c_str());
+    val->m_val.data.v_raw.len = val->m_string.size();
+    return val;
+  }
+
+  /**
+   * Creates a rpc entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  template <typename T>
+  static std::shared_ptr<Value> MakeRpc(T&& value, uint64_t time = 0) {
+    auto val = std::make_shared<Value>(NT_RPC, time, private_init());
+    val->m_string = std::move(value);
+    val->m_val.data.v_raw.str = const_cast<char*>(val->m_string.c_str());
+    val->m_val.data.v_raw.len = val->m_string.size();
+    return val;
+  }
+
+  /**
+   * Creates a boolean array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeBooleanArray(ArrayRef<bool> value,
+                                                 uint64_t time = 0);
+
+  /**
+   * Creates a boolean array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeBooleanArray(ArrayRef<int> value,
+                                                 uint64_t time = 0);
+
+  /**
+   * Creates a double array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeDoubleArray(ArrayRef<double> value,
+                                                uint64_t time = 0);
+
+  /**
+   * Creates a string array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   */
+  static std::shared_ptr<Value> MakeStringArray(ArrayRef<std::string> value,
+                                                uint64_t time = 0);
+
+  /**
+   * Creates a string array entry value.
+   *
+   * @param value the value
+   * @param time if nonzero, the creation time to use (instead of the current
+   *             time)
+   * @return The entry value
+   *
+   * @note This function moves the values out of the vector.
+   */
+  static std::shared_ptr<Value> MakeStringArray(
+      std::vector<std::string>&& value, uint64_t time = 0);
+
+  /** @} */
+
+  Value(const Value&) = delete;
+  Value& operator=(const Value&) = delete;
+  friend bool operator==(const Value& lhs, const Value& rhs);
+
+ private:
+  NT_Value m_val;
+  std::string m_string;
+  std::vector<std::string> m_string_array;
+};
+
+bool operator==(const Value& lhs, const Value& rhs);
+inline bool operator!=(const Value& lhs, const Value& rhs) {
+  return !(lhs == rhs);
+}
+
+/**
+ * NetworkTable Value alias for similarity with Java.
+ * @ingroup ntcore_cpp_api
+ */
+typedef Value NetworkTableValue;
+
+}  // namespace nt
+
+#endif  // NTCORE_NETWORKTABLES_NETWORKTABLEVALUE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/RpcCall.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/RpcCall.h
new file mode 100644
index 0000000..7d83140
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/RpcCall.h
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_RPCCALL_H_
+#define NTCORE_NETWORKTABLES_RPCCALL_H_
+
+#include <string>
+#include <utility>
+
+#include "ntcore_c.h"
+
+namespace nt {
+
+class NetworkTableEntry;
+
+/**
+ * NetworkTables Remote Procedure Call
+ * @ingroup ntcore_cpp_api
+ */
+class RpcCall final {
+ public:
+  /**
+   * Construct invalid instance.
+   */
+  RpcCall() : m_entry(0), m_call(0) {}
+
+  /**
+   * Construct from native handles.
+   *
+   * @param entry Entry handle
+   * @param call  Call handle
+   */
+  RpcCall(NT_Entry entry, NT_RpcCall call) : m_entry(entry), m_call(call) {}
+
+  RpcCall(RpcCall&& other);
+  RpcCall(const RpcCall&) = delete;
+  RpcCall& operator=(const RpcCall&) = delete;
+
+  /**
+   * Destructor.  Cancels the result if no other action taken.
+   */
+  ~RpcCall();
+
+  /**
+   * Determines if the native handle is valid.
+   *
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return m_call != 0; }
+
+  /**
+   * Get the RPC entry.
+   *
+   * @return NetworkTableEntry for the RPC.
+   */
+  NetworkTableEntry GetEntry() const;
+
+  /**
+   * Get the call native handle.
+   *
+   * @return Native handle.
+   */
+  NT_RpcCall GetCall() const { return m_call; }
+
+  /**
+   * Get the result (return value).  This function blocks until
+   * the result is received.
+   *
+   * @param result      received result (output)
+   * @return False on error, true otherwise.
+   */
+  bool GetResult(std::string* result);
+
+  /**
+   * Get the result (return value).  This function blocks until
+   * the result is received or it times out.
+   *
+   * @param result      received result (output)
+   * @param timeout     timeout, in seconds
+   * @param timed_out   true if the timeout period elapsed (output)
+   * @return False on error or timeout, true otherwise.
+   */
+  bool GetResult(std::string* result, double timeout, bool* timed_out);
+
+  /**
+   * Ignore the result.  This function is non-blocking.
+   */
+  void CancelResult();
+
+  friend void swap(RpcCall& first, RpcCall& second) {
+    using std::swap;
+    swap(first.m_entry, second.m_entry);
+    swap(first.m_call, second.m_call);
+  }
+
+ private:
+  NT_Entry m_entry;
+  NT_RpcCall m_call;
+};
+
+}  // namespace nt
+
+#include "networktables/RpcCall.inl"
+
+#endif  // NTCORE_NETWORKTABLES_RPCCALL_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/RpcCall.inl b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/RpcCall.inl
new file mode 100644
index 0000000..d7dacf5
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/RpcCall.inl
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NT_RPCCALL_INL_
+#define NT_RPCCALL_INL_
+
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+inline RpcCall::RpcCall(RpcCall&& other) : RpcCall() {
+  swap(*this, other);
+}
+
+inline RpcCall::~RpcCall() {
+  // automatically cancel result if user didn't request it
+  if (m_call != 0) CancelResult();
+}
+
+inline bool RpcCall::GetResult(std::string* result) {
+  if (GetRpcResult(m_entry, m_call, result)) {
+    m_call = 0;
+    return true;
+  }
+  return false;
+}
+
+inline bool RpcCall::GetResult(std::string* result, double timeout,
+                               bool* timed_out) {
+  if (GetRpcResult(m_entry, m_call, result, timeout, timed_out)) {
+    m_call = 0;
+    return true;
+  }
+  return false;
+}
+
+inline void RpcCall::CancelResult() {
+  CancelRpcResult(m_entry, m_call);
+  m_call = 0;
+}
+
+}  // namespace nt
+
+#endif  // NT_RPCCALL_INL_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/TableEntryListener.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/TableEntryListener.h
new file mode 100644
index 0000000..c4552678
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/TableEntryListener.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_TABLEENTRYLISTENER_H_
+#define NTCORE_NETWORKTABLES_TABLEENTRYLISTENER_H_
+
+#include <functional>
+#include <memory>
+
+#include <wpi/StringRef.h>
+
+namespace nt {
+
+class NetworkTable;
+class NetworkTableEntry;
+class Value;
+
+using wpi::StringRef;
+
+/**
+ * A listener that listens to changes in values in a NetworkTable.
+ *
+ * Called when a key-value pair is changed in a NetworkTable.
+ *
+ * @param table the table the key-value pair exists in
+ * @param key the key associated with the value that changed
+ * @param entry the entry associated with the value that changed
+ * @param value the new value
+ * @param flags update flags; for example, EntryListenerFlags.kNew if the key
+ * did not previously exist
+ *
+ * @ingroup ntcore_cpp_api
+ */
+typedef std::function<void(NetworkTable* table, StringRef name,
+                           NetworkTableEntry entry,
+                           std::shared_ptr<Value> value, int flags)>
+    TableEntryListener;
+
+}  // namespace nt
+
+#endif  // NTCORE_NETWORKTABLES_TABLEENTRYLISTENER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/TableListener.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/TableListener.h
new file mode 100644
index 0000000..9940bad
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/networktables/TableListener.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NETWORKTABLES_TABLELISTENER_H_
+#define NTCORE_NETWORKTABLES_TABLELISTENER_H_
+
+#include <functional>
+#include <memory>
+
+#include <wpi/StringRef.h>
+
+namespace nt {
+
+class NetworkTable;
+
+using wpi::StringRef;
+
+/**
+ * A listener that listens to new sub-tables in a NetworkTable.
+ *
+ * Called when a new table is created.
+ *
+ * @param parent the parent of the table
+ * @param name the name of the new table
+ * @param table the new table
+ *
+ * @ingroup ntcore_cpp_api
+ */
+typedef std::function<void(NetworkTable* parent, StringRef name,
+                           std::shared_ptr<NetworkTable> table)>
+    TableListener;
+
+}  // namespace nt
+
+#endif  // NTCORE_NETWORKTABLES_TABLELISTENER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore.h
new file mode 100644
index 0000000..ff0511a
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NTCORE_H_
+#define NTCORE_NTCORE_H_
+
+/* C API */
+#include "ntcore_c.h"
+
+#ifdef __cplusplus
+/* C++ API */
+#include "ntcore_cpp.h"
+#endif /* __cplusplus */
+
+#endif  // NTCORE_NTCORE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_c.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_c.h
new file mode 100644
index 0000000..60773ea
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_c.h
@@ -0,0 +1,2071 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NTCORE_C_H_
+#define NTCORE_NTCORE_C_H_
+
+#include <stdint.h>
+
+#ifdef __cplusplus
+#include <cstddef>
+#else
+#include <stddef.h>
+#endif
+
+#include <wpi/deprecated.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * @defgroup ntcore_c_api ntcore C API
+ *
+ * Handle-based interface for C.
+ *
+ * @{
+ */
+
+/** Typedefs */
+typedef int NT_Bool;
+
+typedef unsigned int NT_Handle;
+typedef NT_Handle NT_ConnectionListener;
+typedef NT_Handle NT_ConnectionListenerPoller;
+typedef NT_Handle NT_Entry;
+typedef NT_Handle NT_EntryListener;
+typedef NT_Handle NT_EntryListenerPoller;
+typedef NT_Handle NT_Inst;
+typedef NT_Handle NT_Logger;
+typedef NT_Handle NT_LoggerPoller;
+typedef NT_Handle NT_RpcCall;
+typedef NT_Handle NT_RpcCallPoller;
+
+/** Default network tables port number */
+#define NT_DEFAULT_PORT 1735
+
+/** NetworkTables data types. */
+enum NT_Type {
+  NT_UNASSIGNED = 0,
+  NT_BOOLEAN = 0x01,
+  NT_DOUBLE = 0x02,
+  NT_STRING = 0x04,
+  NT_RAW = 0x08,
+  NT_BOOLEAN_ARRAY = 0x10,
+  NT_DOUBLE_ARRAY = 0x20,
+  NT_STRING_ARRAY = 0x40,
+  NT_RPC = 0x80
+};
+
+/** NetworkTables entry flags. */
+enum NT_EntryFlags { NT_PERSISTENT = 0x01 };
+
+/** NetworkTables logging levels. */
+enum NT_LogLevel {
+  NT_LOG_CRITICAL = 50,
+  NT_LOG_ERROR = 40,
+  NT_LOG_WARNING = 30,
+  NT_LOG_INFO = 20,
+  NT_LOG_DEBUG = 10,
+  NT_LOG_DEBUG1 = 9,
+  NT_LOG_DEBUG2 = 8,
+  NT_LOG_DEBUG3 = 7,
+  NT_LOG_DEBUG4 = 6
+};
+
+/** NetworkTables notifier kinds. */
+enum NT_NotifyKind {
+  NT_NOTIFY_NONE = 0,
+  NT_NOTIFY_IMMEDIATE = 0x01, /* initial listener addition */
+  NT_NOTIFY_LOCAL = 0x02,     /* changed locally */
+  NT_NOTIFY_NEW = 0x04,       /* newly created entry */
+  NT_NOTIFY_DELETE = 0x08,    /* deleted */
+  NT_NOTIFY_UPDATE = 0x10,    /* value changed */
+  NT_NOTIFY_FLAGS = 0x20      /* flags changed */
+};
+
+/** Client/server modes */
+enum NT_NetworkMode {
+  NT_NET_MODE_NONE = 0x00,     /* not running */
+  NT_NET_MODE_SERVER = 0x01,   /* running in server mode */
+  NT_NET_MODE_CLIENT = 0x02,   /* running in client mode */
+  NT_NET_MODE_STARTING = 0x04, /* flag for starting (either client or server) */
+  NT_NET_MODE_FAILURE = 0x08,  /* flag for failure (either client or server) */
+};
+
+/*
+ * Structures
+ */
+
+/** A NetworkTables string. */
+struct NT_String {
+  /**
+   * String contents (UTF-8).
+   * The string is NOT required to be zero-terminated.
+   * When returned by the library, this is zero-terminated and allocated with
+   * std::malloc().
+   */
+  char* str;
+
+  /**
+   * Length of the string in bytes.  If the string happens to be zero
+   * terminated, this does not include the zero-termination.
+   */
+  size_t len;
+};
+
+/** NetworkTables Entry Value.  Note this is a typed union. */
+struct NT_Value {
+  enum NT_Type type;
+  uint64_t last_change;
+  union {
+    NT_Bool v_boolean;
+    double v_double;
+    struct NT_String v_string;
+    struct NT_String v_raw;
+    struct {
+      NT_Bool* arr;
+      size_t size;
+    } arr_boolean;
+    struct {
+      double* arr;
+      size_t size;
+    } arr_double;
+    struct {
+      struct NT_String* arr;
+      size_t size;
+    } arr_string;
+  } data;
+};
+
+/** NetworkTables Entry Information */
+struct NT_EntryInfo {
+  /** Entry handle */
+  NT_Entry entry;
+
+  /** Entry name */
+  struct NT_String name;
+
+  /** Entry type */
+  enum NT_Type type;
+
+  /** Entry flags */
+  unsigned int flags;
+
+  /** Timestamp of last change to entry (type or value). */
+  uint64_t last_change;
+};
+
+/** NetworkTables Connection Information */
+struct NT_ConnectionInfo {
+  /**
+   * The remote identifier (as set on the remote node by
+   * NetworkTableInstance::SetNetworkIdentity() or nt::SetNetworkIdentity()).
+   */
+  struct NT_String remote_id;
+
+  /** The IP address of the remote node. */
+  struct NT_String remote_ip;
+
+  /** The port number of the remote node. */
+  unsigned int remote_port;
+
+  /**
+   * The last time any update was received from the remote node (same scale as
+   * returned by nt::Now()).
+   */
+  uint64_t last_update;
+
+  /**
+   * The protocol version being used for this connection.  This in protocol
+   * layer format, so 0x0200 = 2.0, 0x0300 = 3.0).
+   */
+  unsigned int protocol_version;
+};
+
+/** NetworkTables RPC Version 1 Definition Parameter */
+struct NT_RpcParamDef {
+  struct NT_String name;
+  struct NT_Value def_value;
+};
+
+/** NetworkTables RPC Version 1 Definition Result */
+struct NT_RpcResultDef {
+  struct NT_String name;
+  enum NT_Type type;
+};
+
+/** NetworkTables RPC Version 1 Definition */
+struct NT_RpcDefinition {
+  unsigned int version;
+  struct NT_String name;
+  size_t num_params;
+  struct NT_RpcParamDef* params;
+  size_t num_results;
+  struct NT_RpcResultDef* results;
+};
+
+/** NetworkTables RPC Call Data */
+struct NT_RpcAnswer {
+  NT_Entry entry;
+  NT_RpcCall call;
+  struct NT_String name;
+  struct NT_String params;
+  struct NT_ConnectionInfo conn;
+};
+
+/** NetworkTables Entry Notification */
+struct NT_EntryNotification {
+  /** Listener that was triggered. */
+  NT_EntryListener listener;
+
+  /** Entry handle. */
+  NT_Entry entry;
+
+  /** Entry name. */
+  struct NT_String name;
+
+  /** The new value. */
+  struct NT_Value value;
+
+  /**
+   * Update flags.  For example, NT_NOTIFY_NEW if the key did not previously
+   * exist.
+   */
+  unsigned int flags;
+};
+
+/** NetworkTables Connection Notification */
+struct NT_ConnectionNotification {
+  /** Listener that was triggered. */
+  NT_ConnectionListener listener;
+
+  /** True if event is due to connection being established. */
+  NT_Bool connected;
+
+  /** Connection info. */
+  struct NT_ConnectionInfo conn;
+};
+
+/** NetworkTables log message. */
+struct NT_LogMessage {
+  /** The logger that generated the message. */
+  NT_Logger logger;
+
+  /** Log level of the message.  See NT_LogLevel. */
+  unsigned int level;
+
+  /** The filename of the source file that generated the message. */
+  const char* filename;
+
+  /** The line number in the source file that generated the message. */
+  unsigned int line;
+
+  /** The message. */
+  char* message;
+};
+
+/**
+ * @defgroup ntcore_instance_cfunc Instance Functions
+ * @{
+ */
+
+/**
+ * Get default instance.
+ * This is the instance used by non-handle-taking functions.
+ *
+ * @return Instance handle
+ */
+NT_Inst NT_GetDefaultInstance(void);
+
+/**
+ * Create an instance.
+ *
+ * @return Instance handle
+ */
+NT_Inst NT_CreateInstance(void);
+
+/**
+ * Destroy an instance.
+ * The default instance cannot be destroyed.
+ *
+ * @param inst Instance handle
+ */
+void NT_DestroyInstance(NT_Inst inst);
+
+/**
+ * Get instance handle from another handle.
+ *
+ * @param handle    handle
+ * @return Instance handle
+ */
+NT_Inst NT_GetInstanceFromHandle(NT_Handle handle);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_table_cfunc Table Functions
+ * @{
+ */
+
+/**
+ * Get Entry Handle.
+ *
+ * @param inst      instance handle
+ * @param name      entry name (UTF-8 string)
+ * @param name_len  length of name in bytes
+ * @return entry handle
+ */
+NT_Entry NT_GetEntry(NT_Inst inst, const char* name, size_t name_len);
+
+/**
+ * Get Entry Handles.
+ *
+ * Returns an array of entry handles.  The results are optionally
+ * filtered by string prefix and entry type to only return a subset of all
+ * entries.
+ *
+ * @param prefix        entry name required prefix; only entries whose name
+ *                      starts with this string are returned
+ * @param prefix_len    length of prefix in bytes
+ * @param types         bitmask of NT_Type values; 0 is treated specially
+ *                      as a "don't care"
+ * @return Array of entry handles.
+ */
+NT_Entry* NT_GetEntries(NT_Inst inst, const char* prefix, size_t prefix_len,
+                        unsigned int types, size_t* count);
+
+/**
+ * Gets the name of the specified entry.
+ * Returns an empty string if the handle is invalid.
+ *
+ * @param entry     entry handle
+ * @param name_len  length of the returned string (output parameter)
+ * @return Entry name
+ */
+char* NT_GetEntryName(NT_Entry entry, size_t* name_len);
+
+/**
+ * Gets the type for the specified key, or unassigned if non existent.
+ *
+ * @param entry   entry handle
+ * @return Entry type
+ */
+enum NT_Type NT_GetEntryType(NT_Entry entry);
+
+/**
+ * Gets the last time the entry was changed.
+ * Returns 0 if the handle is invalid.
+ *
+ * @param entry   entry handle
+ * @return Entry last change time
+ */
+uint64_t NT_GetEntryLastChange(NT_Entry entry);
+
+/**
+ * Get Entry Value.
+ *
+ * Returns copy of current entry value.
+ * Note that one of the type options is "unassigned".
+ *
+ * @param entry     entry handle
+ * @param value     storage for returned entry value
+ *
+ * It is the caller's responsibility to free value once it's no longer
+ * needed (the utility function NT_DisposeValue() is useful for this
+ * purpose).
+ */
+void NT_GetEntryValue(NT_Entry entry, struct NT_Value* value);
+
+/**
+ * Set Default Entry Value.
+ *
+ * Returns copy of current entry value if it exists.
+ * Otherwise, sets passed in value, and returns set value.
+ * Note that one of the type options is "unassigned".
+ *
+ * @param entry     entry handle
+ * @param default_value     value to be set if name does not exist
+ * @return 0 on error (value not set), 1 on success
+ */
+NT_Bool NT_SetDefaultEntryValue(NT_Entry entry,
+                                const struct NT_Value* default_value);
+
+/**
+ * Set Entry Value.
+ *
+ * Sets new entry value.  If type of new value differs from the type of the
+ * currently stored entry, returns error and does not update value.
+ *
+ * @param entry     entry handle
+ * @param value     new entry value
+ * @return 0 on error (type mismatch), 1 on success
+ */
+NT_Bool NT_SetEntryValue(NT_Entry entry, const struct NT_Value* value);
+
+/**
+ * Set Entry Type and Value.
+ *
+ * Sets new entry value.  If type of new value differs from the type of the
+ * currently stored entry, the currently stored entry type is overridden
+ * (generally this will generate an Entry Assignment message).
+ *
+ * This is NOT the preferred method to update a value; generally
+ * NT_SetEntryValue() should be used instead, with appropriate error handling.
+ *
+ * @param entry     entry handle
+ * @param value     new entry value
+ */
+void NT_SetEntryTypeValue(NT_Entry entry, const struct NT_Value* value);
+
+/**
+ * Set Entry Flags.
+ *
+ * @param entry     entry handle
+ * @param flags     flags value (bitmask of NT_EntryFlags)
+ */
+void NT_SetEntryFlags(NT_Entry entry, unsigned int flags);
+
+/**
+ * Get Entry Flags.
+ *
+ * @param entry     entry handle
+ * @return Flags value (bitmask of NT_EntryFlags)
+ */
+unsigned int NT_GetEntryFlags(NT_Entry entry);
+
+/**
+ * Delete Entry.
+ *
+ * Deletes an entry.  This is a new feature in version 3.0 of the protocol,
+ * so this may not have an effect if any other node in the network is not
+ * version 3.0 or newer.
+ *
+ * Note: NT_GetConnections() can be used to determine the protocol version
+ * of direct remote connection(s), but this is not sufficient to determine
+ * if all nodes in the network are version 3.0 or newer.
+ *
+ * @param entry     entry handle
+ */
+void NT_DeleteEntry(NT_Entry entry);
+
+/**
+ * Delete All Entries.
+ *
+ * Deletes ALL table entries.  This is a new feature in version 3.0 of the
+ * so this may not have an effect if any other node in the network is not
+ * version 3.0 or newer.
+ *
+ * Note: NT_GetConnections() can be used to determine the protocol version
+ * of direct remote connection(s), but this is not sufficient to determine
+ * if all nodes in the network are version 3.0 or newer.
+ *
+ * @param inst      instance handle
+ */
+void NT_DeleteAllEntries(NT_Inst inst);
+
+/**
+ * Get Entry Information.
+ *
+ * Returns an array of entry information (entry handle, name, entry type,
+ * and timestamp of last change to type/value).  The results are optionally
+ * filtered by string prefix and entry type to only return a subset of all
+ * entries.
+ *
+ * @param inst          instance handle
+ * @param prefix        entry name required prefix; only entries whose name
+ *                      starts with this string are returned
+ * @param prefix_len    length of prefix in bytes
+ * @param types         bitmask of NT_Type values; 0 is treated specially
+ *                      as a "don't care"
+ * @param count         output parameter; set to length of returned array
+ * @return Array of entry information.
+ */
+struct NT_EntryInfo* NT_GetEntryInfo(NT_Inst inst, const char* prefix,
+                                     size_t prefix_len, unsigned int types,
+                                     size_t* count);
+
+/**
+ * Get Entry Information.
+ *
+ * Returns information about an entry (name, entry type,
+ * and timestamp of last change to type/value).
+ *
+ * @param entry         entry handle
+ * @param info          entry information (output)
+ * @return True if successful, false on error.
+ */
+NT_Bool NT_GetEntryInfoHandle(NT_Entry entry, struct NT_EntryInfo* info);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_entrylistener_cfunc Entry Listener Functions
+ * @{
+ */
+
+/**
+ * Entry listener callback function.
+ * Called when a key-value pair is changed.
+ *
+ * @param data            data pointer provided to callback creation function
+ * @param event           event information
+ */
+typedef void (*NT_EntryListenerCallback)(
+    void* data, const struct NT_EntryNotification* event);
+
+/**
+ * Add a listener for all entries starting with a certain prefix.
+ *
+ * @param inst              instance handle
+ * @param prefix            UTF-8 string prefix
+ * @param prefix_len        length of prefix in bytes
+ * @param data              data pointer to pass to callback
+ * @param callback          listener to add
+ * @param flags             NT_NotifyKind bitmask
+ * @return Listener handle
+ */
+NT_EntryListener NT_AddEntryListener(NT_Inst inst, const char* prefix,
+                                     size_t prefix_len, void* data,
+                                     NT_EntryListenerCallback callback,
+                                     unsigned int flags);
+
+/**
+ * Add a listener for a single entry.
+ *
+ * @param entry             entry handle
+ * @param data              data pointer to pass to callback
+ * @param callback          listener to add
+ * @param flags             NT_NotifyKind bitmask
+ * @return Listener handle
+ */
+NT_EntryListener NT_AddEntryListenerSingle(NT_Entry entry, void* data,
+                                           NT_EntryListenerCallback callback,
+                                           unsigned int flags);
+
+/**
+ * Create a entry listener poller.
+ *
+ * A poller provides a single queue of poll events.  Events linked to this
+ * poller (using NT_AddPolledEntryListener()) will be stored in the queue and
+ * must be collected by calling NT_PollEntryListener().
+ * The returned handle must be destroyed with NT_DestroyEntryListenerPoller().
+ *
+ * @param inst      instance handle
+ * @return poller handle
+ */
+NT_EntryListenerPoller NT_CreateEntryListenerPoller(NT_Inst inst);
+
+/**
+ * Destroy a entry listener poller.  This will abort any blocked polling
+ * call and prevent additional events from being generated for this poller.
+ *
+ * @param poller    poller handle
+ */
+void NT_DestroyEntryListenerPoller(NT_EntryListenerPoller poller);
+
+/**
+ * Create a polled entry listener.
+ * The caller is responsible for calling NT_PollEntryListener() to poll.
+ *
+ * @param poller            poller handle
+ * @param prefix            UTF-8 string prefix
+ * @param flags             NT_NotifyKind bitmask
+ * @return Listener handle
+ */
+NT_EntryListener NT_AddPolledEntryListener(NT_EntryListenerPoller poller,
+                                           const char* prefix,
+                                           size_t prefix_len,
+                                           unsigned int flags);
+
+/**
+ * Create a polled entry listener.
+ * The caller is responsible for calling NT_PollEntryListener() to poll.
+ *
+ * @param poller            poller handle
+ * @param prefix            UTF-8 string prefix
+ * @param flags             NT_NotifyKind bitmask
+ * @return Listener handle
+ */
+NT_EntryListener NT_AddPolledEntryListenerSingle(NT_EntryListenerPoller poller,
+                                                 NT_Entry entry,
+                                                 unsigned int flags);
+
+/**
+ * Get the next entry listener event.  This blocks until the next event occurs.
+ *
+ * This is intended to be used with NT_AddPolledEntryListener(void); entry
+ * listeners created using NT_AddEntryListener() will not be serviced through
+ * this function.
+ *
+ * @param poller    poller handle
+ * @param len       length of returned array (output)
+ * @return Array of information on the entry listener events.  Returns NULL if
+ *         an erroroccurred (e.g. the instance was invalid or is shutting down).
+ */
+struct NT_EntryNotification* NT_PollEntryListener(NT_EntryListenerPoller poller,
+                                                  size_t* len);
+
+/**
+ * Get the next entry listener event.  This blocks until the next event occurs
+ * or it times out.  This is intended to be used with
+ * NT_AddPolledEntryListener(); entry listeners created using
+ * NT_AddEntryListener() will not be serviced through this function.
+ *
+ * @param poller      poller handle
+ * @param len         length of returned array (output)
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return Array of information on the entry listener events.  If NULL is
+ *         returned and timed_out is also false, an error occurred (e.g. the
+ *         instance was invalid or is shutting down).
+ */
+struct NT_EntryNotification* NT_PollEntryListenerTimeout(
+    NT_EntryListenerPoller poller, size_t* len, double timeout,
+    NT_Bool* timed_out);
+
+/**
+ * Cancel a PollEntryListener call.  This wakes up a call to
+ * PollEntryListener for this poller and causes it to immediately return
+ * an empty array.
+ *
+ * @param poller  poller handle
+ */
+void NT_CancelPollEntryListener(NT_EntryListenerPoller poller);
+
+/**
+ * Remove an entry listener.
+ *
+ * @param entry_listener Listener handle to remove
+ */
+void NT_RemoveEntryListener(NT_EntryListener entry_listener);
+
+/**
+ * Wait for the entry listener queue to be empty.  This is primarily useful
+ * for deterministic testing.  This blocks until either the entry listener
+ * queue is empty (e.g. there are no more events that need to be passed along
+ * to callbacks or poll queues) or the timeout expires.
+ *
+ * @param inst      instance handle
+ * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+ *                  or a negative value to block indefinitely
+ * @return False if timed out, otherwise true.
+ */
+NT_Bool NT_WaitForEntryListenerQueue(NT_Inst inst, double timeout);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_connectionlistener_cfunc Connection Listener Functions
+ * @{
+ */
+
+/**
+ * Connection listener callback function.
+ * Called when a network connection is made or lost.
+ *
+ * @param data            data pointer provided to callback creation function
+ * @param event           event info
+ */
+typedef void (*NT_ConnectionListenerCallback)(
+    void* data, const struct NT_ConnectionNotification* event);
+
+/**
+ * Add a connection listener.
+ *
+ * @param inst              instance handle
+ * @param data              data pointer to pass to callback
+ * @param callback          listener to add
+ * @param immediate_notify  notify listener of all existing connections
+ * @return Listener handle
+ */
+NT_ConnectionListener NT_AddConnectionListener(
+    NT_Inst inst, void* data, NT_ConnectionListenerCallback callback,
+    NT_Bool immediate_notify);
+
+/**
+ * Create a connection listener poller.
+ * A poller provides a single queue of poll events.  Events linked to this
+ * poller (using NT_AddPolledConnectionListener()) will be stored in the queue
+ * and must be collected by calling NT_PollConnectionListener().
+ * The returned handle must be destroyed with
+ * NT_DestroyConnectionListenerPoller().
+ *
+ * @param inst      instance handle
+ * @return poller handle
+ */
+NT_ConnectionListenerPoller NT_CreateConnectionListenerPoller(NT_Inst inst);
+
+/**
+ * Destroy a connection listener poller.  This will abort any blocked polling
+ * call and prevent additional events from being generated for this poller.
+ *
+ * @param poller    poller handle
+ */
+void NT_DestroyConnectionListenerPoller(NT_ConnectionListenerPoller poller);
+
+/**
+ * Create a polled connection listener.
+ * The caller is responsible for calling NT_PollConnectionListener() to poll.
+ *
+ * @param poller            poller handle
+ * @param immediate_notify  notify listener of all existing connections
+ */
+NT_ConnectionListener NT_AddPolledConnectionListener(
+    NT_ConnectionListenerPoller poller, NT_Bool immediate_notify);
+
+/**
+ * Get the next connection event.  This blocks until the next connect or
+ * disconnect occurs.  This is intended to be used with
+ * NT_AddPolledConnectionListener(); connection listeners created using
+ * NT_AddConnectionListener() will not be serviced through this function.
+ *
+ * @param poller    poller handle
+ * @param len       length of returned array (output)
+ * @return Array of information on the connection events.  Only returns NULL
+ *         if an error occurred (e.g. the instance was invalid or is shutting
+ *         down).
+ */
+struct NT_ConnectionNotification* NT_PollConnectionListener(
+    NT_ConnectionListenerPoller poller, size_t* len);
+
+/**
+ * Get the next connection event.  This blocks until the next connect or
+ * disconnect occurs or it times out.  This is intended to be used with
+ * NT_AddPolledConnectionListener(); connection listeners created using
+ * NT_AddConnectionListener() will not be serviced through this function.
+ *
+ * @param poller      poller handle
+ * @param len         length of returned array (output)
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return Array of information on the connection events.  If NULL is returned
+ *         and timed_out is also false, an error occurred (e.g. the instance
+ *         was invalid or is shutting down).
+ */
+struct NT_ConnectionNotification* NT_PollConnectionListenerTimeout(
+    NT_ConnectionListenerPoller poller, size_t* len, double timeout,
+    NT_Bool* timed_out);
+
+/**
+ * Cancel a PollConnectionListener call.  This wakes up a call to
+ * PollConnectionListener for this poller and causes it to immediately return
+ * an empty array.
+ *
+ * @param poller  poller handle
+ */
+void NT_CancelPollConnectionListener(NT_ConnectionListenerPoller poller);
+
+/**
+ * Remove a connection listener.
+ *
+ * @param conn_listener Listener handle to remove
+ */
+void NT_RemoveConnectionListener(NT_ConnectionListener conn_listener);
+
+/**
+ * Wait for the connection listener queue to be empty.  This is primarily useful
+ * for deterministic testing.  This blocks until either the connection listener
+ * queue is empty (e.g. there are no more events that need to be passed along
+ * to callbacks or poll queues) or the timeout expires.
+ *
+ * @param inst      instance handle
+ * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+ *                  or a negative value to block indefinitely
+ * @return False if timed out, otherwise true.
+ */
+NT_Bool NT_WaitForConnectionListenerQueue(NT_Inst inst, double timeout);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_rpc_cfunc Remote Procedure Call Functions
+ * @{
+ */
+
+/**
+ * Remote Procedure Call (RPC) callback function.
+ *
+ * @param data        data pointer provided to NT_CreateRpc()
+ * @param call        call information
+ *
+ * Note: NT_PostRpcResponse() must be called by the callback to provide a
+ * response to the call.
+ */
+typedef void (*NT_RpcCallback)(void* data, const struct NT_RpcAnswer* call);
+
+/**
+ * Create a callback-based RPC entry point.  Only valid to use on the server.
+ * The callback function will be called when the RPC is called.
+ *
+ * @param entry     entry handle of RPC entry
+ * @param def       RPC definition
+ * @param def_len   length of def in bytes
+ * @param data      data pointer to pass to callback function
+ * @param callback  callback function
+ */
+void NT_CreateRpc(NT_Entry entry, const char* def, size_t def_len, void* data,
+                  NT_RpcCallback callback);
+
+/**
+ * Create a RPC call poller.  Only valid to use on the server.
+ *
+ * A poller provides a single queue of poll events.  Events linked to this
+ * poller (using NT_CreatePolledRpc()) will be stored in the queue and must be
+ * collected by calling NT_PollRpc() or NT_PollRpcTimeout().
+ * The returned handle must be destroyed with NT_DestroyRpcCallPoller().
+ *
+ * @param inst      instance handle
+ * @return poller handle
+ */
+NT_RpcCallPoller NT_CreateRpcCallPoller(NT_Inst inst);
+
+/**
+ * Destroy a RPC call poller.  This will abort any blocked polling call and
+ * prevent additional events from being generated for this poller.
+ *
+ * @param poller    poller handle
+ */
+void NT_DestroyRpcCallPoller(NT_RpcCallPoller poller);
+
+/**
+ * Create a polled RPC entry point.  Only valid to use on the server.
+ *
+ * The caller is responsible for calling NT_PollRpc() or NT_PollRpcTimeout()
+ * to poll for servicing incoming RPC calls.
+ *
+ * @param entry     entry handle of RPC entry
+ * @param def       RPC definition
+ * @param def_len   length of def in bytes
+ * @param poller    poller handle
+ */
+void NT_CreatePolledRpc(NT_Entry entry, const char* def, size_t def_len,
+                        NT_RpcCallPoller poller);
+
+/**
+ * Get the next incoming RPC call.  This blocks until the next incoming RPC
+ * call is received.  This is intended to be used with NT_CreatePolledRpc(void);
+ * RPC calls created using NT_CreateRpc() will not be serviced through this
+ * function.  Upon successful return, NT_PostRpcResponse() must be called to
+ * send the return value to the caller.  The returned array must be freed
+ * using NT_DisposeRpcAnswerArray().
+ *
+ * @param poller      poller handle
+ * @param len         length of returned array (output)
+ * @return Array of RPC call information.  Only returns NULL if an error
+ *         occurred (e.g. the instance was invalid or is shutting down).
+ */
+struct NT_RpcAnswer* NT_PollRpc(NT_RpcCallPoller poller, size_t* len);
+
+/**
+ * Get the next incoming RPC call.  This blocks until the next incoming RPC
+ * call is received or it times out.  This is intended to be used with
+ * NT_CreatePolledRpc(); RPC calls created using NT_CreateRpc() will not be
+ * serviced through this function.  Upon successful return,
+ * NT_PostRpcResponse() must be called to send the return value to the caller.
+ * The returned array must be freed using NT_DisposeRpcAnswerArray().
+ *
+ * @param poller      poller handle
+ * @param len         length of returned array (output)
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return Array of RPC call information.  If NULL is returned and timed_out
+ *         is also false, an error occurred (e.g. the instance was invalid or
+ *         is shutting down).
+ */
+struct NT_RpcAnswer* NT_PollRpcTimeout(NT_RpcCallPoller poller, size_t* len,
+                                       double timeout, NT_Bool* timed_out);
+
+/**
+ * Cancel a PollRpc call.  This wakes up a call to PollRpc for this poller
+ * and causes it to immediately return an empty array.
+ *
+ * @param poller  poller handle
+ */
+void NT_CancelPollRpc(NT_RpcCallPoller poller);
+
+/**
+ * Wait for the incoming RPC call queue to be empty.  This is primarily useful
+ * for deterministic testing.  This blocks until either the RPC call
+ * queue is empty (e.g. there are no more events that need to be passed along
+ * to callbacks or poll queues) or the timeout expires.
+ *
+ * @param inst      instance handle
+ * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+ *                  or a negative value to block indefinitely
+ * @return False if timed out, otherwise true.
+ */
+NT_Bool NT_WaitForRpcCallQueue(NT_Inst inst, double timeout);
+
+/**
+ * Post RPC response (return value) for a polled RPC.
+ *
+ * The rpc and call parameters should come from the NT_RpcAnswer returned
+ * by NT_PollRpc().
+ *
+ * @param entry       entry handle of RPC entry (from NT_RpcAnswer)
+ * @param call        RPC call handle (from NT_RpcAnswer)
+ * @param result      result raw data that will be provided to remote caller
+ * @param result_len  length of result in bytes
+ * @return            true if the response was posted, otherwise false
+ */
+NT_Bool NT_PostRpcResponse(NT_Entry entry, NT_RpcCall call, const char* result,
+                           size_t result_len);
+
+/**
+ * Call a RPC function.  May be used on either the client or server.
+ *
+ * This function is non-blocking.  Either NT_GetRpcResult() or
+ * NT_CancelRpcResult() must be called to either get or ignore the result of
+ * the call.
+ *
+ * @param entry       entry handle of RPC entry
+ * @param params      parameter
+ * @param params_len  length of param in bytes
+ * @return RPC call handle (for use with NT_GetRpcResult() or
+ *         NT_CancelRpcResult()).
+ */
+NT_RpcCall NT_CallRpc(NT_Entry entry, const char* params, size_t params_len);
+
+/**
+ * Get the result (return value) of a RPC call.  This function blocks until
+ * the result is received.
+ *
+ * @param entry       entry handle of RPC entry
+ * @param call        RPC call handle returned by NT_CallRpc()
+ * @param result_len  length of returned result in bytes
+ * @return NULL on error, or result.
+ */
+char* NT_GetRpcResult(NT_Entry entry, NT_RpcCall call, size_t* result_len);
+
+/**
+ * Get the result (return value) of a RPC call.  This function blocks until
+ * the result is received or it times out.
+ *
+ * @param entry       entry handle of RPC entry
+ * @param call        RPC call handle returned by NT_CallRpc()
+ * @param result_len  length of returned result in bytes
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return NULL on error or timeout, or result.
+ */
+char* NT_GetRpcResultTimeout(NT_Entry entry, NT_RpcCall call,
+                             size_t* result_len, double timeout,
+                             NT_Bool* timed_out);
+
+/**
+ * Ignore the result of a RPC call.  This function is non-blocking.
+ *
+ * @param entry       entry handle of RPC entry
+ * @param call        RPC call handle returned by NT_CallRpc()
+ */
+void NT_CancelRpcResult(NT_Entry entry, NT_RpcCall call);
+
+/**
+ * Pack a RPC version 1 definition.
+ *
+ * @param def         RPC version 1 definition
+ * @param packed_len  length of return value in bytes
+ * @return Raw packed bytes.  Use C standard library std::free() to release.
+ */
+char* NT_PackRpcDefinition(const struct NT_RpcDefinition* def,
+                           size_t* packed_len);
+
+/**
+ * Unpack a RPC version 1 definition.  This can be used for introspection or
+ * validation.
+ *
+ * @param packed      raw packed bytes
+ * @param packed_len  length of packed in bytes
+ * @param def         RPC version 1 definition (output)
+ * @return True if successfully unpacked, false otherwise.
+ */
+NT_Bool NT_UnpackRpcDefinition(const char* packed, size_t packed_len,
+                               struct NT_RpcDefinition* def);
+
+/**
+ * Pack RPC values as required for RPC version 1 definition messages.
+ *
+ * @param values      array of values to pack
+ * @param values_len  length of values
+ * @param packed_len  length of return value in bytes
+ * @return Raw packed bytes.  Use C standard library std::free() to release.
+ */
+char* NT_PackRpcValues(const struct NT_Value** values, size_t values_len,
+                       size_t* packed_len);
+
+/**
+ * Unpack RPC values as required for RPC version 1 definition messages.
+ *
+ * @param packed      raw packed bytes
+ * @param packed_len  length of packed in bytes
+ * @param types       array of data types (as provided in the RPC definition)
+ * @param types_len   length of types
+ * @return Array of NT_Value's.
+ */
+struct NT_Value** NT_UnpackRpcValues(const char* packed, size_t packed_len,
+                                     const enum NT_Type* types,
+                                     size_t types_len);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_network_cfunc Client/Server Functions
+ * @{
+ */
+
+/**
+ * Set the network identity of this node.
+ * This is the name used during the initial connection handshake, and is
+ * visible through NT_ConnectionInfo on the remote node.
+ *
+ * @param inst      instance handle
+ * @param name      identity to advertise
+ * @param name_len  length of name in bytes
+ */
+void NT_SetNetworkIdentity(NT_Inst inst, const char* name, size_t name_len);
+
+/**
+ * Get the current network mode.
+ *
+ * @param inst  instance handle
+ * @return Bitmask of NT_NetworkMode.
+ */
+unsigned int NT_GetNetworkMode(NT_Inst inst);
+
+/**
+ * Starts a server using the specified filename, listening address, and port.
+ *
+ * @param inst              instance handle
+ * @param persist_filename  the name of the persist file to use (UTF-8 string,
+ *                          null terminated)
+ * @param listen_address    the address to listen on, or null to listen on any
+ *                          address. (UTF-8 string, null terminated)
+ * @param port              port to communicate over.
+ */
+void NT_StartServer(NT_Inst inst, const char* persist_filename,
+                    const char* listen_address, unsigned int port);
+
+/**
+ * Stops the server if it is running.
+ *
+ * @param inst  instance handle
+ */
+void NT_StopServer(NT_Inst inst);
+
+/**
+ * Starts a client.  Use NT_SetServer to set the server name and port.
+ *
+ * @param inst  instance handle
+ */
+void NT_StartClientNone(NT_Inst inst);
+
+/**
+ * Starts a client using the specified server and port
+ *
+ * @param inst        instance handle
+ * @param server_name server name (UTF-8 string, null terminated)
+ * @param port        port to communicate over
+ */
+void NT_StartClient(NT_Inst inst, const char* server_name, unsigned int port);
+
+/**
+ * Starts a client using the specified (server, port) combinations.  The
+ * client will attempt to connect to each server in round robin fashion.
+ *
+ * @param inst         instance handle
+ * @param count        length of the server_names and ports arrays
+ * @param server_names array of server names (each a UTF-8 string, null
+ *                     terminated)
+ * @param ports        array of ports to communicate over (one for each server)
+ */
+void NT_StartClientMulti(NT_Inst inst, size_t count, const char** server_names,
+                         const unsigned int* ports);
+
+/**
+ * Starts a client using commonly known robot addresses for the specified team.
+ *
+ * @param inst        instance handle
+ * @param team        team number
+ * @param port        port to communicate over
+ */
+void NT_StartClientTeam(NT_Inst inst, unsigned int team, unsigned int port);
+
+/**
+ * Stops the client if it is running.
+ *
+ * @param inst  instance handle
+ */
+void NT_StopClient(NT_Inst inst);
+
+/**
+ * Sets server address and port for client (without restarting client).
+ *
+ * @param inst        instance handle
+ * @param server_name server name (UTF-8 string, null terminated)
+ * @param port        port to communicate over
+ */
+void NT_SetServer(NT_Inst inst, const char* server_name, unsigned int port);
+
+/**
+ * Sets server addresses for client (without restarting client).
+ * The client will attempt to connect to each server in round robin fashion.
+ *
+ * @param inst         instance handle
+ * @param count        length of the server_names and ports arrays
+ * @param server_names array of server names (each a UTF-8 string, null
+ *                     terminated)
+ * @param ports        array of ports to communicate over (one for each server)
+ */
+void NT_SetServerMulti(NT_Inst inst, size_t count, const char** server_names,
+                       const unsigned int* ports);
+
+/**
+ * Sets server addresses and port for client (without restarting client).
+ * Connects using commonly known robot addresses for the specified team.
+ *
+ * @param inst        instance handle
+ * @param team        team number
+ * @param port        port to communicate over
+ */
+void NT_SetServerTeam(NT_Inst inst, unsigned int team, unsigned int port);
+
+/**
+ * Starts requesting server address from Driver Station.
+ * This connects to the Driver Station running on localhost to obtain the
+ * server IP address.
+ *
+ * @param inst  instance handle
+ * @param port server port to use in combination with IP from DS
+ */
+void NT_StartDSClient(NT_Inst inst, unsigned int port);
+
+/**
+ * Stops requesting server address from Driver Station.
+ *
+ * @param inst  instance handle
+ */
+void NT_StopDSClient(NT_Inst inst);
+
+/**
+ * Set the periodic update rate.
+ * Sets how frequently updates are sent to other nodes over the network.
+ *
+ * @param inst      instance handle
+ * @param interval  update interval in seconds (range 0.01 to 1.0)
+ */
+void NT_SetUpdateRate(NT_Inst inst, double interval);
+
+/**
+ * Flush Entries.
+ *
+ * Forces an immediate flush of all local entry changes to network.
+ * Normally this is done on a regularly scheduled interval (see
+ * NT_SetUpdateRate()).
+ *
+ * Note: flushes are rate limited to avoid excessive network traffic.  If
+ * the time between calls is too short, the flush will occur after the minimum
+ * time elapses (rather than immediately).
+ *
+ * @param inst      instance handle
+ */
+void NT_Flush(NT_Inst inst);
+
+/**
+ * Get information on the currently established network connections.
+ * If operating as a client, this will return either zero or one values.
+ *
+ * @param inst  instance handle
+ * @param count returns the number of elements in the array
+ * @return      array of connection information
+ *
+ * It is the caller's responsibility to free the array. The
+ * NT_DisposeConnectionInfoArray function is useful for this purpose.
+ */
+struct NT_ConnectionInfo* NT_GetConnections(NT_Inst inst, size_t* count);
+
+/**
+ * Return whether or not the instance is connected to another node.
+ *
+ * @param inst  instance handle
+ * @return True if connected.
+ */
+NT_Bool NT_IsConnected(NT_Inst inst);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_file_cfunc File Save/Load Functions
+ * @{
+ */
+
+/**
+ * Save persistent values to a file.  The server automatically does this,
+ * but this function provides a way to save persistent values in the same
+ * format to a file on either a client or a server.
+ *
+ * @param inst      instance handle
+ * @param filename  filename
+ * @return error string, or NULL if successful
+ */
+const char* NT_SavePersistent(NT_Inst inst, const char* filename);
+
+/**
+ * Load persistent values from a file.  The server automatically does this
+ * at startup, but this function provides a way to restore persistent values
+ * in the same format from a file at any time on either a client or a server.
+ *
+ * @param inst      instance handle
+ * @param filename  filename
+ * @param warn      callback function for warnings
+ * @return error string, or NULL if successful
+ */
+const char* NT_LoadPersistent(NT_Inst inst, const char* filename,
+                              void (*warn)(size_t line, const char* msg));
+
+/**
+ * Save table values to a file.  The file format used is identical to
+ * that used for SavePersistent.
+ *
+ * @param inst        instance handle
+ * @param filename    filename
+ * @param prefix      save only keys starting with this prefix
+ * @param prefix_len  length of prefix in bytes
+ * @return error string, or nullptr if successful
+ */
+const char* NT_SaveEntries(NT_Inst inst, const char* filename,
+                           const char* prefix, size_t prefix_len);
+
+/**
+ * Load table values from a file.  The file format used is identical to
+ * that used for SavePersistent / LoadPersistent.
+ *
+ * @param inst        instance handle
+ * @param filename    filename
+ * @param prefix      load only keys starting with this prefix
+ * @param prefix_len  length of prefix in bytes
+ * @param warn        callback function for warnings
+ * @return error string, or nullptr if successful
+ */
+const char* NT_LoadEntries(NT_Inst inst, const char* filename,
+                           const char* prefix, size_t prefix_len,
+                           void (*warn)(size_t line, const char* msg));
+
+/** @} */
+
+/**
+ * @defgroup ntcore_utility_cfunc Utility Functions
+ * @{
+ */
+
+/**
+ * Frees value memory.
+ *
+ * @param value   value to free
+ */
+void NT_DisposeValue(struct NT_Value* value);
+
+/**
+ * Initializes a NT_Value.
+ * Sets type to NT_UNASSIGNED and clears rest of struct.
+ *
+ * @param value value to initialize
+ */
+void NT_InitValue(struct NT_Value* value);
+
+/**
+ * Frees string memory.
+ *
+ * @param str   string to free
+ */
+void NT_DisposeString(struct NT_String* str);
+
+/**
+ * Initializes a NT_String.
+ * Sets length to zero and pointer to null.
+ *
+ * @param str   string to initialize
+ */
+void NT_InitString(struct NT_String* str);
+
+/**
+ * Disposes an entry handle array.
+ *
+ * @param arr   pointer to the array to dispose
+ * @param count number of elements in the array
+ */
+void NT_DisposeEntryArray(NT_Entry* arr, size_t count);
+
+/**
+ * Disposes a connection info array.
+ *
+ * @param arr   pointer to the array to dispose
+ * @param count number of elements in the array
+ */
+void NT_DisposeConnectionInfoArray(struct NT_ConnectionInfo* arr, size_t count);
+
+/**
+ * Disposes an entry info array.
+ *
+ * @param arr   pointer to the array to dispose
+ * @param count number of elements in the array
+ */
+void NT_DisposeEntryInfoArray(struct NT_EntryInfo* arr, size_t count);
+
+/**
+ * Disposes a single entry info (as returned by NT_GetEntryInfoHandle).
+ *
+ * @param info  pointer to the info to dispose
+ */
+void NT_DisposeEntryInfo(struct NT_EntryInfo* info);
+
+/**
+ * Disposes a Rpc Definition structure.
+ *
+ * @param def  pointer to the struct to dispose
+ */
+void NT_DisposeRpcDefinition(struct NT_RpcDefinition* def);
+
+/**
+ * Disposes a Rpc Answer array.
+ *
+ * @param arr   pointer to the array to dispose
+ * @param count number of elements in the array
+ */
+void NT_DisposeRpcAnswerArray(struct NT_RpcAnswer* arr, size_t count);
+
+/**
+ * Disposes a Rpc Answer structure.
+ *
+ * @param answer     pointer to the struct to dispose
+ */
+void NT_DisposeRpcAnswer(struct NT_RpcAnswer* answer);
+
+/**
+ * Disposes an entry notification array.
+ *
+ * @param arr   pointer to the array to dispose
+ * @param count number of elements in the array
+ */
+void NT_DisposeEntryNotificationArray(struct NT_EntryNotification* arr,
+                                      size_t count);
+
+/**
+ * Disposes a single entry notification.
+ *
+ * @param info  pointer to the info to dispose
+ */
+void NT_DisposeEntryNotification(struct NT_EntryNotification* info);
+
+/**
+ * Disposes a connection notification array.
+ *
+ * @param arr   pointer to the array to dispose
+ * @param count number of elements in the array
+ */
+void NT_DisposeConnectionNotificationArray(
+    struct NT_ConnectionNotification* arr, size_t count);
+
+/**
+ * Disposes a single connection notification.
+ *
+ * @param info  pointer to the info to dispose
+ */
+void NT_DisposeConnectionNotification(struct NT_ConnectionNotification* info);
+
+/**
+ * Disposes a log message array.
+ *
+ * @param arr   pointer to the array to dispose
+ * @param count number of elements in the array
+ */
+void NT_DisposeLogMessageArray(struct NT_LogMessage* arr, size_t count);
+
+/**
+ * Disposes a single log message.
+ *
+ * @param info  pointer to the info to dispose
+ */
+void NT_DisposeLogMessage(struct NT_LogMessage* info);
+
+/**
+ * Returns monotonic current time in 1 us increments.
+ * This is the same time base used for entry and connection timestamps.
+ * This function is a compatibility wrapper around WPI_Now().
+ *
+ * @return Timestamp
+ */
+uint64_t NT_Now(void);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_logger_cfunc Logger Functions
+ * @{
+ */
+
+/**
+ * Log function.
+ *
+ * @param data    data pointer passed to NT_AddLogger()
+ * @param msg     message information
+ */
+typedef void (*NT_LogFunc)(void* data, const struct NT_LogMessage* msg);
+
+/**
+ * Add logger callback function.  By default, log messages are sent to stderr;
+ * this function sends log messages to the provided callback function instead.
+ * The callback function will only be called for log messages with level
+ * greater than or equal to min_level and less than or equal to max_level;
+ * messages outside this range will be silently ignored.
+ *
+ * @param inst        instance handle
+ * @param data        data pointer to pass to func
+ * @param func        log callback function
+ * @param min_level   minimum log level
+ * @param max_level   maximum log level
+ * @return Logger handle
+ */
+NT_Logger NT_AddLogger(NT_Inst inst, void* data, NT_LogFunc func,
+                       unsigned int min_level, unsigned int max_level);
+
+/**
+ * Create a log poller.  A poller provides a single queue of poll events.
+ * The returned handle must be destroyed with NT_DestroyLoggerPoller().
+ *
+ * @param inst      instance handle
+ * @return poller handle
+ */
+NT_LoggerPoller NT_CreateLoggerPoller(NT_Inst inst);
+
+/**
+ * Destroy a log poller.  This will abort any blocked polling call and prevent
+ * additional events from being generated for this poller.
+ *
+ * @param poller    poller handle
+ */
+void NT_DestroyLoggerPoller(NT_LoggerPoller poller);
+
+/**
+ * Set the log level for a log poller.  Events will only be generated for
+ * log messages with level greater than or equal to min_level and less than or
+ * equal to max_level; messages outside this range will be silently ignored.
+ *
+ * @param poller        poller handle
+ * @param min_level     minimum log level
+ * @param max_level     maximum log level
+ * @return Logger handle
+ */
+NT_Logger NT_AddPolledLogger(NT_LoggerPoller poller, unsigned int min_level,
+                             unsigned int max_level);
+
+/**
+ * Get the next log event.  This blocks until the next log occurs.
+ *
+ * @param poller    poller handle
+ * @param len       length of returned array (output)
+ * @return Array of information on the log events.  Only returns NULL if an
+ *         error occurred (e.g. the instance was invalid or is shutting down).
+ */
+struct NT_LogMessage* NT_PollLogger(NT_LoggerPoller poller, size_t* len);
+
+/**
+ * Get the next log event.  This blocks until the next log occurs or it times
+ * out.
+ *
+ * @param poller      poller handle
+ * @param len         length of returned array (output)
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return Array of information on the log events.  If NULL is returned and
+ *         timed_out is also false, an error occurred (e.g. the instance was
+ *         invalid or is shutting down).
+ */
+struct NT_LogMessage* NT_PollLoggerTimeout(NT_LoggerPoller poller, size_t* len,
+                                           double timeout, NT_Bool* timed_out);
+
+/**
+ * Cancel a PollLogger call.  This wakes up a call to PollLogger for this
+ * poller and causes it to immediately return an empty array.
+ *
+ * @param poller  poller handle
+ */
+void NT_CancelPollLogger(NT_LoggerPoller poller);
+
+/**
+ * Remove a logger.
+ *
+ * @param logger Logger handle to remove
+ */
+void NT_RemoveLogger(NT_Logger logger);
+
+/**
+ * Wait for the incoming log event queue to be empty.  This is primarily useful
+ * for deterministic testing.  This blocks until either the log event
+ * queue is empty (e.g. there are no more events that need to be passed along
+ * to callbacks or poll queues) or the timeout expires.
+ *
+ * @param inst      instance handle
+ * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+ *                  or a negative value to block indefinitely
+ * @return False if timed out, otherwise true.
+ */
+NT_Bool NT_WaitForLoggerQueue(NT_Inst inst, double timeout);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_interop_cfunc Interop Utility Functions
+ * @{
+ */
+
+/**
+ * @defgroup ntcore_memoryallocators_cfunc Memory Allocators
+ * @{
+ */
+
+/**
+ * Allocates an array of chars.
+ * Note that the size is the number of elements, and not the
+ * specific number of bytes to allocate. That is calculated internally.
+ *
+ * @param size  the number of elements the array will contain
+ * @return      the allocated char array
+ *
+ * After use, the array should be freed using the NT_FreeCharArray()
+ * function.
+ */
+char* NT_AllocateCharArray(size_t size);
+
+/**
+ * Allocates an array of booleans.
+ * Note that the size is the number of elements, and not the
+ * specific number of bytes to allocate. That is calculated internally.
+ *
+ * @param size  the number of elements the array will contain
+ * @return      the allocated boolean array
+ *
+ * After use, the array should be freed using the NT_FreeBooleanArray()
+ * function.
+ */
+NT_Bool* NT_AllocateBooleanArray(size_t size);
+
+/**
+ * Allocates an array of doubles.
+ * Note that the size is the number of elements, and not the
+ * specific number of bytes to allocate. That is calculated internally.
+ *
+ * @param size  the number of elements the array will contain
+ * @return      the allocated double array
+ *
+ * After use, the array should be freed using the NT_FreeDoubleArray()
+ * function.
+ */
+double* NT_AllocateDoubleArray(size_t size);
+
+/**
+ * Allocates an array of NT_Strings.
+ * Note that the size is the number of elements, and not the
+ * specific number of bytes to allocate. That is calculated internally.
+ *
+ * @param size  the number of elements the array will contain
+ * @return      the allocated NT_String array
+ *
+ * After use, the array should be freed using the NT_FreeStringArray()
+ * function.
+ */
+struct NT_String* NT_AllocateStringArray(size_t size);
+
+/**
+ * Frees an array of chars.
+ *
+ * @param v_boolean  pointer to the char array to free
+ */
+void NT_FreeCharArray(char* v_char);
+
+/**
+ * Frees an array of doubles.
+ *
+ * @param v_boolean  pointer to the double array to free
+ */
+void NT_FreeDoubleArray(double* v_double);
+
+/**
+ * Frees an array of booleans.
+ *
+ * @param v_boolean  pointer to the boolean array to free
+ */
+void NT_FreeBooleanArray(NT_Bool* v_boolean);
+
+/**
+ * Frees an array of NT_Strings.
+ *
+ * @param v_string  pointer to the string array to free
+ * @param arr_size  size of the string array to free
+ *
+ * Note that the individual NT_Strings in the array should NOT be
+ * freed before calling this. This function will free all the strings
+ * individually.
+ */
+void NT_FreeStringArray(struct NT_String* v_string, size_t arr_size);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_typedgetters_cfunc Typed Getters
+ * @{
+ */
+
+/**
+ * Returns the type of an NT_Value struct.
+ * Note that one of the type options is "unassigned".
+ *
+ * @param value  The NT_Value struct to get the type from.
+ * @return       The type of the value, or unassigned if null.
+ */
+enum NT_Type NT_GetValueType(const struct NT_Value* value);
+
+/**
+ * Returns the boolean from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns 0.
+ *
+ * @param value       NT_Value struct to get the boolean from
+ * @param last_change returns time in ms since the last change in the value
+ * @param v_boolean   returns the boolean assigned to the name
+ * @return            1 if successful, or 0 if value is null or not a boolean
+ */
+NT_Bool NT_GetValueBoolean(const struct NT_Value* value, uint64_t* last_change,
+                           NT_Bool* v_boolean);
+
+/**
+ * Returns the double from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns 0.
+ *
+ * @param value       NT_Value struct to get the double from
+ * @param last_change returns time in ms since the last change in the value
+ * @param v_double    returns the boolean assigned to the name
+ * @return            1 if successful, or 0 if value is null or not a double
+ */
+NT_Bool NT_GetValueDouble(const struct NT_Value* value, uint64_t* last_change,
+                          double* v_double);
+
+/**
+ * Returns a copy of the string from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns 0.
+ *
+ * @param value       NT_Value struct to get the string from
+ * @param last_change returns time in ms since the last change in the value
+ * @param str_len     returns the length of the string
+ * @return            pointer to the string (UTF-8), or null if error
+ *
+ * It is the caller's responsibility to free the string once its no longer
+ * needed. The NT_FreeCharArray() function is useful for this purpose. The
+ * returned string is a copy of the string in the value, and must be freed
+ * separately.
+ */
+char* NT_GetValueString(const struct NT_Value* value, uint64_t* last_change,
+                        size_t* str_len);
+
+/**
+ * Returns a copy of the raw value from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns null.
+ *
+ * @param value       NT_Value struct to get the string from
+ * @param last_change returns time in ms since the last change in the value
+ * @param raw_len     returns the length of the string
+ * @return            pointer to the raw value (UTF-8), or null if error
+ *
+ * It is the caller's responsibility to free the raw value once its no longer
+ * needed. The NT_FreeCharArray() function is useful for this purpose. The
+ * returned string is a copy of the string in the value, and must be freed
+ * separately.
+ */
+char* NT_GetValueRaw(const struct NT_Value* value, uint64_t* last_change,
+                     size_t* raw_len);
+
+/**
+ * Returns a copy of the boolean array from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns null.
+ *
+ * @param value       NT_Value struct to get the boolean array from
+ * @param last_change returns time in ms since the last change in the value
+ * @param arr_size    returns the number of elements in the array
+ * @return            pointer to the boolean array, or null if error
+ *
+ * It is the caller's responsibility to free the array once its no longer
+ * needed. The NT_FreeBooleanArray() function is useful for this purpose.
+ * The returned array is a copy of the array in the value, and must be
+ * freed separately.
+ */
+NT_Bool* NT_GetValueBooleanArray(const struct NT_Value* value,
+                                 uint64_t* last_change, size_t* arr_size);
+
+/**
+ * Returns a copy of the double array from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns null.
+ *
+ * @param value       NT_Value struct to get the double array from
+ * @param last_change returns time in ms since the last change in the value
+ * @param arr_size    returns the number of elements in the array
+ * @return            pointer to the double array, or null if error
+ *
+ * It is the caller's responsibility to free the array once its no longer
+ * needed. The NT_FreeDoubleArray() function is useful for this purpose.
+ * The returned array is a copy of the array in the value, and must be
+ * freed separately.
+ */
+double* NT_GetValueDoubleArray(const struct NT_Value* value,
+                               uint64_t* last_change, size_t* arr_size);
+
+/**
+ * Returns a copy of the NT_String array from the NT_Value.
+ * If the NT_Value is null, or is assigned to a different type, returns null.
+ *
+ * @param value       NT_Value struct to get the NT_String array from
+ * @param last_change returns time in ms since the last change in the value
+ * @param arr_size    returns the number of elements in the array
+ * @return            pointer to the NT_String array, or null if error
+ *
+ * It is the caller's responsibility to free the array once its no longer
+ * needed. The NT_FreeStringArray() function is useful for this purpose.
+ * The returned array is a copy of the array in the value, and must be
+ * freed seperately. Note that the individual NT_Strings should not be freed,
+ * but the entire array should be freed at once. The NT_FreeStringArray()
+ * function will free all the NT_Strings.
+ */
+struct NT_String* NT_GetValueStringArray(const struct NT_Value* value,
+                                         uint64_t* last_change,
+                                         size_t* arr_size);
+
+/**
+ * Returns the boolean currently assigned to the entry name.
+ * If the entry name is not currently assigned, or is assigned to a
+ * different type, returns 0.
+ *
+ * @param entry       entry handle
+ * @param last_change returns time in ms since the last change in the value
+ * @param v_boolean   returns the boolean assigned to the name
+ * @return            1 if successful, or 0 if value is unassigned or not a
+ *                    boolean
+ */
+NT_Bool NT_GetEntryBoolean(NT_Entry entry, uint64_t* last_change,
+                           NT_Bool* v_boolean);
+
+/**
+ * Returns the double currently assigned to the entry name.
+ * If the entry name is not currently assigned, or is assigned to a
+ * different type, returns 0.
+ *
+ * @param entry       entry handle
+ * @param last_change returns time in ms since the last change in the value
+ * @param v_double    returns the double assigned to the name
+ * @return            1 if successful, or 0 if value is unassigned or not a
+ *                    double
+ */
+NT_Bool NT_GetEntryDouble(NT_Entry entry, uint64_t* last_change,
+                          double* v_double);
+
+/**
+ * Returns a copy of the string assigned to the entry name.
+ * If the entry name is not currently assigned, or is assigned to a
+ * different type, returns null.
+ *
+ * @param entry       entry handle
+ * @param last_change returns time in ms since the last change in the value
+ * @param str_len     returns the length of the string
+ * @return            pointer to the string (UTF-8), or null if error
+ *
+ * It is the caller's responsibility to free the string once its no longer
+ * needed. The NT_FreeCharArray() function is useful for this purpose.
+ */
+char* NT_GetEntryString(NT_Entry entry, uint64_t* last_change, size_t* str_len);
+
+/**
+ * Returns a copy of the raw value assigned to the entry name.
+ * If the entry name is not currently assigned, or is assigned to a
+ * different type, returns null.
+ *
+ * @param entry       entry handle
+ * @param last_change returns time in ms since the last change in the value
+ * @param raw_len     returns the length of the string
+ * @return            pointer to the raw value (UTF-8), or null if error
+ *
+ * It is the caller's responsibility to free the raw value once its no longer
+ * needed. The NT_FreeCharArray() function is useful for this purpose.
+ */
+char* NT_GetEntryRaw(NT_Entry entry, uint64_t* last_change, size_t* raw_len);
+
+/**
+ * Returns a copy of the boolean array assigned to the entry name.
+ * If the entry name is not currently assigned, or is assigned to a
+ * different type, returns null.
+ *
+ * @param entry       entry handle
+ * @param last_change returns time in ms since the last change in the value
+ * @param arr_size    returns the number of elements in the array
+ * @return            pointer to the boolean array, or null if error
+ *
+ * It is the caller's responsibility to free the array once its no longer
+ * needed. The NT_FreeBooleanArray() function is useful for this purpose.
+ */
+NT_Bool* NT_GetEntryBooleanArray(NT_Entry entry, uint64_t* last_change,
+                                 size_t* arr_size);
+
+/**
+ * Returns a copy of the double array assigned to the entry name.
+ * If the entry name is not currently assigned, or is assigned to a
+ * different type, returns null.
+ *
+ * @param entry       entry handle
+ * @param last_change returns time in ms since the last change in the value
+ * @param arr_size    returns the number of elements in the array
+ * @return            pointer to the double array, or null if error
+ *
+ * It is the caller's responsibility to free the array once its no longer
+ * needed. The NT_FreeDoubleArray() function is useful for this purpose.
+ */
+double* NT_GetEntryDoubleArray(NT_Entry entry, uint64_t* last_change,
+                               size_t* arr_size);
+
+/**
+ * Returns a copy of the NT_String array assigned to the entry name.
+ * If the entry name is not currently assigned, or is assigned to a
+ * different type, returns null.
+ *
+ * @param entry       entry handle
+ * @param last_change returns time in ms since the last change in the value
+ * @param arr_size    returns the number of elements in the array
+ * @return            pointer to the NT_String array, or null if error
+ *
+ * It is the caller's responsibility to free the array once its no longer
+ * needed. The NT_FreeStringArray() function is useful for this purpose. Note
+ * that the individual NT_Strings should not be freed, but the entire array
+ * should be freed at once. The NT_FreeStringArray() function will free all the
+ * NT_Strings.
+ */
+struct NT_String* NT_GetEntryStringArray(NT_Entry entry, uint64_t* last_change,
+                                         size_t* arr_size);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_setdefault_cfunc Set Default Values
+ * @{
+ */
+
+/** Set Default Entry Boolean.
+ * Sets the default for the specified key to be a boolean.
+ * If key exists with same type, does not set value. Otherwise
+ * sets value to the default.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param default_boolean     value to be set if name does not exist
+ * @return 0 on error (value not set), 1 on success
+ */
+NT_Bool NT_SetDefaultEntryBoolean(NT_Entry entry, uint64_t time,
+                                  NT_Bool default_boolean);
+
+/** Set Default Entry Double.
+ * Sets the default for the specified key.
+ * If key exists with same type, does not set value. Otherwise
+ * sets value to the default.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param default_double     value to be set if name does not exist
+ * @return 0 on error (value not set), 1 on success
+ */
+NT_Bool NT_SetDefaultEntryDouble(NT_Entry entry, uint64_t time,
+                                 double default_double);
+
+/** Set Default Entry String.
+ * Sets the default for the specified key.
+ * If key exists with same type, does not set value. Otherwise
+ * sets value to the default.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param default_value     value to be set if name does not exist
+ * @param default_len       length of value
+ * @return 0 on error (value not set), 1 on success
+ */
+NT_Bool NT_SetDefaultEntryString(NT_Entry entry, uint64_t time,
+                                 const char* default_value, size_t default_len);
+
+/** Set Default Entry Raw.
+ * Sets the default for the specified key.
+ * If key exists with same type, does not set value. Otherwise
+ * sets value to the default.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param default_value     value to be set if name does not exist
+ * @param default_len       length of value array
+ * @return 0 on error (value not set), 1 on success
+ */
+NT_Bool NT_SetDefaultEntryRaw(NT_Entry entry, uint64_t time,
+                              const char* default_value, size_t default_len);
+
+/** Set Default Entry Boolean Array.
+ * Sets the default for the specified key.
+ * If key exists with same type, does not set value. Otherwise
+ * sets value to the default.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param default_value     value to be set if name does not exist
+ * @param default_size      size of value array
+ * @return 0 on error (value not set), 1 on success
+ */
+NT_Bool NT_SetDefaultEntryBooleanArray(NT_Entry entry, uint64_t time,
+                                       const int* default_value,
+                                       size_t default_size);
+
+/** Set Default Entry Double Array.
+ * Sets the default for the specified key.
+ * If key exists with same type, does not set value. Otherwise
+ * sets value to the default.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param default_value     value to be set if name does not exist
+ * @param default_size      size of value array
+ * @return 0 on error (value not set), 1 on success
+ */
+NT_Bool NT_SetDefaultEntryDoubleArray(NT_Entry entry, uint64_t time,
+                                      const double* default_value,
+                                      size_t default_size);
+
+/** Set Default Entry String Array.
+ * Sets the default for the specified key.
+ * If key exists with same type, does not set value. Otherwise
+ * sets value to the default.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param default_value     value to be set if name does not exist
+ * @param default_size      size of value array
+ * @return 0 on error (value not set), 1 on success
+ */
+NT_Bool NT_SetDefaultEntryStringArray(NT_Entry entry, uint64_t time,
+                                      const struct NT_String* default_value,
+                                      size_t default_size);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_valuesetters_cfunc Entry Value Setters
+ * @{
+ */
+
+/** Set Entry Boolean
+ * Sets an entry boolean. If the entry name is not currently assigned to a
+ * boolean, returns error unless the force parameter is set.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param v_boolean boolean value to set
+ * @param force     1 to force the entry to get overwritten, otherwise 0
+ * @return          0 on error (type mismatch), 1 on success
+ */
+NT_Bool NT_SetEntryBoolean(NT_Entry entry, uint64_t time, NT_Bool v_boolean,
+                           NT_Bool force);
+
+/** Set Entry Double
+ * Sets an entry double. If the entry name is not currently assigned to a
+ * double, returns error unless the force parameter is set.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param v_double  double value to set
+ * @param force     1 to force the entry to get overwritten, otherwise 0
+ * @return          0 on error (type mismatch), 1 on success
+ */
+NT_Bool NT_SetEntryDouble(NT_Entry entry, uint64_t time, double v_double,
+                          NT_Bool force);
+
+/** Set Entry String
+ * Sets an entry string. If the entry name is not currently assigned to a
+ * string, returns error unless the force parameter is set.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param str       string to set (UTF-8 string)
+ * @param str_len   length of string to write in bytes
+ * @param force     1 to force the entry to get overwritten, otherwise 0
+ * @return          0 on error (type mismatch), 1 on success
+ */
+NT_Bool NT_SetEntryString(NT_Entry entry, uint64_t time, const char* str,
+                          size_t str_len, NT_Bool force);
+
+/** Set Entry Raw
+ * Sets the raw value of an entry. If the entry name is not currently assigned
+ * to a raw value, returns error unless the force parameter is set.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param raw       raw string to set (UTF-8 string)
+ * @param raw_len   length of raw string to write in bytes
+ * @param force     1 to force the entry to get overwritten, otherwise 0
+ * @return          0 on error (type mismatch), 1 on success
+ */
+NT_Bool NT_SetEntryRaw(NT_Entry entry, uint64_t time, const char* raw,
+                       size_t raw_len, NT_Bool force);
+
+/** Set Entry Boolean Array
+ * Sets an entry boolean array. If the entry name is not currently assigned to
+ * a boolean array, returns error unless the force parameter is set.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param arr       boolean array to write
+ * @param size      number of elements in the array
+ * @param force     1 to force the entry to get overwritten, otherwise 0
+ * @return          0 on error (type mismatch), 1 on success
+ */
+NT_Bool NT_SetEntryBooleanArray(NT_Entry entry, uint64_t time, const int* arr,
+                                size_t size, NT_Bool force);
+
+/** Set Entry Double Array
+ * Sets an entry double array. If the entry name is not currently assigned to
+ * a double array, returns error unless the force parameter is set.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param arr       double array to write
+ * @param size      number of elements in the array
+ * @param force     1 to force the entry to get overwritten, otherwise 0
+ * @return          0 on error (type mismatch), 1 on success
+ */
+NT_Bool NT_SetEntryDoubleArray(NT_Entry entry, uint64_t time, const double* arr,
+                               size_t size, NT_Bool force);
+
+/** Set Entry String Array
+ * Sets an entry string array. If the entry name is not currently assigned to
+ * a string array, returns error unless the force parameter is set.
+ *
+ * @param entry     entry handle
+ * @param time      timestamp
+ * @param arr       NT_String array to write
+ * @param size      number of elements in the array
+ * @param force     1 to force the entry to get overwritten, otherwise 0
+ * @return          0 on error (type mismatch), 1 on success
+ */
+NT_Bool NT_SetEntryStringArray(NT_Entry entry, uint64_t time,
+                               const struct NT_String* arr, size_t size,
+                               NT_Bool force);
+
+/** @} */
+/** @} */
+/** @} */
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#endif  // NTCORE_NTCORE_C_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_cpp.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_cpp.h
new file mode 100644
index 0000000..56cb5af
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_cpp.h
@@ -0,0 +1,1600 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NTCORE_CPP_H_
+#define NTCORE_NTCORE_CPP_H_
+
+#include <stdint.h>
+
+#include <cassert>
+#include <functional>
+#include <memory>
+#include <string>
+#include <thread>
+#include <utility>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+
+#include "networktables/NetworkTableValue.h"
+
+/** NetworkTables (ntcore) namespace */
+namespace nt {
+
+/**
+ * @defgroup ntcore_cpp_handle_api ntcore C++ API
+ *
+ * Handle-based interface for C++.
+ *
+ * @{
+ */
+
+using wpi::ArrayRef;
+using wpi::StringRef;
+using wpi::Twine;
+
+/** NetworkTables Entry Information */
+struct EntryInfo {
+  /** Entry handle */
+  NT_Entry entry;
+
+  /** Entry name */
+  std::string name;
+
+  /** Entry type */
+  NT_Type type;
+
+  /** Entry flags */
+  unsigned int flags;
+
+  /** Timestamp of last change to entry (type or value). */
+  uint64_t last_change;
+
+  friend void swap(EntryInfo& first, EntryInfo& second) {
+    using std::swap;
+    swap(first.entry, second.entry);
+    swap(first.name, second.name);
+    swap(first.type, second.type);
+    swap(first.flags, second.flags);
+    swap(first.last_change, second.last_change);
+  }
+};
+
+/** NetworkTables Connection Information */
+struct ConnectionInfo {
+  /**
+   * The remote identifier (as set on the remote node by
+   * NetworkTableInstance::SetNetworkIdentity() or nt::SetNetworkIdentity()).
+   */
+  std::string remote_id;
+
+  /** The IP address of the remote node. */
+  std::string remote_ip;
+
+  /** The port number of the remote node. */
+  unsigned int remote_port;
+
+  /**
+   * The last time any update was received from the remote node (same scale as
+   * returned by nt::Now()).
+   */
+  uint64_t last_update;
+
+  /**
+   * The protocol version being used for this connection.  This in protocol
+   * layer format, so 0x0200 = 2.0, 0x0300 = 3.0).
+   */
+  unsigned int protocol_version;
+
+  friend void swap(ConnectionInfo& first, ConnectionInfo& second) {
+    using std::swap;
+    swap(first.remote_id, second.remote_id);
+    swap(first.remote_ip, second.remote_ip);
+    swap(first.remote_port, second.remote_port);
+    swap(first.last_update, second.last_update);
+    swap(first.protocol_version, second.protocol_version);
+  }
+};
+
+/** NetworkTables RPC Version 1 Definition Parameter */
+struct RpcParamDef {
+  RpcParamDef() = default;
+  RpcParamDef(StringRef name_, std::shared_ptr<Value> def_value_)
+      : name(name_), def_value(def_value_) {}
+
+  std::string name;
+  std::shared_ptr<Value> def_value;
+};
+
+/** NetworkTables RPC Version 1 Definition Result */
+struct RpcResultDef {
+  RpcResultDef() = default;
+  RpcResultDef(StringRef name_, NT_Type type_) : name(name_), type(type_) {}
+
+  std::string name;
+  NT_Type type;
+};
+
+/** NetworkTables RPC Version 1 Definition */
+struct RpcDefinition {
+  unsigned int version;
+  std::string name;
+  std::vector<RpcParamDef> params;
+  std::vector<RpcResultDef> results;
+};
+
+/** NetworkTables Remote Procedure Call (Server Side) */
+class RpcAnswer {
+ public:
+  RpcAnswer() : entry(0), call(0) {}
+  RpcAnswer(NT_Entry entry_, NT_RpcCall call_, StringRef name_,
+            StringRef params_, const ConnectionInfo& conn_)
+      : entry(entry_), call(call_), name(name_), params(params_), conn(conn_) {}
+
+  /** Entry handle. */
+  NT_Entry entry;
+
+  /** Call handle. */
+  mutable NT_RpcCall call;
+
+  /** Entry name. */
+  std::string name;
+
+  /** Call raw parameters. */
+  std::string params;
+
+  /** Connection that called the RPC. */
+  ConnectionInfo conn;
+
+  /**
+   * Determines if the native handle is valid.
+   * @return True if the native handle is valid, false otherwise.
+   */
+  explicit operator bool() const { return call != 0; }
+
+  /**
+   * Post RPC response (return value) for a polled RPC.
+   * @param result  result raw data that will be provided to remote caller
+   * @return True if posting the response is valid, otherwise false
+   */
+  bool PostResponse(StringRef result) const;
+
+  friend void swap(RpcAnswer& first, RpcAnswer& second) {
+    using std::swap;
+    swap(first.entry, second.entry);
+    swap(first.call, second.call);
+    swap(first.name, second.name);
+    swap(first.params, second.params);
+    swap(first.conn, second.conn);
+  }
+};
+
+/** NetworkTables Entry Notification */
+class EntryNotification {
+ public:
+  EntryNotification() : listener(0), entry(0) {}
+  EntryNotification(NT_EntryListener listener_, NT_Entry entry_,
+                    StringRef name_, std::shared_ptr<Value> value_,
+                    unsigned int flags_)
+      : listener(listener_),
+        entry(entry_),
+        name(name_),
+        value(value_),
+        flags(flags_) {}
+
+  /** Listener that was triggered. */
+  NT_EntryListener listener;
+
+  /** Entry handle. */
+  NT_Entry entry;
+
+  /** Entry name. */
+  std::string name;
+
+  /** The new value. */
+  std::shared_ptr<Value> value;
+
+  /**
+   * Update flags.  For example, NT_NOTIFY_NEW if the key did not previously
+   * exist.
+   */
+  unsigned int flags;
+
+  friend void swap(EntryNotification& first, EntryNotification& second) {
+    using std::swap;
+    swap(first.listener, second.listener);
+    swap(first.entry, second.entry);
+    swap(first.name, second.name);
+    swap(first.value, second.value);
+    swap(first.flags, second.flags);
+  }
+};
+
+/** NetworkTables Connection Notification */
+class ConnectionNotification {
+ public:
+  ConnectionNotification() : listener(0), connected(false) {}
+  ConnectionNotification(NT_ConnectionListener listener_, bool connected_,
+                         const ConnectionInfo& conn_)
+      : listener(listener_), connected(connected_), conn(conn_) {}
+
+  /** Listener that was triggered. */
+  NT_ConnectionListener listener;
+
+  /** True if event is due to connection being established. */
+  bool connected = false;
+
+  /** Connection info. */
+  ConnectionInfo conn;
+
+  friend void swap(ConnectionNotification& first,
+                   ConnectionNotification& second) {
+    using std::swap;
+    swap(first.listener, second.listener);
+    swap(first.connected, second.connected);
+    swap(first.conn, second.conn);
+  }
+};
+
+/** NetworkTables log message. */
+class LogMessage {
+ public:
+  LogMessage() : logger(0), level(0), filename(""), line(0) {}
+  LogMessage(NT_Logger logger_, unsigned int level_, const char* filename_,
+             unsigned int line_, StringRef message_)
+      : logger(logger_),
+        level(level_),
+        filename(filename_),
+        line(line_),
+        message(message_) {}
+
+  /** The logger that generated the message. */
+  NT_Logger logger;
+
+  /** Log level of the message.  See NT_LogLevel. */
+  unsigned int level;
+
+  /** The filename of the source file that generated the message. */
+  const char* filename;
+
+  /** The line number in the source file that generated the message. */
+  unsigned int line;
+
+  /** The message. */
+  std::string message;
+
+  friend void swap(LogMessage& first, LogMessage& second) {
+    using std::swap;
+    swap(first.logger, second.logger);
+    swap(first.level, second.level);
+    swap(first.filename, second.filename);
+    swap(first.line, second.line);
+    swap(first.message, second.message);
+  }
+};
+
+/**
+ * @defgroup ntcore_instance_func Instance Functions
+ * @{
+ */
+
+/**
+ * Get default instance.
+ * This is the instance used by non-handle-taking functions.
+ *
+ * @return Instance handle
+ */
+NT_Inst GetDefaultInstance();
+
+/**
+ * Create an instance.
+ *
+ * @return Instance handle
+ */
+NT_Inst CreateInstance();
+
+/**
+ * Destroy an instance.
+ * The default instance cannot be destroyed.
+ *
+ * @param inst Instance handle
+ */
+void DestroyInstance(NT_Inst inst);
+
+/**
+ * Get instance handle from another handle.
+ *
+ * @param handle    entry/instance/etc. handle
+ * @return Instance handle
+ */
+NT_Inst GetInstanceFromHandle(NT_Handle handle);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_table_func Table Functions
+ * @{
+ */
+
+/**
+ * Get Entry Handle.
+ *
+ * @param inst      instance handle
+ * @param name      entry name (UTF-8 string)
+ * @return entry handle
+ */
+NT_Entry GetEntry(NT_Inst inst, const Twine& name);
+
+/**
+ * Get Entry Handles.
+ *
+ * Returns an array of entry handles.  The results are optionally
+ * filtered by string prefix and entry type to only return a subset of all
+ * entries.
+ *
+ * @param inst          instance handle
+ * @param prefix        entry name required prefix; only entries whose name
+ *                      starts with this string are returned
+ * @param types         bitmask of NT_Type values; 0 is treated specially
+ *                      as a "don't care"
+ * @return Array of entry handles.
+ */
+std::vector<NT_Entry> GetEntries(NT_Inst inst, const Twine& prefix,
+                                 unsigned int types);
+
+/**
+ * Gets the name of the specified entry.
+ * Returns an empty string if the handle is invalid.
+ *
+ * @param entry   entry handle
+ * @return Entry name
+ */
+std::string GetEntryName(NT_Entry entry);
+
+/**
+ * Gets the type for the specified entry, or unassigned if non existent.
+ *
+ * @param entry   entry handle
+ * @return Entry type
+ */
+NT_Type GetEntryType(NT_Entry entry);
+
+/**
+ * Gets the last time the entry was changed.
+ * Returns 0 if the handle is invalid.
+ *
+ * @param entry   entry handle
+ * @return Entry last change time
+ */
+uint64_t GetEntryLastChange(NT_Entry entry);
+
+/**
+ * Get Entry Value.
+ *
+ * Returns copy of current entry value.
+ * Note that one of the type options is "unassigned".
+ *
+ * @param name      entry name (UTF-8 string)
+ * @return entry value
+ */
+WPI_DEPRECATED("use NT_Entry function instead")
+std::shared_ptr<Value> GetEntryValue(StringRef name);
+
+/**
+ * Get Entry Value.
+ *
+ * Returns copy of current entry value.
+ * Note that one of the type options is "unassigned".
+ *
+ * @param entry     entry handle
+ * @return entry value
+ */
+std::shared_ptr<Value> GetEntryValue(NT_Entry entry);
+
+/**
+ * Set Default Entry Value
+ *
+ * Returns copy of current entry value if it exists.
+ * Otherwise, sets passed in value, and returns set value.
+ * Note that one of the type options is "unassigned".
+ *
+ * @param name      entry name (UTF-8 string)
+ * @param value     value to be set if name does not exist
+ * @return False on error (value not set), True on success
+ */
+WPI_DEPRECATED("use NT_Entry function instead")
+bool SetDefaultEntryValue(StringRef name, std::shared_ptr<Value> value);
+
+/**
+ * Set Default Entry Value
+ *
+ * Returns copy of current entry value if it exists.
+ * Otherwise, sets passed in value, and returns set value.
+ * Note that one of the type options is "unassigned".
+ *
+ * @param entry     entry handle
+ * @param value     value to be set if name does not exist
+ * @return False on error (value not set), True on success
+ */
+bool SetDefaultEntryValue(NT_Entry entry, std::shared_ptr<Value> value);
+
+/**
+ * Set Entry Value.
+ *
+ * Sets new entry value.  If type of new value differs from the type of the
+ * currently stored entry, returns error and does not update value.
+ *
+ * @param name      entry name (UTF-8 string)
+ * @param value     new entry value
+ * @return False on error (type mismatch), True on success
+ */
+WPI_DEPRECATED("use NT_Entry function instead")
+bool SetEntryValue(StringRef name, std::shared_ptr<Value> value);
+
+/**
+ * Set Entry Value.
+ *
+ * Sets new entry value.  If type of new value differs from the type of the
+ * currently stored entry, returns error and does not update value.
+ *
+ * @param entry     entry handle
+ * @param value     new entry value
+ * @return False on error (type mismatch), True on success
+ */
+bool SetEntryValue(NT_Entry entry, std::shared_ptr<Value> value);
+
+/**
+ * Set Entry Type and Value.
+ *
+ * Sets new entry value.  If type of new value differs from the type of the
+ * currently stored entry, the currently stored entry type is overridden
+ * (generally this will generate an Entry Assignment message).
+ *
+ * This is NOT the preferred method to update a value; generally
+ * SetEntryValue() should be used instead, with appropriate error handling.
+ *
+ * @param name      entry name (UTF-8 string)
+ * @param value     new entry value
+ */
+WPI_DEPRECATED("use NT_Entry function instead")
+void SetEntryTypeValue(StringRef name, std::shared_ptr<Value> value);
+
+/**
+ * Set Entry Type and Value.
+ *
+ * Sets new entry value.  If type of new value differs from the type of the
+ * currently stored entry, the currently stored entry type is overridden
+ * (generally this will generate an Entry Assignment message).
+ *
+ * This is NOT the preferred method to update a value; generally
+ * SetEntryValue() should be used instead, with appropriate error handling.
+ *
+ * @param entry     entry handle
+ * @param value     new entry value
+ */
+void SetEntryTypeValue(NT_Entry entry, std::shared_ptr<Value> value);
+
+/**
+ * Set Entry Flags.
+ *
+ * @param name      entry name (UTF-8 string)
+ * @param flags     flags value (bitmask of NT_EntryFlags)
+ */
+WPI_DEPRECATED("use NT_Entry function instead")
+void SetEntryFlags(StringRef name, unsigned int flags);
+
+/**
+ * Set Entry Flags.
+ *
+ * @param entry     entry handle
+ * @param flags     flags value (bitmask of NT_EntryFlags)
+ */
+void SetEntryFlags(NT_Entry entry, unsigned int flags);
+
+/**
+ * Get Entry Flags.
+ *
+ * @param name      entry name (UTF-8 string)
+ * @return Flags value (bitmask of NT_EntryFlags)
+ */
+WPI_DEPRECATED("use NT_Entry function instead")
+unsigned int GetEntryFlags(StringRef name);
+
+/**
+ * Get Entry Flags.
+ *
+ * @param entry     entry handle
+ * @return Flags value (bitmask of NT_EntryFlags)
+ */
+unsigned int GetEntryFlags(NT_Entry entry);
+
+/**
+ * Delete Entry.
+ *
+ * Deletes an entry.  This is a new feature in version 3.0 of the protocol,
+ * so this may not have an effect if any other node in the network is not
+ * version 3.0 or newer.
+ *
+ * Note: GetConnections() can be used to determine the protocol version
+ * of direct remote connection(s), but this is not sufficient to determine
+ * if all nodes in the network are version 3.0 or newer.
+ *
+ * @param name      entry name (UTF-8 string)
+ */
+WPI_DEPRECATED("use NT_Entry function instead")
+void DeleteEntry(StringRef name);
+
+/**
+ * Delete Entry.
+ *
+ * Deletes an entry.  This is a new feature in version 3.0 of the protocol,
+ * so this may not have an effect if any other node in the network is not
+ * version 3.0 or newer.
+ *
+ * Note: GetConnections() can be used to determine the protocol version
+ * of direct remote connection(s), but this is not sufficient to determine
+ * if all nodes in the network are version 3.0 or newer.
+ *
+ * @param entry     entry handle
+ */
+void DeleteEntry(NT_Entry entry);
+
+/**
+ * Delete All Entries.
+ *
+ * Deletes ALL table entries.  This is a new feature in version 3.0 of the
+ * so this may not have an effect if any other node in the network is not
+ * version 3.0 or newer.
+ *
+ * Note: GetConnections() can be used to determine the protocol version
+ * of direct remote connection(s), but this is not sufficient to determine
+ * if all nodes in the network are version 3.0 or newer.
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void DeleteAllEntries();
+
+/**
+ * @copydoc DeleteAllEntries()
+ *
+ * @param inst      instance handle
+ */
+void DeleteAllEntries(NT_Inst inst);
+
+/**
+ * Get Entry Information.
+ *
+ * Returns an array of entry information (name, entry type,
+ * and timestamp of last change to type/value).  The results are optionally
+ * filtered by string prefix and entry type to only return a subset of all
+ * entries.
+ *
+ * @param prefix        entry name required prefix; only entries whose name
+ *                      starts with this string are returned
+ * @param types         bitmask of NT_Type values; 0 is treated specially
+ *                      as a "don't care"
+ * @return Array of entry information.
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+std::vector<EntryInfo> GetEntryInfo(StringRef prefix, unsigned int types);
+
+/**
+ * @copydoc GetEntryInfo(StringRef, unsigned int)
+ *
+ * @param inst    instance handle
+ */
+std::vector<EntryInfo> GetEntryInfo(NT_Inst inst, const Twine& prefix,
+                                    unsigned int types);
+
+/**
+ * Get Entry Information.
+ *
+ * Returns information about an entry (name, entry type,
+ * and timestamp of last change to type/value).
+ *
+ * @param entry         entry handle
+ * @return Entry information.
+ */
+EntryInfo GetEntryInfo(NT_Entry entry);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_entrylistener_func Entry Listener Functions
+ * @{
+ */
+
+/**
+ * Entry listener callback function.
+ * Called when a key-value pair is changed.
+ *
+ * @param entry_listener  entry listener handle returned by callback creation
+ *                        function
+ * @param name            entry name
+ * @param value           the new value
+ * @param flags           update flags; for example, NT_NOTIFY_NEW if the key
+ *                        did not previously exist
+ */
+typedef std::function<void(NT_EntryListener entry_listener, StringRef name,
+                           std::shared_ptr<Value> value, unsigned int flags)>
+    EntryListenerCallback;
+
+/**
+ * Add a listener for all entries starting with a certain prefix.
+ *
+ * @param prefix            UTF-8 string prefix
+ * @param callback          listener to add
+ * @param flags             NotifyKind bitmask
+ * @return Listener handle
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+NT_EntryListener AddEntryListener(StringRef prefix,
+                                  EntryListenerCallback callback,
+                                  unsigned int flags);
+
+/**
+ * @copydoc AddEntryListener(StringRef, EntryListenerCallback, unsigned int)
+ *
+ * @param inst              instance handle
+ */
+NT_EntryListener AddEntryListener(
+    NT_Inst inst, const Twine& prefix,
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int flags);
+
+/**
+ * Add a listener for a single entry.
+ *
+ * @param entry             entry handle
+ * @param callback          listener to add
+ * @param flags             NotifyKind bitmask
+ * @return Listener handle
+ */
+NT_EntryListener AddEntryListener(
+    NT_Entry entry,
+    std::function<void(const EntryNotification& event)> callback,
+    unsigned int flags);
+
+/**
+ * Create a entry listener poller.
+ *
+ * A poller provides a single queue of poll events.  Events linked to this
+ * poller (using AddPolledEntryListener()) will be stored in the queue and
+ * must be collected by calling PollEntryListener().
+ * The returned handle must be destroyed with DestroyEntryListenerPoller().
+ *
+ * @param inst      instance handle
+ * @return poller handle
+ */
+NT_EntryListenerPoller CreateEntryListenerPoller(NT_Inst inst);
+
+/**
+ * Destroy a entry listener poller.  This will abort any blocked polling
+ * call and prevent additional events from being generated for this poller.
+ *
+ * @param poller    poller handle
+ */
+void DestroyEntryListenerPoller(NT_EntryListenerPoller poller);
+
+/**
+ * Create a polled entry listener.
+ * The caller is responsible for calling PollEntryListener() to poll.
+ *
+ * @param poller            poller handle
+ * @param prefix            UTF-8 string prefix
+ * @param flags             NotifyKind bitmask
+ * @return Listener handle
+ */
+NT_EntryListener AddPolledEntryListener(NT_EntryListenerPoller poller,
+                                        const Twine& prefix,
+                                        unsigned int flags);
+
+/**
+ * Create a polled entry listener.
+ * The caller is responsible for calling PollEntryListener() to poll.
+ *
+ * @param poller            poller handle
+ * @param prefix            UTF-8 string prefix
+ * @param flags             NotifyKind bitmask
+ * @return Listener handle
+ */
+NT_EntryListener AddPolledEntryListener(NT_EntryListenerPoller poller,
+                                        NT_Entry entry, unsigned int flags);
+
+/**
+ * Get the next entry listener event.  This blocks until the next event occurs.
+ * This is intended to be used with AddPolledEntryListener(); entry listeners
+ * created using AddEntryListener() will not be serviced through this function.
+ *
+ * @param poller    poller handle
+ * @return Information on the entry listener events.  Only returns empty if an
+ *         error occurred (e.g. the instance was invalid or is shutting down).
+ */
+std::vector<EntryNotification> PollEntryListener(NT_EntryListenerPoller poller);
+
+/**
+ * Get the next entry listener event.  This blocks until the next event occurs
+ * or it times out.  This is intended to be used with AddPolledEntryListener();
+ * entry listeners created using AddEntryListener() will not be serviced
+ * through this function.
+ *
+ * @param poller      poller handle
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return Information on the entry listener events.  If empty is returned and
+ *         and timed_out is also false, an error occurred (e.g. the instance
+ *         was invalid or is shutting down).
+ */
+std::vector<EntryNotification> PollEntryListener(NT_EntryListenerPoller poller,
+                                                 double timeout,
+                                                 bool* timed_out);
+
+/**
+ * Cancel a PollEntryListener call.  This wakes up a call to
+ * PollEntryListener for this poller and causes it to immediately return
+ * an empty array.
+ *
+ * @param poller  poller handle
+ */
+void CancelPollEntryListener(NT_EntryListenerPoller poller);
+
+/**
+ * Remove an entry listener.
+ *
+ * @param entry_listener Listener handle to remove
+ */
+void RemoveEntryListener(NT_EntryListener entry_listener);
+
+/**
+ * Wait for the entry listener queue to be empty.  This is primarily useful
+ * for deterministic testing.  This blocks until either the entry listener
+ * queue is empty (e.g. there are no more events that need to be passed along
+ * to callbacks or poll queues) or the timeout expires.
+ *
+ * @param inst      instance handle
+ * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+ *                  or a negative value to block indefinitely
+ * @return False if timed out, otherwise true.
+ */
+bool WaitForEntryListenerQueue(NT_Inst inst, double timeout);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_connectionlistener_func Connection Listener Functions
+ * @{
+ */
+
+/**
+ * Connection listener callback function.
+ * Called when a network connection is made or lost.
+ *
+ * @param conn_listener   connection listener handle returned by callback
+ *                        creation function
+ * @param connected       true if event is due to connection being established
+ * @param conn            connection info
+ */
+typedef std::function<void(NT_ConnectionListener conn_listener, bool connected,
+                           const ConnectionInfo& conn)>
+    ConnectionListenerCallback;
+
+/**
+ * Add a connection listener.
+ *
+ * @param callback          listener to add
+ * @param immediate_notify  notify listener of all existing connections
+ * @return Listener handle
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+NT_ConnectionListener AddConnectionListener(ConnectionListenerCallback callback,
+                                            bool immediate_notify);
+
+/**
+ * @copydoc AddConnectionListener(ConnectionListenerCallback, bool)
+ *
+ * @param inst              instance handle
+ */
+NT_ConnectionListener AddConnectionListener(
+    NT_Inst inst,
+    std::function<void(const ConnectionNotification& event)> callback,
+    bool immediate_notify);
+
+/**
+ * Create a connection listener poller.
+ *
+ * A poller provides a single queue of poll events.  Events linked to this
+ * poller (using AddPolledConnectionListener()) will be stored in the queue and
+ * must be collected by calling PollConnectionListener().
+ * The returned handle must be destroyed with DestroyConnectionListenerPoller().
+ *
+ * @param inst      instance handle
+ * @return poller handle
+ */
+NT_ConnectionListenerPoller CreateConnectionListenerPoller(NT_Inst inst);
+
+/**
+ * Destroy a connection listener poller.  This will abort any blocked polling
+ * call and prevent additional events from being generated for this poller.
+ *
+ * @param poller    poller handle
+ */
+void DestroyConnectionListenerPoller(NT_ConnectionListenerPoller poller);
+
+/**
+ * Create a polled connection listener.
+ * The caller is responsible for calling PollConnectionListener() to poll.
+ *
+ * @param poller            poller handle
+ * @param immediate_notify  notify listener of all existing connections
+ */
+NT_ConnectionListener AddPolledConnectionListener(
+    NT_ConnectionListenerPoller poller, bool immediate_notify);
+
+/**
+ * Get the next connection event.  This blocks until the next connect or
+ * disconnect occurs.  This is intended to be used with
+ * AddPolledConnectionListener(); connection listeners created using
+ * AddConnectionListener() will not be serviced through this function.
+ *
+ * @param poller    poller handle
+ * @return Information on the connection events.  Only returns empty if an
+ *         error occurred (e.g. the instance was invalid or is shutting down).
+ */
+std::vector<ConnectionNotification> PollConnectionListener(
+    NT_ConnectionListenerPoller poller);
+
+/**
+ * Get the next connection event.  This blocks until the next connect or
+ * disconnect occurs or it times out.  This is intended to be used with
+ * AddPolledConnectionListener(); connection listeners created using
+ * AddConnectionListener() will not be serviced through this function.
+ *
+ * @param poller      poller handle
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return Information on the connection events.  If empty is returned and
+ *         timed_out is also false, an error occurred (e.g. the instance was
+ *         invalid or is shutting down).
+ */
+std::vector<ConnectionNotification> PollConnectionListener(
+    NT_ConnectionListenerPoller poller, double timeout, bool* timed_out);
+
+/**
+ * Cancel a PollConnectionListener call.  This wakes up a call to
+ * PollConnectionListener for this poller and causes it to immediately return
+ * an empty array.
+ *
+ * @param poller  poller handle
+ */
+void CancelPollConnectionListener(NT_ConnectionListenerPoller poller);
+
+/**
+ * Remove a connection listener.
+ *
+ * @param conn_listener Listener handle to remove
+ */
+void RemoveConnectionListener(NT_ConnectionListener conn_listener);
+
+/**
+ * Wait for the connection listener queue to be empty.  This is primarily useful
+ * for deterministic testing.  This blocks until either the connection listener
+ * queue is empty (e.g. there are no more events that need to be passed along
+ * to callbacks or poll queues) or the timeout expires.
+ *
+ * @param inst      instance handle
+ * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+ *                  or a negative value to block indefinitely
+ * @return False if timed out, otherwise true.
+ */
+bool WaitForConnectionListenerQueue(NT_Inst inst, double timeout);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_rpc_func Remote Procedure Call Functions
+ * @{
+ */
+
+/**
+ * Create a callback-based RPC entry point.  Only valid to use on the server.
+ * The callback function will be called when the RPC is called.
+ *
+ * @param entry     entry handle of RPC entry
+ * @param def       RPC definition
+ * @param callback  callback function; note the callback function must call
+ *                  PostRpcResponse() to provide a response to the call
+ */
+void CreateRpc(NT_Entry entry, StringRef def,
+               std::function<void(const RpcAnswer& answer)> callback);
+
+/**
+ * Create a RPC call poller.  Only valid to use on the server.
+ *
+ * A poller provides a single queue of poll events.  Events linked to this
+ * poller (using CreatePolledRpc()) will be stored in the queue and must be
+ * collected by calling PollRpc().
+ * The returned handle must be destroyed with DestroyRpcCallPoller().
+ *
+ * @param inst      instance handle
+ * @return poller handle
+ */
+NT_RpcCallPoller CreateRpcCallPoller(NT_Inst inst);
+
+/**
+ * Destroy a RPC call poller.  This will abort any blocked polling call and
+ * prevent additional events from being generated for this poller.
+ *
+ * @param poller    poller handle
+ */
+void DestroyRpcCallPoller(NT_RpcCallPoller poller);
+
+/**
+ * Create a polled RPC entry point.  Only valid to use on the server.
+ * The caller is responsible for calling PollRpc() to poll for servicing
+ * incoming RPC calls.
+ *
+ * @param entry     entry handle of RPC entry
+ * @param def       RPC definition
+ * @param poller    poller handle
+ */
+void CreatePolledRpc(NT_Entry entry, StringRef def, NT_RpcCallPoller poller);
+
+/**
+ * Get the next incoming RPC call.  This blocks until the next incoming RPC
+ * call is received.  This is intended to be used with CreatePolledRpc();
+ * RPC calls created using CreateRpc() will not be serviced through this
+ * function.  Upon successful return, PostRpcResponse() must be called to
+ * send the return value to the caller.
+ *
+ * @param poller      poller handle
+ * @return Information on the next RPC calls.  Only returns empty if an error
+ *         occurred (e.g. the instance was invalid or is shutting down).
+ */
+std::vector<RpcAnswer> PollRpc(NT_RpcCallPoller poller);
+
+/**
+ * Get the next incoming RPC call.  This blocks until the next incoming RPC
+ * call is received or it times out.  This is intended to be used with
+ * CreatePolledRpc(); RPC calls created using CreateRpc() will not be
+ * serviced through this function.  Upon successful return,
+ * PostRpcResponse() must be called to send the return value to the caller.
+ *
+ * @param poller      poller handle
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return Information on the next RPC calls.  If empty and timed_out is also
+ *         false, an error occurred (e.g. the instance was invalid or is
+ *         shutting down).
+ */
+std::vector<RpcAnswer> PollRpc(NT_RpcCallPoller poller, double timeout,
+                               bool* timed_out);
+
+/**
+ * Cancel a PollRpc call.  This wakes up a call to PollRpc for this poller
+ * and causes it to immediately return an empty array.
+ *
+ * @param poller  poller handle
+ */
+void CancelPollRpc(NT_RpcCallPoller poller);
+
+/**
+ * Wait for the incoming RPC call queue to be empty.  This is primarily useful
+ * for deterministic testing.  This blocks until either the RPC call
+ * queue is empty (e.g. there are no more events that need to be passed along
+ * to callbacks or poll queues) or the timeout expires.
+ *
+ * @param inst      instance handle
+ * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+ *                  or a negative value to block indefinitely
+ * @return False if timed out, otherwise true.
+ */
+bool WaitForRpcCallQueue(NT_Inst inst, double timeout);
+
+/**
+ * Post RPC response (return value) for a polled RPC.
+ * The rpc and call parameters should come from the RpcAnswer returned
+ * by PollRpc().
+ *
+ * @param entry       entry handle of RPC entry (from RpcAnswer)
+ * @param call        RPC call handle (from RpcAnswer)
+ * @param result      result raw data that will be provided to remote caller
+ * @return            true if the response was posted, otherwise false
+ */
+bool PostRpcResponse(NT_Entry entry, NT_RpcCall call, StringRef result);
+
+/**
+ * Call a RPC function.  May be used on either the client or server.
+ * This function is non-blocking.  Either GetRpcResult() or
+ * CancelRpcResult() must be called to either get or ignore the result of
+ * the call.
+ *
+ * @param entry       entry handle of RPC entry
+ * @param params      parameter
+ * @return RPC call handle (for use with GetRpcResult() or
+ *         CancelRpcResult()).
+ */
+NT_RpcCall CallRpc(NT_Entry entry, StringRef params);
+
+/**
+ * Get the result (return value) of a RPC call.  This function blocks until
+ * the result is received.
+ *
+ * @param entry       entry handle of RPC entry
+ * @param call        RPC call handle returned by CallRpc()
+ * @param result      received result (output)
+ * @return False on error, true otherwise.
+ */
+bool GetRpcResult(NT_Entry entry, NT_RpcCall call, std::string* result);
+
+/**
+ * Get the result (return value) of a RPC call.  This function blocks until
+ * the result is received or it times out.
+ *
+ * @param entry       entry handle of RPC entry
+ * @param call        RPC call handle returned by CallRpc()
+ * @param result      received result (output)
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return False on error or timeout, true otherwise.
+ */
+bool GetRpcResult(NT_Entry entry, NT_RpcCall call, std::string* result,
+                  double timeout, bool* timed_out);
+
+/**
+ * Ignore the result of a RPC call.  This function is non-blocking.
+ *
+ * @param entry       entry handle of RPC entry
+ * @param call        RPC call handle returned by CallRpc()
+ */
+void CancelRpcResult(NT_Entry entry, NT_RpcCall call);
+
+/**
+ * Pack a RPC version 1 definition.
+ *
+ * @param def         RPC version 1 definition
+ * @return Raw packed bytes.
+ */
+std::string PackRpcDefinition(const RpcDefinition& def);
+
+/**
+ * Unpack a RPC version 1 definition.  This can be used for introspection or
+ * validation.
+ *
+ * @param packed      raw packed bytes
+ * @param def         RPC version 1 definition (output)
+ * @return True if successfully unpacked, false otherwise.
+ */
+bool UnpackRpcDefinition(StringRef packed, RpcDefinition* def);
+
+/**
+ * Pack RPC values as required for RPC version 1 definition messages.
+ *
+ * @param values      array of values to pack
+ * @return Raw packed bytes.
+ */
+std::string PackRpcValues(ArrayRef<std::shared_ptr<Value>> values);
+
+/**
+ * Unpack RPC values as required for RPC version 1 definition messages.
+ *
+ * @param packed      raw packed bytes
+ * @param types       array of data types (as provided in the RPC definition)
+ * @return Array of values.
+ */
+std::vector<std::shared_ptr<Value>> UnpackRpcValues(StringRef packed,
+                                                    ArrayRef<NT_Type> types);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_network_func Client/Server Functions
+ * @{
+ */
+
+/**
+ * Set the network identity of this node.
+ * This is the name used during the initial connection handshake, and is
+ * visible through ConnectionInfo on the remote node.
+ *
+ * @param name      identity to advertise
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void SetNetworkIdentity(StringRef name);
+
+/**
+ * @copydoc SetNetworkIdentity(StringRef)
+ *
+ * @param inst      instance handle
+ */
+void SetNetworkIdentity(NT_Inst inst, const Twine& name);
+
+/**
+ * Get the current network mode.
+ *
+ * @return Bitmask of NT_NetworkMode.
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+unsigned int GetNetworkMode();
+
+/**
+ * Get the current network mode.
+ *
+ * @param inst  instance handle
+ * @return Bitmask of NT_NetworkMode.
+ */
+unsigned int GetNetworkMode(NT_Inst inst);
+
+/**
+ * Starts a server using the specified filename, listening address, and port.
+ *
+ * @param persist_filename  the name of the persist file to use (UTF-8 string,
+ *                          null terminated)
+ * @param listen_address    the address to listen on, or null to listen on any
+ *                          address. (UTF-8 string, null terminated)
+ * @param port              port to communicate over.
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StartServer(StringRef persist_filename, const char* listen_address,
+                 unsigned int port);
+
+/**
+ * @copydoc StartServer(StringRef, const char*, unsigned int)
+ *
+ * @param inst              instance handle
+ */
+void StartServer(NT_Inst inst, const Twine& persist_filename,
+                 const char* listen_address, unsigned int port);
+
+/**
+ * Stops the server if it is running.
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StopServer();
+
+/**
+ * @copydoc StopServer()
+ *
+ * @param inst  instance handle
+ */
+void StopServer(NT_Inst inst);
+
+/**
+ * Starts a client.  Use SetServer to set the server name and port.
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StartClient();
+
+/**
+ * Starts a client using the specified server and port
+ *
+ * @param server_name server name (UTF-8 string, null terminated)
+ * @param port        port to communicate over
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StartClient(const char* server_name, unsigned int port);
+
+/**
+ * Starts a client using the specified (server, port) combinations.  The
+ * client will attempt to connect to each server in round robin fashion.
+ *
+ * @param servers   array of server name and port pairs
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StartClient(ArrayRef<std::pair<StringRef, unsigned int>> servers);
+
+/**
+ * @copydoc StartClient()
+ *
+ * @param inst  instance handle
+ */
+void StartClient(NT_Inst inst);
+
+/**
+ * @copydoc StartClient(const char*, unsigned int)
+ *
+ * @param inst        instance handle
+ */
+void StartClient(NT_Inst inst, const char* server_name, unsigned int port);
+
+/**
+ * @copydoc StartClient(ArrayRef<std::pair<StringRef, unsigned int>>)
+ *
+ * @param inst      instance handle
+ */
+void StartClient(NT_Inst inst,
+                 ArrayRef<std::pair<StringRef, unsigned int>> servers);
+
+/**
+ * Starts a client using commonly known robot addresses for the specified
+ * team.
+ *
+ * @param inst        instance handle
+ * @param team        team number
+ * @param port        port to communicate over
+ */
+void StartClientTeam(NT_Inst inst, unsigned int team, unsigned int port);
+
+/**
+ * Stops the client if it is running.
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StopClient();
+
+/**
+ * @copydoc StopClient()
+ * @param inst  instance handle
+ */
+void StopClient(NT_Inst inst);
+
+/**
+ * Sets server address and port for client (without restarting client).
+ *
+ * @param server_name server name (UTF-8 string, null terminated)
+ * @param port        port to communicate over
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void SetServer(const char* server_name, unsigned int port);
+
+/**
+ * Sets server addresses for client (without restarting client).
+ * The client will attempt to connect to each server in round robin fashion.
+ *
+ * @param servers   array of server name and port pairs
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void SetServer(ArrayRef<std::pair<StringRef, unsigned int>> servers);
+
+/**
+ * @copydoc SetServer(const char*, unsigned int)
+ *
+ * @param inst        instance handle
+ */
+void SetServer(NT_Inst inst, const char* server_name, unsigned int port);
+
+/**
+ * @copydoc SetServer(ArrayRef<std::pair<StringRef, unsigned int>>)
+ *
+ * @param inst      instance handle
+ */
+void SetServer(NT_Inst inst,
+               ArrayRef<std::pair<StringRef, unsigned int>> servers);
+
+/**
+ * Sets server addresses and port for client (without restarting client).
+ * Connects using commonly known robot addresses for the specified team.
+ *
+ * @param inst        instance handle
+ * @param team        team number
+ * @param port        port to communicate over
+ */
+void SetServerTeam(NT_Inst inst, unsigned int team, unsigned int port);
+
+/**
+ * Starts requesting server address from Driver Station.
+ * This connects to the Driver Station running on localhost to obtain the
+ * server IP address.
+ *
+ * @param port server port to use in combination with IP from DS
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StartDSClient(unsigned int port);
+
+/**
+ * @copydoc StartDSClient(unsigned int)
+ * @param inst  instance handle
+ */
+void StartDSClient(NT_Inst inst, unsigned int port);
+
+/** Stops requesting server address from Driver Station. */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StopDSClient();
+
+/**
+ * @copydoc StopDSClient()
+ *
+ * @param inst  instance handle
+ */
+void StopDSClient(NT_Inst inst);
+
+/** Stops the RPC server if it is running. */
+WPI_DEPRECATED("use NT_Inst function instead")
+void StopRpcServer();
+
+/**
+ * Set the periodic update rate.
+ * Sets how frequently updates are sent to other nodes over the network.
+ *
+ * @param interval  update interval in seconds (range 0.01 to 1.0)
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void SetUpdateRate(double interval);
+
+/**
+ * @copydoc SetUpdateRate(double)
+ *
+ * @param inst      instance handle
+ */
+void SetUpdateRate(NT_Inst inst, double interval);
+
+/**
+ * Flush Entries.
+ *
+ * Forces an immediate flush of all local entry changes to network.
+ * Normally this is done on a regularly scheduled interval (see
+ * SetUpdateRate()).
+ *
+ * Note: flushes are rate limited to avoid excessive network traffic.  If
+ * the time between calls is too short, the flush will occur after the minimum
+ * time elapses (rather than immediately).
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void Flush();
+
+/**
+ * @copydoc Flush()
+ *
+ * @param inst      instance handle
+ */
+void Flush(NT_Inst inst);
+
+/**
+ * Get information on the currently established network connections.
+ * If operating as a client, this will return either zero or one values.
+ *
+ * @return      array of connection information
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+std::vector<ConnectionInfo> GetConnections();
+
+/**
+ * @copydoc GetConnections()
+ *
+ * @param inst  instance handle
+ */
+std::vector<ConnectionInfo> GetConnections(NT_Inst inst);
+
+/**
+ * Return whether or not the instance is connected to another node.
+ *
+ * @param inst  instance handle
+ * @return True if connected.
+ */
+bool IsConnected(NT_Inst inst);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_file_func File Save/Load Functions
+ * @{
+ */
+
+/**
+ * Save persistent values to a file.  The server automatically does this,
+ * but this function provides a way to save persistent values in the same
+ * format to a file on either a client or a server.
+ *
+ * @param filename  filename
+ * @return error string, or nullptr if successful
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+const char* SavePersistent(StringRef filename);
+
+/**
+ * @copydoc SavePersistent(StringRef)
+ * @param inst      instance handle
+ */
+const char* SavePersistent(NT_Inst inst, const Twine& filename);
+
+/**
+ * Load persistent values from a file.  The server automatically does this
+ * at startup, but this function provides a way to restore persistent values
+ * in the same format from a file at any time on either a client or a server.
+ *
+ * @param filename  filename
+ * @param warn      callback function for warnings
+ * @return error string, or nullptr if successful
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+const char* LoadPersistent(
+    StringRef filename, std::function<void(size_t line, const char* msg)> warn);
+
+/**
+ * @copydoc LoadPersistent(StringRef, std::function<void(size_t, const
+ * char*)>)
+ *
+ * @param inst      instance handle
+ */
+const char* LoadPersistent(
+    NT_Inst inst, const Twine& filename,
+    std::function<void(size_t line, const char* msg)> warn);
+
+/**
+ * Save table values to a file.  The file format used is identical to
+ * that used for SavePersistent.
+ *
+ * @param inst      instance handle
+ * @param filename  filename
+ * @param prefix    save only keys starting with this prefix
+ * @return error string, or nullptr if successful
+ */
+const char* SaveEntries(NT_Inst inst, const Twine& filename,
+                        const Twine& prefix);
+
+/**
+ * Load table values from a file.  The file format used is identical to
+ * that used for SavePersistent / LoadPersistent.
+ *
+ * @param inst      instance handle
+ * @param filename  filename
+ * @param prefix    load only keys starting with this prefix
+ * @param warn      callback function for warnings
+ * @return error string, or nullptr if successful
+ */
+const char* LoadEntries(NT_Inst inst, const Twine& filename,
+                        const Twine& prefix,
+                        std::function<void(size_t line, const char* msg)> warn);
+
+/** @} */
+
+/**
+ * @defgroup ntcore_utility_func Utility Functions
+ * @{
+ */
+
+/**
+ * Returns monotonic current time in 1 us increments.
+ * This is the same time base used for entry and connection timestamps.
+ * This function is a compatibility wrapper around wpi::Now().
+ *
+ * @return Timestamp
+ */
+uint64_t Now();
+
+/** @} */
+
+/**
+ * @defgroup ntcore_logger_func Logger Functions
+ * @{
+ */
+
+/**
+ * Log function.
+ *
+ * @param level   log level of the message (see NT_LogLevel)
+ * @param file    origin source filename
+ * @param line    origin source line number
+ * @param msg     message
+ */
+typedef std::function<void(unsigned int level, const char* file,
+                           unsigned int line, const char* msg)>
+    LogFunc;
+
+/**
+ * Set logger callback function.  By default, log messages are sent to stderr;
+ * this function changes the log level and sends log messages to the provided
+ * callback function instead.  The callback function will only be called for
+ * log messages with level greater than or equal to min_level; messages lower
+ * than this level will be silently ignored.
+ *
+ * @param func        log callback function
+ * @param min_level   minimum log level
+ */
+WPI_DEPRECATED("use NT_Inst function instead")
+void SetLogger(LogFunc func, unsigned int min_level);
+
+/**
+ * Add logger callback function.  By default, log messages are sent to stderr;
+ * this function sends log messages to the provided callback function instead.
+ * The callback function will only be called for log messages with level
+ * greater than or equal to min_level and less than or equal to max_level;
+ * messages outside this range will be silently ignored.
+ *
+ * @param inst        instance handle
+ * @param func        log callback function
+ * @param min_level   minimum log level
+ * @param max_level   maximum log level
+ * @return Logger handle
+ */
+NT_Logger AddLogger(NT_Inst inst,
+                    std::function<void(const LogMessage& msg)> func,
+                    unsigned int min_level, unsigned int max_level);
+
+/**
+ * Create a log poller.  A poller provides a single queue of poll events.
+ * The returned handle must be destroyed with DestroyLoggerPoller().
+ *
+ * @param inst      instance handle
+ * @return poller handle
+ */
+NT_LoggerPoller CreateLoggerPoller(NT_Inst inst);
+
+/**
+ * Destroy a log poller.  This will abort any blocked polling call and prevent
+ * additional events from being generated for this poller.
+ *
+ * @param poller    poller handle
+ */
+void DestroyLoggerPoller(NT_LoggerPoller poller);
+
+/**
+ * Set the log level for a log poller.  Events will only be generated for
+ * log messages with level greater than or equal to min_level and less than or
+ * equal to max_level; messages outside this range will be silently ignored.
+ *
+ * @param poller        poller handle
+ * @param min_level     minimum log level
+ * @param max_level     maximum log level
+ * @return Logger handle
+ */
+NT_Logger AddPolledLogger(NT_LoggerPoller poller, unsigned int min_level,
+                          unsigned int max_level);
+
+/**
+ * Get the next log event.  This blocks until the next log occurs.
+ *
+ * @param poller    poller handle
+ * @return Information on the log events.  Only returns empty if an error
+ *         occurred (e.g. the instance was invalid or is shutting down).
+ */
+std::vector<LogMessage> PollLogger(NT_LoggerPoller poller);
+
+/**
+ * Get the next log event.  This blocks until the next log occurs or it times
+ * out.
+ *
+ * @param poller      poller handle
+ * @param timeout     timeout, in seconds
+ * @param timed_out   true if the timeout period elapsed (output)
+ * @return Information on the log events.  If empty is returned and timed_out
+ *         is also false, an error occurred (e.g. the instance was invalid or
+ *         is shutting down).
+ */
+std::vector<LogMessage> PollLogger(NT_LoggerPoller poller, double timeout,
+                                   bool* timed_out);
+
+/**
+ * Cancel a PollLogger call.  This wakes up a call to PollLogger for this
+ * poller and causes it to immediately return an empty array.
+ *
+ * @param poller  poller handle
+ */
+void CancelPollLogger(NT_LoggerPoller poller);
+
+/**
+ * Remove a logger.
+ *
+ * @param logger Logger handle to remove
+ */
+void RemoveLogger(NT_Logger logger);
+
+/**
+ * Wait for the incoming log event queue to be empty.  This is primarily useful
+ * for deterministic testing.  This blocks until either the log event
+ * queue is empty (e.g. there are no more events that need to be passed along
+ * to callbacks or poll queues) or the timeout expires.
+ *
+ * @param inst      instance handle
+ * @param timeout   timeout, in seconds.  Set to 0 for non-blocking behavior,
+ *                  or a negative value to block indefinitely
+ * @return False if timed out, otherwise true.
+ */
+bool WaitForLoggerQueue(NT_Inst inst, double timeout);
+
+/** @} */
+/** @} */
+
+inline bool RpcAnswer::PostResponse(StringRef result) const {
+  auto ret = PostRpcResponse(entry, call, result);
+  call = 0;
+  return ret;
+}
+
+}  // namespace nt
+
+#endif  // NTCORE_NTCORE_CPP_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_test.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_test.h
new file mode 100644
index 0000000..920fd68
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/ntcore_test.h
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_NTCORE_TEST_H_
+#define NTCORE_NTCORE_TEST_H_
+
+#include <stdint.h>
+
+#include <string>
+
+#include "ntcore.h"
+
+// Functions in this header are to be used only for testing
+
+extern "C" {
+struct NT_String* NT_GetStringForTesting(const char* string, int* struct_size);
+// No need for free as one already exists in main library
+
+struct NT_EntryInfo* NT_GetEntryInfoForTesting(const char* name,
+                                               enum NT_Type type,
+                                               unsigned int flags,
+                                               uint64_t last_change,
+                                               int* struct_size);
+
+void NT_FreeEntryInfoForTesting(struct NT_EntryInfo* info);
+
+struct NT_ConnectionInfo* NT_GetConnectionInfoForTesting(
+    const char* remote_id, const char* remote_ip, unsigned int remote_port,
+    uint64_t last_update, unsigned int protocol_version, int* struct_size);
+
+void NT_FreeConnectionInfoForTesting(struct NT_ConnectionInfo* info);
+
+struct NT_Value* NT_GetValueBooleanForTesting(uint64_t last_change, int val,
+                                              int* struct_size);
+
+struct NT_Value* NT_GetValueDoubleForTesting(uint64_t last_change, double val,
+                                             int* struct_size);
+
+struct NT_Value* NT_GetValueStringForTesting(uint64_t last_change,
+                                             const char* str, int* struct_size);
+
+struct NT_Value* NT_GetValueRawForTesting(uint64_t last_change, const char* raw,
+                                          int raw_len, int* struct_size);
+
+struct NT_Value* NT_GetValueBooleanArrayForTesting(uint64_t last_change,
+                                                   const int* arr,
+                                                   size_t array_len,
+                                                   int* struct_size);
+
+struct NT_Value* NT_GetValueDoubleArrayForTesting(uint64_t last_change,
+                                                  const double* arr,
+                                                  size_t array_len,
+                                                  int* struct_size);
+
+struct NT_Value* NT_GetValueStringArrayForTesting(uint64_t last_change,
+                                                  const struct NT_String* arr,
+                                                  size_t array_len,
+                                                  int* struct_size);
+// No need for free as one already exists in the main library
+
+struct NT_RpcParamDef* NT_GetRpcParamDefForTesting(const char* name,
+                                                   const struct NT_Value* val,
+                                                   int* struct_size);
+
+void NT_FreeRpcParamDefForTesting(struct NT_RpcParamDef* def);
+
+struct NT_RpcResultDef* NT_GetRpcResultsDefForTesting(const char* name,
+                                                      enum NT_Type type,
+                                                      int* struct_size);
+
+void NT_FreeRpcResultsDefForTesting(struct NT_RpcResultDef* def);
+
+struct NT_RpcDefinition* NT_GetRpcDefinitionForTesting(
+    unsigned int version, const char* name, size_t num_params,
+    const struct NT_RpcParamDef* params, size_t num_results,
+    const struct NT_RpcResultDef* results, int* struct_size);
+// No need for free as one already exists in the main library
+
+struct NT_RpcCallInfo* NT_GetRpcCallInfoForTesting(
+    unsigned int rpc_id, unsigned int call_uid, const char* name,
+    const char* params, size_t params_len, int* struct_size);
+// No need for free as one already exists in the main library
+}  // extern "C"
+
+#endif  // NTCORE_NTCORE_TEST_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/tables/ITable.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/tables/ITable.h
new file mode 100644
index 0000000..d03aaa7
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/tables/ITable.h
@@ -0,0 +1,456 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_TABLES_ITABLE_H_
+#define NTCORE_TABLES_ITABLE_H_
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+
+#include "networktables/NetworkTableValue.h"
+
+namespace nt {
+class NetworkTable;
+}  // namespace nt
+
+class ITableListener;
+
+/**
+ * A table whose values can be read and written to
+ */
+class WPI_DEPRECATED("Use NetworkTable directly") ITable {
+ public:
+  /**
+   * Determines whether the given key is in this table.
+   *
+   * @param key the key to search for
+   * @return true if the table as a value assigned to the given key
+   */
+  virtual bool ContainsKey(const wpi::Twine& key) const = 0;
+
+  /**
+   * Determines whether there exists a non-empty subtable for this key
+   * in this table.
+   *
+   * @param key the key to search for
+   * @return true if there is a subtable with the key which contains at least
+   * one key/subtable of its own
+   */
+  virtual bool ContainsSubTable(const wpi::Twine& key) const = 0;
+
+  /**
+   * Gets the subtable in this table for the given name.
+   *
+   * @param key the name of the table relative to this one
+   * @return a sub table relative to this one
+   */
+  virtual std::shared_ptr<nt::NetworkTable> GetSubTable(
+      const wpi::Twine& key) const = 0;
+
+  /**
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return keys currently in the table
+   */
+  virtual std::vector<std::string> GetKeys(int types = 0) const = 0;
+
+  /**
+   * @return subtables currently in the table
+   */
+  virtual std::vector<std::string> GetSubTables() const = 0;
+
+  /**
+   * Makes a key's value persistent through program restarts.
+   *
+   * @param key the key to make persistent
+   */
+  virtual void SetPersistent(wpi::StringRef key) = 0;
+
+  /**
+   * Stop making a key's value persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  virtual void ClearPersistent(wpi::StringRef key) = 0;
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  virtual bool IsPersistent(wpi::StringRef key) const = 0;
+
+  /**
+   * Sets flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to set (bitmask)
+   */
+  virtual void SetFlags(wpi::StringRef key, unsigned int flags) = 0;
+
+  /**
+   * Clears flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to clear (bitmask)
+   */
+  virtual void ClearFlags(wpi::StringRef key, unsigned int flags) = 0;
+
+  /**
+   * Returns the flags for the specified key.
+   *
+   * @param key the key name
+   * @return the flags, or 0 if the key is not defined
+   */
+  virtual unsigned int GetFlags(wpi::StringRef key) const = 0;
+
+  /**
+   * Deletes the specified key in this table.
+   *
+   * @param key the key name
+   */
+  virtual void Delete(const wpi::Twine& key) = 0;
+
+  /**
+   * Gets the value associated with a key as an object
+   *
+   * @param key the key of the value to look up
+   * @return the value associated with the given key, or nullptr if the key
+   * does not exist
+   */
+  virtual std::shared_ptr<nt::Value> GetValue(const wpi::Twine& key) const = 0;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  virtual bool SetDefaultValue(const wpi::Twine& key,
+                               std::shared_ptr<nt::Value> defaultValue) = 0;
+
+  /**
+   * Put a value in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  virtual bool PutValue(const wpi::Twine& key,
+                        std::shared_ptr<nt::Value> value) = 0;
+
+  /**
+   * Put a number in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  virtual bool PutNumber(wpi::StringRef key, double value) = 0;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  virtual bool SetDefaultNumber(wpi::StringRef key, double defaultValue) = 0;
+
+  /**
+   * Gets the number associated with the given name.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  virtual double GetNumber(wpi::StringRef key, double defaultValue) const = 0;
+
+  /**
+   * Put a string in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  virtual bool PutString(wpi::StringRef key, wpi::StringRef value) = 0;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  virtual bool SetDefaultString(wpi::StringRef key,
+                                wpi::StringRef defaultValue) = 0;
+
+  /**
+   * Gets the string associated with the given name. If the key does not
+   * exist or is of different type, it will return the default value.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the string.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  virtual std::string GetString(wpi::StringRef key,
+                                wpi::StringRef defaultValue) const = 0;
+
+  /**
+   * Put a boolean in the table
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  virtual bool PutBoolean(wpi::StringRef key, bool value) = 0;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  virtual bool SetDefaultBoolean(wpi::StringRef key, bool defaultValue) = 0;
+
+  /**
+   * Gets the boolean associated with the given name. If the key does not
+   * exist or is of different type, it will return the default value.
+   *
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   */
+  virtual bool GetBoolean(wpi::StringRef key, bool defaultValue) const = 0;
+
+  /**
+   * Put a boolean array in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   *
+   * @note The array must be of int's rather than of bool's because
+   *       std::vector<bool> is special-cased in C++.  0 is false, any
+   *       non-zero value is true.
+   */
+  virtual bool PutBooleanArray(wpi::StringRef key,
+                               wpi::ArrayRef<int> value) = 0;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  virtual bool SetDefaultBooleanArray(wpi::StringRef key,
+                                      wpi::ArrayRef<int> defaultValue) = 0;
+
+  /**
+   * Returns the boolean array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   *
+   * @note The returned array is std::vector<int> instead of std::vector<bool>
+   *       because std::vector<bool> is special-cased in C++.  0 is false, any
+   *       non-zero value is true.
+   */
+  virtual std::vector<int> GetBooleanArray(
+      wpi::StringRef key, wpi::ArrayRef<int> defaultValue) const = 0;
+
+  /**
+   * Put a number array in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  virtual bool PutNumberArray(wpi::StringRef key,
+                              wpi::ArrayRef<double> value) = 0;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  virtual bool SetDefaultNumberArray(wpi::StringRef key,
+                                     wpi::ArrayRef<double> defaultValue) = 0;
+
+  /**
+   * Returns the number array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  virtual std::vector<double> GetNumberArray(
+      wpi::StringRef key, wpi::ArrayRef<double> defaultValue) const = 0;
+
+  /**
+   * Put a string array in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  virtual bool PutStringArray(wpi::StringRef key,
+                              wpi::ArrayRef<std::string> value) = 0;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  virtual bool SetDefaultStringArray(
+      wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue) = 0;
+
+  /**
+   * Returns the string array the key maps to. If the key does not exist or is
+   * of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  virtual std::vector<std::string> GetStringArray(
+      wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue) const = 0;
+
+  /**
+   * Put a raw value (byte array) in the table
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  virtual bool PutRaw(wpi::StringRef key, wpi::StringRef value) = 0;
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  virtual bool SetDefaultRaw(wpi::StringRef key,
+                             wpi::StringRef defaultValue) = 0;
+
+  /**
+   * Returns the raw value (byte array) the key maps to. If the key does not
+   * exist or is of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the raw contents.  If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  virtual std::string GetRaw(wpi::StringRef key,
+                             wpi::StringRef defaultValue) const = 0;
+
+  /**
+   * Add a listener for changes to the table
+   *
+   * @param listener the listener to add
+   */
+  virtual void AddTableListener(ITableListener* listener) = 0;
+
+  /**
+   * Add a listener for changes to the table
+   *
+   * @param listener the listener to add
+   * @param immediateNotify if true then this listener will be notified of all
+   * current entries (marked as new)
+   */
+  virtual void AddTableListener(ITableListener* listener,
+                                bool immediateNotify) = 0;
+
+  /**
+   * Add a listener for changes to the table
+   *
+   * @param listener the listener to add
+   * @param immediateNotify if true then this listener will be notified of all
+   * current entries (marked as new)
+   * @param flags bitmask of NT_NotifyKind specifying desired notifications
+   */
+  virtual void AddTableListenerEx(ITableListener* listener,
+                                  unsigned int flags) = 0;
+
+  /**
+   * Add a listener for changes to a specific key the table
+   *
+   * @param key the key to listen for
+   * @param listener the listener to add
+   * @param immediateNotify if true then this listener will be notified of all
+   * current entries (marked as new)
+   */
+  virtual void AddTableListener(wpi::StringRef key, ITableListener* listener,
+                                bool immediateNotify) = 0;
+
+  /**
+   * Add a listener for changes to a specific key the table
+   *
+   * @param key the key to listen for
+   * @param listener the listener to add
+   * @param immediateNotify if true then this listener will be notified of all
+   * current entries (marked as new)
+   * @param flags bitmask of NT_NotifyKind specifying desired notifications
+   */
+  virtual void AddTableListenerEx(wpi::StringRef key, ITableListener* listener,
+                                  unsigned int flags) = 0;
+
+  /**
+   * This will immediately notify the listener of all current sub tables
+   * @param listener the listener to add
+   */
+  virtual void AddSubTableListener(ITableListener* listener) = 0;
+
+  /**
+   * This will immediately notify the listener of all current sub tables
+   * @param listener the listener to add
+   * @param localNotify if true then this listener will be notified of all
+   * local changes in addition to all remote changes
+   */
+  virtual void AddSubTableListener(ITableListener* listener,
+                                   bool localNotify) = 0;
+
+  /**
+   * Remove a listener from receiving table events
+   *
+   * @param listener the listener to be removed
+   */
+  virtual void RemoveTableListener(ITableListener* listener) = 0;
+
+  /**
+   * Gets the full path of this table.
+   */
+  virtual wpi::StringRef GetPath() const = 0;
+};
+
+#endif  // NTCORE_TABLES_ITABLE_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/main/native/include/tables/ITableListener.h b/third_party/allwpilib_2019/ntcore/src/main/native/include/tables/ITableListener.h
new file mode 100644
index 0000000..e836b51
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/main/native/include/tables/ITableListener.h
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_TABLES_ITABLELISTENER_H_
+#define NTCORE_TABLES_ITABLELISTENER_H_
+
+#include <memory>
+
+#include <wpi/StringRef.h>
+#include <wpi/deprecated.h>
+
+#include "networktables/NetworkTableValue.h"
+
+#ifdef __GNUC__
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
+#endif
+
+class ITable;
+
+/**
+ * A listener that listens to changes in values in a {@link ITable}
+ */
+class WPI_DEPRECATED(
+    "Use EntryListener, TableEntryListener, or TableListener as appropriate")
+    ITableListener {
+ public:
+  virtual ~ITableListener() = default;
+  /**
+   * Called when a key-value pair is changed in a {@link ITable}
+   * @param source the table the key-value pair exists in
+   * @param key the key associated with the value that changed
+   * @param value the new value
+   * @param isNew true if the key did not previously exist in the table,
+   * otherwise it is false
+   */
+  virtual void ValueChanged(ITable* source, wpi::StringRef key,
+                            std::shared_ptr<nt::Value> value, bool isNew) = 0;
+
+  /**
+   * Extended version of ValueChanged.  Called when a key-value pair is
+   * changed in a {@link ITable}.  The default implementation simply calls
+   * ValueChanged().  If this is overridden, ValueChanged() will not be called.
+   * @param source the table the key-value pair exists in
+   * @param key the key associated with the value that changed
+   * @param value the new value
+   * @param flags update flags; for example, NT_NOTIFY_NEW if the key did not
+   * previously exist in the table
+   */
+  virtual void ValueChangedEx(ITable* source, wpi::StringRef key,
+                              std::shared_ptr<nt::Value> value,
+                              unsigned int flags);
+};
+
+#ifdef __GNUC__
+#pragma GCC diagnostic pop
+#endif
+
+#endif  // NTCORE_TABLES_ITABLELISTENER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/ConnectionListenerTest.java b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/ConnectionListenerTest.java
new file mode 100644
index 0000000..9628a0e
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/ConnectionListenerTest.java
@@ -0,0 +1,160 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.util.ArrayList;
+import java.util.List;
+
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+import org.junit.jupiter.api.condition.DisabledOnOs;
+import org.junit.jupiter.api.condition.OS;
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.ValueSource;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertNotNull;
+import static org.junit.jupiter.api.Assertions.assertNotSame;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+import static org.junit.jupiter.api.Assertions.fail;
+
+class ConnectionListenerTest {
+  private NetworkTableInstance m_serverInst;
+  private NetworkTableInstance m_clientInst;
+
+  @BeforeEach
+  void setUp() {
+    m_serverInst = NetworkTableInstance.create();
+    m_serverInst.setNetworkIdentity("server");
+
+    m_clientInst = NetworkTableInstance.create();
+    m_clientInst.setNetworkIdentity("client");
+  }
+
+  @AfterEach
+  void tearDown() {
+    m_clientInst.close();
+    m_serverInst.close();
+  }
+
+  /**
+   * Connect to the server.
+   */
+  @SuppressWarnings("PMD.AvoidUsingHardCodedIP")
+  private void connect() {
+    m_serverInst.startServer("connectionlistenertest.ini", "127.0.0.1", 10000);
+    m_clientInst.startClient("127.0.0.1", 10000);
+
+    // wait for client to report it's started, then wait another 0.1 sec
+    try {
+      while ((m_clientInst.getNetworkMode() & NetworkTableInstance.kNetModeStarting) != 0) {
+        Thread.sleep(100);
+      }
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for client to start");
+    }
+  }
+
+  @Test
+  @DisabledOnOs(OS.WINDOWS)
+  void testJNI() {
+    // set up the poller
+    int poller = NetworkTablesJNI.createConnectionListenerPoller(m_serverInst.getHandle());
+    assertNotSame(poller, 0, "bad poller handle");
+    int handle = NetworkTablesJNI.addPolledConnectionListener(poller, false);
+    assertNotSame(handle, 0, "bad listener handle");
+
+    // trigger a connect event
+    connect();
+
+    // get the event
+    assertTrue(m_serverInst.waitForConnectionListenerQueue(1.0));
+    ConnectionNotification[] events = null;
+    try {
+      events = NetworkTablesJNI.pollConnectionListenerTimeout(m_serverInst, poller, 0.0);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+      fail("unexpected interrupted exception" + ex);
+    }
+
+    assertNotNull(events);
+    assertEquals(1, events.length);
+    assertEquals(handle, events[0].listener);
+    assertTrue(events[0].connected);
+
+    // trigger a disconnect event
+    m_clientInst.stopClient();
+    try {
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for client to stop");
+    }
+
+    // get the event
+    assertTrue(m_serverInst.waitForConnectionListenerQueue(1.0));
+    try {
+      events = NetworkTablesJNI.pollConnectionListenerTimeout(m_serverInst, poller, 0.0);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+      fail("unexpected interrupted exception" + ex);
+    }
+
+    assertNotNull(events);
+    assertEquals(1, events.length);
+    assertEquals(handle, events[0].listener);
+    assertFalse(events[0].connected);
+
+  }
+
+  @ParameterizedTest
+  @DisabledOnOs(OS.WINDOWS)
+  @SuppressWarnings("PMD.AvoidUsingHardCodedIP")
+  @ValueSource(strings = { "127.0.0.1", "127.0.0.1 ", " 127.0.0.1 " })
+  void testThreaded(String address) {
+    m_serverInst.startServer("connectionlistenertest.ini", address, 10000);
+    List<ConnectionNotification> events = new ArrayList<>();
+    final int handle = m_serverInst.addConnectionListener(events::add, false);
+
+    // trigger a connect event
+    m_clientInst.startClient(address, 10000);
+
+    // wait for client to report it's started, then wait another 0.1 sec
+    try {
+      while ((m_clientInst.getNetworkMode() & NetworkTableInstance.kNetModeStarting) != 0) {
+        Thread.sleep(100);
+      }
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for client to start");
+    }
+    assertTrue(m_serverInst.waitForConnectionListenerQueue(1.0));
+
+    // get the event
+    assertEquals(1, events.size());
+    assertEquals(handle, events.get(0).listener);
+    assertTrue(events.get(0).connected);
+    events.clear();
+
+    // trigger a disconnect event
+    m_clientInst.stopClient();
+    try {
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for client to stop");
+    }
+
+    // get the event
+    assertTrue(m_serverInst.waitForConnectionListenerQueue(1.0));
+    assertEquals(1, events.size());
+    assertEquals(handle, events.get(0).listener);
+    assertFalse(events.get(0).connected);
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/EntryListenerTest.java b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/EntryListenerTest.java
new file mode 100644
index 0000000..80627a4
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/EntryListenerTest.java
@@ -0,0 +1,91 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.util.ArrayList;
+import java.util.List;
+
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+import static org.junit.jupiter.api.Assertions.fail;
+
+class EntryListenerTest {
+  private NetworkTableInstance m_serverInst;
+  private NetworkTableInstance m_clientInst;
+
+  @BeforeEach
+  void setUp() {
+    m_serverInst = NetworkTableInstance.create();
+    m_serverInst.setNetworkIdentity("server");
+
+    m_clientInst = NetworkTableInstance.create();
+    m_clientInst.setNetworkIdentity("client");
+  }
+
+  @AfterEach
+  void tearDown() {
+    m_clientInst.close();
+    m_serverInst.close();
+  }
+
+  @SuppressWarnings("PMD.AvoidUsingHardCodedIP")
+  private void connect() {
+    m_serverInst.startServer("connectionlistenertest.ini", "127.0.0.1", 10000);
+    m_clientInst.startClient("127.0.0.1", 10000);
+
+    // Use connection listener to ensure we've connected
+    int poller = NetworkTablesJNI.createConnectionListenerPoller(m_clientInst.getHandle());
+    NetworkTablesJNI.addPolledConnectionListener(poller, false);
+    try {
+      if (NetworkTablesJNI.pollConnectionListenerTimeout(m_clientInst, poller, 1.0).length == 0) {
+        fail("client didn't connect to server");
+      }
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+      fail("interrupted while waiting for server connection");
+    }
+  }
+
+  /**
+   * Test prefix with a new remote.
+   */
+  @Test
+  void testPrefixNewRemote() {
+    connect();
+    List<EntryNotification> events = new ArrayList<>();
+    final int handle = m_serverInst.addEntryListener("/foo", events::add,
+        EntryListenerFlags.kNew);
+
+    // Trigger an event
+    m_clientInst.getEntry("/foo/bar").setDouble(1.0);
+    m_clientInst.getEntry("/baz").setDouble(1.0);
+    m_clientInst.flush();
+    try {
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for entries to update");
+    }
+
+    assertTrue(m_serverInst.waitForEntryListenerQueue(1.0));
+
+    // Check the event
+    assertAll("Event",
+        () -> assertEquals(1, events.size()),
+        () -> assertEquals(handle, events.get(0).listener),
+        () -> assertEquals(m_serverInst.getEntry("/foo/bar"), events.get(0).getEntry()),
+        () -> assertEquals("/foo/bar", events.get(0).name),
+        () -> assertEquals(NetworkTableValue.makeDouble(1.0), events.get(0).value),
+        () -> assertEquals(EntryListenerFlags.kNew, events.get(0).flags)
+    );
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/JNITest.java b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/JNITest.java
new file mode 100644
index 0000000..ef2b42b
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/JNITest.java
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import org.junit.jupiter.api.Test;
+
+class JNITest {
+  @Test
+  void jniLinkTest() {
+    // Test to verify that the JNI test link works correctly.
+    int inst = NetworkTablesJNI.getDefaultInstance();
+    NetworkTablesJNI.flush(inst);
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/LoggerTest.java b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/LoggerTest.java
new file mode 100644
index 0000000..420f9dc
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/LoggerTest.java
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.util.ArrayList;
+import java.util.List;
+
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.fail;
+
+class LoggerTest {
+  private NetworkTableInstance m_clientInst;
+
+  @BeforeEach
+  protected void setUp() {
+    m_clientInst = NetworkTableInstance.create();
+  }
+
+  @AfterEach
+  protected void tearDown() {
+    m_clientInst.close();
+  }
+
+  @Test
+  @SuppressWarnings("PMD.AvoidUsingHardCodedIP")
+  void addMessageTest() {
+    List<LogMessage> msgs = new ArrayList<>();
+    m_clientInst.addLogger(msgs::add, LogMessage.kInfo, 100);
+
+    m_clientInst.startClient("127.0.0.1", 10000);
+
+    // wait for client to report it's started, then wait another 0.1 sec
+    try {
+      while ((m_clientInst.getNetworkMode() & NetworkTableInstance.kNetModeStarting) != 0) {
+        Thread.sleep(100);
+      }
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      fail("interrupted while waiting for client to start");
+    }
+
+    assertFalse(msgs.isEmpty());
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/NetworkTableTest.java b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/NetworkTableTest.java
new file mode 100644
index 0000000..e45f197
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/java/edu/wpi/first/networktables/NetworkTableTest.java
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.networktables;
+
+import java.util.Arrays;
+import java.util.List;
+import java.util.stream.Stream;
+
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.Arguments;
+import org.junit.jupiter.params.provider.MethodSource;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+class NetworkTableTest {
+  private static Stream<Arguments> basenameKeyArguments() {
+    return Stream.of(
+        Arguments.of("simple", "simple"),
+        Arguments.of("simple", "one/two/many/simple"),
+        Arguments.of("simple", "//////an/////awful/key////simple")
+    );
+  }
+
+  @ParameterizedTest
+  @MethodSource("basenameKeyArguments")
+  void basenameKeyTest(final String expected, final String testString) {
+    assertEquals(expected, NetworkTable.basenameKey(testString));
+  }
+
+  private static Stream<Arguments> normalizeKeySlashArguments() {
+    return Stream.of(
+        Arguments.of("/", "///"),
+        Arguments.of("/no/normal/req", "/no/normal/req"),
+        Arguments.of("/no/leading/slash", "no/leading/slash"),
+        Arguments.of("/what/an/awful/key/", "//////what////an/awful/////key///")
+    );
+  }
+
+  @ParameterizedTest
+  @MethodSource("normalizeKeySlashArguments")
+  void normalizeKeySlashTest(final String expected, final String testString) {
+    assertEquals(expected, NetworkTable.normalizeKey(testString));
+  }
+
+  private static Stream<Arguments> normalizeKeyNoSlashArguments() {
+    return Stream.of(
+        Arguments.of("a", "a"),
+        Arguments.of("a", "///a"),
+        Arguments.of("leading/slash", "/leading/slash"),
+        Arguments.of("no/leading/slash", "no/leading/slash"),
+        Arguments.of("what/an/awful/key/", "//////what////an/awful/////key///")
+    );
+  }
+
+  @ParameterizedTest
+  @MethodSource("normalizeKeyNoSlashArguments")
+  void normalizeKeyNoSlashTest(final String expected, final String testString) {
+    assertEquals(expected, NetworkTable.normalizeKey(testString, false));
+  }
+
+  private static Stream<Arguments> getHierarchyArguments() {
+    return Stream.of(
+        Arguments.of(Arrays.asList("/"), ""),
+        Arguments.of(Arrays.asList("/"), "/"),
+        Arguments.of(Arrays.asList("/", "/foo", "/foo/bar", "/foo/bar/baz"), "/foo/bar/baz"),
+        Arguments.of(Arrays.asList("/", "/foo", "/foo/bar", "/foo/bar/"), "/foo/bar/")
+    );
+  }
+
+  @ParameterizedTest
+  @MethodSource("getHierarchyArguments")
+  void getHierarchyTest(final List<String> expected, final String testString) {
+    assertEquals(expected, NetworkTable.getHierarchy(testString));
+  }
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp
new file mode 100644
index 0000000..a56e45c
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp
@@ -0,0 +1,108 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <chrono>
+#include <thread>
+
+#include "TestPrinters.h"
+#include "gtest/gtest.h"
+#include "ntcore_cpp.h"
+
+class ConnectionListenerTest : public ::testing::Test {
+ public:
+  ConnectionListenerTest()
+      : server_inst(nt::CreateInstance()), client_inst(nt::CreateInstance()) {
+    nt::SetNetworkIdentity(server_inst, "server");
+    nt::SetNetworkIdentity(client_inst, "client");
+  }
+
+  ~ConnectionListenerTest() override {
+    nt::DestroyInstance(server_inst);
+    nt::DestroyInstance(client_inst);
+  }
+
+  void Connect();
+
+ protected:
+  NT_Inst server_inst;
+  NT_Inst client_inst;
+};
+
+void ConnectionListenerTest::Connect() {
+  nt::StartServer(server_inst, "connectionlistenertest.ini", "127.0.0.1",
+                  10000);
+  nt::StartClient(client_inst, "127.0.0.1", 10000);
+
+  // wait for client to report it's started, then wait another 0.1 sec
+  while ((nt::GetNetworkMode(client_inst) & NT_NET_MODE_STARTING) != 0)
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+}
+
+TEST_F(ConnectionListenerTest, Polled) {
+  // set up the poller
+  NT_ConnectionListenerPoller poller =
+      nt::CreateConnectionListenerPoller(server_inst);
+  ASSERT_NE(poller, 0u);
+  NT_ConnectionListener handle = nt::AddPolledConnectionListener(poller, false);
+  ASSERT_NE(handle, 0u);
+
+  // trigger a connect event
+  Connect();
+
+  // get the event
+  ASSERT_TRUE(nt::WaitForConnectionListenerQueue(server_inst, 1.0));
+  bool timed_out = false;
+  auto result = nt::PollConnectionListener(poller, 0.1, &timed_out);
+  EXPECT_FALSE(timed_out);
+  ASSERT_EQ(result.size(), 1u);
+  EXPECT_EQ(handle, result[0].listener);
+  EXPECT_TRUE(result[0].connected);
+
+  // trigger a disconnect event
+  nt::StopClient(client_inst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  // get the event
+  ASSERT_TRUE(nt::WaitForConnectionListenerQueue(server_inst, 1.0));
+  timed_out = false;
+  result = nt::PollConnectionListener(poller, 0.1, &timed_out);
+  EXPECT_FALSE(timed_out);
+  ASSERT_EQ(result.size(), 1u);
+  EXPECT_EQ(handle, result[0].listener);
+  EXPECT_FALSE(result[0].connected);
+
+  // trigger a disconnect event
+}
+
+TEST_F(ConnectionListenerTest, Threaded) {
+  std::vector<nt::ConnectionNotification> result;
+  auto handle = nt::AddConnectionListener(
+      server_inst,
+      [&](const nt::ConnectionNotification& event) { result.push_back(event); },
+      false);
+
+  // trigger a connect event
+  Connect();
+
+  ASSERT_TRUE(nt::WaitForConnectionListenerQueue(server_inst, 1.0));
+
+  // get the event
+  ASSERT_EQ(result.size(), 1u);
+  EXPECT_EQ(handle, result[0].listener);
+  EXPECT_TRUE(result[0].connected);
+  result.clear();
+
+  // trigger a disconnect event
+  nt::StopClient(client_inst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  // get the event
+  ASSERT_EQ(result.size(), 1u);
+  EXPECT_EQ(handle, result[0].listener);
+  EXPECT_FALSE(result[0].connected);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/EntryListenerTest.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/EntryListenerTest.cpp
new file mode 100644
index 0000000..b7bf2f6
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/EntryListenerTest.cpp
@@ -0,0 +1,164 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <chrono>
+#include <thread>
+
+#include "TestPrinters.h"
+#include "ValueMatcher.h"
+#include "gtest/gtest.h"
+#include "ntcore_cpp.h"
+
+class EntryListenerTest : public ::testing::Test {
+ public:
+  EntryListenerTest()
+      : server_inst(nt::CreateInstance()), client_inst(nt::CreateInstance()) {
+    nt::SetNetworkIdentity(server_inst, "server");
+    nt::SetNetworkIdentity(client_inst, "client");
+#if 0
+    nt::AddLogger(server_inst,
+                  [](const nt::LogMessage& msg) {
+                    std::fprintf(stderr, "SERVER: %s\n", msg.message.c_str());
+                  },
+                  0, UINT_MAX);
+    nt::AddLogger(client_inst,
+                  [](const nt::LogMessage& msg) {
+                    std::fprintf(stderr, "CLIENT: %s\n", msg.message.c_str());
+                  },
+                  0, UINT_MAX);
+#endif
+  }
+
+  ~EntryListenerTest() override {
+    nt::DestroyInstance(server_inst);
+    nt::DestroyInstance(client_inst);
+  }
+
+  void Connect();
+
+ protected:
+  NT_Inst server_inst;
+  NT_Inst client_inst;
+};
+
+void EntryListenerTest::Connect() {
+  nt::StartServer(server_inst, "entrylistenertest.ini", "127.0.0.1", 10000);
+  nt::StartClient(client_inst, "127.0.0.1", 10000);
+
+  // Use connection listener to ensure we've connected
+  NT_ConnectionListenerPoller poller =
+      nt::CreateConnectionListenerPoller(server_inst);
+  nt::AddPolledConnectionListener(poller, false);
+  bool timed_out = false;
+  if (nt::PollConnectionListener(poller, 1.0, &timed_out).empty()) {
+    FAIL() << "client didn't connect to server";
+  }
+}
+
+TEST_F(EntryListenerTest, EntryNewLocal) {
+  std::vector<nt::EntryNotification> events;
+  auto handle = nt::AddEntryListener(
+      nt::GetEntry(server_inst, "/foo"),
+      [&](const nt::EntryNotification& event) { events.push_back(event); },
+      NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
+
+  // Trigger an event
+  nt::SetEntryValue(nt::GetEntry(server_inst, "/foo/bar"),
+                    nt::Value::MakeDouble(2.0));
+  nt::SetEntryValue(nt::GetEntry(server_inst, "/foo"),
+                    nt::Value::MakeDouble(1.0));
+
+  ASSERT_TRUE(nt::WaitForEntryListenerQueue(server_inst, 1.0));
+
+  // Check the event
+  ASSERT_EQ(events.size(), 1u);
+  ASSERT_EQ(events[0].listener, handle);
+  ASSERT_EQ(events[0].entry, nt::GetEntry(server_inst, "/foo"));
+  ASSERT_EQ(events[0].name, "/foo");
+  ASSERT_THAT(events[0].value, nt::ValueEq(nt::Value::MakeDouble(1.0)));
+  ASSERT_EQ(events[0].flags, (unsigned int)(NT_NOTIFY_NEW | NT_NOTIFY_LOCAL));
+}
+
+TEST_F(EntryListenerTest, DISABLED_EntryNewRemote) {
+  Connect();
+  if (HasFatalFailure()) return;
+  std::vector<nt::EntryNotification> events;
+  auto handle = nt::AddEntryListener(
+      nt::GetEntry(server_inst, "/foo"),
+      [&](const nt::EntryNotification& event) { events.push_back(event); },
+      NT_NOTIFY_NEW);
+
+  // Trigger an event
+  nt::SetEntryValue(nt::GetEntry(client_inst, "/foo/bar"),
+                    nt::Value::MakeDouble(2.0));
+  nt::SetEntryValue(nt::GetEntry(client_inst, "/foo"),
+                    nt::Value::MakeDouble(1.0));
+  nt::Flush(client_inst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  ASSERT_TRUE(nt::WaitForEntryListenerQueue(server_inst, 1.0));
+
+  // Check the event
+  ASSERT_EQ(events.size(), 1u);
+  ASSERT_EQ(events[0].listener, handle);
+  ASSERT_EQ(events[0].entry, nt::GetEntry(server_inst, "/foo"));
+  ASSERT_EQ(events[0].name, "/foo");
+  ASSERT_THAT(events[0].value, nt::ValueEq(nt::Value::MakeDouble(1.0)));
+  ASSERT_EQ(events[0].flags, NT_NOTIFY_NEW);
+}
+
+TEST_F(EntryListenerTest, PrefixNewLocal) {
+  std::vector<nt::EntryNotification> events;
+  auto handle = nt::AddEntryListener(
+      server_inst, "/foo",
+      [&](const nt::EntryNotification& event) { events.push_back(event); },
+      NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
+
+  // Trigger an event
+  nt::SetEntryValue(nt::GetEntry(server_inst, "/foo/bar"),
+                    nt::Value::MakeDouble(1.0));
+  nt::SetEntryValue(nt::GetEntry(server_inst, "/baz"),
+                    nt::Value::MakeDouble(1.0));
+
+  ASSERT_TRUE(nt::WaitForEntryListenerQueue(server_inst, 1.0));
+
+  // Check the event
+  ASSERT_EQ(events.size(), 1u);
+  ASSERT_EQ(events[0].listener, handle);
+  ASSERT_EQ(events[0].entry, nt::GetEntry(server_inst, "/foo/bar"));
+  ASSERT_EQ(events[0].name, "/foo/bar");
+  ASSERT_THAT(events[0].value, nt::ValueEq(nt::Value::MakeDouble(1.0)));
+  ASSERT_EQ(events[0].flags, (unsigned int)(NT_NOTIFY_NEW | NT_NOTIFY_LOCAL));
+}
+
+TEST_F(EntryListenerTest, DISABLED_PrefixNewRemote) {
+  Connect();
+  if (HasFatalFailure()) return;
+  std::vector<nt::EntryNotification> events;
+  auto handle = nt::AddEntryListener(
+      server_inst, "/foo",
+      [&](const nt::EntryNotification& event) { events.push_back(event); },
+      NT_NOTIFY_NEW);
+
+  // Trigger an event
+  nt::SetEntryValue(nt::GetEntry(client_inst, "/foo/bar"),
+                    nt::Value::MakeDouble(1.0));
+  nt::SetEntryValue(nt::GetEntry(client_inst, "/baz"),
+                    nt::Value::MakeDouble(1.0));
+  nt::Flush(client_inst);
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+
+  ASSERT_TRUE(nt::WaitForEntryListenerQueue(server_inst, 1.0));
+
+  // Check the event
+  ASSERT_EQ(events.size(), 1u);
+  ASSERT_EQ(events[0].listener, handle);
+  ASSERT_EQ(events[0].entry, nt::GetEntry(server_inst, "/foo/bar"));
+  ASSERT_EQ(events[0].name, "/foo/bar");
+  ASSERT_THAT(events[0].value, nt::ValueEq(nt::Value::MakeDouble(1.0)));
+  ASSERT_EQ(events[0].flags, NT_NOTIFY_NEW);
+}
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/EntryNotifierTest.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/EntryNotifierTest.cpp
new file mode 100644
index 0000000..4f1df77
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/EntryNotifierTest.cpp
@@ -0,0 +1,314 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <wpi/Logger.h>
+
+#include "EntryNotifier.h"
+#include "TestPrinters.h"
+#include "ValueMatcher.h"
+#include "gtest/gtest.h"
+
+using ::testing::AnyNumber;
+using ::testing::IsNull;
+using ::testing::Return;
+using ::testing::_;
+
+namespace nt {
+
+class EntryNotifierTest : public ::testing::Test {
+ public:
+  EntryNotifierTest() : notifier(1, logger) { notifier.Start(); }
+
+  void GenerateNotifications();
+
+ protected:
+  wpi::Logger logger;
+  EntryNotifier notifier;
+};
+
+void EntryNotifierTest::GenerateNotifications() {
+  // All flags combos that can be generated by Storage
+  static const unsigned int flags[] = {
+      // "normal" notifications
+      NT_NOTIFY_NEW, NT_NOTIFY_DELETE, NT_NOTIFY_UPDATE, NT_NOTIFY_FLAGS,
+      NT_NOTIFY_UPDATE | NT_NOTIFY_FLAGS,
+      // immediate notifications are always "new"
+      NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW,
+      // local notifications can be of any flag combo
+      NT_NOTIFY_LOCAL | NT_NOTIFY_NEW, NT_NOTIFY_LOCAL | NT_NOTIFY_DELETE,
+      NT_NOTIFY_LOCAL | NT_NOTIFY_UPDATE, NT_NOTIFY_LOCAL | NT_NOTIFY_FLAGS,
+      NT_NOTIFY_LOCAL | NT_NOTIFY_UPDATE | NT_NOTIFY_FLAGS};
+  // Generate across keys
+  static const char* keys[] = {"/foo/bar", "/baz", "/boo"};
+
+  auto val = Value::MakeDouble(1);
+
+  // Provide unique key indexes for each key
+  unsigned int keyindex = 5;
+  for (auto key : keys) {
+    for (auto flag : flags) {
+      notifier.NotifyEntry(keyindex, key, val, flag);
+    }
+    ++keyindex;
+  }
+}
+
+TEST_F(EntryNotifierTest, PollEntryMultiple) {
+  auto poller1 = notifier.CreatePoller();
+  auto poller2 = notifier.CreatePoller();
+  auto poller3 = notifier.CreatePoller();
+  auto h1 = notifier.AddPolled(poller1, 6, NT_NOTIFY_NEW);
+  auto h2 = notifier.AddPolled(poller2, 6, NT_NOTIFY_NEW);
+  auto h3 = notifier.AddPolled(poller3, 6, NT_NOTIFY_UPDATE);
+
+  ASSERT_FALSE(notifier.local_notifiers());
+
+  GenerateNotifications();
+
+  ASSERT_TRUE(notifier.WaitForQueue(1.0));
+  bool timed_out = false;
+  auto results1 = notifier.Poll(poller1, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+  auto results2 = notifier.Poll(poller2, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+  auto results3 = notifier.Poll(poller3, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+
+  ASSERT_EQ(results1.size(), 2u);
+  for (const auto& result : results1) {
+    SCOPED_TRACE(::testing::PrintToString(result));
+    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h1);
+  }
+
+  ASSERT_EQ(results2.size(), 2u);
+  for (const auto& result : results2) {
+    SCOPED_TRACE(::testing::PrintToString(result));
+    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h2);
+  }
+
+  ASSERT_EQ(results3.size(), 2u);
+  for (const auto& result : results3) {
+    SCOPED_TRACE(::testing::PrintToString(result));
+    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h3);
+  }
+}
+
+TEST_F(EntryNotifierTest, PollEntryBasic) {
+  auto poller = notifier.CreatePoller();
+  auto g1 = notifier.AddPolled(poller, 6, NT_NOTIFY_NEW);
+  auto g2 = notifier.AddPolled(poller, 6, NT_NOTIFY_DELETE);
+  auto g3 = notifier.AddPolled(poller, 6, NT_NOTIFY_UPDATE);
+  auto g4 = notifier.AddPolled(poller, 6, NT_NOTIFY_FLAGS);
+
+  ASSERT_FALSE(notifier.local_notifiers());
+
+  GenerateNotifications();
+
+  ASSERT_TRUE(notifier.WaitForQueue(1.0));
+  bool timed_out = false;
+  auto results = notifier.Poll(poller, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+
+  int g1count = 0;
+  int g2count = 0;
+  int g3count = 0;
+  int g4count = 0;
+  for (const auto& result : results) {
+    SCOPED_TRACE(::testing::PrintToString(result));
+    EXPECT_EQ(result.name, "/baz");
+    EXPECT_THAT(result.value, ValueEq(Value::MakeDouble(1)));
+    EXPECT_EQ(Handle{result.entry}.GetType(), Handle::kEntry);
+    EXPECT_EQ(Handle{result.entry}.GetInst(), 1);
+    EXPECT_EQ(Handle{result.entry}.GetIndex(), 6);
+    EXPECT_EQ(Handle{result.listener}.GetType(), Handle::kEntryListener);
+    EXPECT_EQ(Handle{result.listener}.GetInst(), 1);
+    if (Handle{result.listener}.GetIndex() == static_cast<int>(g1)) {
+      ++g1count;
+      EXPECT_TRUE((result.flags & NT_NOTIFY_NEW) != 0);
+    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g2)) {
+      ++g2count;
+      EXPECT_TRUE((result.flags & NT_NOTIFY_DELETE) != 0);
+    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g3)) {
+      ++g3count;
+      EXPECT_TRUE((result.flags & NT_NOTIFY_UPDATE) != 0);
+    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g4)) {
+      ++g4count;
+      EXPECT_TRUE((result.flags & NT_NOTIFY_FLAGS) != 0);
+    } else {
+      ADD_FAILURE() << "unknown listener index";
+    }
+  }
+  EXPECT_EQ(g1count, 2);
+  EXPECT_EQ(g2count, 1);  // NT_NOTIFY_DELETE
+  EXPECT_EQ(g3count, 2);
+  EXPECT_EQ(g4count, 2);
+}
+
+TEST_F(EntryNotifierTest, PollEntryImmediate) {
+  auto poller = notifier.CreatePoller();
+  notifier.AddPolled(poller, 6, NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
+  notifier.AddPolled(poller, 6, NT_NOTIFY_NEW);
+
+  ASSERT_FALSE(notifier.local_notifiers());
+
+  GenerateNotifications();
+
+  ASSERT_TRUE(notifier.WaitForQueue(1.0));
+  bool timed_out = false;
+  auto results = notifier.Poll(poller, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+  SCOPED_TRACE(::testing::PrintToString(results));
+  ASSERT_EQ(results.size(), 4u);
+}
+
+TEST_F(EntryNotifierTest, PollEntryLocal) {
+  auto poller = notifier.CreatePoller();
+  notifier.AddPolled(poller, 6, NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
+  notifier.AddPolled(poller, 6, NT_NOTIFY_NEW);
+
+  ASSERT_TRUE(notifier.local_notifiers());
+
+  GenerateNotifications();
+
+  ASSERT_TRUE(notifier.WaitForQueue(1.0));
+  bool timed_out = false;
+  auto results = notifier.Poll(poller, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+  SCOPED_TRACE(::testing::PrintToString(results));
+  ASSERT_EQ(results.size(), 6u);
+}
+
+TEST_F(EntryNotifierTest, PollPrefixMultiple) {
+  auto poller1 = notifier.CreatePoller();
+  auto poller2 = notifier.CreatePoller();
+  auto poller3 = notifier.CreatePoller();
+  auto h1 = notifier.AddPolled(poller1, "/foo", NT_NOTIFY_NEW);
+  auto h2 = notifier.AddPolled(poller2, "/foo", NT_NOTIFY_NEW);
+  auto h3 = notifier.AddPolled(poller3, "/foo", NT_NOTIFY_UPDATE);
+
+  ASSERT_FALSE(notifier.local_notifiers());
+
+  GenerateNotifications();
+
+  ASSERT_TRUE(notifier.WaitForQueue(1.0));
+  bool timed_out = false;
+  auto results1 = notifier.Poll(poller1, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+  auto results2 = notifier.Poll(poller2, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+  auto results3 = notifier.Poll(poller3, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+
+  ASSERT_EQ(results1.size(), 2u);
+  for (const auto& result : results1) {
+    SCOPED_TRACE(::testing::PrintToString(result));
+    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h1);
+  }
+
+  ASSERT_EQ(results2.size(), 2u);
+  for (const auto& result : results2) {
+    SCOPED_TRACE(::testing::PrintToString(result));
+    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h2);
+  }
+
+  ASSERT_EQ(results3.size(), 2u);
+  for (const auto& result : results3) {
+    SCOPED_TRACE(::testing::PrintToString(result));
+    EXPECT_EQ(Handle{result.listener}.GetIndex(), (int)h3);
+  }
+}
+
+TEST_F(EntryNotifierTest, PollPrefixBasic) {
+  auto poller = notifier.CreatePoller();
+  auto g1 = notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW);
+  auto g2 = notifier.AddPolled(poller, "/foo", NT_NOTIFY_DELETE);
+  auto g3 = notifier.AddPolled(poller, "/foo", NT_NOTIFY_UPDATE);
+  auto g4 = notifier.AddPolled(poller, "/foo", NT_NOTIFY_FLAGS);
+  notifier.AddPolled(poller, "/bar", NT_NOTIFY_NEW);
+  notifier.AddPolled(poller, "/bar", NT_NOTIFY_DELETE);
+  notifier.AddPolled(poller, "/bar", NT_NOTIFY_UPDATE);
+  notifier.AddPolled(poller, "/bar", NT_NOTIFY_FLAGS);
+
+  ASSERT_FALSE(notifier.local_notifiers());
+
+  GenerateNotifications();
+
+  ASSERT_TRUE(notifier.WaitForQueue(1.0));
+  bool timed_out = false;
+  auto results = notifier.Poll(poller, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+
+  int g1count = 0;
+  int g2count = 0;
+  int g3count = 0;
+  int g4count = 0;
+  for (const auto& result : results) {
+    SCOPED_TRACE(::testing::PrintToString(result));
+    EXPECT_TRUE(StringRef(result.name).startswith("/foo"));
+    EXPECT_THAT(result.value, ValueEq(Value::MakeDouble(1)));
+    EXPECT_EQ(Handle{result.entry}.GetType(), Handle::kEntry);
+    EXPECT_EQ(Handle{result.entry}.GetInst(), 1);
+    EXPECT_EQ(Handle{result.entry}.GetIndex(), 5);
+    EXPECT_EQ(Handle{result.listener}.GetType(), Handle::kEntryListener);
+    EXPECT_EQ(Handle{result.listener}.GetInst(), 1);
+    if (Handle{result.listener}.GetIndex() == static_cast<int>(g1)) {
+      ++g1count;
+      EXPECT_TRUE((result.flags & NT_NOTIFY_NEW) != 0);
+    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g2)) {
+      ++g2count;
+      EXPECT_TRUE((result.flags & NT_NOTIFY_DELETE) != 0);
+    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g3)) {
+      ++g3count;
+      EXPECT_TRUE((result.flags & NT_NOTIFY_UPDATE) != 0);
+    } else if (Handle{result.listener}.GetIndex() == static_cast<int>(g4)) {
+      ++g4count;
+      EXPECT_TRUE((result.flags & NT_NOTIFY_FLAGS) != 0);
+    } else {
+      ADD_FAILURE() << "unknown listener index";
+    }
+  }
+  EXPECT_EQ(g1count, 2);
+  EXPECT_EQ(g2count, 1);  // NT_NOTIFY_DELETE
+  EXPECT_EQ(g3count, 2);
+  EXPECT_EQ(g4count, 2);
+}
+
+TEST_F(EntryNotifierTest, PollPrefixImmediate) {
+  auto poller = notifier.CreatePoller();
+  notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
+  notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW);
+
+  ASSERT_FALSE(notifier.local_notifiers());
+
+  GenerateNotifications();
+
+  ASSERT_TRUE(notifier.WaitForQueue(1.0));
+  bool timed_out = false;
+  auto results = notifier.Poll(poller, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+  SCOPED_TRACE(::testing::PrintToString(results));
+  ASSERT_EQ(results.size(), 4u);
+}
+
+TEST_F(EntryNotifierTest, PollPrefixLocal) {
+  auto poller = notifier.CreatePoller();
+  notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW | NT_NOTIFY_LOCAL);
+  notifier.AddPolled(poller, "/foo", NT_NOTIFY_NEW);
+
+  ASSERT_TRUE(notifier.local_notifiers());
+
+  GenerateNotifications();
+
+  ASSERT_TRUE(notifier.WaitForQueue(1.0));
+  bool timed_out = false;
+  auto results = notifier.Poll(poller, 0, &timed_out);
+  ASSERT_FALSE(timed_out);
+  SCOPED_TRACE(::testing::PrintToString(results));
+  ASSERT_EQ(results.size(), 6u);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MessageMatcher.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MessageMatcher.cpp
new file mode 100644
index 0000000..35d4f8b
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MessageMatcher.cpp
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "MessageMatcher.h"
+
+namespace nt {
+
+bool MessageMatcher::MatchAndExplain(
+    std::shared_ptr<Message> msg,
+    ::testing::MatchResultListener* listener) const {
+  bool match = true;
+  if (!msg) return false;
+  if (msg->str() != goodmsg->str()) {
+    *listener << "str mismatch ";
+    match = false;
+  }
+  if ((!msg->value() && goodmsg->value()) ||
+      (msg->value() && !goodmsg->value()) ||
+      (msg->value() && goodmsg->value() &&
+       *msg->value() != *goodmsg->value())) {
+    *listener << "value mismatch ";
+    match = false;
+  }
+  if (msg->id() != goodmsg->id()) {
+    *listener << "id mismatch ";
+    match = false;
+  }
+  if (msg->flags() != goodmsg->flags()) {
+    *listener << "flags mismatch";
+    match = false;
+  }
+  if (msg->seq_num_uid() != goodmsg->seq_num_uid()) {
+    *listener << "seq_num_uid mismatch";
+    match = false;
+  }
+  return match;
+}
+
+void MessageMatcher::DescribeTo(::std::ostream* os) const {
+  PrintTo(goodmsg, os);
+}
+
+void MessageMatcher::DescribeNegationTo(::std::ostream* os) const {
+  *os << "is not equal to ";
+  PrintTo(goodmsg, os);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MessageMatcher.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MessageMatcher.h
new file mode 100644
index 0000000..5b14334
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MessageMatcher.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_MESSAGEMATCHER_H_
+#define NTCORE_MESSAGEMATCHER_H_
+
+#include <memory>
+#include <ostream>
+
+#include "Message.h"
+#include "TestPrinters.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class MessageMatcher
+    : public ::testing::MatcherInterface<std::shared_ptr<Message>> {
+ public:
+  explicit MessageMatcher(std::shared_ptr<Message> goodmsg_)
+      : goodmsg(goodmsg_) {}
+
+  bool MatchAndExplain(std::shared_ptr<Message> msg,
+                       ::testing::MatchResultListener* listener) const override;
+  void DescribeTo(::std::ostream* os) const override;
+  void DescribeNegationTo(::std::ostream* os) const override;
+
+ private:
+  std::shared_ptr<Message> goodmsg;
+};
+
+inline ::testing::Matcher<std::shared_ptr<Message>> MessageEq(
+    std::shared_ptr<Message> goodmsg) {
+  return ::testing::MakeMatcher(new MessageMatcher(goodmsg));
+}
+
+}  // namespace nt
+
+#endif  // NTCORE_MESSAGEMATCHER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockConnectionNotifier.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockConnectionNotifier.h
new file mode 100644
index 0000000..ddf8b2e
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockConnectionNotifier.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_MOCKCONNECTIONNOTIFIER_H_
+#define NTCORE_MOCKCONNECTIONNOTIFIER_H_
+
+#include "IConnectionNotifier.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class MockConnectionNotifier : public IConnectionNotifier {
+ public:
+  MOCK_METHOD1(
+      Add,
+      unsigned int(
+          std::function<void(const ConnectionNotification& event)> callback));
+  MOCK_METHOD1(AddPolled, unsigned int(unsigned int poller_uid));
+  MOCK_METHOD3(NotifyConnection,
+               void(bool connected, const ConnectionInfo& conn_info,
+                    unsigned int only_listener));
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_MOCKCONNECTIONNOTIFIER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockDispatcher.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockDispatcher.h
new file mode 100644
index 0000000..10af839
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockDispatcher.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_MOCKDISPATCHER_H_
+#define NTCORE_MOCKDISPATCHER_H_
+
+#include <memory>
+
+#include "IDispatcher.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class MockDispatcher : public IDispatcher {
+ public:
+  MOCK_METHOD3(QueueOutgoing,
+               void(std::shared_ptr<Message> msg, INetworkConnection* only,
+                    INetworkConnection* except));
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_MOCKDISPATCHER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockEntryNotifier.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockEntryNotifier.h
new file mode 100644
index 0000000..2f078cb
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockEntryNotifier.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_MOCKENTRYNOTIFIER_H_
+#define NTCORE_MOCKENTRYNOTIFIER_H_
+
+#include <memory>
+
+#include "IEntryNotifier.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class MockEntryNotifier : public IEntryNotifier {
+ public:
+  MOCK_CONST_METHOD0(local_notifiers, bool());
+  MOCK_METHOD3(
+      Add,
+      unsigned int(std::function<void(const EntryNotification& event)> callback,
+                   wpi::StringRef prefix, unsigned int flags));
+  MOCK_METHOD3(
+      Add,
+      unsigned int(std::function<void(const EntryNotification& event)> callback,
+                   unsigned int local_id, unsigned int flags));
+  MOCK_METHOD3(AddPolled,
+               unsigned int(unsigned int poller_uid, wpi::StringRef prefix,
+                            unsigned int flags));
+  MOCK_METHOD3(AddPolled,
+               unsigned int(unsigned int poller_uid, unsigned int local_id,
+                            unsigned int flags));
+  MOCK_METHOD5(NotifyEntry,
+               void(unsigned int local_id, StringRef name,
+                    std::shared_ptr<Value> value, unsigned int flags,
+                    unsigned int only_listener));
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_MOCKENTRYNOTIFIER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockNetworkConnection.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockNetworkConnection.h
new file mode 100644
index 0000000..52c917d
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockNetworkConnection.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_MOCKNETWORKCONNECTION_H_
+#define NTCORE_MOCKNETWORKCONNECTION_H_
+
+#include <memory>
+
+#include "INetworkConnection.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class MockNetworkConnection : public INetworkConnection {
+ public:
+  MOCK_CONST_METHOD0(info, ConnectionInfo());
+
+  MOCK_METHOD1(QueueOutgoing, void(std::shared_ptr<Message> msg));
+  MOCK_METHOD1(PostOutgoing, void(bool keep_alive));
+
+  MOCK_CONST_METHOD0(proto_rev, unsigned int());
+  MOCK_METHOD1(set_proto_rev, void(unsigned int proto_rev));
+
+  MOCK_CONST_METHOD0(state, State());
+  MOCK_METHOD1(set_state, void(State state));
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_MOCKNETWORKCONNECTION_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockRpcServer.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockRpcServer.h
new file mode 100644
index 0000000..6e9d970
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/MockRpcServer.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_MOCKRPCSERVER_H_
+#define NTCORE_MOCKRPCSERVER_H_
+
+#include "IRpcServer.h"
+#include "gmock/gmock.h"
+
+namespace nt {
+
+class MockRpcServer : public IRpcServer {
+ public:
+  MOCK_METHOD0(Start, void());
+  MOCK_METHOD1(RemoveRpc, void(unsigned int rpc_uid));
+  MOCK_METHOD7(ProcessRpc,
+               void(unsigned int local_id, unsigned int call_uid,
+                    StringRef name, StringRef params,
+                    const ConnectionInfo& conn, SendResponseFunc send_response,
+                    unsigned int rpc_uid));
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_MOCKRPCSERVER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/NetworkTableTest.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/NetworkTableTest.cpp
new file mode 100644
index 0000000..d9a2743
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/NetworkTableTest.cpp
@@ -0,0 +1,91 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "TestPrinters.h"
+#include "gtest/gtest.h"
+#include "networktables/NetworkTable.h"
+#include "networktables/NetworkTableInstance.h"
+
+class NetworkTableTest : public ::testing::Test {};
+
+TEST_F(NetworkTableTest, BasenameKey) {
+  EXPECT_EQ("simple", NetworkTable::BasenameKey("simple"));
+  EXPECT_EQ("simple", NetworkTable::BasenameKey("one/two/many/simple"));
+  EXPECT_EQ("simple",
+            NetworkTable::BasenameKey("//////an/////awful/key////simple"));
+}
+
+TEST_F(NetworkTableTest, NormalizeKeySlash) {
+  EXPECT_EQ("/", NetworkTable::NormalizeKey("///"));
+  EXPECT_EQ("/no/normal/req", NetworkTable::NormalizeKey("/no/normal/req"));
+  EXPECT_EQ("/no/leading/slash",
+            NetworkTable::NormalizeKey("no/leading/slash"));
+  EXPECT_EQ("/what/an/awful/key/",
+            NetworkTable::NormalizeKey("//////what////an/awful/////key///"));
+}
+
+TEST_F(NetworkTableTest, NormalizeKeyNoSlash) {
+  EXPECT_EQ("a", NetworkTable::NormalizeKey("a", false));
+  EXPECT_EQ("a", NetworkTable::NormalizeKey("///a", false));
+  EXPECT_EQ("leading/slash",
+            NetworkTable::NormalizeKey("/leading/slash", false));
+  EXPECT_EQ("no/leading/slash",
+            NetworkTable::NormalizeKey("no/leading/slash", false));
+  EXPECT_EQ(
+      "what/an/awful/key/",
+      NetworkTable::NormalizeKey("//////what////an/awful/////key///", false));
+}
+
+TEST_F(NetworkTableTest, GetHierarchyEmpty) {
+  std::vector<std::string> expected{"/"};
+  ASSERT_EQ(expected, NetworkTable::GetHierarchy(""));
+}
+
+TEST_F(NetworkTableTest, GetHierarchyRoot) {
+  std::vector<std::string> expected{"/"};
+  ASSERT_EQ(expected, NetworkTable::GetHierarchy("/"));
+}
+
+TEST_F(NetworkTableTest, GetHierarchyNormal) {
+  std::vector<std::string> expected{"/", "/foo", "/foo/bar", "/foo/bar/baz"};
+  ASSERT_EQ(expected, NetworkTable::GetHierarchy("/foo/bar/baz"));
+}
+
+TEST_F(NetworkTableTest, GetHierarchyTrailingSlash) {
+  std::vector<std::string> expected{"/", "/foo", "/foo/bar", "/foo/bar/"};
+  ASSERT_EQ(expected, NetworkTable::GetHierarchy("/foo/bar/"));
+}
+
+TEST_F(NetworkTableTest, ContainsKey) {
+  auto inst = nt::NetworkTableInstance::Create();
+  auto nt = inst.GetTable("containskey");
+  ASSERT_FALSE(nt->ContainsKey("testkey"));
+  nt->PutNumber("testkey", 5);
+  ASSERT_TRUE(nt->ContainsKey("testkey"));
+  ASSERT_TRUE(inst.GetEntry("/containskey/testkey").Exists());
+  ASSERT_FALSE(inst.GetEntry("containskey/testkey").Exists());
+}
+
+TEST_F(NetworkTableTest, LeadingSlash) {
+  auto inst = nt::NetworkTableInstance::Create();
+  auto nt = inst.GetTable("leadingslash");
+  auto nt2 = inst.GetTable("/leadingslash");
+  ASSERT_FALSE(nt->ContainsKey("testkey"));
+  nt2->PutNumber("testkey", 5);
+  ASSERT_TRUE(nt->ContainsKey("testkey"));
+  ASSERT_TRUE(inst.GetEntry("/leadingslash/testkey").Exists());
+}
+
+TEST_F(NetworkTableTest, EmptyOrNoSlash) {
+  auto inst = nt::NetworkTableInstance::Create();
+  auto nt = inst.GetTable("/");
+  auto nt2 = inst.GetTable("");
+  ASSERT_FALSE(nt->ContainsKey("testkey"));
+  nt2->PutNumber("testkey", 5);
+  ASSERT_TRUE(nt->ContainsKey("testkey"));
+  ASSERT_TRUE(inst.GetEntry("/testkey").Exists());
+}
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
new file mode 100644
index 0000000..5a6982b
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/StorageTest.cpp
@@ -0,0 +1,987 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "StorageTest.h"
+
+#include <wpi/raw_istream.h>
+#include <wpi/raw_ostream.h>
+
+#include "MessageMatcher.h"
+#include "MockNetworkConnection.h"
+#include "Storage.h"
+#include "TestPrinters.h"
+#include "ValueMatcher.h"
+#include "gmock/gmock.h"
+#include "gtest/gtest.h"
+
+using ::testing::AnyNumber;
+using ::testing::IsNull;
+using ::testing::Return;
+using ::testing::_;
+
+namespace nt {
+
+class StorageTestEmpty : public StorageTest,
+                         public ::testing::TestWithParam<bool> {
+ public:
+  StorageTestEmpty() {
+    HookOutgoing(GetParam());
+    EXPECT_CALL(notifier, local_notifiers())
+        .Times(AnyNumber())
+        .WillRepeatedly(Return(true));
+  }
+};
+
+class StorageTestPopulateOne : public StorageTestEmpty {
+ public:
+  StorageTestPopulateOne() {
+    EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
+    EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
+    EXPECT_CALL(notifier, local_notifiers())
+        .Times(AnyNumber())
+        .WillRepeatedly(Return(false));
+    storage.SetEntryTypeValue("foo", Value::MakeBoolean(true));
+    ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
+    ::testing::Mock::VerifyAndClearExpectations(&notifier);
+    EXPECT_CALL(notifier, local_notifiers())
+        .Times(AnyNumber())
+        .WillRepeatedly(Return(true));
+  }
+};
+
+class StorageTestPopulated : public StorageTestEmpty {
+ public:
+  StorageTestPopulated() {
+    EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
+    EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
+    EXPECT_CALL(notifier, local_notifiers())
+        .Times(AnyNumber())
+        .WillRepeatedly(Return(false));
+    storage.SetEntryTypeValue("foo", Value::MakeBoolean(true));
+    storage.SetEntryTypeValue("foo2", Value::MakeDouble(0.0));
+    storage.SetEntryTypeValue("bar", Value::MakeDouble(1.0));
+    storage.SetEntryTypeValue("bar2", Value::MakeBoolean(false));
+    ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
+    ::testing::Mock::VerifyAndClearExpectations(&notifier);
+    EXPECT_CALL(notifier, local_notifiers())
+        .Times(AnyNumber())
+        .WillRepeatedly(Return(true));
+  }
+};
+
+class StorageTestPersistent : public StorageTestEmpty {
+ public:
+  StorageTestPersistent() {
+    EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
+    EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
+    EXPECT_CALL(notifier, local_notifiers())
+        .Times(AnyNumber())
+        .WillRepeatedly(Return(false));
+    storage.SetEntryTypeValue("boolean/true", Value::MakeBoolean(true));
+    storage.SetEntryTypeValue("boolean/false", Value::MakeBoolean(false));
+    storage.SetEntryTypeValue("double/neg", Value::MakeDouble(-1.5));
+    storage.SetEntryTypeValue("double/zero", Value::MakeDouble(0.0));
+    storage.SetEntryTypeValue("double/big", Value::MakeDouble(1.3e8));
+    storage.SetEntryTypeValue("string/empty", Value::MakeString(""));
+    storage.SetEntryTypeValue("string/normal", Value::MakeString("hello"));
+    storage.SetEntryTypeValue("string/special",
+                              Value::MakeString(StringRef("\0\3\5\n", 4)));
+    storage.SetEntryTypeValue("raw/empty", Value::MakeRaw(""));
+    storage.SetEntryTypeValue("raw/normal", Value::MakeRaw("hello"));
+    storage.SetEntryTypeValue("raw/special",
+                              Value::MakeRaw(StringRef("\0\3\5\n", 4)));
+    storage.SetEntryTypeValue("booleanarr/empty",
+                              Value::MakeBooleanArray(std::vector<int>{}));
+    storage.SetEntryTypeValue("booleanarr/one",
+                              Value::MakeBooleanArray(std::vector<int>{1}));
+    storage.SetEntryTypeValue("booleanarr/two",
+                              Value::MakeBooleanArray(std::vector<int>{1, 0}));
+    storage.SetEntryTypeValue("doublearr/empty",
+                              Value::MakeDoubleArray(std::vector<double>{}));
+    storage.SetEntryTypeValue("doublearr/one",
+                              Value::MakeDoubleArray(std::vector<double>{0.5}));
+    storage.SetEntryTypeValue(
+        "doublearr/two",
+        Value::MakeDoubleArray(std::vector<double>{0.5, -0.25}));
+    storage.SetEntryTypeValue(
+        "stringarr/empty", Value::MakeStringArray(std::vector<std::string>{}));
+    storage.SetEntryTypeValue(
+        "stringarr/one",
+        Value::MakeStringArray(std::vector<std::string>{"hello"}));
+    storage.SetEntryTypeValue(
+        "stringarr/two",
+        Value::MakeStringArray(std::vector<std::string>{"hello", "world\n"}));
+    storage.SetEntryTypeValue(StringRef("\0\3\5\n", 4),
+                              Value::MakeBoolean(true));
+    storage.SetEntryTypeValue("=", Value::MakeBoolean(true));
+    ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
+    ::testing::Mock::VerifyAndClearExpectations(&notifier);
+    EXPECT_CALL(notifier, local_notifiers())
+        .Times(AnyNumber())
+        .WillRepeatedly(Return(true));
+  }
+};
+
+class MockLoadWarn {
+ public:
+  MOCK_METHOD2(Warn, void(size_t line, wpi::StringRef msg));
+};
+
+TEST_P(StorageTestEmpty, Construct) {
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, StorageEntryInit) {
+  auto entry = GetEntry("foo");
+  EXPECT_FALSE(entry->value);
+  EXPECT_EQ(0u, entry->flags);
+  EXPECT_EQ("foobar", entry->name);  // since GetEntry uses the tmp_entry.
+  EXPECT_EQ(0xffffu, entry->id);
+  EXPECT_EQ(SequenceNumber(), entry->seq_num);
+}
+
+TEST_P(StorageTestEmpty, GetEntryValueNotExist) {
+  EXPECT_FALSE(storage.GetEntryValue("foo"));
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, GetEntryValueExist) {
+  auto value = Value::MakeBoolean(true);
+  EXPECT_CALL(dispatcher, QueueOutgoing(_, IsNull(), IsNull()));
+  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _));
+  storage.SetEntryTypeValue("foo", value);
+  EXPECT_EQ(value, storage.GetEntryValue("foo"));
+}
+
+TEST_P(StorageTestEmpty, SetEntryTypeValueAssignNew) {
+  // brand new entry
+  auto value = Value::MakeBoolean(true);
+  // id assigned if server
+  EXPECT_CALL(dispatcher,
+              QueueOutgoing(MessageEq(Message::EntryAssign(
+                                "foo", GetParam() ? 0 : 0xffff, 1, value, 0)),
+                            IsNull(), IsNull()));
+  EXPECT_CALL(notifier, NotifyEntry(0, StringRef("foo"), value,
+                                    NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  storage.SetEntryTypeValue("foo", value);
+  EXPECT_EQ(value, GetEntry("foo")->value);
+  if (GetParam()) {
+    ASSERT_EQ(1u, idmap().size());
+    EXPECT_EQ(value, idmap()[0]->value);
+  } else {
+    EXPECT_TRUE(idmap().empty());
+  }
+}
+
+TEST_P(StorageTestPopulateOne, SetEntryTypeValueAssignTypeChange) {
+  // update with different type results in assignment message
+  auto value = Value::MakeDouble(0.0);
+
+  // id assigned if server; seq_num incremented
+  EXPECT_CALL(dispatcher,
+              QueueOutgoing(MessageEq(Message::EntryAssign(
+                                "foo", GetParam() ? 0 : 0xffff, 2, value, 0)),
+                            IsNull(), IsNull()));
+  EXPECT_CALL(notifier,
+              NotifyEntry(0, StringRef("foo"), value,
+                          NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  storage.SetEntryTypeValue("foo", value);
+  EXPECT_EQ(value, GetEntry("foo")->value);
+}
+
+TEST_P(StorageTestPopulateOne, SetEntryTypeValueEqualValue) {
+  // update with same type and same value: change value contents but no update
+  // message is issued (minimizing bandwidth usage)
+  auto value = Value::MakeBoolean(true);
+  storage.SetEntryTypeValue("foo", value);
+  EXPECT_EQ(value, GetEntry("foo")->value);
+}
+
+TEST_P(StorageTestPopulated, SetEntryTypeValueDifferentValue) {
+  // update with same type and different value results in value update message
+  auto value = Value::MakeDouble(1.0);
+
+  // client shouldn't send an update as id not assigned yet
+  if (GetParam()) {
+    // id assigned if server; seq_num incremented
+    EXPECT_CALL(dispatcher,
+                QueueOutgoing(MessageEq(Message::EntryUpdate(1, 2, value)),
+                              IsNull(), IsNull()));
+  }
+  EXPECT_CALL(notifier,
+              NotifyEntry(1, StringRef("foo2"), value,
+                          NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL, UINT_MAX));
+  storage.SetEntryTypeValue("foo2", value);
+  EXPECT_EQ(value, GetEntry("foo2")->value);
+
+  if (!GetParam()) {
+    // seq_num should still be incremented
+    EXPECT_EQ(2u, GetEntry("foo2")->seq_num.value());
+  }
+}
+
+TEST_P(StorageTestEmpty, SetEntryTypeValueEmptyName) {
+  auto value = Value::MakeBoolean(true);
+  storage.SetEntryTypeValue("", value);
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, SetEntryTypeValueEmptyValue) {
+  storage.SetEntryTypeValue("foo", nullptr);
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, SetEntryValueAssignNew) {
+  // brand new entry
+  auto value = Value::MakeBoolean(true);
+
+  // id assigned if server
+  EXPECT_CALL(dispatcher,
+              QueueOutgoing(MessageEq(Message::EntryAssign(
+                                "foo", GetParam() ? 0 : 0xffff, 1, value, 0)),
+                            IsNull(), IsNull()));
+  EXPECT_CALL(notifier, NotifyEntry(0, StringRef("foo"), value,
+                                    NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  EXPECT_TRUE(storage.SetEntryValue("foo", value));
+  EXPECT_EQ(value, GetEntry("foo")->value);
+}
+
+TEST_P(StorageTestPopulateOne, SetEntryValueAssignTypeChange) {
+  // update with different type results in error and no message or notification
+  auto value = Value::MakeDouble(0.0);
+  EXPECT_FALSE(storage.SetEntryValue("foo", value));
+  auto entry = GetEntry("foo");
+  EXPECT_NE(value, entry->value);
+}
+
+TEST_P(StorageTestPopulateOne, SetEntryValueEqualValue) {
+  // update with same type and same value: change value contents but no update
+  // message is issued (minimizing bandwidth usage)
+  auto value = Value::MakeBoolean(true);
+  EXPECT_TRUE(storage.SetEntryValue("foo", value));
+  auto entry = GetEntry("foo");
+  EXPECT_EQ(value, entry->value);
+}
+
+TEST_P(StorageTestPopulated, SetEntryValueDifferentValue) {
+  // update with same type and different value results in value update message
+  auto value = Value::MakeDouble(1.0);
+
+  // client shouldn't send an update as id not assigned yet
+  if (GetParam()) {
+    // id assigned if server; seq_num incremented
+    EXPECT_CALL(dispatcher,
+                QueueOutgoing(MessageEq(Message::EntryUpdate(1, 2, value)),
+                              IsNull(), IsNull()));
+  }
+  EXPECT_CALL(notifier,
+              NotifyEntry(1, StringRef("foo2"), value,
+                          NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  EXPECT_TRUE(storage.SetEntryValue("foo2", value));
+  auto entry = GetEntry("foo2");
+  EXPECT_EQ(value, entry->value);
+
+  if (!GetParam()) {
+    // seq_num should still be incremented
+    EXPECT_EQ(2u, GetEntry("foo2")->seq_num.value());
+  }
+}
+
+TEST_P(StorageTestEmpty, SetEntryValueEmptyName) {
+  auto value = Value::MakeBoolean(true);
+  EXPECT_TRUE(storage.SetEntryValue("", value));
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, SetEntryValueEmptyValue) {
+  EXPECT_TRUE(storage.SetEntryValue("foo", nullptr));
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, SetDefaultEntryAssignNew) {
+  // brand new entry
+  auto value = Value::MakeBoolean(true);
+
+  // id assigned if server
+  EXPECT_CALL(dispatcher,
+              QueueOutgoing(MessageEq(Message::EntryAssign(
+                                "foo", GetParam() ? 0 : 0xffff, 1, value, 0)),
+                            IsNull(), IsNull()));
+  EXPECT_CALL(notifier, NotifyEntry(0, StringRef("foo"), value,
+                                    NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  auto ret_val = storage.SetDefaultEntryValue("foo", value);
+  EXPECT_TRUE(ret_val);
+  EXPECT_EQ(value, GetEntry("foo")->value);
+}
+
+TEST_P(StorageTestPopulateOne, SetDefaultEntryExistsSameType) {
+  // existing entry
+  auto value = Value::MakeBoolean(true);
+  auto ret_val = storage.SetDefaultEntryValue("foo", value);
+  EXPECT_TRUE(ret_val);
+  EXPECT_NE(value, GetEntry("foo")->value);
+}
+
+TEST_P(StorageTestPopulateOne, SetDefaultEntryExistsDifferentType) {
+  // existing entry is boolean
+  auto value = Value::MakeDouble(2.0);
+  auto ret_val = storage.SetDefaultEntryValue("foo", value);
+  EXPECT_FALSE(ret_val);
+  // should not have updated value in table if it already existed.
+  EXPECT_NE(value, GetEntry("foo")->value);
+}
+
+TEST_P(StorageTestEmpty, SetDefaultEntryEmptyName) {
+  auto value = Value::MakeBoolean(true);
+  auto ret_val = storage.SetDefaultEntryValue("", value);
+  EXPECT_FALSE(ret_val);
+  auto entry = GetEntry("foo");
+  EXPECT_FALSE(entry->value);
+  EXPECT_EQ(0u, entry->flags);
+  EXPECT_EQ("foobar", entry->name);  // since GetEntry uses the tmp_entry.
+  EXPECT_EQ(0xffffu, entry->id);
+  EXPECT_EQ(SequenceNumber(), entry->seq_num);
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, SetDefaultEntryEmptyValue) {
+  auto value = Value::MakeBoolean(true);
+  auto ret_val = storage.SetDefaultEntryValue("", nullptr);
+  EXPECT_FALSE(ret_val);
+  auto entry = GetEntry("foo");
+  EXPECT_FALSE(entry->value);
+  EXPECT_EQ(0u, entry->flags);
+  EXPECT_EQ("foobar", entry->name);  // since GetEntry uses the tmp_entry.
+  EXPECT_EQ(0xffffu, entry->id);
+  EXPECT_EQ(SequenceNumber(), entry->seq_num);
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestPopulated, SetDefaultEntryEmptyName) {
+  auto value = Value::MakeBoolean(true);
+  auto ret_val = storage.SetDefaultEntryValue("", value);
+  EXPECT_FALSE(ret_val);
+  // assert that no entries get added
+  EXPECT_EQ(4u, entries().size());
+  if (GetParam())
+    EXPECT_EQ(4u, idmap().size());
+  else
+    EXPECT_EQ(0u, idmap().size());
+}
+
+TEST_P(StorageTestPopulated, SetDefaultEntryEmptyValue) {
+  auto value = Value::MakeBoolean(true);
+  auto ret_val = storage.SetDefaultEntryValue("", nullptr);
+  EXPECT_FALSE(ret_val);
+  // assert that no entries get added
+  EXPECT_EQ(4u, entries().size());
+  if (GetParam())
+    EXPECT_EQ(4u, idmap().size());
+  else
+    EXPECT_EQ(0u, idmap().size());
+}
+
+TEST_P(StorageTestEmpty, SetEntryFlagsNew) {
+  // flags setting doesn't create an entry
+  storage.SetEntryFlags("foo", 0u);
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestPopulateOne, SetEntryFlagsEqualValue) {
+  // update with same value: no update message is issued (minimizing bandwidth
+  // usage)
+  storage.SetEntryFlags("foo", 0u);
+  auto entry = GetEntry("foo");
+  EXPECT_EQ(0u, entry->flags);
+}
+
+TEST_P(StorageTestPopulated, SetEntryFlagsDifferentValue) {
+  // update with different value results in flags update message
+  // client shouldn't send an update as id not assigned yet
+  if (GetParam()) {
+    // id assigned as this is the server
+    EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::FlagsUpdate(1, 1)),
+                                          IsNull(), IsNull()));
+  }
+  EXPECT_CALL(notifier,
+              NotifyEntry(1, StringRef("foo2"), _,
+                          NT_NOTIFY_FLAGS | NT_NOTIFY_LOCAL, UINT_MAX));
+  storage.SetEntryFlags("foo2", 1u);
+  EXPECT_EQ(1u, GetEntry("foo2")->flags);
+}
+
+TEST_P(StorageTestEmpty, SetEntryFlagsEmptyName) {
+  storage.SetEntryFlags("", 0u);
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, GetEntryFlagsNotExist) {
+  EXPECT_EQ(0u, storage.GetEntryFlags("foo"));
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestPopulateOne, GetEntryFlagsExist) {
+  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
+  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _));
+  storage.SetEntryFlags("foo", 1u);
+  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
+  EXPECT_EQ(1u, storage.GetEntryFlags("foo"));
+}
+
+TEST_P(StorageTestEmpty, DeleteEntryNotExist) { storage.DeleteEntry("foo"); }
+
+TEST_P(StorageTestPopulated, DeleteEntryExist) {
+  // client shouldn't send an update as id not assigned yet
+  if (GetParam()) {
+    // id assigned as this is the server
+    EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::EntryDelete(1)),
+                                          IsNull(), IsNull()));
+  }
+  EXPECT_CALL(notifier,
+              NotifyEntry(1, StringRef("foo2"), ValueEq(Value::MakeDouble(0)),
+                          NT_NOTIFY_DELETE | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  storage.DeleteEntry("foo2");
+  ASSERT_EQ(1u, entries().count("foo2"));
+  EXPECT_EQ(nullptr, entries()["foo2"]->value);
+  EXPECT_EQ(0xffffu, entries()["foo2"]->id);
+  EXPECT_FALSE(entries()["foo2"]->local_write);
+  if (GetParam()) {
+    ASSERT_TRUE(idmap().size() >= 2);
+    EXPECT_FALSE(idmap()[1]);
+  }
+}
+
+TEST_P(StorageTestEmpty, DeleteAllEntriesEmpty) {
+  storage.DeleteAllEntries();
+  ASSERT_TRUE(entries().empty());
+}
+
+TEST_P(StorageTestPopulated, DeleteAllEntries) {
+  EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::ClearEntries()),
+                                        IsNull(), IsNull()));
+  EXPECT_CALL(notifier, NotifyEntry(_, _, _, NT_NOTIFY_DELETE | NT_NOTIFY_LOCAL,
+                                    UINT_MAX))
+      .Times(4);
+
+  storage.DeleteAllEntries();
+  ASSERT_EQ(1u, entries().count("foo2"));
+  EXPECT_EQ(nullptr, entries()["foo2"]->value);
+}
+
+TEST_P(StorageTestPopulated, DeleteAllEntriesPersistent) {
+  GetEntry("foo2")->flags = NT_PERSISTENT;
+
+  EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::ClearEntries()),
+                                        IsNull(), IsNull()));
+  EXPECT_CALL(notifier, NotifyEntry(_, _, _, NT_NOTIFY_DELETE | NT_NOTIFY_LOCAL,
+                                    UINT_MAX))
+      .Times(3);
+
+  storage.DeleteAllEntries();
+  ASSERT_EQ(1u, entries().count("foo2"));
+  EXPECT_NE(nullptr, entries()["foo2"]->value);
+}
+
+TEST_P(StorageTestPopulated, GetEntryInfoAll) {
+  auto info = storage.GetEntryInfo(0, "", 0u);
+  ASSERT_EQ(4u, info.size());
+}
+
+TEST_P(StorageTestPopulated, GetEntryInfoPrefix) {
+  auto info = storage.GetEntryInfo(0, "foo", 0u);
+  ASSERT_EQ(2u, info.size());
+  if (info[0].name == "foo") {
+    EXPECT_EQ("foo", info[0].name);
+    EXPECT_EQ(NT_BOOLEAN, info[0].type);
+    EXPECT_EQ("foo2", info[1].name);
+    EXPECT_EQ(NT_DOUBLE, info[1].type);
+  } else {
+    EXPECT_EQ("foo2", info[0].name);
+    EXPECT_EQ(NT_DOUBLE, info[0].type);
+    EXPECT_EQ("foo", info[1].name);
+    EXPECT_EQ(NT_BOOLEAN, info[1].type);
+  }
+}
+
+TEST_P(StorageTestPopulated, GetEntryInfoTypes) {
+  auto info = storage.GetEntryInfo(0, "", NT_DOUBLE);
+  ASSERT_EQ(2u, info.size());
+  EXPECT_EQ(NT_DOUBLE, info[0].type);
+  EXPECT_EQ(NT_DOUBLE, info[1].type);
+  if (info[0].name == "foo2") {
+    EXPECT_EQ("foo2", info[0].name);
+    EXPECT_EQ("bar", info[1].name);
+  } else {
+    EXPECT_EQ("bar", info[0].name);
+    EXPECT_EQ("foo2", info[1].name);
+  }
+}
+
+TEST_P(StorageTestPopulated, GetEntryInfoPrefixTypes) {
+  auto info = storage.GetEntryInfo(0, "bar", NT_BOOLEAN);
+  ASSERT_EQ(1u, info.size());
+  EXPECT_EQ("bar2", info[0].name);
+  EXPECT_EQ(NT_BOOLEAN, info[0].type);
+}
+
+TEST_P(StorageTestPersistent, SavePersistentEmpty) {
+  wpi::SmallString<256> buf;
+  wpi::raw_svector_ostream oss(buf);
+  storage.SavePersistent(oss, false);
+  ASSERT_EQ("[NetworkTables Storage 3.0]\n", oss.str());
+}
+
+TEST_P(StorageTestPersistent, SavePersistent) {
+  for (auto& i : entries()) i.getValue()->flags = NT_PERSISTENT;
+  wpi::SmallString<256> buf;
+  wpi::raw_svector_ostream oss(buf);
+  storage.SavePersistent(oss, false);
+  wpi::StringRef out = oss.str();
+  // std::fputs(out.c_str(), stderr);
+  wpi::StringRef line, rem = out;
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("[NetworkTables Storage 3.0]", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("boolean \"\\x00\\x03\\x05\\n\"=true", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("boolean \"\\x3D\"=true", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("boolean \"boolean/false\"=false", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("boolean \"boolean/true\"=true", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array boolean \"booleanarr/empty\"=", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array boolean \"booleanarr/one\"=true", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array boolean \"booleanarr/two\"=true,false", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("double \"double/big\"=1.3e+08", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("double \"double/neg\"=-1.5", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("double \"double/zero\"=0", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array double \"doublearr/empty\"=", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array double \"doublearr/one\"=0.5", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array double \"doublearr/two\"=0.5,-0.25", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("raw \"raw/empty\"=", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("raw \"raw/normal\"=aGVsbG8=", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("raw \"raw/special\"=AAMFCg==", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("string \"string/empty\"=\"\"", line);
+  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/special\"=\"\\x00\\x03\\x05\\n\"", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array string \"stringarr/empty\"=", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array string \"stringarr/one\"=\"hello\"", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("array string \"stringarr/two\"=\"hello\",\"world\\n\"", line);
+  std::tie(line, rem) = rem.split('\n');
+  ASSERT_EQ("", line);
+}
+
+TEST_P(StorageTestEmpty, LoadPersistentBadHeader) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  wpi::raw_mem_istream iss("");
+  EXPECT_CALL(
+      warn,
+      Warn(1, wpi::StringRef("header line mismatch, ignoring rest of file")));
+  EXPECT_FALSE(storage.LoadEntries(iss, "", true, warn_func));
+
+  wpi::raw_mem_istream iss2("[NetworkTables");
+  EXPECT_CALL(
+      warn,
+      Warn(1, wpi::StringRef("header line mismatch, ignoring rest of file")));
+
+  EXPECT_FALSE(storage.LoadEntries(iss2, "", true, warn_func));
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, LoadPersistentCommentHeader) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  wpi::raw_mem_istream iss(
+      "\n; comment\n# comment\n[NetworkTables Storage 3.0]\n");
+  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, LoadPersistentEmptyName) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  wpi::raw_mem_istream iss("[NetworkTables Storage 3.0]\nboolean \"\"=true\n");
+  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, LoadPersistentAssign) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  auto value = Value::MakeBoolean(true);
+
+  // id assigned if server
+  EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::EntryAssign(
+                                            "foo", GetParam() ? 0 : 0xffff, 1,
+                                            value, NT_PERSISTENT)),
+                                        IsNull(), IsNull()));
+  EXPECT_CALL(notifier, NotifyEntry(0, StringRef("foo"),
+                                    ValueEq(Value::MakeBoolean(true)),
+                                    NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  wpi::raw_mem_istream iss(
+      "[NetworkTables Storage 3.0]\nboolean \"foo\"=true\n");
+  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
+  auto entry = GetEntry("foo");
+  EXPECT_EQ(*value, *entry->value);
+  EXPECT_EQ(NT_PERSISTENT, entry->flags);
+}
+
+TEST_P(StorageTestPopulated, LoadPersistentUpdateFlags) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  // client shouldn't send an update as id not assigned yet
+  if (GetParam()) {
+    // id assigned as this is server
+    EXPECT_CALL(dispatcher,
+                QueueOutgoing(MessageEq(Message::FlagsUpdate(1, NT_PERSISTENT)),
+                              IsNull(), IsNull()));
+  }
+  EXPECT_CALL(notifier,
+              NotifyEntry(1, StringRef("foo2"), ValueEq(Value::MakeDouble(0)),
+                          NT_NOTIFY_FLAGS | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  wpi::raw_mem_istream iss(
+      "[NetworkTables Storage 3.0]\ndouble \"foo2\"=0.0\n");
+  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
+  auto entry = GetEntry("foo2");
+  EXPECT_EQ(*Value::MakeDouble(0.0), *entry->value);
+  EXPECT_EQ(NT_PERSISTENT, entry->flags);
+}
+
+TEST_P(StorageTestPopulated, LoadPersistentUpdateValue) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  GetEntry("foo2")->flags = NT_PERSISTENT;
+
+  auto value = Value::MakeDouble(1.0);
+
+  // client shouldn't send an update as id not assigned yet
+  if (GetParam()) {
+    // id assigned as this is the server; seq_num incremented
+    EXPECT_CALL(dispatcher,
+                QueueOutgoing(MessageEq(Message::EntryUpdate(1, 2, value)),
+                              IsNull(), IsNull()));
+  }
+  EXPECT_CALL(notifier,
+              NotifyEntry(1, StringRef("foo2"), ValueEq(Value::MakeDouble(1)),
+                          NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL, UINT_MAX));
+
+  wpi::raw_mem_istream iss(
+      "[NetworkTables Storage 3.0]\ndouble \"foo2\"=1.0\n");
+  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
+  auto entry = GetEntry("foo2");
+  EXPECT_EQ(*value, *entry->value);
+  EXPECT_EQ(NT_PERSISTENT, entry->flags);
+
+  if (!GetParam()) {
+    // seq_num should still be incremented
+    EXPECT_EQ(2u, GetEntry("foo2")->seq_num.value());
+  }
+}
+
+TEST_P(StorageTestPopulated, LoadPersistentUpdateValueFlags) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  auto value = Value::MakeDouble(1.0);
+
+  // client shouldn't send an update as id not assigned yet
+  if (GetParam()) {
+    // id assigned as this is the server; seq_num incremented
+    EXPECT_CALL(dispatcher,
+                QueueOutgoing(MessageEq(Message::EntryUpdate(1, 2, value)),
+                              IsNull(), IsNull()));
+    EXPECT_CALL(dispatcher,
+                QueueOutgoing(MessageEq(Message::FlagsUpdate(1, NT_PERSISTENT)),
+                              IsNull(), IsNull()));
+  }
+  EXPECT_CALL(notifier,
+              NotifyEntry(1, StringRef("foo2"), ValueEq(Value::MakeDouble(1)),
+                          NT_NOTIFY_FLAGS | NT_NOTIFY_UPDATE | NT_NOTIFY_LOCAL,
+                          UINT_MAX));
+
+  wpi::raw_mem_istream iss(
+      "[NetworkTables Storage 3.0]\ndouble \"foo2\"=1.0\n");
+  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
+  auto entry = GetEntry("foo2");
+  EXPECT_EQ(*value, *entry->value);
+  EXPECT_EQ(NT_PERSISTENT, entry->flags);
+
+  if (!GetParam()) {
+    // seq_num should still be incremented
+    EXPECT_EQ(2u, GetEntry("foo2")->seq_num.value());
+  }
+}
+
+TEST_P(StorageTestEmpty, LoadPersistent) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  std::string in = "[NetworkTables Storage 3.0]\n";
+  in += "boolean \"\\x00\\x03\\x05\\n\"=true\n";
+  in += "boolean \"\\x3D\"=true\n";
+  in += "boolean \"boolean/false\"=false\n";
+  in += "boolean \"boolean/true\"=true\n";
+  in += "array boolean \"booleanarr/empty\"=\n";
+  in += "array boolean \"booleanarr/one\"=true\n";
+  in += "array boolean \"booleanarr/two\"=true,false\n";
+  in += "double \"double/big\"=1.3e+08\n";
+  in += "double \"double/neg\"=-1.5\n";
+  in += "double \"double/zero\"=0\n";
+  in += "array double \"doublearr/empty\"=\n";
+  in += "array double \"doublearr/one\"=0.5\n";
+  in += "array double \"doublearr/two\"=0.5,-0.25\n";
+  in += "raw \"raw/empty\"=\n";
+  in += "raw \"raw/normal\"=aGVsbG8=\n";
+  in += "raw \"raw/special\"=AAMFCg==\n";
+  in += "string \"string/empty\"=\"\"\n";
+  in += "string \"string/normal\"=\"hello\"\n";
+  in += "string \"string/special\"=\"\\x00\\x03\\x05\\n\"\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(notifier,
+              NotifyEntry(_, _, _, NT_NOTIFY_NEW | NT_NOTIFY_LOCAL, UINT_MAX))
+      .Times(22);
+
+  wpi::raw_mem_istream iss(in);
+  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
+  ASSERT_EQ(22u, entries().size());
+
+  EXPECT_EQ(*Value::MakeBoolean(true), *storage.GetEntryValue("boolean/true"));
+  EXPECT_EQ(*Value::MakeBoolean(false),
+            *storage.GetEntryValue("boolean/false"));
+  EXPECT_EQ(*Value::MakeDouble(-1.5), *storage.GetEntryValue("double/neg"));
+  EXPECT_EQ(*Value::MakeDouble(0.0), *storage.GetEntryValue("double/zero"));
+  EXPECT_EQ(*Value::MakeDouble(1.3e8), *storage.GetEntryValue("double/big"));
+  EXPECT_EQ(*Value::MakeString(""), *storage.GetEntryValue("string/empty"));
+  EXPECT_EQ(*Value::MakeString("hello"),
+            *storage.GetEntryValue("string/normal"));
+  EXPECT_EQ(*Value::MakeString(StringRef("\0\3\5\n", 4)),
+            *storage.GetEntryValue("string/special"));
+  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)),
+            *storage.GetEntryValue("raw/special"));
+  EXPECT_EQ(*Value::MakeBooleanArray(std::vector<int>{}),
+            *storage.GetEntryValue("booleanarr/empty"));
+  EXPECT_EQ(*Value::MakeBooleanArray(std::vector<int>{1}),
+            *storage.GetEntryValue("booleanarr/one"));
+  EXPECT_EQ(*Value::MakeBooleanArray(std::vector<int>{1, 0}),
+            *storage.GetEntryValue("booleanarr/two"));
+  EXPECT_EQ(*Value::MakeDoubleArray(std::vector<double>{}),
+            *storage.GetEntryValue("doublearr/empty"));
+  EXPECT_EQ(*Value::MakeDoubleArray(std::vector<double>{0.5}),
+            *storage.GetEntryValue("doublearr/one"));
+  EXPECT_EQ(*Value::MakeDoubleArray(std::vector<double>{0.5, -0.25}),
+            *storage.GetEntryValue("doublearr/two"));
+  EXPECT_EQ(*Value::MakeStringArray(std::vector<std::string>{}),
+            *storage.GetEntryValue("stringarr/empty"));
+  EXPECT_EQ(*Value::MakeStringArray(std::vector<std::string>{"hello"}),
+            *storage.GetEntryValue("stringarr/one"));
+  EXPECT_EQ(
+      *Value::MakeStringArray(std::vector<std::string>{"hello", "world\n"}),
+      *storage.GetEntryValue("stringarr/two"));
+  EXPECT_EQ(*Value::MakeBoolean(true),
+            *storage.GetEntryValue(StringRef("\0\3\5\n", 4)));
+  EXPECT_EQ(*Value::MakeBoolean(true), *storage.GetEntryValue("="));
+}
+
+TEST_P(StorageTestEmpty, LoadPersistentWarn) {
+  MockLoadWarn warn;
+  auto warn_func = [&](size_t line, const char* msg) { warn.Warn(line, msg); };
+
+  wpi::raw_mem_istream iss(
+      "[NetworkTables Storage 3.0]\nboolean \"foo\"=foo\n");
+  EXPECT_CALL(
+      warn, Warn(2, wpi::StringRef(
+                        "unrecognized boolean value, not 'true' or 'false'")));
+  EXPECT_TRUE(storage.LoadEntries(iss, "", true, warn_func));
+
+  EXPECT_TRUE(entries().empty());
+  EXPECT_TRUE(idmap().empty());
+}
+
+TEST_P(StorageTestEmpty, ProcessIncomingEntryAssign) {
+  auto conn = std::make_shared<MockNetworkConnection>();
+  auto value = Value::MakeDouble(1.0);
+  if (GetParam()) {
+    // id assign message reply generated on the server; sent to everyone
+    EXPECT_CALL(
+        dispatcher,
+        QueueOutgoing(MessageEq(Message::EntryAssign("foo", 0, 0, value, 0)),
+                      IsNull(), IsNull()));
+  }
+  EXPECT_CALL(notifier, NotifyEntry(0, StringRef("foo"), ValueEq(value),
+                                    NT_NOTIFY_NEW, UINT_MAX));
+
+  storage.ProcessIncoming(
+      Message::EntryAssign("foo", GetParam() ? 0xffff : 0, 0, value, 0),
+      conn.get(), conn);
+}
+
+TEST_P(StorageTestPopulateOne, ProcessIncomingEntryAssign) {
+  auto conn = std::make_shared<MockNetworkConnection>();
+  auto value = Value::MakeDouble(1.0);
+  EXPECT_CALL(*conn, proto_rev()).WillRepeatedly(Return(0x0300u));
+  if (GetParam()) {
+    // server broadcasts new value to all *other* connections
+    EXPECT_CALL(
+        dispatcher,
+        QueueOutgoing(MessageEq(Message::EntryAssign("foo", 0, 1, value, 0)),
+                      IsNull(), conn.get()));
+  }
+  EXPECT_CALL(notifier, NotifyEntry(0, StringRef("foo"), ValueEq(value),
+                                    NT_NOTIFY_UPDATE, UINT_MAX));
+
+  storage.ProcessIncoming(Message::EntryAssign("foo", 0, 1, value, 0),
+                          conn.get(), conn);
+}
+
+TEST_P(StorageTestPopulateOne, ProcessIncomingEntryAssignIgnore) {
+  auto conn = std::make_shared<MockNetworkConnection>();
+  auto value = Value::MakeDouble(1.0);
+  storage.ProcessIncoming(Message::EntryAssign("foo", 0xffff, 1, value, 0),
+                          conn.get(), conn);
+}
+
+TEST_P(StorageTestPopulateOne, ProcessIncomingEntryAssignWithFlags) {
+  auto conn = std::make_shared<MockNetworkConnection>();
+  auto value = Value::MakeDouble(1.0);
+  EXPECT_CALL(*conn, proto_rev()).WillRepeatedly(Return(0x0300u));
+  if (GetParam()) {
+    // server broadcasts new value/flags to all *other* connections
+    EXPECT_CALL(
+        dispatcher,
+        QueueOutgoing(MessageEq(Message::EntryAssign("foo", 0, 1, value, 0x2)),
+                      IsNull(), conn.get()));
+    EXPECT_CALL(notifier,
+                NotifyEntry(0, StringRef("foo"), ValueEq(value),
+                            NT_NOTIFY_UPDATE | NT_NOTIFY_FLAGS, UINT_MAX));
+  } else {
+    // client forces flags back when an assign message is received for an
+    // existing entry with different flags
+    EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::FlagsUpdate(0, 0)),
+                                          IsNull(), IsNull()));
+    EXPECT_CALL(notifier, NotifyEntry(0, StringRef("foo"), ValueEq(value),
+                                      NT_NOTIFY_UPDATE, UINT_MAX));
+  }
+
+  storage.ProcessIncoming(Message::EntryAssign("foo", 0, 1, value, 0x2),
+                          conn.get(), conn);
+}
+
+TEST_P(StorageTestPopulateOne, DeleteCheckHandle) {
+  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
+  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
+  auto handle = storage.GetEntry("foo");
+  storage.DeleteEntry("foo");
+  storage.SetEntryTypeValue("foo", Value::MakeBoolean(true));
+  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
+  ::testing::Mock::VerifyAndClearExpectations(&notifier);
+
+  auto handle2 = storage.GetEntry("foo");
+  ASSERT_EQ(handle, handle2);
+}
+
+TEST_P(StorageTestPopulateOne, DeletedEntryFlags) {
+  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
+  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
+  auto handle = storage.GetEntry("foo");
+  storage.SetEntryFlags("foo", 2);
+  storage.DeleteEntry("foo");
+  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
+  ::testing::Mock::VerifyAndClearExpectations(&notifier);
+
+  EXPECT_EQ(storage.GetEntryFlags("foo"), 0u);
+  EXPECT_EQ(storage.GetEntryFlags(handle), 0u);
+  storage.SetEntryFlags("foo", 4);
+  storage.SetEntryFlags(handle, 4);
+  EXPECT_EQ(storage.GetEntryFlags("foo"), 0u);
+  EXPECT_EQ(storage.GetEntryFlags(handle), 0u);
+}
+
+TEST_P(StorageTestPopulateOne, DeletedDeleteAllEntries) {
+  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
+  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
+  storage.DeleteEntry("foo");
+  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
+  ::testing::Mock::VerifyAndClearExpectations(&notifier);
+
+  EXPECT_CALL(dispatcher, QueueOutgoing(MessageEq(Message::ClearEntries()),
+                                        IsNull(), IsNull()));
+  storage.DeleteAllEntries();
+}
+
+TEST_P(StorageTestPopulateOne, DeletedGetEntries) {
+  EXPECT_CALL(dispatcher, QueueOutgoing(_, _, _)).Times(AnyNumber());
+  EXPECT_CALL(notifier, NotifyEntry(_, _, _, _, _)).Times(AnyNumber());
+  storage.DeleteEntry("foo");
+  ::testing::Mock::VerifyAndClearExpectations(&dispatcher);
+  ::testing::Mock::VerifyAndClearExpectations(&notifier);
+
+  EXPECT_TRUE(storage.GetEntries("", 0).empty());
+}
+
+INSTANTIATE_TEST_CASE_P(StorageTestsEmpty, StorageTestEmpty,
+                        ::testing::Bool(), );
+INSTANTIATE_TEST_CASE_P(StorageTestsPopulateOne, StorageTestPopulateOne,
+                        ::testing::Bool(), );
+INSTANTIATE_TEST_CASE_P(StorageTestsPopulated, StorageTestPopulated,
+                        ::testing::Bool(), );
+INSTANTIATE_TEST_CASE_P(StorageTestsPersistent, StorageTestPersistent,
+                        ::testing::Bool(), );
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/StorageTest.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/StorageTest.h
new file mode 100644
index 0000000..1bb8a8c
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/StorageTest.h
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_STORAGETEST_H_
+#define NTCORE_STORAGETEST_H_
+
+#include <functional>
+#include <memory>
+#include <vector>
+
+#include "Log.h"
+#include "MockDispatcher.h"
+#include "MockEntryNotifier.h"
+#include "MockRpcServer.h"
+#include "Storage.h"
+
+namespace nt {
+
+class StorageTest {
+ public:
+  StorageTest() : storage(notifier, rpc_server, logger), tmp_entry("foobar") {}
+
+  Storage::EntriesMap& entries() { return storage.m_entries; }
+  Storage::IdMap& idmap() { return storage.m_idmap; }
+
+  Storage::Entry* GetEntry(StringRef name) {
+    auto i = storage.m_entries.find(name);
+    return i == storage.m_entries.end() ? &tmp_entry : i->getValue();
+  }
+
+  void HookOutgoing(bool server) { storage.SetDispatcher(&dispatcher, server); }
+
+  wpi::Logger logger;
+  ::testing::StrictMock<MockEntryNotifier> notifier;
+  ::testing::StrictMock<MockRpcServer> rpc_server;
+  ::testing::StrictMock<MockDispatcher> dispatcher;
+  Storage storage;
+  Storage::Entry tmp_entry;
+};
+
+}  // namespace nt
+
+#endif  // NTCORE_STORAGETEST_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/TestPrinters.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/TestPrinters.cpp
new file mode 100644
index 0000000..3368b8c
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/TestPrinters.cpp
@@ -0,0 +1,156 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "TestPrinters.h"
+
+#include "Handle.h"
+#include "Message.h"
+#include "networktables/NetworkTableValue.h"
+#include "ntcore_cpp.h"
+
+namespace nt {
+
+void PrintTo(const EntryNotification& event, std::ostream* os) {
+  *os << "EntryNotification{listener=";
+  PrintTo(Handle{event.listener}, os);
+  *os << ", entry=";
+  PrintTo(Handle{event.entry}, os);
+  *os << ", name=\"" << event.name << "\", flags=" << event.flags << ", value=";
+  PrintTo(event.value, os);
+  *os << '}';
+}
+
+void PrintTo(const Handle& handle, std::ostream* os) {
+  *os << "Handle{";
+  switch (handle.GetType()) {
+    case Handle::kConnectionListener:
+      *os << "kConnectionListener";
+      break;
+    case Handle::kConnectionListenerPoller:
+      *os << "kConnectionListenerPoller";
+      break;
+    case Handle::kEntry:
+      *os << "kEntry";
+      break;
+    case Handle::kEntryListener:
+      *os << "kEntryListener";
+      break;
+    case Handle::kEntryListenerPoller:
+      *os << "kEntryListenerPoller";
+      break;
+    case Handle::kInstance:
+      *os << "kInstance";
+      break;
+    case Handle::kLogger:
+      *os << "kLogger";
+      break;
+    case Handle::kLoggerPoller:
+      *os << "kLoggerPoller";
+      break;
+    case Handle::kRpcCall:
+      *os << "kRpcCall";
+      break;
+    case Handle::kRpcCallPoller:
+      *os << "kRpcCallPoller";
+      break;
+    default:
+      *os << "UNKNOWN";
+      break;
+  }
+  *os << ", " << handle.GetInst() << ", " << handle.GetIndex() << '}';
+}
+
+void PrintTo(const Message& msg, std::ostream* os) {
+  *os << "Message{";
+  switch (msg.type()) {
+    case Message::kKeepAlive:
+      *os << "kKeepAlive";
+      break;
+    case Message::kClientHello:
+      *os << "kClientHello";
+      break;
+    case Message::kProtoUnsup:
+      *os << "kProtoUnsup";
+      break;
+    case Message::kServerHelloDone:
+      *os << "kServerHelloDone";
+      break;
+    case Message::kServerHello:
+      *os << "kServerHello";
+      break;
+    case Message::kClientHelloDone:
+      *os << "kClientHelloDone";
+      break;
+    case Message::kEntryAssign:
+      *os << "kEntryAssign";
+      break;
+    case Message::kEntryUpdate:
+      *os << "kEntryUpdate";
+      break;
+    case Message::kFlagsUpdate:
+      *os << "kFlagsUpdate";
+      break;
+    case Message::kEntryDelete:
+      *os << "kEntryDelete";
+      break;
+    case Message::kClearEntries:
+      *os << "kClearEntries";
+      break;
+    case Message::kExecuteRpc:
+      *os << "kExecuteRpc";
+      break;
+    case Message::kRpcResponse:
+      *os << "kRpcResponse";
+      break;
+    default:
+      *os << "UNKNOWN";
+      break;
+  }
+  *os << ": str=\"" << msg.str() << "\", id=" << msg.id()
+      << ", flags=" << msg.flags() << ", seq_num_uid=" << msg.seq_num_uid()
+      << ", value=";
+  PrintTo(msg.value(), os);
+  *os << '}';
+}
+
+void PrintTo(const Value& value, std::ostream* os) {
+  *os << "Value{";
+  switch (value.type()) {
+    case NT_UNASSIGNED:
+      break;
+    case NT_BOOLEAN:
+      *os << (value.GetBoolean() ? "true" : "false");
+      break;
+    case NT_DOUBLE:
+      *os << value.GetDouble();
+      break;
+    case NT_STRING:
+      *os << '"' << value.GetString().str() << '"';
+      break;
+    case NT_RAW:
+      *os << ::testing::PrintToString(value.GetRaw());
+      break;
+    case NT_BOOLEAN_ARRAY:
+      *os << ::testing::PrintToString(value.GetBooleanArray());
+      break;
+    case NT_DOUBLE_ARRAY:
+      *os << ::testing::PrintToString(value.GetDoubleArray());
+      break;
+    case NT_STRING_ARRAY:
+      *os << ::testing::PrintToString(value.GetStringArray());
+      break;
+    case NT_RPC:
+      *os << ::testing::PrintToString(value.GetRpc());
+      break;
+    default:
+      *os << "UNKNOWN TYPE " << value.type();
+      break;
+  }
+  *os << '}';
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/TestPrinters.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/TestPrinters.h
new file mode 100644
index 0000000..2976c1c
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/TestPrinters.h
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_TESTPRINTERS_H_
+#define NTCORE_TESTPRINTERS_H_
+
+#include <memory>
+#include <ostream>
+
+#include <wpi/StringRef.h>
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+inline void PrintTo(StringRef str, ::std::ostream* os) {
+  ::testing::internal::PrintStringTo(str.str(), os);
+}
+
+}  // namespace wpi
+
+namespace nt {
+
+class EntryNotification;
+class Handle;
+class Message;
+class Value;
+
+void PrintTo(const EntryNotification& event, std::ostream* os);
+void PrintTo(const Handle& handle, std::ostream* os);
+
+void PrintTo(const Message& msg, std::ostream* os);
+
+inline void PrintTo(std::shared_ptr<Message> msg, std::ostream* os) {
+  *os << "shared_ptr{";
+  if (msg) PrintTo(*msg, os);
+  *os << '}';
+}
+
+void PrintTo(const Value& value, std::ostream* os);
+
+inline void PrintTo(std::shared_ptr<Value> value, std::ostream* os) {
+  *os << "shared_ptr{";
+  if (value) PrintTo(*value, os);
+  *os << '}';
+}
+
+}  // namespace nt
+
+#endif  // NTCORE_TESTPRINTERS_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueMatcher.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueMatcher.cpp
new file mode 100644
index 0000000..45b09ed
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueMatcher.cpp
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ValueMatcher.h"
+
+#include "TestPrinters.h"
+
+namespace nt {
+
+bool ValueMatcher::MatchAndExplain(
+    std::shared_ptr<Value> val,
+    ::testing::MatchResultListener* listener) const {
+  if ((!val && goodval) || (val && !goodval) ||
+      (val && goodval && *val != *goodval)) {
+    return false;
+  }
+  return true;
+}
+
+void ValueMatcher::DescribeTo(::std::ostream* os) const {
+  PrintTo(goodval, os);
+}
+
+void ValueMatcher::DescribeNegationTo(::std::ostream* os) const {
+  *os << "is not equal to ";
+  PrintTo(goodval, os);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueMatcher.h b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueMatcher.h
new file mode 100644
index 0000000..5c417d7
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueMatcher.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef NTCORE_VALUEMATCHER_H_
+#define NTCORE_VALUEMATCHER_H_
+
+#include <memory>
+#include <ostream>
+
+#include "gmock/gmock.h"
+#include "networktables/NetworkTableValue.h"
+
+namespace nt {
+
+class ValueMatcher
+    : public ::testing::MatcherInterface<std::shared_ptr<Value>> {
+ public:
+  explicit ValueMatcher(std::shared_ptr<Value> goodval_) : goodval(goodval_) {}
+
+  bool MatchAndExplain(std::shared_ptr<Value> msg,
+                       ::testing::MatchResultListener* listener) const override;
+  void DescribeTo(::std::ostream* os) const override;
+  void DescribeNegationTo(::std::ostream* os) const override;
+
+ private:
+  std::shared_ptr<Value> goodval;
+};
+
+inline ::testing::Matcher<std::shared_ptr<Value>> ValueEq(
+    std::shared_ptr<Value> goodval) {
+  return ::testing::MakeMatcher(new ValueMatcher(goodval));
+}
+
+}  // namespace nt
+
+#endif  // NTCORE_VALUEMATCHER_H_
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueTest.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueTest.cpp
new file mode 100644
index 0000000..818cdac
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/ValueTest.cpp
@@ -0,0 +1,365 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "TestPrinters.h"
+#include "Value_internal.h"
+#include "gtest/gtest.h"
+#include "networktables/NetworkTableValue.h"
+
+namespace nt {
+
+class ValueTest : public ::testing::Test {};
+
+typedef ValueTest ValueDeathTest;
+
+TEST_F(ValueTest, ConstructEmpty) {
+  Value v;
+  ASSERT_EQ(NT_UNASSIGNED, v.type());
+}
+
+TEST_F(ValueTest, Boolean) {
+  auto v = Value::MakeBoolean(false);
+  ASSERT_EQ(NT_BOOLEAN, v->type());
+  ASSERT_FALSE(v->GetBoolean());
+  NT_Value cv;
+  NT_InitValue(&cv);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_BOOLEAN, cv.type);
+  ASSERT_EQ(0, cv.data.v_boolean);
+
+  v = Value::MakeBoolean(true);
+  ASSERT_EQ(NT_BOOLEAN, v->type());
+  ASSERT_TRUE(v->GetBoolean());
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_BOOLEAN, cv.type);
+  ASSERT_EQ(1, cv.data.v_boolean);
+
+  NT_DisposeValue(&cv);
+}
+
+TEST_F(ValueTest, Double) {
+  auto v = Value::MakeDouble(0.5);
+  ASSERT_EQ(NT_DOUBLE, v->type());
+  ASSERT_EQ(0.5, v->GetDouble());
+  NT_Value cv;
+  NT_InitValue(&cv);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_DOUBLE, cv.type);
+  ASSERT_EQ(0.5, cv.data.v_double);
+
+  v = Value::MakeDouble(0.25);
+  ASSERT_EQ(NT_DOUBLE, v->type());
+  ASSERT_EQ(0.25, v->GetDouble());
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_DOUBLE, cv.type);
+  ASSERT_EQ(0.25, cv.data.v_double);
+
+  NT_DisposeValue(&cv);
+}
+
+TEST_F(ValueTest, String) {
+  auto v = Value::MakeString("hello");
+  ASSERT_EQ(NT_STRING, v->type());
+  ASSERT_EQ("hello", v->GetString());
+  NT_Value cv;
+  NT_InitValue(&cv);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_STRING, cv.type);
+  ASSERT_EQ(wpi::StringRef("hello"), cv.data.v_string.str);
+  ASSERT_EQ(5u, cv.data.v_string.len);
+
+  v = Value::MakeString("goodbye");
+  ASSERT_EQ(NT_STRING, v->type());
+  ASSERT_EQ("goodbye", v->GetString());
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_STRING, cv.type);
+  ASSERT_EQ(wpi::StringRef("goodbye"), cv.data.v_string.str);
+  ASSERT_EQ(7u, cv.data.v_string.len);
+
+  NT_DisposeValue(&cv);
+}
+
+TEST_F(ValueTest, Raw) {
+  auto v = Value::MakeRaw("hello");
+  ASSERT_EQ(NT_RAW, v->type());
+  ASSERT_EQ("hello", v->GetRaw());
+  NT_Value cv;
+  NT_InitValue(&cv);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_RAW, cv.type);
+  ASSERT_EQ(wpi::StringRef("hello"), cv.data.v_string.str);
+  ASSERT_EQ(5u, cv.data.v_string.len);
+
+  v = Value::MakeRaw("goodbye");
+  ASSERT_EQ(NT_RAW, v->type());
+  ASSERT_EQ("goodbye", v->GetRaw());
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_RAW, cv.type);
+  ASSERT_EQ(wpi::StringRef("goodbye"), cv.data.v_string.str);
+  ASSERT_EQ(7u, cv.data.v_string.len);
+
+  NT_DisposeValue(&cv);
+}
+
+TEST_F(ValueTest, BooleanArray) {
+  std::vector<int> vec{1, 0, 1};
+  auto v = Value::MakeBooleanArray(vec);
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, v->type());
+  ASSERT_EQ(wpi::ArrayRef<int>(vec), v->GetBooleanArray());
+  NT_Value cv;
+  NT_InitValue(&cv);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, cv.type);
+  ASSERT_EQ(3u, cv.data.arr_boolean.size);
+  ASSERT_EQ(vec[0], cv.data.arr_boolean.arr[0]);
+  ASSERT_EQ(vec[1], cv.data.arr_boolean.arr[1]);
+  ASSERT_EQ(vec[2], cv.data.arr_boolean.arr[2]);
+
+  // assign with same size
+  vec = {0, 1, 0};
+  v = Value::MakeBooleanArray(vec);
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, v->type());
+  ASSERT_EQ(wpi::ArrayRef<int>(vec), v->GetBooleanArray());
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, cv.type);
+  ASSERT_EQ(3u, cv.data.arr_boolean.size);
+  ASSERT_EQ(vec[0], cv.data.arr_boolean.arr[0]);
+  ASSERT_EQ(vec[1], cv.data.arr_boolean.arr[1]);
+  ASSERT_EQ(vec[2], cv.data.arr_boolean.arr[2]);
+
+  // assign with different size
+  vec = {1, 0};
+  v = Value::MakeBooleanArray(vec);
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, v->type());
+  ASSERT_EQ(wpi::ArrayRef<int>(vec), v->GetBooleanArray());
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_BOOLEAN_ARRAY, cv.type);
+  ASSERT_EQ(2u, cv.data.arr_boolean.size);
+  ASSERT_EQ(vec[0], cv.data.arr_boolean.arr[0]);
+  ASSERT_EQ(vec[1], cv.data.arr_boolean.arr[1]);
+
+  NT_DisposeValue(&cv);
+}
+
+TEST_F(ValueTest, DoubleArray) {
+  std::vector<double> vec{0.5, 0.25, 0.5};
+  auto v = Value::MakeDoubleArray(vec);
+  ASSERT_EQ(NT_DOUBLE_ARRAY, v->type());
+  ASSERT_EQ(wpi::ArrayRef<double>(vec), v->GetDoubleArray());
+  NT_Value cv;
+  NT_InitValue(&cv);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_DOUBLE_ARRAY, cv.type);
+  ASSERT_EQ(3u, cv.data.arr_double.size);
+  ASSERT_EQ(vec[0], cv.data.arr_double.arr[0]);
+  ASSERT_EQ(vec[1], cv.data.arr_double.arr[1]);
+  ASSERT_EQ(vec[2], cv.data.arr_double.arr[2]);
+
+  // assign with same size
+  vec = {0.25, 0.5, 0.25};
+  v = Value::MakeDoubleArray(vec);
+  ASSERT_EQ(NT_DOUBLE_ARRAY, v->type());
+  ASSERT_EQ(wpi::ArrayRef<double>(vec), v->GetDoubleArray());
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_DOUBLE_ARRAY, cv.type);
+  ASSERT_EQ(3u, cv.data.arr_double.size);
+  ASSERT_EQ(vec[0], cv.data.arr_double.arr[0]);
+  ASSERT_EQ(vec[1], cv.data.arr_double.arr[1]);
+  ASSERT_EQ(vec[2], cv.data.arr_double.arr[2]);
+
+  // assign with different size
+  vec = {0.5, 0.25};
+  v = Value::MakeDoubleArray(vec);
+  ASSERT_EQ(NT_DOUBLE_ARRAY, v->type());
+  ASSERT_EQ(wpi::ArrayRef<double>(vec), v->GetDoubleArray());
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_DOUBLE_ARRAY, cv.type);
+  ASSERT_EQ(2u, cv.data.arr_double.size);
+  ASSERT_EQ(vec[0], cv.data.arr_double.arr[0]);
+  ASSERT_EQ(vec[1], cv.data.arr_double.arr[1]);
+
+  NT_DisposeValue(&cv);
+}
+
+TEST_F(ValueTest, StringArray) {
+  std::vector<std::string> vec;
+  vec.push_back("hello");
+  vec.push_back("goodbye");
+  vec.push_back("string");
+  auto v = Value::MakeStringArray(std::move(vec));
+  ASSERT_EQ(NT_STRING_ARRAY, v->type());
+  ASSERT_EQ(3u, v->GetStringArray().size());
+  ASSERT_EQ(wpi::StringRef("hello"), v->GetStringArray()[0]);
+  ASSERT_EQ(wpi::StringRef("goodbye"), v->GetStringArray()[1]);
+  ASSERT_EQ(wpi::StringRef("string"), v->GetStringArray()[2]);
+  NT_Value cv;
+  NT_InitValue(&cv);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_STRING_ARRAY, cv.type);
+  ASSERT_EQ(3u, cv.data.arr_string.size);
+  ASSERT_EQ(wpi::StringRef("hello"), cv.data.arr_string.arr[0].str);
+  ASSERT_EQ(wpi::StringRef("goodbye"), cv.data.arr_string.arr[1].str);
+  ASSERT_EQ(wpi::StringRef("string"), cv.data.arr_string.arr[2].str);
+
+  // assign with same size
+  vec.clear();
+  vec.push_back("s1");
+  vec.push_back("str2");
+  vec.push_back("string3");
+  v = Value::MakeStringArray(vec);
+  ASSERT_EQ(NT_STRING_ARRAY, v->type());
+  ASSERT_EQ(3u, v->GetStringArray().size());
+  ASSERT_EQ(wpi::StringRef("s1"), v->GetStringArray()[0]);
+  ASSERT_EQ(wpi::StringRef("str2"), v->GetStringArray()[1]);
+  ASSERT_EQ(wpi::StringRef("string3"), v->GetStringArray()[2]);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_STRING_ARRAY, cv.type);
+  ASSERT_EQ(3u, cv.data.arr_string.size);
+  ASSERT_EQ(wpi::StringRef("s1"), cv.data.arr_string.arr[0].str);
+  ASSERT_EQ(wpi::StringRef("str2"), cv.data.arr_string.arr[1].str);
+  ASSERT_EQ(wpi::StringRef("string3"), cv.data.arr_string.arr[2].str);
+
+  // assign with different size
+  vec.clear();
+  vec.push_back("short");
+  vec.push_back("er");
+  v = Value::MakeStringArray(std::move(vec));
+  ASSERT_EQ(NT_STRING_ARRAY, v->type());
+  ASSERT_EQ(2u, v->GetStringArray().size());
+  ASSERT_EQ(wpi::StringRef("short"), v->GetStringArray()[0]);
+  ASSERT_EQ(wpi::StringRef("er"), v->GetStringArray()[1]);
+  ConvertToC(*v, &cv);
+  ASSERT_EQ(NT_STRING_ARRAY, cv.type);
+  ASSERT_EQ(2u, cv.data.arr_string.size);
+  ASSERT_EQ(wpi::StringRef("short"), cv.data.arr_string.arr[0].str);
+  ASSERT_EQ(wpi::StringRef("er"), cv.data.arr_string.arr[1].str);
+
+  NT_DisposeValue(&cv);
+}
+
+TEST_F(ValueDeathTest, GetAssertions) {
+  Value v;
+  ASSERT_DEATH((void)v.GetBoolean(), "type == NT_BOOLEAN");
+  ASSERT_DEATH((void)v.GetDouble(), "type == NT_DOUBLE");
+  ASSERT_DEATH((void)v.GetString(), "type == NT_STRING");
+  ASSERT_DEATH((void)v.GetRaw(), "type == NT_RAW");
+  ASSERT_DEATH((void)v.GetBooleanArray(), "type == NT_BOOLEAN_ARRAY");
+  ASSERT_DEATH((void)v.GetDoubleArray(), "type == NT_DOUBLE_ARRAY");
+  ASSERT_DEATH((void)v.GetStringArray(), "type == NT_STRING_ARRAY");
+}
+
+TEST_F(ValueTest, UnassignedComparison) {
+  Value v1, v2;
+  ASSERT_EQ(v1, v2);
+}
+
+TEST_F(ValueTest, MixedComparison) {
+  Value v1;
+  auto v2 = Value::MakeBoolean(true);
+  ASSERT_NE(v1, *v2);  // unassigned vs boolean
+  auto v3 = Value::MakeDouble(0.5);
+  ASSERT_NE(*v2, *v3);  // boolean vs double
+}
+
+TEST_F(ValueTest, BooleanComparison) {
+  auto v1 = Value::MakeBoolean(true);
+  auto v2 = Value::MakeBoolean(true);
+  ASSERT_EQ(*v1, *v2);
+  v2 = Value::MakeBoolean(false);
+  ASSERT_NE(*v1, *v2);
+}
+
+TEST_F(ValueTest, DoubleComparison) {
+  auto v1 = Value::MakeDouble(0.25);
+  auto v2 = Value::MakeDouble(0.25);
+  ASSERT_EQ(*v1, *v2);
+  v2 = Value::MakeDouble(0.5);
+  ASSERT_NE(*v1, *v2);
+}
+
+TEST_F(ValueTest, StringComparison) {
+  auto v1 = Value::MakeString("hello");
+  auto v2 = Value::MakeString("hello");
+  ASSERT_EQ(*v1, *v2);
+  v2 = Value::MakeString("world");  // different contents
+  ASSERT_NE(*v1, *v2);
+  v2 = Value::MakeString("goodbye");  // different size
+  ASSERT_NE(*v1, *v2);
+}
+
+TEST_F(ValueTest, BooleanArrayComparison) {
+  std::vector<int> vec{1, 0, 1};
+  auto v1 = Value::MakeBooleanArray(vec);
+  auto v2 = Value::MakeBooleanArray(vec);
+  ASSERT_EQ(*v1, *v2);
+
+  // different contents
+  vec = {1, 1, 1};
+  v2 = Value::MakeBooleanArray(vec);
+  ASSERT_NE(*v1, *v2);
+
+  // different size
+  vec = {1, 0};
+  v2 = Value::MakeBooleanArray(vec);
+  ASSERT_NE(*v1, *v2);
+}
+
+TEST_F(ValueTest, DoubleArrayComparison) {
+  std::vector<double> vec{0.5, 0.25, 0.5};
+  auto v1 = Value::MakeDoubleArray(vec);
+  auto v2 = Value::MakeDoubleArray(vec);
+  ASSERT_EQ(*v1, *v2);
+
+  // different contents
+  vec = {0.5, 0.5, 0.5};
+  v2 = Value::MakeDoubleArray(vec);
+  ASSERT_NE(*v1, *v2);
+
+  // different size
+  vec = {0.5, 0.25};
+  v2 = Value::MakeDoubleArray(vec);
+  ASSERT_NE(*v1, *v2);
+}
+
+TEST_F(ValueTest, StringArrayComparison) {
+  std::vector<std::string> vec;
+  vec.push_back("hello");
+  vec.push_back("goodbye");
+  vec.push_back("string");
+  auto v1 = Value::MakeStringArray(vec);
+  vec.clear();
+  vec.push_back("hello");
+  vec.push_back("goodbye");
+  vec.push_back("string");
+  auto v2 = Value::MakeStringArray(std::move(vec));
+  ASSERT_EQ(*v1, *v2);
+
+  // different contents
+  vec.clear();
+  vec.push_back("hello");
+  vec.push_back("goodby2");
+  vec.push_back("string");
+  v2 = Value::MakeStringArray(std::move(vec));
+  ASSERT_NE(*v1, *v2);
+
+  // different sized contents
+  vec.clear();
+  vec.push_back("hello");
+  vec.push_back("goodbye2");
+  vec.push_back("string");
+  v2 = Value::MakeStringArray(vec);
+  ASSERT_NE(*v1, *v2);
+
+  // different size
+  vec.clear();
+  vec.push_back("hello");
+  vec.push_back("goodbye");
+  v2 = Value::MakeStringArray(std::move(vec));
+  ASSERT_NE(*v1, *v2);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/WireDecoderTest.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/WireDecoderTest.cpp
new file mode 100644
index 0000000..a13fa7a
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/WireDecoderTest.cpp
@@ -0,0 +1,643 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <stdint.h>
+
+#include <cfloat>
+#include <climits>
+#include <string>
+
+#include <wpi/StringRef.h>
+
+#include "TestPrinters.h"
+#include "WireDecoder.h"
+#include "gtest/gtest.h"
+
+namespace nt {
+
+class WireDecoderTest : public ::testing::Test {
+ protected:
+  WireDecoderTest() {
+    v_boolean = Value::MakeBoolean(true);
+    v_double = Value::MakeDouble(1.0);
+    v_string = Value::MakeString(wpi::StringRef("hello"));
+    v_raw = Value::MakeRaw(wpi::StringRef("hello"));
+    v_boolean_array = Value::MakeBooleanArray(std::vector<int>{0, 1, 0});
+    v_boolean_array_big = Value::MakeBooleanArray(std::vector<int>(255));
+    v_double_array = Value::MakeDoubleArray(std::vector<double>{0.5, 0.25});
+    v_double_array_big = Value::MakeDoubleArray(std::vector<double>(255));
+
+    std::vector<std::string> sa;
+    sa.push_back("hello");
+    sa.push_back("goodbye");
+    v_string_array = Value::MakeStringArray(std::move(sa));
+
+    sa.clear();
+    for (int i = 0; i < 255; ++i) sa.push_back("h");
+    v_string_array_big = Value::MakeStringArray(std::move(sa));
+
+    s_normal = std::string("hello");
+
+    s_long.clear();
+    s_long.append(127, '*');
+    s_long.push_back('x');
+
+    s_big2.clear();
+    s_big2.append(65534, '*');
+    s_big2.push_back('x');
+
+    s_big3.clear();
+    s_big3.append(65534, '*');
+    s_big3.append(3, 'x');
+  }
+
+  std::shared_ptr<Value> v_boolean, v_double, v_string, v_raw;
+  std::shared_ptr<Value> v_boolean_array, v_boolean_array_big;
+  std::shared_ptr<Value> v_double_array, v_double_array_big;
+  std::shared_ptr<Value> v_string_array, v_string_array_big;
+
+  std::string s_normal, s_long, s_big2, s_big3;
+};
+
+TEST_F(WireDecoderTest, Construct) {
+  wpi::raw_mem_istream is("", 0);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  EXPECT_EQ(nullptr, d.error());
+  EXPECT_EQ(0x0300u, d.proto_rev());
+}
+
+TEST_F(WireDecoderTest, SetProtoRev) {
+  wpi::raw_mem_istream is("", 0);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  d.set_proto_rev(0x0200u);
+  EXPECT_EQ(0x0200u, d.proto_rev());
+}
+
+TEST_F(WireDecoderTest, Read8) {
+  wpi::raw_mem_istream is("\x05\x01\x00", 3);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  unsigned int val;
+  ASSERT_TRUE(d.Read8(&val));
+  EXPECT_EQ(5u, val);
+  ASSERT_TRUE(d.Read8(&val));
+  EXPECT_EQ(1u, val);
+  ASSERT_TRUE(d.Read8(&val));
+  EXPECT_EQ(0u, val);
+  ASSERT_FALSE(d.Read8(&val));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, Read16) {
+  wpi::raw_mem_istream is("\x00\x05\x00\x01\x45\x67\x00\x00", 8);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  unsigned int val;
+  ASSERT_TRUE(d.Read16(&val));
+  EXPECT_EQ(5u, val);
+  ASSERT_TRUE(d.Read16(&val));
+  EXPECT_EQ(1u, val);
+  ASSERT_TRUE(d.Read16(&val));
+  EXPECT_EQ(0x4567u, val);
+  ASSERT_TRUE(d.Read16(&val));
+  EXPECT_EQ(0u, val);
+  ASSERT_FALSE(d.Read16(&val));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, Read32) {
+  wpi::raw_mem_istream is(
+      "\x00\x00\x00\x05\x00\x00\x00\x01\x00\x00\xab\xcd"
+      "\x12\x34\x56\x78\x00\x00\x00\x00",
+      20);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  uint32_t val;
+  ASSERT_TRUE(d.Read32(&val));
+  EXPECT_EQ(5ul, val);
+  ASSERT_TRUE(d.Read32(&val));
+  EXPECT_EQ(1ul, val);
+  ASSERT_TRUE(d.Read32(&val));
+  EXPECT_EQ(0xabcdul, val);
+  ASSERT_TRUE(d.Read32(&val));
+  EXPECT_EQ(0x12345678ul, val);
+  ASSERT_TRUE(d.Read32(&val));
+  EXPECT_EQ(0ul, val);
+  ASSERT_FALSE(d.Read32(&val));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadDouble) {
+  // values except min and max from
+  // http://www.binaryconvert.com/result_double.html
+  wpi::raw_mem_istream is(
+      "\x00\x00\x00\x00\x00\x00\x00\x00"
+      "\x41\x0c\x13\x80\x00\x00\x00\x00"
+      "\x7f\xf0\x00\x00\x00\x00\x00\x00"
+      "\x00\x10\x00\x00\x00\x00\x00\x00"
+      "\x7f\xef\xff\xff\xff\xff\xff\xff",
+      40);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  double val;
+  ASSERT_TRUE(d.ReadDouble(&val));
+  EXPECT_EQ(0.0, val);
+  ASSERT_TRUE(d.ReadDouble(&val));
+  EXPECT_EQ(2.3e5, val);
+  ASSERT_TRUE(d.ReadDouble(&val));
+  EXPECT_EQ(std::numeric_limits<double>::infinity(), val);
+  ASSERT_TRUE(d.ReadDouble(&val));
+  EXPECT_EQ(DBL_MIN, val);
+  ASSERT_TRUE(d.ReadDouble(&val));
+  EXPECT_EQ(DBL_MAX, val);
+  ASSERT_FALSE(d.ReadDouble(&val));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadUleb128) {
+  wpi::raw_mem_istream is("\x00\x7f\x80\x01\x80", 5);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  uint64_t val;
+  ASSERT_TRUE(d.ReadUleb128(&val));
+  EXPECT_EQ(0ul, val);
+  ASSERT_TRUE(d.ReadUleb128(&val));
+  EXPECT_EQ(0x7ful, val);
+  ASSERT_TRUE(d.ReadUleb128(&val));
+  EXPECT_EQ(0x80ul, val);
+  ASSERT_FALSE(d.ReadUleb128(&val));  // partial
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadType) {
+  wpi::raw_mem_istream is("\x00\x01\x02\x03\x10\x11\x12\x20", 8);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  NT_Type val;
+  ASSERT_TRUE(d.ReadType(&val));
+  EXPECT_EQ(NT_BOOLEAN, val);
+  ASSERT_TRUE(d.ReadType(&val));
+  EXPECT_EQ(NT_DOUBLE, val);
+  ASSERT_TRUE(d.ReadType(&val));
+  EXPECT_EQ(NT_STRING, val);
+  ASSERT_TRUE(d.ReadType(&val));
+  EXPECT_EQ(NT_RAW, val);
+  ASSERT_TRUE(d.ReadType(&val));
+  EXPECT_EQ(NT_BOOLEAN_ARRAY, val);
+  ASSERT_TRUE(d.ReadType(&val));
+  EXPECT_EQ(NT_DOUBLE_ARRAY, val);
+  ASSERT_TRUE(d.ReadType(&val));
+  EXPECT_EQ(NT_STRING_ARRAY, val);
+  ASSERT_TRUE(d.ReadType(&val));
+  EXPECT_EQ(NT_RPC, val);
+  ASSERT_FALSE(d.ReadType(&val));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadTypeError) {
+  wpi::raw_mem_istream is("\x30", 1);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  NT_Type val;
+  ASSERT_FALSE(d.ReadType(&val));
+  EXPECT_EQ(NT_UNASSIGNED, val);
+  ASSERT_NE(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, Reset) {
+  wpi::raw_mem_istream is("\x30", 1);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  NT_Type val;
+  ASSERT_FALSE(d.ReadType(&val));
+  EXPECT_EQ(NT_UNASSIGNED, val);
+  ASSERT_NE(nullptr, d.error());
+  d.Reset();
+  EXPECT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadBooleanValue2) {
+  wpi::raw_mem_istream is("\x01\x00", 2);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_BOOLEAN);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_boolean, *val);
+
+  auto v_false = Value::MakeBoolean(false);
+  val = d.ReadValue(NT_BOOLEAN);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_false, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadDoubleValue2) {
+  wpi::raw_mem_istream is(
+      "\x3f\xf0\x00\x00\x00\x00\x00\x00"
+      "\x3f\xf0\x00\x00\x00\x00\x00\x00",
+      16);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_DOUBLE);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_double, *val);
+
+  val = d.ReadValue(NT_DOUBLE);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_double, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_DOUBLE));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadStringValue2) {
+  wpi::raw_mem_istream is(
+      "\x00\x05hello\x00\x03"
+      "bye\x55",
+      13);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_STRING);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_string, *val);
+
+  auto v_bye = Value::MakeString(wpi::StringRef("bye"));
+  val = d.ReadValue(NT_STRING);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_bye, *val);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadValue(NT_STRING));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadBooleanArrayValue2) {
+  wpi::raw_mem_istream is("\x03\x00\x01\x00\x02\x01\x00\xff", 8);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_BOOLEAN_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_boolean_array, *val);
+
+  auto v_boolean_array2 = Value::MakeBooleanArray(std::vector<int>{1, 0});
+  val = d.ReadValue(NT_BOOLEAN_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_boolean_array2, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadBooleanArrayBigValue2) {
+  std::string s;
+  s.push_back('\xff');
+  s.append(255, '\x00');
+  wpi::raw_mem_istream is(s.data(), s.size());
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_BOOLEAN_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_boolean_array_big, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadDoubleArrayValue2) {
+  wpi::raw_mem_istream is(
+      "\x02\x3f\xe0\x00\x00\x00\x00\x00\x00"
+      "\x3f\xd0\x00\x00\x00\x00\x00\x00\x55",
+      18);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_DOUBLE_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_double_array, *val);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadValue(NT_DOUBLE_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadDoubleArrayBigValue2) {
+  std::string s;
+  s.push_back('\xff');
+  s.append(255 * 8, '\x00');
+  wpi::raw_mem_istream is(s.data(), s.size());
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_DOUBLE_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_double_array_big, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_DOUBLE_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadStringArrayValue2) {
+  wpi::raw_mem_istream is("\x02\x00\x05hello\x00\x07goodbye\x55", 18);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_STRING_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_string_array, *val);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadValue(NT_STRING_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadStringArrayBigValue2) {
+  std::string s;
+  s.push_back('\xff');
+  for (int i = 0; i < 255; ++i) s.append("\x00\x01h", 3);
+  wpi::raw_mem_istream is(s.data(), s.size());
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  auto val = d.ReadValue(NT_STRING_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_string_array_big, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_STRING_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadValueError2) {
+  wpi::raw_mem_istream is("", 0);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  ASSERT_FALSE(d.ReadValue(NT_UNASSIGNED));  // unassigned
+  ASSERT_NE(nullptr, d.error());
+
+  d.Reset();
+  ASSERT_FALSE(d.ReadValue(NT_RAW));  // not supported
+  ASSERT_NE(nullptr, d.error());
+
+  d.Reset();
+  ASSERT_FALSE(d.ReadValue(NT_RPC));  // not supported
+  ASSERT_NE(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadBooleanValue3) {
+  wpi::raw_mem_istream is("\x01\x00", 2);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_BOOLEAN);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_boolean, *val);
+
+  auto v_false = Value::MakeBoolean(false);
+  val = d.ReadValue(NT_BOOLEAN);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_false, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadDoubleValue3) {
+  wpi::raw_mem_istream is(
+      "\x3f\xf0\x00\x00\x00\x00\x00\x00"
+      "\x3f\xf0\x00\x00\x00\x00\x00\x00",
+      16);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_DOUBLE);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_double, *val);
+
+  val = d.ReadValue(NT_DOUBLE);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_double, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_DOUBLE));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadStringValue3) {
+  wpi::raw_mem_istream is(
+      "\x05hello\x03"
+      "bye\x55",
+      11);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_STRING);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_string, *val);
+
+  auto v_bye = Value::MakeString(wpi::StringRef("bye"));
+  val = d.ReadValue(NT_STRING);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_bye, *val);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadValue(NT_STRING));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadRawValue3) {
+  wpi::raw_mem_istream is(
+      "\x05hello\x03"
+      "bye\x55",
+      11);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_RAW);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_raw, *val);
+
+  auto v_bye = Value::MakeRaw(wpi::StringRef("bye"));
+  val = d.ReadValue(NT_RAW);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_bye, *val);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadValue(NT_RAW));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadBooleanArrayValue3) {
+  wpi::raw_mem_istream is("\x03\x00\x01\x00\x02\x01\x00\xff", 8);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_BOOLEAN_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_boolean_array, *val);
+
+  auto v_boolean_array2 = Value::MakeBooleanArray(std::vector<int>{1, 0});
+  val = d.ReadValue(NT_BOOLEAN_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_boolean_array2, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadBooleanArrayBigValue3) {
+  std::string s;
+  s.push_back('\xff');
+  s.append(255, '\x00');
+  wpi::raw_mem_istream is(s.data(), s.size());
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_BOOLEAN_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_boolean_array_big, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_BOOLEAN_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadDoubleArrayValue3) {
+  wpi::raw_mem_istream is(
+      "\x02\x3f\xe0\x00\x00\x00\x00\x00\x00"
+      "\x3f\xd0\x00\x00\x00\x00\x00\x00\x55",
+      18);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_DOUBLE_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_double_array, *val);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadValue(NT_DOUBLE_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadDoubleArrayBigValue3) {
+  std::string s;
+  s.push_back('\xff');
+  s.append(255 * 8, '\x00');
+  wpi::raw_mem_istream is(s.data(), s.size());
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_DOUBLE_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_double_array_big, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_DOUBLE_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadStringArrayValue3) {
+  wpi::raw_mem_istream is("\x02\x05hello\x07goodbye\x55", 16);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_STRING_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_string_array, *val);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadValue(NT_STRING_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadStringArrayBigValue3) {
+  std::string s;
+  s.push_back('\xff');
+  for (int i = 0; i < 255; ++i) s.append("\x01h", 2);
+  wpi::raw_mem_istream is(s.data(), s.size());
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  auto val = d.ReadValue(NT_STRING_ARRAY);
+  ASSERT_TRUE(static_cast<bool>(val));
+  EXPECT_EQ(*v_string_array_big, *val);
+
+  ASSERT_FALSE(d.ReadValue(NT_STRING_ARRAY));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadValueError3) {
+  wpi::raw_mem_istream is("", 0);
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  ASSERT_FALSE(d.ReadValue(NT_UNASSIGNED));  // unassigned
+  ASSERT_NE(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadString2) {
+  std::string s;
+  s.append("\x00\x05", 2);
+  s += s_normal;
+  s.append("\x00\x80", 2);
+  s += s_long;
+  s.append("\xff\xff", 2);
+  s += s_big2;
+  s.push_back('\x55');
+  wpi::raw_mem_istream is(s.data(), s.size());
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0200u, logger);
+  std::string outs;
+  ASSERT_TRUE(d.ReadString(&outs));
+  EXPECT_EQ(s_normal, outs);
+  ASSERT_TRUE(d.ReadString(&outs));
+  EXPECT_EQ(s_long, outs);
+  ASSERT_TRUE(d.ReadString(&outs));
+  EXPECT_EQ(s_big2, outs);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadString(&outs));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+TEST_F(WireDecoderTest, ReadString3) {
+  std::string s;
+  s.push_back('\x05');
+  s += s_normal;
+  s.append("\x80\x01", 2);
+  s += s_long;
+  s.append("\x81\x80\x04", 3);
+  s += s_big3;
+  s.push_back('\x55');
+  wpi::raw_mem_istream is(s.data(), s.size());
+  wpi::Logger logger;
+  WireDecoder d(is, 0x0300u, logger);
+  std::string outs;
+  ASSERT_TRUE(d.ReadString(&outs));
+  EXPECT_EQ(s_normal, outs);
+  ASSERT_TRUE(d.ReadString(&outs));
+  EXPECT_EQ(s_long, outs);
+  ASSERT_TRUE(d.ReadString(&outs));
+  EXPECT_EQ(s_big3, outs);
+
+  unsigned int b;
+  ASSERT_TRUE(d.Read8(&b));
+  EXPECT_EQ(0x55u, b);
+
+  ASSERT_FALSE(d.ReadString(&outs));
+  ASSERT_EQ(nullptr, d.error());
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/WireEncoderTest.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/WireEncoderTest.cpp
new file mode 100644
index 0000000..664344f
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/WireEncoderTest.cpp
@@ -0,0 +1,493 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <cfloat>
+#include <climits>
+#include <string>
+
+#include <wpi/StringRef.h>
+
+#include "TestPrinters.h"
+#include "WireEncoder.h"
+#include "gtest/gtest.h"
+
+#define BUFSIZE 1024
+
+namespace nt {
+
+class WireEncoderTest : public ::testing::Test {
+ protected:
+  WireEncoderTest() {
+    v_empty = std::make_shared<Value>();
+    v_boolean = Value::MakeBoolean(true);
+    v_double = Value::MakeDouble(1.0);
+    v_string = Value::MakeString(wpi::StringRef("hello"));
+    v_raw = Value::MakeRaw(wpi::StringRef("hello"));
+    v_boolean_array = Value::MakeBooleanArray(std::vector<int>{0, 1, 0});
+    v_boolean_array_big = Value::MakeBooleanArray(std::vector<int>(256));
+    v_double_array = Value::MakeDoubleArray(std::vector<double>{0.5, 0.25});
+    v_double_array_big = Value::MakeDoubleArray(std::vector<double>(256));
+
+    std::vector<std::string> sa;
+    sa.push_back("hello");
+    sa.push_back("goodbye");
+    v_string_array = Value::MakeStringArray(std::move(sa));
+
+    sa.clear();
+    for (int i = 0; i < 256; ++i) sa.push_back("h");
+    v_string_array_big = Value::MakeStringArray(std::move(sa));
+
+    s_normal = "hello";
+
+    s_long.clear();
+    s_long.append(127, '*');
+    s_long.push_back('x');
+
+    s_big.clear();
+    s_big.append(65534, '*');
+    s_big.append(3, 'x');
+  }
+
+  std::shared_ptr<Value> v_empty;
+  std::shared_ptr<Value> v_boolean, v_double, v_string, v_raw;
+  std::shared_ptr<Value> v_boolean_array, v_boolean_array_big;
+  std::shared_ptr<Value> v_double_array, v_double_array_big;
+  std::shared_ptr<Value> v_string_array, v_string_array_big;
+
+  std::string s_normal, s_long, s_big;
+};
+
+TEST_F(WireEncoderTest, Construct) {
+  WireEncoder e(0x0300u);
+  EXPECT_EQ(0u, e.size());
+  EXPECT_EQ(nullptr, e.error());
+  EXPECT_EQ(0x0300u, e.proto_rev());
+}
+
+TEST_F(WireEncoderTest, SetProtoRev) {
+  WireEncoder e(0x0300u);
+  e.set_proto_rev(0x0200u);
+  EXPECT_EQ(0x0200u, e.proto_rev());
+}
+
+TEST_F(WireEncoderTest, Write8) {
+  size_t off = BUFSIZE - 1;
+  WireEncoder e(0x0300u);
+  for (size_t i = 0; i < off; ++i) e.Write8(0u);  // test across Reserve()
+  e.Write8(5u);
+  e.Write8(0x101u);  // should be truncated
+  e.Write8(0u);
+  ASSERT_EQ(3u, e.size() - off);
+  ASSERT_EQ(wpi::StringRef("\x05\x01\x00", 3),
+            wpi::StringRef(e.data(), e.size()).substr(off));
+}
+
+TEST_F(WireEncoderTest, Write16) {
+  size_t off = BUFSIZE - 2;
+  WireEncoder e(0x0300u);
+  for (size_t i = 0; i < off; ++i) e.Write8(0u);  // test across Reserve()
+  e.Write16(5u);
+  e.Write16(0x10001u);  // should be truncated
+  e.Write16(0x4567u);
+  e.Write16(0u);
+  ASSERT_EQ(8u, e.size() - off);
+  ASSERT_EQ(wpi::StringRef("\x00\x05\x00\x01\x45\x67\x00\x00", 8),
+            wpi::StringRef(e.data(), e.size()).substr(off));
+}
+
+TEST_F(WireEncoderTest, Write32) {
+  size_t off = BUFSIZE - 4;
+  WireEncoder e(0x0300u);
+  for (size_t i = 0; i < off; ++i) e.Write8(0u);  // test across Reserve()
+  e.Write32(5ul);
+  e.Write32(1ul);
+  e.Write32(0xabcdul);
+  e.Write32(0x12345678ul);
+  e.Write32(0ul);
+  ASSERT_EQ(20u, e.size() - off);
+  ASSERT_EQ(wpi::StringRef("\x00\x00\x00\x05\x00\x00\x00\x01\x00\x00\xab\xcd"
+                           "\x12\x34\x56\x78\x00\x00\x00\x00",
+                           20),
+            wpi::StringRef(e.data(), e.size()).substr(off));
+}
+
+TEST_F(WireEncoderTest, WriteDouble) {
+  size_t off = BUFSIZE - 8;
+  WireEncoder e(0x0300u);
+  for (size_t i = 0; i < off; ++i) e.Write8(0u);  // test across Reserve()
+  e.WriteDouble(0.0);
+  e.WriteDouble(2.3e5);
+  e.WriteDouble(std::numeric_limits<double>::infinity());
+  e.WriteDouble(DBL_MIN);
+  e.WriteDouble(DBL_MAX);
+  ASSERT_EQ(40u, e.size() - off);
+  // golden values except min and max from
+  // http://www.binaryconvert.com/result_double.html
+  ASSERT_EQ(wpi::StringRef("\x00\x00\x00\x00\x00\x00\x00\x00"
+                           "\x41\x0c\x13\x80\x00\x00\x00\x00"
+                           "\x7f\xf0\x00\x00\x00\x00\x00\x00"
+                           "\x00\x10\x00\x00\x00\x00\x00\x00"
+                           "\x7f\xef\xff\xff\xff\xff\xff\xff",
+                           40),
+            wpi::StringRef(e.data(), e.size()).substr(off));
+}
+
+TEST_F(WireEncoderTest, WriteUleb128) {
+  size_t off = BUFSIZE - 2;
+  WireEncoder e(0x0300u);
+  for (size_t i = 0; i < off; ++i) e.Write8(0u);  // test across Reserve()
+  e.WriteUleb128(0ul);
+  e.WriteUleb128(0x7ful);
+  e.WriteUleb128(0x80ul);
+  ASSERT_EQ(4u, e.size() - off);
+  ASSERT_EQ(wpi::StringRef("\x00\x7f\x80\x01", 4),
+            wpi::StringRef(e.data(), e.size()).substr(off));
+}
+
+TEST_F(WireEncoderTest, WriteType) {
+  size_t off = BUFSIZE - 1;
+  WireEncoder e(0x0300u);
+  for (size_t i = 0; i < off; ++i) e.Write8(0u);  // test across Reserve()
+  e.WriteType(NT_BOOLEAN);
+  e.WriteType(NT_DOUBLE);
+  e.WriteType(NT_STRING);
+  e.WriteType(NT_RAW);
+  e.WriteType(NT_BOOLEAN_ARRAY);
+  e.WriteType(NT_DOUBLE_ARRAY);
+  e.WriteType(NT_STRING_ARRAY);
+  e.WriteType(NT_RPC);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(8u, e.size() - off);
+  ASSERT_EQ(wpi::StringRef("\x00\x01\x02\x03\x10\x11\x12\x20", 8),
+            wpi::StringRef(e.data(), e.size()).substr(off));
+}
+
+TEST_F(WireEncoderTest, WriteTypeError) {
+  WireEncoder e(0x0200u);
+  e.WriteType(NT_UNASSIGNED);
+  EXPECT_EQ(0u, e.size());
+  EXPECT_EQ(std::string("unrecognized type"), e.error());
+
+  e.Reset();
+  e.WriteType(NT_RAW);
+  EXPECT_EQ(0u, e.size());
+  EXPECT_EQ(std::string("raw type not supported in protocol < 3.0"), e.error());
+
+  e.Reset();
+  e.WriteType(NT_RPC);
+  EXPECT_EQ(0u, e.size());
+  EXPECT_EQ(std::string("RPC type not supported in protocol < 3.0"), e.error());
+}
+
+TEST_F(WireEncoderTest, Reset) {
+  WireEncoder e(0x0300u);
+  e.WriteType(NT_UNASSIGNED);
+  EXPECT_NE(nullptr, e.error());
+  e.Reset();
+  EXPECT_EQ(nullptr, e.error());
+
+  e.Write8(0u);
+  EXPECT_EQ(1u, e.size());
+  e.Reset();
+  EXPECT_EQ(0u, e.size());
+}
+
+TEST_F(WireEncoderTest, GetValueSize2) {
+  WireEncoder e(0x0200u);
+  EXPECT_EQ(0u, e.GetValueSize(*v_empty));  // empty
+  EXPECT_EQ(1u, e.GetValueSize(*v_boolean));
+  EXPECT_EQ(8u, e.GetValueSize(*v_double));
+  EXPECT_EQ(7u, e.GetValueSize(*v_string));
+  EXPECT_EQ(0u, e.GetValueSize(*v_raw));  // not supported
+
+  EXPECT_EQ(1u + 3u, e.GetValueSize(*v_boolean_array));
+  // truncated
+  EXPECT_EQ(1u + 255u, e.GetValueSize(*v_boolean_array_big));
+
+  EXPECT_EQ(1u + 2u * 8u, e.GetValueSize(*v_double_array));
+  // truncated
+  EXPECT_EQ(1u + 255u * 8u, e.GetValueSize(*v_double_array_big));
+
+  EXPECT_EQ(1u + 7u + 9u, e.GetValueSize(*v_string_array));
+  // truncated
+  EXPECT_EQ(1u + 255u * 3u, e.GetValueSize(*v_string_array_big));
+}
+
+TEST_F(WireEncoderTest, WriteBooleanValue2) {
+  WireEncoder e(0x0200u);
+  e.WriteValue(*v_boolean);
+  auto v_false = Value::MakeBoolean(false);
+  e.WriteValue(*v_false);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(2u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x01\x00", 2), wpi::StringRef(e.data(), e.size()));
+}
+
+TEST_F(WireEncoderTest, WriteDoubleValue2) {
+  WireEncoder e(0x0200u);
+  e.WriteValue(*v_double);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(8u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x3f\xf0\x00\x00\x00\x00\x00\x00", 8),
+            wpi::StringRef(e.data(), e.size()));
+}
+
+TEST_F(WireEncoderTest, WriteStringValue2) {
+  WireEncoder e(0x0200u);
+  e.WriteValue(*v_string);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(7u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x00\x05hello", 7),
+            wpi::StringRef(e.data(), e.size()));
+}
+
+TEST_F(WireEncoderTest, WriteBooleanArrayValue2) {
+  WireEncoder e(0x0200u);
+  e.WriteValue(*v_boolean_array);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 3u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x03\x00\x01\x00", 4),
+            wpi::StringRef(e.data(), e.size()));
+
+  // truncated
+  e.Reset();
+  e.WriteValue(*v_boolean_array_big);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 255u, e.size());
+  ASSERT_EQ(wpi::StringRef("\xff\x00", 2), wpi::StringRef(e.data(), 2));
+}
+
+TEST_F(WireEncoderTest, WriteDoubleArrayValue2) {
+  WireEncoder e(0x0200u);
+  e.WriteValue(*v_double_array);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 2u * 8u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x02\x3f\xe0\x00\x00\x00\x00\x00\x00"
+                           "\x3f\xd0\x00\x00\x00\x00\x00\x00",
+                           17),
+            wpi::StringRef(e.data(), e.size()));
+
+  // truncated
+  e.Reset();
+  e.WriteValue(*v_double_array_big);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 255u * 8u, e.size());
+  ASSERT_EQ(wpi::StringRef("\xff\x00", 2), wpi::StringRef(e.data(), 2));
+}
+
+TEST_F(WireEncoderTest, WriteStringArrayValue2) {
+  WireEncoder e(0x0200u);
+  e.WriteValue(*v_string_array);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 7u + 9u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x02\x00\x05hello\x00\x07goodbye", 17),
+            wpi::StringRef(e.data(), e.size()));
+
+  // truncated
+  e.Reset();
+  e.WriteValue(*v_string_array_big);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 255u * 3u, e.size());
+  ASSERT_EQ(wpi::StringRef("\xff\x00\x01", 3), wpi::StringRef(e.data(), 3));
+}
+
+TEST_F(WireEncoderTest, WriteValueError2) {
+  WireEncoder e(0x0200u);
+  e.WriteValue(*v_empty);  // empty
+  ASSERT_EQ(0u, e.size());
+  ASSERT_NE(nullptr, e.error());
+
+  e.Reset();
+  e.WriteValue(*v_raw);  // not supported
+  ASSERT_EQ(0u, e.size());
+  ASSERT_NE(nullptr, e.error());
+}
+
+TEST_F(WireEncoderTest, GetValueSize3) {
+  WireEncoder e(0x0300u);
+  EXPECT_EQ(0u, e.GetValueSize(*v_empty));  // empty
+  EXPECT_EQ(1u, e.GetValueSize(*v_boolean));
+  EXPECT_EQ(8u, e.GetValueSize(*v_double));
+  EXPECT_EQ(6u, e.GetValueSize(*v_string));
+  EXPECT_EQ(6u, e.GetValueSize(*v_raw));
+
+  EXPECT_EQ(1u + 3u, e.GetValueSize(*v_boolean_array));
+  // truncated
+  EXPECT_EQ(1u + 255u, e.GetValueSize(*v_boolean_array_big));
+
+  EXPECT_EQ(1u + 2u * 8u, e.GetValueSize(*v_double_array));
+  // truncated
+  EXPECT_EQ(1u + 255u * 8u, e.GetValueSize(*v_double_array_big));
+
+  EXPECT_EQ(1u + 6u + 8u, e.GetValueSize(*v_string_array));
+  // truncated
+  EXPECT_EQ(1u + 255u * 2u, e.GetValueSize(*v_string_array_big));
+}
+
+TEST_F(WireEncoderTest, WriteBooleanValue3) {
+  WireEncoder e(0x0300u);
+  e.WriteValue(*v_boolean);
+  auto v_false = Value::MakeBoolean(false);
+  e.WriteValue(*v_false);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(2u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x01\x00", 2), wpi::StringRef(e.data(), e.size()));
+}
+
+TEST_F(WireEncoderTest, WriteDoubleValue3) {
+  WireEncoder e(0x0300u);
+  e.WriteValue(*v_double);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(8u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x3f\xf0\x00\x00\x00\x00\x00\x00", 8),
+            wpi::StringRef(e.data(), e.size()));
+}
+
+TEST_F(WireEncoderTest, WriteStringValue3) {
+  WireEncoder e(0x0300u);
+  e.WriteValue(*v_string);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(6u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x05hello", 6), wpi::StringRef(e.data(), e.size()));
+}
+
+TEST_F(WireEncoderTest, WriteRawValue3) {
+  WireEncoder e(0x0300u);
+  e.WriteValue(*v_raw);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(6u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x05hello", 6), wpi::StringRef(e.data(), e.size()));
+}
+
+TEST_F(WireEncoderTest, WriteBooleanArrayValue3) {
+  WireEncoder e(0x0300u);
+  e.WriteValue(*v_boolean_array);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 3u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x03\x00\x01\x00", 4),
+            wpi::StringRef(e.data(), e.size()));
+
+  // truncated
+  e.Reset();
+  e.WriteValue(*v_boolean_array_big);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 255u, e.size());
+  ASSERT_EQ(wpi::StringRef("\xff\x00", 2), wpi::StringRef(e.data(), 2));
+}
+
+TEST_F(WireEncoderTest, WriteDoubleArrayValue3) {
+  WireEncoder e(0x0300u);
+  e.WriteValue(*v_double_array);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 2u * 8u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x02\x3f\xe0\x00\x00\x00\x00\x00\x00"
+                           "\x3f\xd0\x00\x00\x00\x00\x00\x00",
+                           17),
+            wpi::StringRef(e.data(), e.size()));
+
+  // truncated
+  e.Reset();
+  e.WriteValue(*v_double_array_big);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 255u * 8u, e.size());
+  ASSERT_EQ(wpi::StringRef("\xff\x00", 2), wpi::StringRef(e.data(), 2));
+}
+
+TEST_F(WireEncoderTest, WriteStringArrayValue3) {
+  WireEncoder e(0x0300u);
+  e.WriteValue(*v_string_array);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 6u + 8u, e.size());
+  ASSERT_EQ(wpi::StringRef("\x02\x05hello\x07goodbye", 15),
+            wpi::StringRef(e.data(), e.size()));
+
+  // truncated
+  e.Reset();
+  e.WriteValue(*v_string_array_big);
+  ASSERT_EQ(nullptr, e.error());
+  ASSERT_EQ(1u + 255u * 2u, e.size());
+  ASSERT_EQ(wpi::StringRef("\xff\x01", 2), wpi::StringRef(e.data(), 2));
+}
+
+TEST_F(WireEncoderTest, WriteValueError3) {
+  WireEncoder e(0x0300u);
+  e.WriteValue(*v_empty);  // empty
+  ASSERT_EQ(0u, e.size());
+  ASSERT_NE(nullptr, e.error());
+}
+
+TEST_F(WireEncoderTest, GetStringSize2) {
+  // 2-byte length
+  WireEncoder e(0x0200u);
+  EXPECT_EQ(7u, e.GetStringSize(s_normal));
+  EXPECT_EQ(130u, e.GetStringSize(s_long));
+  // truncated
+  EXPECT_EQ(65537u, e.GetStringSize(s_big));
+}
+
+TEST_F(WireEncoderTest, WriteString2) {
+  WireEncoder e(0x0200u);
+  e.WriteString(s_normal);
+  EXPECT_EQ(nullptr, e.error());
+  EXPECT_EQ(7u, e.size());
+  EXPECT_EQ(wpi::StringRef("\x00\x05hello", 7),
+            wpi::StringRef(e.data(), e.size()));
+
+  e.Reset();
+  e.WriteString(s_long);
+  EXPECT_EQ(nullptr, e.error());
+  ASSERT_EQ(130u, e.size());
+  EXPECT_EQ(wpi::StringRef("\x00\x80**", 4), wpi::StringRef(e.data(), 4));
+  EXPECT_EQ('*', e.data()[128]);
+  EXPECT_EQ('x', e.data()[129]);
+
+  // truncated
+  e.Reset();
+  e.WriteString(s_big);
+  EXPECT_EQ(nullptr, e.error());
+  ASSERT_EQ(65537u, e.size());
+  EXPECT_EQ(wpi::StringRef("\xff\xff**", 4), wpi::StringRef(e.data(), 4));
+  EXPECT_EQ('*', e.data()[65535]);
+  EXPECT_EQ('x', e.data()[65536]);
+}
+
+TEST_F(WireEncoderTest, GetStringSize3) {
+  // leb128-encoded length
+  WireEncoder e(0x0300u);
+  EXPECT_EQ(6u, e.GetStringSize(s_normal));
+  EXPECT_EQ(130u, e.GetStringSize(s_long));
+  EXPECT_EQ(65540u, e.GetStringSize(s_big));
+}
+
+TEST_F(WireEncoderTest, WriteString3) {
+  WireEncoder e(0x0300u);
+  e.WriteString(s_normal);
+  EXPECT_EQ(nullptr, e.error());
+  EXPECT_EQ(6u, e.size());
+  EXPECT_EQ(wpi::StringRef("\x05hello", 6), wpi::StringRef(e.data(), e.size()));
+
+  e.Reset();
+  e.WriteString(s_long);
+  EXPECT_EQ(nullptr, e.error());
+  ASSERT_EQ(130u, e.size());
+  EXPECT_EQ(wpi::StringRef("\x80\x01**", 4), wpi::StringRef(e.data(), 4));
+  EXPECT_EQ('*', e.data()[128]);
+  EXPECT_EQ('x', e.data()[129]);
+
+  // NOT truncated
+  e.Reset();
+  e.WriteString(s_big);
+  EXPECT_EQ(nullptr, e.error());
+  ASSERT_EQ(65540u, e.size());
+  EXPECT_EQ(wpi::StringRef("\x81\x80\x04*", 4), wpi::StringRef(e.data(), 4));
+  EXPECT_EQ('*', e.data()[65536]);
+  EXPECT_EQ('x', e.data()[65537]);
+  EXPECT_EQ('x', e.data()[65538]);
+  EXPECT_EQ('x', e.data()[65539]);
+}
+
+}  // namespace nt
diff --git a/third_party/allwpilib_2019/ntcore/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..d0b0e3c
--- /dev/null
+++ b/third_party/allwpilib_2019/ntcore/src/test/native/cpp/main.cpp
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <climits>
+
+#include "gmock/gmock.h"
+#include "ntcore.h"
+
+int main(int argc, char** argv) {
+  nt::AddLogger(nt::GetDefaultInstance(),
+                [](const nt::LogMessage& msg) {
+                  std::fputs(msg.message.c_str(), stderr);
+                  std::fputc('\n', stderr);
+                },
+                0, UINT_MAX);
+  ::testing::InitGoogleMock(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/settings.gradle b/third_party/allwpilib_2019/settings.gradle
new file mode 100644
index 0000000..553adc9
--- /dev/null
+++ b/third_party/allwpilib_2019/settings.gradle
@@ -0,0 +1,30 @@
+pluginManagement {
+    repositories {
+        mavenLocal()
+        gradlePluginPortal()
+    }
+}
+
+include 'wpiutil'
+include 'ntcore'
+include 'hal'
+include 'cscore'
+include 'wpilibc'
+include 'wpilibcExamples'
+include 'wpilibcIntegrationTests'
+include 'wpilibjExamples'
+include 'wpilibjIntegrationTests'
+include 'wpilibj'
+include 'simulation:halsim_print'
+include 'simulation:halsim_lowfi'
+include 'simulation:halsim_adx_gyro_accelerometer'
+include 'simulation:halsim_ds_nt'
+include 'simulation:gz_msgs'
+include 'simulation:frc_gazebo_plugins'
+include 'simulation:halsim_gazebo'
+include 'simulation:lowfi_simulation'
+include 'simulation:halsim_ds_socket'
+include 'cameraserver'
+include 'cameraserver:multiCameraServer'
+include 'myRobot'
+include 'docs'
diff --git a/third_party/allwpilib_2019/shared/config.gradle b/third_party/allwpilib_2019/shared/config.gradle
new file mode 100644
index 0000000..02c2b68
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/config.gradle
@@ -0,0 +1,395 @@
+import edu.wpi.first.nativeutils.*
+import org.gradle.internal.os.OperatingSystem
+
+def windowsCompilerArgs = ['/EHsc', '/DNOMINMAX', '/Zi', '/FS', '/Zc:inline', '/MP4']
+def windowsCCompilerArgs = ['/Zi', '/FS', '/Zc:inline']
+def windowsReleaseCompilerArgs = ['/O2', '/MD']
+def windowsDebugCompilerArgs = ['/Od', '/MDd']
+def windowsLinkerArgs = ['/DEBUG:FULL']
+def windowsReleaseLinkerArgs = ['/OPT:REF', '/OPT:ICF']
+
+def linuxCrossCompilerArgs = ['-std=c++14', '-Wformat=2', '-Wall', '-Wextra', '-Werror', '-pedantic', '-Wno-psabi', '-g',
+                         '-Wno-unused-parameter', '-Wno-error=deprecated-declarations', '-fPIC', '-rdynamic',
+                         '-pthread']
+def linuxCrossCCompilerArgs = ['-Wformat=2', '-Wall', '-Wextra', '-Werror', '-pedantic', '-Wno-psabi', '-g',
+                          '-Wno-unused-parameter', '-fPIC', '-rdynamic', '-pthread']
+def linuxCrossLinkerArgs = ['-rdynamic', '-pthread', '-ldl']
+def linuxCrossReleaseCompilerArgs = ['-O2']
+def linuxCrossDebugCompilerArgs = ['-Og']
+
+def linuxCompilerArgs = ['-std=c++14', '-Wformat=2', '-Wall', '-Wextra', '-Werror', '-pedantic', '-Wno-psabi', '-g',
+                         '-Wno-unused-parameter', '-Wno-error=deprecated-declarations', '-fPIC', '-rdynamic',
+                         '-pthread']
+def linuxCCompilerArgs = ['-Wformat=2', '-Wall', '-Wextra', '-Werror', '-pedantic', '-Wno-psabi', '-g',
+                          '-Wno-unused-parameter', '-fPIC', '-rdynamic', '-pthread']
+def linuxLinkerArgs = ['-rdynamic', '-pthread', '-ldl']
+def linuxReleaseCompilerArgs = ['-O2']
+def linuxDebugCompilerArgs = ['-O0']
+def linux32BitArg = '-m32'
+
+def macCompilerArgs = ['-std=c++14', '-Wall', '-Wextra', '-Werror', '-pedantic-errors', '-fPIC', '-g',
+                       '-Wno-unused-parameter', '-Wno-error=deprecated-declarations', '-Wno-missing-field-initializers',
+                       '-Wno-unused-private-field', '-Wno-unused-const-variable', '-pthread']
+def macCCompilerArgs = ['-Wall', '-Wextra', '-Werror', '-pedantic-errors', '-fPIC', '-g',
+                        '-Wno-unused-parameter', '-Wno-missing-field-initializers', '-Wno-unused-private-field']
+def macObjCLinkerArgs = ['-std=c++14', '-stdlib=libc++','-fobjc-arc', '-g', '-fPIC', '-Wall', '-Wextra', '-Werror']
+def macReleaseCompilerArgs = ['-O2']
+def macDebugCompilerArgs = ['-O0']
+def macLinkerArgs = ['-framework', 'CoreFoundation', '-framework', 'AVFoundation', '-framework', 'Foundation', '-framework', 'CoreMedia', '-framework', 'CoreVideo']
+def mac32BitArg = '-m32'
+
+def buildAll = project.hasProperty('buildAll')
+
+def windows64PlatformDetect = {
+    def arch = System.getProperty("os.arch")
+    def isWin = OperatingSystem.current().isWindows()
+    if (buildAll) {
+        return isWin
+    } else {
+        return isWin && arch == 'amd64'
+    }
+}
+
+def windows32PlatformDetect = {
+    def arch = System.getProperty("os.arch")
+    def isWin = OperatingSystem.current().isWindows()
+    if (buildAll) {
+        return isWin
+    } else {
+        return isWin && arch == 'x86'
+    }
+}
+
+def linux32IntelPlatformDetect = {
+    def arch = System.getProperty("os.arch")
+    def isLinux = OperatingSystem.current().isLinux()
+    def isIntel = (arch == 'amd64' || arch == 'i386')
+    if (buildAll) {
+        return isLinux && isIntel
+    } else {
+        return isLinux && arch == 'i386'
+    }
+}
+
+def linux64IntelPlatformDetect = {
+    def arch = System.getProperty("os.arch")
+    def isLinux = OperatingSystem.current().isLinux()
+    def isIntel = (arch == 'amd64' || arch == 'i386')
+    if (buildAll) {
+        return isLinux && isIntel
+    } else {
+        return isLinux && arch == 'amd64'
+    }
+}
+
+def linuxArmPlatformDetect = {
+    def arch = System.getProperty("os.arch")
+    def isIntel = (arch == 'amd64' || arch == 'i386')
+    return OperatingSystem.current().isLinux() && !isIntel
+}
+
+def mac64PlatformDetect = {
+    def arch = System.getProperty("os.arch")
+    def isMac = OperatingSystem.current().isMacOsX()
+    if (buildAll) {
+        return isMac
+    } else {
+        return isMac && arch == 'x86_64'
+    }
+}
+
+def mac32PlatformDetect = {
+    def arch = System.getProperty("os.arch")
+    def isMac = OperatingSystem.current().isMacOsX()
+    if (buildAll) {
+        return isMac
+    } else {
+        return isMac && arch == 'x86'
+    }
+}
+
+if (!project.hasProperty('skipAthena') && !project.hasProperty('onlyRaspbian')) {
+    model {
+        buildConfigs {
+            roboRio(CrossBuildConfig) {
+                architecture = 'athena'
+                operatingSystem = 'linux'
+                toolChainPrefix = 'arm-frc2019-linux-gnueabi-'
+                compilerArgs = linuxCrossCompilerArgs
+                CCompilerArgs = linuxCrossCCompilerArgs
+                linkerArgs = linuxCrossLinkerArgs
+                debugCompilerArgs = linuxCrossDebugCompilerArgs
+                releaseCompilerArgs = linuxCrossReleaseCompilerArgs
+                stripBuildTypes = ['debug', 'release']
+                compilerFamily = 'Gcc'
+            }
+        }
+    }
+}
+
+if (!project.hasProperty('skipRaspbian') && !project.hasProperty('onlyAthena')) {
+    model {
+        buildConfigs {
+            raspbian(CrossBuildConfig) {
+                architecture = 'raspbian'
+                operatingSystem = 'linux'
+                toolChainPrefix = 'arm-raspbian9-linux-gnueabihf-'
+                compilerArgs = linuxCrossCompilerArgs
+                CCompilerArgs = linuxCrossCCompilerArgs
+                linkerArgs = linuxCrossLinkerArgs
+                debugCompilerArgs = linuxCrossDebugCompilerArgs
+                releaseCompilerArgs = linuxCrossReleaseCompilerArgs
+                stripBuildTypes = ['debug', 'release']
+                compilerFamily = 'Gcc'
+            }
+        }
+    }
+}
+
+if (!project.hasProperty('onlyAthena') && !hasProperty('onlyRaspbian')) {
+    model {
+        buildConfigs {
+            winX86(BuildConfig) {
+                architecture = 'x86'
+                operatingSystem = 'windows'
+                compilerArgs = windowsCompilerArgs
+                CCompilerArgs = windowsCCompilerArgs
+                linkerArgs = windowsLinkerArgs
+                releaseCompilerArgs = windowsReleaseCompilerArgs
+                releaseLinkerArgs = windowsReleaseLinkerArgs
+                debugCompilerArgs = windowsDebugCompilerArgs
+                compilerFamily = 'VisualCpp'
+                detectPlatform = windows32PlatformDetect
+            }
+            winX64(BuildConfig) {
+                architecture = 'x86-64'
+                operatingSystem = 'windows'
+                compilerArgs = windowsCompilerArgs
+                CCompilerArgs = windowsCCompilerArgs
+                linkerArgs = windowsLinkerArgs
+                releaseCompilerArgs = windowsReleaseCompilerArgs
+                releaseLinkerArgs = windowsReleaseLinkerArgs
+                debugCompilerArgs = windowsDebugCompilerArgs
+                compilerFamily = 'VisualCpp'
+                detectPlatform = windows64PlatformDetect
+            }
+            linuxX64(BuildConfig) {
+                architecture = 'x86-64'
+                operatingSystem = 'linux'
+                compilerArgs = linuxCompilerArgs
+                CCompilerArgs = linuxCCompilerArgs
+                linkerArgs = linuxLinkerArgs
+                debugCompilerArgs = linuxDebugCompilerArgs
+                releaseCompilerArgs = linuxReleaseCompilerArgs
+                stripBuildTypes = ['debug', 'release']
+                compilerFamily = 'Gcc'
+                detectPlatform = linux64IntelPlatformDetect
+            }
+            macX64(BuildConfig) {
+                architecture = 'x86-64'
+                operatingSystem = 'osx'
+                compilerArgs = macCompilerArgs
+                CCompilerArgs = macCCompilerArgs
+                debugCompilerArgs = macDebugCompilerArgs
+                releaseCompilerArgs = macReleaseCompilerArgs
+                objCppCompilerArgs = macObjCLinkerArgs
+                linkerArgs = macLinkerArgs
+                compilerFamily = 'Clang'
+                detectPlatform = mac64PlatformDetect
+            }
+        }
+    }
+}
+
+if (project.hasProperty('linuxCross')) {
+    model {
+        buildConfigs {
+            linuxArm(CrossBuildConfig) {
+                architecture = 'nativearm'
+                operatingSystem = 'linux'
+                toolChainPrefix = 'PLEASE_PROVIDE_A_COMPILER_NAME'
+                compilerArgs = linuxCompilerArgs
+                CCompilerArgs = linuxCCompilerArgs
+                linkerArgs = linuxLinkerArgs
+                debugCompilerArgs = linuxDebugCompilerArgs
+                releaseCompilerArgs = linuxReleaseCompilerArgs
+                stripBuildTypes = ['debug', 'release']
+                skipByDefault = true
+                compilerFamily = 'Gcc'
+            }
+        }
+    }
+} else {
+    model {
+        buildConfigs {
+            linuxArm(BuildConfig) {
+                architecture = 'nativearm'
+                operatingSystem = 'linux'
+                compilerArgs = linuxCompilerArgs
+                CCompilerArgs = linuxCCompilerArgs
+                linkerArgs = linuxLinkerArgs
+                debugCompilerArgs = linuxDebugCompilerArgs
+                releaseCompilerArgs = linuxReleaseCompilerArgs
+                stripBuildTypes = ['debug', 'release']
+                compilerFamily = 'Gcc'
+                detectPlatform = linuxArmPlatformDetect
+            }
+        }
+    }
+}
+
+ext.getPublishClassifier = { binary ->
+    return NativeUtils.getPublishClassifier(binary)
+}
+
+ext.getPlatformPath = { binary ->
+    return NativeUtils.getPlatformPath(binary)
+}
+
+ext.appendDebugPathToBinaries = { binaries->
+    binaries.withType(StaticLibraryBinarySpec) {
+        if (it.buildType.name.contains('debug')) {
+            def staticFileDir = it.staticLibraryFile.parentFile
+            def staticFileName = it.staticLibraryFile.name
+            def staticFileExtension = staticFileName.substring(staticFileName.lastIndexOf('.'))
+            staticFileName = staticFileName.substring(0, staticFileName.lastIndexOf('.'))
+            staticFileName = staticFileName + 'd' + staticFileExtension
+            def newStaticFile = new File(staticFileDir, staticFileName)
+            it.staticLibraryFile = newStaticFile
+        }
+    }
+    binaries.withType(SharedLibraryBinarySpec) {
+        if (it.buildType.name.contains('debug')) {
+            def sharedFileDir = it.sharedLibraryFile.parentFile
+            def sharedFileName = it.sharedLibraryFile.name
+            def sharedFileExtension = sharedFileName.substring(sharedFileName.lastIndexOf('.'))
+            sharedFileName = sharedFileName.substring(0, sharedFileName.lastIndexOf('.'))
+            sharedFileName = sharedFileName + 'd' + sharedFileExtension
+            def newSharedFile = new File(sharedFileDir, sharedFileName)
+
+            def sharedLinkFileDir = it.sharedLibraryLinkFile.parentFile
+            def sharedLinkFileName = it.sharedLibraryLinkFile.name
+            def sharedLinkFileExtension = sharedLinkFileName.substring(sharedLinkFileName.lastIndexOf('.'))
+            sharedLinkFileName = sharedLinkFileName.substring(0, sharedLinkFileName.lastIndexOf('.'))
+            sharedLinkFileName = sharedLinkFileName + 'd' + sharedLinkFileExtension
+            def newLinkFile = new File(sharedLinkFileDir, sharedLinkFileName)
+
+            it.sharedLibraryLinkFile = newLinkFile
+            it.sharedLibraryFile = newSharedFile
+        }
+    }
+}
+
+ext.createComponentZipTasks = { components, names, base, type, project, func ->
+    def stringNames = names.collect {it.toString()}
+    def configMap = [:]
+    components.each {
+        if (it in NativeLibrarySpec && stringNames.contains(it.name)) {
+            it.binaries.each {
+                if (!it.buildable) return
+                def target = getPublishClassifier(it)
+                if (configMap.containsKey(target)) {
+                    configMap.get(target).add(it)
+                } else {
+                    configMap.put(target, [])
+                    configMap.get(target).add(it)
+                }
+            }
+        }
+    }
+    def taskList = []
+    def outputsFolder = file("$project.buildDir/outputs")
+    configMap.each { key, value ->
+        def task = project.tasks.create(base + "-${key}", type) {
+            description = 'Creates component archive for platform ' + key
+            destinationDir = outputsFolder
+            classifier = key
+            baseName = '_M_' + base
+            duplicatesStrategy = 'exclude'
+
+            from(licenseFile) {
+                into '/'
+            }
+
+            func(it, value)
+        }
+        taskList.add(task)
+
+        project.build.dependsOn task
+
+        project.artifacts {
+            task
+        }
+        addTaskToCopyAllOutputs(task)
+    }
+    return taskList
+}
+
+ext.createAllCombined = { list, name, base, type, project ->
+    def outputsFolder = file("$project.buildDir/outputs")
+
+    def task = project.tasks.create(base + "-all", type) {
+        description = "Creates component archive for all classifiers"
+        destinationDir = outputsFolder
+        classifier = "all"
+        baseName = base
+        duplicatesStrategy = 'exclude'
+
+        list.each {
+            if (it.name.endsWith('debug')) return
+            from project.zipTree(it.archivePath)
+            dependsOn it
+        }
+    }
+
+    project.build.dependsOn task
+
+    project.artifacts {
+        task
+    }
+
+    return task
+
+}
+
+ext.includeStandardZipFormat = { task, value ->
+    value.each { binary ->
+        if (binary.buildable) {
+            if (binary instanceof SharedLibraryBinarySpec) {
+                task.dependsOn binary.tasks.link
+                task.from(new File(binary.sharedLibraryFile.absolutePath + ".debug")) {
+                    into getPlatformPath(binary) + '/shared'
+                }
+                def sharedPath = binary.sharedLibraryFile.absolutePath
+                sharedPath = sharedPath.substring(0, sharedPath.length() - 4)
+
+                task.from(new File(sharedPath + '.pdb')) {
+                    into getPlatformPath(binary) + '/shared'
+                }
+                task.from(binary.sharedLibraryFile) {
+                    into getPlatformPath(binary) + '/shared'
+                }
+                task.from(binary.sharedLibraryLinkFile) {
+                    into getPlatformPath(binary) + '/shared'
+                }
+            } else  if (binary instanceof StaticLibraryBinarySpec) {
+                task.dependsOn binary.tasks.createStaticLib
+                task.from(binary.staticLibraryFile) {
+                    into getPlatformPath(binary) + '/static'
+                }
+            }
+        }
+    }
+}
+
+ext.getCurrentArch = {
+    def arch = System.getProperty('os.arch');
+
+    if (arch.equals("x86") || arch.equals("i386")) {
+        return 'x86'
+    } else if (arch.equals("amd64") || arch.equals("x86_64")) {
+        return 'x86-64'
+    } else {
+        return arch
+    }
+}
diff --git a/third_party/allwpilib_2019/shared/examplecheck.gradle b/third_party/allwpilib_2019/shared/examplecheck.gradle
new file mode 100644
index 0000000..64a83c7
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/examplecheck.gradle
@@ -0,0 +1,47 @@
+def fileCheck = { file, folder ->
+    def folderNames = new groovy.json.JsonSlurper().parseText(file.text).collect { it.foldername }
+    def folders = []
+    folder.eachDir {
+        folders << it.name
+    }
+    def disjunct = (folders + folderNames) - folders.intersect(folderNames)
+    def missingFromFolders = folderNames.intersect(disjunct)
+    def missingFromJson = folders.intersect(disjunct)
+
+    if (!missingFromFolders.empty || !missingFromJson.empty) {
+        StringBuilder missingString = new StringBuilder();
+        missingString.append("Missing From Folders\n")
+        for (String symbol : missingFromFolders) {
+            missingString.append(symbol);
+            missingString.append('\n');
+        }
+        missingString.append("\nMissing from JSON\n")
+        for (String symbol : missingFromJson) {
+            missingString.append(symbol);
+            missingString.append('\n');
+        }
+        throw new GradleException("Found missing items\n" + missingString.toString());
+    }
+}
+
+task checkTemplates(type: Task) {
+    doLast {
+        fileCheck(templateFile, templateDirectory)
+    }
+}
+
+task checkExamples(type: Task) {
+    doLast {
+        fileCheck(exampleFile, exampleDirectory)
+    }
+}
+
+task checkCommands(type: Task) {
+    doLast {
+        fileCheck(commandFile, commandDirectory)
+    }
+}
+
+check.dependsOn checkTemplates
+check.dependsOn checkExamples
+check.dependsOn checkCommands
diff --git a/third_party/allwpilib_2019/shared/googletest.gradle b/third_party/allwpilib_2019/shared/googletest.gradle
new file mode 100644
index 0000000..736d886
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/googletest.gradle
@@ -0,0 +1,13 @@
+model {
+    dependencyConfigs {
+        googletest(DependencyConfig) {
+            groupId = 'edu.wpi.first.thirdparty.frc2019'
+            artifactId = 'googletest'
+            headerClassifier = 'headers'
+            ext = 'zip'
+            version = '1.8.0-4-4e4df22'
+            sharedConfigs = [:]
+            staticConfigs = project.staticGtestConfigs
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/shared/java/javacommon.gradle b/third_party/allwpilib_2019/shared/java/javacommon.gradle
new file mode 100644
index 0000000..6595223
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/java/javacommon.gradle
@@ -0,0 +1,124 @@
+apply plugin: 'maven-publish'
+apply plugin: 'java'
+//apply plugin: 'net.ltgt.errorprone'
+
+def pubVersion
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseArtifactId = project.baseId
+def artifactGroupId = project.groupId
+def javaBaseName = "_GROUP_edu_wpi_first_${project.baseId}_ID_${project.baseId}-java_CLS"
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task sourcesJar(type: Jar, dependsOn: classes) {
+    classifier = 'sources'
+    from sourceSets.main.allSource
+}
+
+task javadocJar(type: Jar, dependsOn: javadoc) {
+    classifier = 'javadoc'
+    from javadoc.destinationDir
+}
+
+task outputJar(type: Jar, dependsOn: classes) {
+    baseName javaBaseName
+    destinationDir outputsFolder
+    from sourceSets.main.output
+}
+
+task outputSourcesJar(type: Jar, dependsOn: classes) {
+    baseName javaBaseName
+    destinationDir outputsFolder
+    classifier = 'sources'
+    from sourceSets.main.allSource
+}
+
+task outputJavadocJar(type: Jar, dependsOn: javadoc) {
+    baseName javaBaseName
+    destinationDir outputsFolder
+    classifier = 'javadoc'
+    from javadoc.destinationDir
+}
+
+artifacts {
+    archives sourcesJar
+    archives javadocJar
+    archives outputJar
+    archives outputSourcesJar
+    archives outputJavadocJar
+}
+
+addTaskToCopyAllOutputs(outputSourcesJar)
+addTaskToCopyAllOutputs(outputJavadocJar)
+addTaskToCopyAllOutputs(outputJar)
+
+build.dependsOn outputSourcesJar
+build.dependsOn outputJavadocJar
+build.dependsOn outputJar
+
+project(':').libraryBuild.dependsOn build
+
+publishing {
+    publications {
+
+        java(MavenPublication) {
+            artifact jar
+            artifact sourcesJar
+            artifact javadocJar
+
+            artifactId = "${baseArtifactId}-java"
+            groupId artifactGroupId
+            version pubVersion
+        }
+    }
+}
+
+test {
+    useJUnitPlatform()
+    systemProperty 'junit.jupiter.extensions.autodetection.enabled', 'true'
+    testLogging {
+        events "failed"
+        exceptionFormat "full"
+    }
+}
+
+if (project.hasProperty('onlyAthena') || project.hasProperty('onlyRaspbian')) {
+    test.enabled = false
+}
+
+repositories {
+    mavenCentral()
+    //maven.url "https://oss.sonatype.org/content/repositories/snapshots/"
+}
+
+sourceSets {
+    dev
+}
+
+tasks.withType(JavaCompile).configureEach {
+    options.compilerArgs = ['--release', '8']
+}
+
+dependencies {
+    testImplementation 'org.junit.jupiter:junit-jupiter-api:5.2.0'
+    testImplementation 'org.junit.jupiter:junit-jupiter-params:5.2.0'
+    testRuntimeOnly 'org.junit.jupiter:junit-jupiter-engine:5.2.0'
+
+    devCompile sourceSets.main.output
+
+    //errorprone 'com.google.errorprone:error_prone_core:2.3.2-SNAPSHOT'
+    //errorproneJavac 'com.google.errorprone:error_prone_core:2.3.1'
+}
+
+task run(type: JavaExec) {
+    classpath = sourceSets.dev.runtimeClasspath
+
+    main = project.devMain
+}
+
+build.dependsOn devClasses
diff --git a/third_party/allwpilib_2019/shared/java/javastyle.gradle b/third_party/allwpilib_2019/shared/java/javastyle.gradle
new file mode 100644
index 0000000..e091988
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/java/javastyle.gradle
@@ -0,0 +1,17 @@
+
+apply plugin: 'checkstyle'
+apply plugin: 'pmd'
+
+checkstyle {
+    toolVersion = "8.12"
+    configDir = file("${project.rootDir}/styleguide")
+    config = resources.text.fromFile(new File(configDir, "checkstyle.xml"))
+}
+
+pmd {
+    toolVersion = '6.7.0'
+    consoleOutput = true
+    reportsDir = file("$project.buildDir/reports/pmd")
+    ruleSetFiles = files(new File(rootDir, "styleguide/pmd-ruleset.xml"))
+    ruleSets = []
+}
diff --git a/third_party/allwpilib_2019/shared/javacpp/publish.gradle b/third_party/allwpilib_2019/shared/javacpp/publish.gradle
new file mode 100644
index 0000000..854a996
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/javacpp/publish.gradle
@@ -0,0 +1,72 @@
+apply plugin: 'maven-publish'
+
+def pubVersion
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def outputsFolder = file("$buildDir/outputs")
+
+def baseArtifactId = nativeName
+def artifactGroupId = "edu.wpi.first.${nativeName}"
+def zipBaseName = "_GROUP_edu_wpi_first_${nativeName}_ID_${nativeName}-cpp_CLS"
+
+def licenseFile = file("$rootDir/license.txt")
+
+task cppSourcesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "sources"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/cpp') {
+        into '/'
+    }
+}
+
+task cppHeadersZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "headers"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/include') {
+        into '/'
+    }
+}
+
+artifacts {
+    archives cppHeadersZip
+    archives cppSourcesZip
+}
+
+addTaskToCopyAllOutputs(cppSourcesZip)
+addTaskToCopyAllOutputs(cppHeadersZip)
+
+model {
+    publishing {
+        def taskList = createComponentZipTasks($.components, [nativeName], zipBaseName, Zip, project, includeStandardZipFormat)
+
+        publications {
+            cpp(MavenPublication) {
+                taskList.each {
+                    artifact it
+                }
+                artifact cppHeadersZip
+                artifact cppSourcesZip
+
+                artifactId = "${baseArtifactId}-cpp"
+                groupId artifactGroupId
+                version pubVersion
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/shared/javacpp/setupBuild.gradle b/third_party/allwpilib_2019/shared/javacpp/setupBuild.gradle
new file mode 100644
index 0000000..d2cdd1d
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/javacpp/setupBuild.gradle
@@ -0,0 +1,153 @@
+apply plugin: 'cpp'
+apply plugin: 'google-test-test-suite'
+apply plugin: 'visual-studio'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: SingleNativeBuild
+apply plugin: ExtraTasks
+
+apply from: "${rootDir}/shared/config.gradle"
+
+ext {
+    baseId = nativeName
+    groupId = "edu.wpi.first.${nativeName}"
+}
+
+apply from: "${rootDir}/shared/java/javacommon.gradle"
+
+project(':').libraryBuild.dependsOn build
+
+ext {
+    staticGtestConfigs = [:]
+}
+
+staticGtestConfigs["${nativeName}Test"] = []
+
+apply from: "${rootDir}/shared/googletest.gradle"
+
+model {
+    components {
+        "${nativeName}Base"(NativeLibrarySpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/main/native/cpp'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include'
+                    }
+                }
+            }
+            binaries.all {
+                if (it instanceof SharedLibraryBinarySpec) {
+                    it.buildable = false
+                    return
+                }
+                if (project.hasProperty('extraSetup')) {
+                    extraSetup(it)
+                }
+            }
+        }
+        "${nativeName}"(NativeLibrarySpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDirs "${rootDir}/shared/singlelib"
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include'
+                    }
+                }
+            }
+            appendDebugPathToBinaries(binaries)
+        }
+        // By default, a development executable will be generated. This is to help the case of
+        // testing specific functionality of the library.
+        "${nativeName}Dev"(NativeExecutableSpec) {
+            targetBuildTypes 'debug'
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/dev/native/cpp'
+                        include '**/*.cpp'
+                        lib library: nativeName
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/dev/native/include'
+                    }
+                }
+            }
+        }
+    }
+    testSuites {
+        "${nativeName}Test"(GoogleTestTestSuiteSpec) {
+            for(NativeComponentSpec c : $.components) {
+                if (c.name == nativeName) {
+                    testing c
+                    break
+                }
+            }
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/test/native/cpp'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/test/native/include', 'src/main/native/cpp'
+                    }
+                }
+            }
+        }
+    }
+    binaries {
+        withType(GoogleTestTestSuiteBinarySpec) {
+            if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+                lib library: nativeName, linkage: 'shared'
+            } else {
+                it.buildable = false
+            }
+        }
+    }
+    tasks {
+        def c = $.components
+        project.tasks.create('runCpp', Exec) {
+            group = 'WPILib'
+            description = "Run the ${nativeName}Dev executable"
+            def found = false
+            def systemArch = getCurrentArch()
+            c.each {
+                if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
+                    it.binaries.each {
+                        if (!found) {
+                            def arch = it.targetPlatform.architecture.name
+                            if (arch == systemArch) {
+                                dependsOn it.tasks.install
+                                commandLine it.tasks.install.runScriptFile.get().asFile.toString()
+                                def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib'
+                                test.dependsOn it.tasks.install
+                                test.systemProperty 'java.library.path', filePath
+                                test.environment 'LD_LIBRARY_PATH', filePath
+                                test.workingDir filePath
+                                run.dependsOn it.tasks.install
+                                run.systemProperty 'java.library.path', filePath
+                                run.environment 'LD_LIBRARY_PATH', filePath
+                                run.workingDir filePath
+
+                                found = true
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+tasks.withType(RunTestExecutable) {
+    args "--gtest_output=xml:test_detail.xml"
+    outputs.dir outputDir
+}
+
+apply from: "${rootDir}/shared/javacpp/publish.gradle"
diff --git a/third_party/allwpilib_2019/shared/jni/publish.gradle b/third_party/allwpilib_2019/shared/jni/publish.gradle
new file mode 100644
index 0000000..a6a1abe
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/jni/publish.gradle
@@ -0,0 +1,130 @@
+import java.security.MessageDigest
+apply plugin: 'maven-publish'
+
+def pubVersion
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def outputsFolder = file("$buildDir/outputs")
+
+def baseArtifactId = nativeName
+def artifactGroupId = "edu.wpi.first.${nativeName}"
+def zipBaseName = "_GROUP_edu_wpi_first_${nativeName}_ID_${nativeName}-cpp_CLS"
+def jniBaseName = "_GROUP_edu_wpi_first_${nativeName}_ID_${nativeName}-jni_CLS"
+
+def licenseFile = file("$rootDir/license.txt")
+
+task cppSourcesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "sources"
+    duplicatesStrategy = 'exclude'
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/cpp') {
+        into '/'
+    }
+
+    model {
+        components {
+            it.all {
+                if (it in getJniSpecClass()) {
+                    it.jniHeaderLocations.each {
+                        dependsOn it.key
+                        from(it.value) {
+                            into '/jni'
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+task cppHeadersZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "headers"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/include') {
+        into '/'
+    }
+}
+
+artifacts {
+    archives cppHeadersZip
+    archives cppSourcesZip
+}
+
+addTaskToCopyAllOutputs(cppSourcesZip)
+addTaskToCopyAllOutputs(cppHeadersZip)
+
+model {
+    publishing {
+        def taskList = createComponentZipTasks($.components, [nativeName, "${nativeName}JNIShared"], zipBaseName, Zip, project, includeStandardZipFormat)
+
+        def jniTaskList = createComponentZipTasks($.components, ["${nativeName}JNI"], jniBaseName, Jar, project, { task, value ->
+            value.each { binary ->
+                if (binary.buildable) {
+                    if (binary instanceof SharedLibraryBinarySpec) {
+                        task.dependsOn binary.tasks.link
+                        def hashFile = new File(binary.sharedLibraryFile.parentFile.absolutePath, "${binary.component.baseName}.hash")
+                        task.outputs.file(hashFile)
+                        task.inputs.file(binary.sharedLibraryFile)
+                        task.from(hashFile) {
+                            into getPlatformPath(binary)
+                        }
+                        task.doFirst {
+                            hashFile.text = MessageDigest.getInstance("MD5").digest(binary.sharedLibraryFile.bytes).encodeHex().toString()
+                        }
+                        task.from(binary.sharedLibraryFile) {
+                            into getPlatformPath(binary)
+                        }
+                    }
+                }
+            }
+        })
+
+        def allJniTask
+        if (!project.hasProperty('jenkinsBuild')) {
+            allJniTask = createAllCombined(jniTaskList, "${nativeName}JNI", jniBaseName, Jar, project)
+        }
+
+        publications {
+            cpp(MavenPublication) {
+                taskList.each {
+                    artifact it
+                }
+                artifact cppHeadersZip
+                artifact cppSourcesZip
+
+                artifactId = "${baseArtifactId}-cpp"
+                groupId artifactGroupId
+                version pubVersion
+            }
+            jni(MavenPublication) {
+                jniTaskList.each {
+                    artifact it
+                }
+
+                if (!project.hasProperty('jenkinsBuild')) {
+                    artifact allJniTask
+                }
+
+                artifactId = "${baseArtifactId}-jni"
+                groupId artifactGroupId
+                version pubVersion
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/shared/jni/setupBuild.gradle b/third_party/allwpilib_2019/shared/jni/setupBuild.gradle
new file mode 100644
index 0000000..a22a67d
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/jni/setupBuild.gradle
@@ -0,0 +1,279 @@
+apply plugin: 'cpp'
+apply plugin: 'google-test-test-suite'
+apply plugin: 'visual-studio'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: 'edu.wpi.first.GradleJni'
+apply plugin: SingleNativeBuild
+apply plugin: ExtraTasks
+
+apply from: "${rootDir}/shared/config.gradle"
+
+ext {
+    baseId = nativeName
+    groupId = "edu.wpi.first.${nativeName}"
+}
+
+apply from: "${rootDir}/shared/java/javacommon.gradle"
+
+dependencies {
+    compile project(':wpiutil')
+    devCompile project(':wpiutil')
+}
+
+project(':').libraryBuild.dependsOn build
+
+ext {
+    staticGtestConfigs = [:]
+}
+
+staticGtestConfigs["${nativeName}Test"] = []
+
+apply from: "${rootDir}/shared/googletest.gradle"
+
+if (project.hasProperty('niLibraries')) {
+    ext {
+        chipObjectComponents = ["$nativeName".toString(), "${nativeName}Dev".toString(), "${nativeName}Base".toString(),
+                                "${nativeName}JNI".toString(), "${nativeName}JNIShared".toString(), "${nativeName}Test".toString()]
+        netCommComponents = ["$nativeName".toString(), "${nativeName}Dev".toString(), "${nativeName}Base".toString(),
+                             "${nativeName}JNI".toString(), "${nativeName}JNIShared".toString(), "${nativeName}Test".toString()]
+        useNiJava = true
+    }
+
+    apply from: "${rootDir}/shared/nilibraries.gradle"
+}
+
+model {
+    components {
+        "${nativeName}Base"(NativeLibrarySpec) {
+            if (project.hasProperty('setBaseName')) {
+                baseName = setBaseName
+            }
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/main/native/cpp'
+                        include '**/*.cpp'
+                        exclude '**/jni/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        if (project.hasProperty('generatedHeaders')) {
+                            srcDir generatedHeaders
+                        }
+                        include '**/*.h'
+                    }
+                }
+            }
+            binaries.all {
+                if (it instanceof SharedLibraryBinarySpec) {
+                    it.buildable = false
+                    return
+                }
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                if (project.hasProperty('splitSetup')) {
+                    splitSetup(it)
+                }
+            }
+        }
+        "${nativeName}"(NativeLibrarySpec) {
+            if (project.hasProperty('setBaseName')) {
+                baseName = setBaseName
+            }
+            sources {
+                cpp {
+                    source {
+                        srcDirs "${rootDir}/shared/singlelib"
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        if (project.hasProperty('generatedHeaders')) {
+                            srcDir generatedHeaders
+                        }
+                    }
+                }
+            }
+            binaries.all {
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            }
+            appendDebugPathToBinaries(binaries)
+        }
+        "${nativeName}JNIShared"(JniNativeLibrarySpec) {
+            if (project.hasProperty('setBaseName')) {
+                baseName = setBaseName + 'jni'
+            } else {
+                baseName = nativeName + 'jni'
+            }
+            enableCheckTask true
+            javaCompileTasks << compileJava
+            jniCrossCompileOptions << JniCrossCompileOptions('athena')
+            jniCrossCompileOptions << JniCrossCompileOptions('raspbian')
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/main/native/cpp'
+                        include '**/jni/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        if (project.hasProperty('generatedHeaders')) {
+                            srcDir generatedHeaders
+                        }
+                        include '**/*.h'
+                    }
+
+                }
+            }
+            binaries.all {
+                if (it instanceof StaticLibraryBinarySpec) {
+                    it.buildable = false
+                    return
+                }
+                lib library: "${nativeName}", linkage: 'shared'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                if (project.hasProperty('jniSplitSetup')) {
+                    jniSplitSetup(it)
+                }
+            }
+        }
+        "${nativeName}JNI"(JniNativeLibrarySpec) {
+            if (project.hasProperty('setBaseName')) {
+                baseName = setBaseName + 'jni'
+            } else {
+                baseName = nativeName + 'jni'
+            }
+            enableCheckTask true
+            javaCompileTasks << compileJava
+            jniCrossCompileOptions << JniCrossCompileOptions('athena')
+            jniCrossCompileOptions << JniCrossCompileOptions('raspbian')
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/main/native/cpp'
+                        include '**/jni/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        if (project.hasProperty('generatedHeaders')) {
+                            srcDir generatedHeaders
+                        }
+                        include '**/*.h'
+                    }
+                }
+            }
+            binaries.all {
+                if (it instanceof StaticLibraryBinarySpec) {
+                    it.buildable = false
+                    return
+                }
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+                if (project.hasProperty('jniSplitSetup')) {
+                    jniSplitSetup(it)
+                }
+            }
+        }
+        // By default, a development executable will be generated. This is to help the case of
+        // testing specific functionality of the library.
+        "${nativeName}Dev"(NativeExecutableSpec) {
+            targetBuildTypes 'debug'
+            sources {
+                cpp {
+
+                    source {
+                        srcDirs 'src/dev/native/cpp'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDir 'src/main/native/include'
+                        if (project.hasProperty('generatedHeaders')) {
+                            srcDir generatedHeaders
+                        }
+                    }
+                }
+            }
+            binaries.all {
+                lib library: nativeName, linkage: 'shared'
+                lib library: "${nativeName}JNIShared", linkage: 'shared'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            }
+        }
+    }
+    testSuites {
+        "${nativeName}Test"(GoogleTestTestSuiteSpec) {
+            for(NativeComponentSpec c : $.components) {
+                if (c.name == nativeName) {
+                    testing c
+                    break
+                }
+            }
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/test/native/cpp'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/test/native/include', 'src/main/native/cpp'
+                        if (project.hasProperty('generatedHeaders')) {
+                            srcDir generatedHeaders
+                        }
+                    }
+                }
+            }
+        }
+    }
+    binaries {
+        withType(GoogleTestTestSuiteBinarySpec) {
+            if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+                lib library: nativeName, linkage: 'shared'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            } else {
+                it.buildable = false
+            }
+        }
+    }
+    tasks {
+        def c = $.components
+        project.tasks.create('runCpp', Exec) {
+            group = 'WPILib'
+            description = "Run the ${nativeName}Dev executable"
+            def found = false
+            def systemArch = getCurrentArch()
+            c.each {
+                if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
+                    it.binaries.each {
+                        if (!found) {
+                            def arch = it.targetPlatform.architecture.name
+                            if (arch == systemArch) {
+                                dependsOn it.tasks.install
+                                commandLine it.tasks.install.runScriptFile.get().asFile.toString()
+                                def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib'
+                                test.dependsOn it.tasks.install
+                                test.systemProperty 'java.library.path', filePath
+                                test.environment 'LD_LIBRARY_PATH', filePath
+                                test.workingDir filePath
+                                run.dependsOn it.tasks.install
+                                run.systemProperty 'java.library.path', filePath
+                                run.environment 'LD_LIBRARY_PATH', filePath
+                                run.workingDir filePath
+
+                                found = true
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+ext.getJniSpecClass = {
+    return JniNativeLibrarySpec
+}
+
+tasks.withType(RunTestExecutable) {
+    args "--gtest_output=xml:test_detail.xml"
+    outputs.dir outputDir
+}
+
+apply from: "${rootDir}/shared/jni/publish.gradle"
diff --git a/third_party/allwpilib_2019/shared/nilibraries.gradle b/third_party/allwpilib_2019/shared/nilibraries.gradle
new file mode 100644
index 0000000..937abbf
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/nilibraries.gradle
@@ -0,0 +1,37 @@
+def netCommLibConfigs = [:];

+def chipObjectConfigs = [:];

+

+project.chipObjectComponents.each { String s->

+  chipObjectConfigs[s] = ['linux:athena']

+}

+

+project.netCommComponents.each { String s->

+  netCommLibConfigs[s] = ['linux:athena']

+}

+

+def niLibrariesVersion = '2019.12.1'

+

+model {

+  dependencyConfigs {

+    chipobject(DependencyConfig) {

+      groupId = 'edu.wpi.first.ni-libraries'

+      artifactId = 'chipobject'

+      headerClassifier = 'headers'

+      ext = 'zip'

+      version = niLibrariesVersion

+      sharedConfigs = chipObjectConfigs

+      staticConfigs = [:]

+      compileOnlyShared = true

+    }

+    netcomm(DependencyConfig) {

+      groupId = 'edu.wpi.first.ni-libraries'

+      artifactId = 'netcomm'

+      headerClassifier = 'headers'

+      ext = 'zip'

+      version = niLibrariesVersion

+      sharedConfigs = netCommLibConfigs

+      staticConfigs = [:]

+      compileOnlyShared = true

+    }

+  }

+}

diff --git a/third_party/allwpilib_2019/shared/opencv.gradle b/third_party/allwpilib_2019/shared/opencv.gradle
new file mode 100644
index 0000000..ee9403c
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/opencv.gradle
@@ -0,0 +1,30 @@
+def opencvVersion = '3.4.4-4'
+
+if (project.hasProperty('useCpp') && project.useCpp) {
+    model {
+        dependencyConfigs {
+            opencv(DependencyConfig) {
+                groupId = 'edu.wpi.first.thirdparty.frc2019.opencv'
+                artifactId = 'opencv-cpp'
+                headerClassifier = 'headers'
+                ext = 'zip'
+                version = opencvVersion
+                sharedConfigs = project.sharedCvConfigs
+                staticConfigs = project.staticCvConfigs
+                linkExcludes = ['**/*java*']
+            }
+        }
+    }
+}
+
+if (project.hasProperty('useJava') && project.useJava) {
+    dependencies {
+        compile "edu.wpi.first.thirdparty.frc2019.opencv:opencv-java:${opencvVersion}"
+        if (!project.hasProperty('skipDev') || !project.skipDev) {
+            devCompile "edu.wpi.first.thirdparty.frc2019.opencv:opencv-java:${opencvVersion}"
+        }
+        if (project.hasProperty('useDocumentation') && project.useDocumentation) {
+            javaSource "edu.wpi.first.thirdparty.frc2019.opencv:opencv-java:${opencvVersion}:sources"
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/shared/plugins/publish.gradle b/third_party/allwpilib_2019/shared/plugins/publish.gradle
new file mode 100644
index 0000000..a9ba538
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/plugins/publish.gradle
@@ -0,0 +1,82 @@
+apply plugin: 'maven-publish'
+
+def pubVersion = ''
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseArtifactId = pluginName
+def artifactGroupId = 'edu.wpi.first.halsim'
+def zipBaseName = "_GROUP_edu_wpi_first_halsim_ID_${pluginName}_CLS"
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task cppSourcesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "sources"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/cpp') {
+        into '/'
+    }
+}
+
+task cppHeadersZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "headers"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/include') {
+        into '/'
+    }
+}
+
+build.dependsOn cppSourcesZip
+build.dependsOn cppHeadersZip
+
+addTaskToCopyAllOutputs(cppSourcesZip)
+addTaskToCopyAllOutputs(cppHeadersZip)
+
+
+model {
+    publishing {
+        def pluginTaskList = createComponentZipTasks($.components, [pluginName], zipBaseName, Zip, project, { task, value ->
+            value.each { binary ->
+                if (binary.buildable) {
+                    if (binary instanceof SharedLibraryBinarySpec) {
+                        task.dependsOn binary.buildTask
+                        task.from(binary.sharedLibraryFile) {
+                            into getPlatformPath(binary) + '/shared'
+                        }
+                    }
+                }
+            }
+        })
+
+        publications {
+            cpp(MavenPublication) {
+                pluginTaskList.each {
+                    artifact it
+                }
+
+                artifact cppHeadersZip
+                artifact cppSourcesZip
+
+
+                artifactId = baseArtifactId
+                groupId artifactGroupId
+                version pubVersion
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/shared/plugins/setupBuild.gradle b/third_party/allwpilib_2019/shared/plugins/setupBuild.gradle
new file mode 100644
index 0000000..ba4c6f0
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/plugins/setupBuild.gradle
@@ -0,0 +1,110 @@
+apply plugin: 'cpp'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: ExtraTasks
+
+ext {
+    chipObjectComponents = ["$pluginName".toString(), "${pluginName}Dev".toString(), "${pluginName}Test".toString()]
+    netCommComponents = ["$pluginName".toString(), "${pluginName}Dev".toString(), "${pluginName}Test".toString()]
+    useNiJava = false
+}
+
+apply from: "${rootDir}/shared/nilibraries.gradle"
+
+if (!project.hasProperty('onlyAthena')) {
+    ext.skipAthena = true
+    apply from: "${rootDir}/shared/config.gradle"
+
+    model {
+        components {
+            "${pluginName}"(NativeLibrarySpec) {
+                sources {
+                    cpp {
+                        source {
+                            srcDirs = ['src/main/native/cpp']
+                            includes = ["**/*.cpp"]
+                        }
+                        exportedHeaders {
+                            srcDirs = ["src/main/native/include"]
+                        }
+                    }
+                }
+                binaries.all {
+                    if (it instanceof StaticLibraryBinarySpec) {
+                        it.buildable = false
+                        return
+                    }
+                    project(':hal').addHalDependency(it, 'shared')
+                    if (project.hasProperty('includeNtCore')) {
+                        lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    }
+                    if (project.hasProperty('includeWpiutil')) {
+                        lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    }
+                }
+                appendDebugPathToBinaries(binaries)
+            }
+            "${pluginName}Dev"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                sources {
+                    cpp {
+                        source {
+                            srcDirs = ['src/dev/native/cpp']
+                            includes = ["**/*.cpp"]
+                        }
+                        exportedHeaders {
+                            srcDirs = ["src/dev/native/include"]
+                        }
+                    }
+                }
+                binaries.all {
+                    if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+                        project(':hal').addHalDependency(it, 'shared')
+                        lib library: pluginName
+                        if (project.hasProperty('includeNtCore')) {
+                            lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                        }
+                        lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    } else {
+                        it.buildable = false
+                    }
+                }
+            }
+        }
+    }
+
+    apply from: "${rootDir}/shared/plugins/publish.gradle"
+}
+
+model {
+    tasks {
+        def c = $.components
+        if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+            project.tasks.create('runCpp', Exec) {
+                group = 'WPILib'
+                description = "Run the ${pluginName}Dev executable"
+                def found = false
+                def systemArch = getCurrentArch()
+                c.each {
+                    if (it in NativeExecutableSpec && it.name == "${pluginName}Dev") {
+                        it.binaries.each {
+                            if (!found) {
+                                def arch = it.targetPlatform.architecture.name
+                                if (arch == systemArch) {
+                                    dependsOn it.tasks.install
+                                    commandLine it.tasks.install.runScriptFile.get().asFile.toString()
+                                    // it.tasks.install.libs.each { lib ->
+                                    //     if (lib.name.contains(pluginName)) {
+                                    //         def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib' + File.separatorChar + lib.name
+                                    //         environment('HALSIM_EXTENSIONS', filePath)
+                                    //     }
+                                    // }
+                                    found = true
+                                }
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/shared/resources.gradle b/third_party/allwpilib_2019/shared/resources.gradle
new file mode 100644
index 0000000..21da736
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/resources.gradle
@@ -0,0 +1,50 @@
+ext.createGenerateResourcesTask = { name, prefix, namespace, project ->
+    def generatedOutputDir = file("$buildDir/generated/$name/cpp")
+
+    def inputDir = file("$projectDir/src/$name/native/resources")
+
+    if (!prefix.isEmpty()) prefix += '_'
+
+    def task = project.tasks.create("generateResources-$name") {
+        outputs.dir generatedOutputDir
+        inputs.dir inputDir
+
+        doLast {
+            generatedOutputDir.mkdirs()
+            inputDir.eachFile { inputFile ->
+                if (inputFile.name.startsWith('.')) return
+                def fileBytes = inputFile.bytes
+                def outputFile = file("$generatedOutputDir/${inputFile.name}.cpp")
+                def funcName = "GetResource_" + inputFile.name.replaceAll('[^a-zA-Z0-9]', '_')
+                outputFile.withWriter { out ->
+                    def inputBytes = inputFile.bytes
+                    out.print '''#include <stddef.h>
+#include <wpi/StringRef.h>
+extern "C" {
+static const unsigned char contents[] = { '''
+
+                    for (int i = 0; i < fileBytes.size(); i++) {
+                        out.print String.format('0x%02x', (int) fileBytes[i] & 0xff)
+                        out.print ', '
+                    }
+                    out.println """};
+const unsigned char* ${prefix}${funcName}(size_t* len) {
+  *len = ${fileBytes.size()};
+  return contents;
+}
+}"""
+                    if (!namespace.isEmpty()) {
+                        out.println "namespace ${namespace} {"
+                    }
+                    out.println """wpi::StringRef ${funcName}() {
+  return wpi::StringRef(reinterpret_cast<const char*>(contents), ${fileBytes.size()});
+}"""
+                    if (!namespace.isEmpty()) {
+                        out.println '}'
+                    }
+                }
+            }
+        }
+    }
+    return task
+}
diff --git a/third_party/allwpilib_2019/shared/singlelib/singlelib.cpp b/third_party/allwpilib_2019/shared/singlelib/singlelib.cpp
new file mode 100644
index 0000000..6c9476a
--- /dev/null
+++ b/third_party/allwpilib_2019/shared/singlelib/singlelib.cpp
@@ -0,0 +1,6 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/README.md b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/README.md
new file mode 100644
index 0000000..4a5a59a
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/README.md
@@ -0,0 +1,45 @@
+Gazebo plugins for FRC
+======================
+
+These plugins enable the use of the Gazebo physics simulator to model robots,
+and then use WPILIB programming libraries to control those simulated robots.
+
+At the present time, this only builds on Linux, and has a fairly complex
+installation process.
+
+You must have the gazebo development packages available on Linux.
+The gradle build system will automatically skip building this directory
+if those requirements are not met.
+
+This command:
+
+    `./gradlew build -PmakeSim`
+
+will force it to attempt to build.
+
+TODO:  The meshes for the models are large, and are not hosted in
+the main allwpilib repository.  An alternate method of hosting
+and using is being built at the time of this commit. You must
+manually locate and copy the the models and world from that
+either into /usr/share/frcgazebo or into build/share/frcgazebo
+in order to use this facility.
+
+Once you have built it, then a command like this:
+
+  `simulation/frc_gazebo_plugins/build/bin/frcgazebo PacGoat2014.world`
+
+should run the Gazebo simulation using our plugins against the
+2014 model, with the PacGoat robot on the field.
+
+The halsim_gazebo simulation library will provide a method for
+running robot code to control a simulated robot.
+
+
+TODO:  Package the plugins more nicely, and then put instructions here.
+
+TODO:  Build and package the plugins for Windows.  The key there is to get gazebo
+working on Windows.  This link was a useful trove of information on Windows/Gazebo
+issues as of September, 2017:
+  https://bitbucket.org/osrf/gazebo/issues/2129/visual-studio-2015-compatibility
+
+Note that the sense remains that this will be difficult at best.
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/build.gradle b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/build.gradle
new file mode 100644
index 0000000..6d3c908
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/build.gradle
@@ -0,0 +1,116 @@
+description = "A set of C++ plugins to interface the FRC Simulator with Gazebo."
+
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: 'cpp'
+apply plugin: "google-test"
+
+ext.skipAthena = true
+ext.skipRaspbian = true
+
+apply from: "${rootDir}/shared/config.gradle"
+
+/* If gz_msgs or gazebo is not available, do not attempt a build */
+def gazebo_version = ""
+def gazebo_cppflags = ""
+def gazebo_linker_args = ""
+
+try {
+    gazebo_version = "pkg-config --modversion gazebo".execute().text.trim()
+    println "Gazebo version is [${gazebo_version}]"
+    gazebo_cppflags = "pkg-config --cflags gazebo".execute().text.split()
+    gazebo_linker_args = "pkg-config --libs gazebo protobuf".execute().text.split()
+} catch(Exception ex) { }
+
+if (!gazebo_version?.trim()) {
+    println "Gazebo development files are not available. (pkg-config --modversion gazebo failed)"
+    if (project.hasProperty("makeSim")) {
+        /* Force the build even though we did not find protobuf. */
+        println "makeSim set. Forcing build - failure likely."
+    }
+    else {
+        ext.skip_frc_plugins = true
+        println "Skipping FRC Plugins."
+    }
+}
+
+evaluationDependsOn(":simulation:gz_msgs")
+def gz_msgs_project = project(":simulation:gz_msgs")
+
+tasks.whenTaskAdded { task ->
+    task.onlyIf { !gz_msgs_project.hasProperty('skip_gz_msgs') && !project.hasProperty('skip_frc_plugins') }
+}
+
+model {
+    components {
+        clock(NativeLibrarySpec)
+        dc_motor(NativeLibrarySpec)
+        encoder(NativeLibrarySpec)
+        gyro(NativeLibrarySpec)
+        limit_switch(NativeLibrarySpec)
+        potentiometer(NativeLibrarySpec)
+        pneumatic_piston(NativeLibrarySpec)
+        rangefinder(NativeLibrarySpec)
+        servo(NativeLibrarySpec)
+        drive_motor(NativeLibrarySpec)
+        all { component ->
+            component.targetBuildTypes 'debug'
+            sources {
+                cpp.lib library:  "${component.name}", linkage: "static"
+            }
+        }
+
+    }
+
+    /* TODO:  Finish writing the test case */
+
+    /* We pass the name of the .so and a .world file to each test */
+    testSuites {
+        all { test->
+            def library_file
+            testedComponent.binaries.withType(SharedLibraryBinarySpec).each { b->
+                library_file = b.sharedLibraryFile
+            }
+
+            tasks.withType(RunTestExecutable) {
+                args library_file, file("src/${baseName}/world/${baseName}.world")
+            }
+        }
+    }
+
+
+    binaries {
+        all {
+            linker.args gazebo_linker_args
+            cppCompiler.args gazebo_cppflags
+            lib project: ":simulation:gz_msgs", library: "gz_msgs", linkage: "static"
+        }
+
+        /* TODO: build only shared object? Figure out why this doesn't work? */
+        withType(StaticLibraryBinarySpec) {
+            buildable = false
+        }
+
+        withType(GoogleTestTestSuiteBinarySpec) {
+
+            /* We currently only have a test for the clock plugin */
+            /* TODO: learn how to add this back to gmock */
+            //if (it.projectScopedName.contains("clockTest")) {
+            //    buildable = true
+            //    project(':gmock').addGmockToLinker(it)
+            //}
+            //else {
+                buildable = false
+            //}
+        }
+    }
+}
+
+task copyScript(type: Copy, group: "FRC Gazebo", description: "Copy the frcgazebo script to the output directory.") {
+    from "scripts"
+    into "$project.buildDir/bin"
+    fileMode 0755
+}
+
+build.dependsOn copyScript
+
+/* TODO:  Publish this library */
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/frc_gazebo_plugins.doxy b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/frc_gazebo_plugins.doxy
new file mode 100644
index 0000000..887c9c1
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/frc_gazebo_plugins.doxy
@@ -0,0 +1,2303 @@
+# Doxyfile 1.8.6
+
+# This file describes the settings to be used by the documentation system
+# doxygen (www.doxygen.org) for a project.
+#
+# All text after a double hash (##) is considered a comment and is placed in
+# front of the TAG it is preceding.
+#
+# All text after a single hash (#) is considered a comment and will be ignored.
+# The format is:
+# TAG = value [value, ...]
+# For lists, items can also be appended using:
+# TAG += value [value, ...]
+# Values that contain spaces should be placed between quotes (\" \").
+
+#---------------------------------------------------------------------------
+# Project related configuration options
+#---------------------------------------------------------------------------
+
+# This tag specifies the encoding used for all characters in the config file
+# that follow. The default is UTF-8 which is also the encoding used for all text
+# before the first occurrence of this tag. Doxygen uses libiconv (or the iconv
+# built into libc) for the transcoding. See http://www.gnu.org/software/libiconv
+# for the list of possible encodings.
+# The default value is: UTF-8.
+
+DOXYFILE_ENCODING      = UTF-8
+
+# The PROJECT_NAME tag is a single word (or a sequence of words surrounded by
+# double-quotes, unless you are using Doxywizard) that should identify the
+# project for which the documentation is generated. This name is used in the
+# title of most generated pages and in a few other places.
+# The default value is: My Project.
+
+PROJECT_NAME           = "FRC Gazebo Plugins"
+
+# The PROJECT_NUMBER tag can be used to enter a project or revision number. This
+# could be handy for archiving the generated documentation or if some version
+# control system is used.
+
+PROJECT_NUMBER         = DEVELOPMENT
+
+# Using the PROJECT_BRIEF tag one can provide an optional one line description
+# for a project that appears at the top of each page and should give viewer a
+# quick idea about the purpose of the project. Keep the description short.
+
+PROJECT_BRIEF          = "Gazebo plugins to enable WPILib to control simulated robots."
+
+# With the PROJECT_LOGO tag one can specify an logo or icon that is included in
+# the documentation. The maximum height of the logo should not exceed 55 pixels
+# and the maximum width should not exceed 200 pixels. Doxygen will copy the logo
+# to the output directory.
+
+PROJECT_LOGO           =
+
+# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) path
+# into which the generated documentation will be written. If a relative path is
+# entered, it will be relative to the location where doxygen was started. If
+# left blank the current directory will be used.
+
+OUTPUT_DIRECTORY       = docs
+
+# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create 4096 sub-
+# directories (in 2 levels) under the output directory of each output format and
+# will distribute the generated files over these directories. Enabling this
+# option can be useful when feeding doxygen a huge amount of source files, where
+# putting all generated files in the same directory would otherwise causes
+# performance problems for the file system.
+# The default value is: NO.
+
+CREATE_SUBDIRS         = NO
+
+# The OUTPUT_LANGUAGE tag is used to specify the language in which all
+# documentation generated by doxygen is written. Doxygen will use this
+# information to generate all constant output in the proper language.
+# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese,
+# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States),
+# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian,
+# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages),
+# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian,
+# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian,
+# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish,
+# Ukrainian and Vietnamese.
+# The default value is: English.
+
+OUTPUT_LANGUAGE        = English
+
+# If the BRIEF_MEMBER_DESC tag is set to YES doxygen will include brief member
+# descriptions after the members that are listed in the file and class
+# documentation (similar to Javadoc). Set to NO to disable this.
+# The default value is: YES.
+
+BRIEF_MEMBER_DESC      = YES
+
+# If the REPEAT_BRIEF tag is set to YES doxygen will prepend the brief
+# description of a member or function before the detailed description
+#
+# Note: If both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the
+# brief descriptions will be completely suppressed.
+# The default value is: YES.
+
+REPEAT_BRIEF           = YES
+
+# This tag implements a quasi-intelligent brief description abbreviator that is
+# used to form the text in various listings. Each string in this list, if found
+# as the leading text of the brief description, will be stripped from the text
+# and the result, after processing the whole list, is used as the annotated
+# text. Otherwise, the brief description is used as-is. If left blank, the
+# following values are used ($name is automatically replaced with the name of
+# the entity):The $name class, The $name widget, The $name file, is, provides,
+# specifies, contains, represents, a, an and the.
+
+ABBREVIATE_BRIEF       =
+
+# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then
+# doxygen will generate a detailed section even if there is only a brief
+# description.
+# The default value is: NO.
+
+ALWAYS_DETAILED_SEC    = NO
+
+# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all
+# inherited members of a class in the documentation of that class as if those
+# members were ordinary class members. Constructors, destructors and assignment
+# operators of the base classes will not be shown.
+# The default value is: NO.
+
+INLINE_INHERITED_MEMB  = NO
+
+# If the FULL_PATH_NAMES tag is set to YES doxygen will prepend the full path
+# before files name in the file list and in the header files. If set to NO the
+# shortest path that makes the file name unique will be used
+# The default value is: YES.
+
+FULL_PATH_NAMES        = YES
+
+# The STRIP_FROM_PATH tag can be used to strip a user-defined part of the path.
+# Stripping is only done if one of the specified strings matches the left-hand
+# part of the path. The tag can be used to show relative paths in the file list.
+# If left blank the directory from which doxygen is run is used as the path to
+# strip.
+#
+# Note that you can specify absolute paths here, but also relative paths, which
+# will be relative from the directory where doxygen is started.
+# This tag requires that the tag FULL_PATH_NAMES is set to YES.
+
+STRIP_FROM_PATH        =
+
+# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of the
+# path mentioned in the documentation of a class, which tells the reader which
+# header file to include in order to use a class. If left blank only the name of
+# the header file containing the class definition is used. Otherwise one should
+# specify the list of include paths that are normally passed to the compiler
+# using the -I flag.
+
+STRIP_FROM_INC_PATH    =
+
+# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter (but
+# less readable) file names. This can be useful is your file systems doesn't
+# support long names like on DOS, Mac, or CD-ROM.
+# The default value is: NO.
+
+SHORT_NAMES            = NO
+
+# If the JAVADOC_AUTOBRIEF tag is set to YES then doxygen will interpret the
+# first line (until the first dot) of a Javadoc-style comment as the brief
+# description. If set to NO, the Javadoc-style will behave just like regular Qt-
+# style comments (thus requiring an explicit @brief command for a brief
+# description.)
+# The default value is: NO.
+
+JAVADOC_AUTOBRIEF      = NO
+
+# If the QT_AUTOBRIEF tag is set to YES then doxygen will interpret the first
+# line (until the first dot) of a Qt-style comment as the brief description. If
+# set to NO, the Qt-style will behave just like regular Qt-style comments (thus
+# requiring an explicit \brief command for a brief description.)
+# The default value is: NO.
+
+QT_AUTOBRIEF           = NO
+
+# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make doxygen treat a
+# multi-line C++ special comment block (i.e. a block of //! or /// comments) as
+# a brief description. This used to be the default behavior. The new default is
+# to treat a multi-line C++ comment block as a detailed description. Set this
+# tag to YES if you prefer the old behavior instead.
+#
+# Note that setting this tag to YES also means that rational rose comments are
+# not recognized any more.
+# The default value is: NO.
+
+MULTILINE_CPP_IS_BRIEF = NO
+
+# If the INHERIT_DOCS tag is set to YES then an undocumented member inherits the
+# documentation from any documented member that it re-implements.
+# The default value is: YES.
+
+INHERIT_DOCS           = YES
+
+# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce a
+# new page for each member. If set to NO, the documentation of a member will be
+# part of the file/class/namespace that contains it.
+# The default value is: NO.
+
+SEPARATE_MEMBER_PAGES  = NO
+
+# The TAB_SIZE tag can be used to set the number of spaces in a tab. Doxygen
+# uses this value to replace tabs by spaces in code fragments.
+# Minimum value: 1, maximum value: 16, default value: 4.
+
+TAB_SIZE               = 4
+
+# This tag can be used to specify a number of aliases that act as commands in
+# the documentation. An alias has the form:
+# name=value
+# For example adding
+# "sideeffect=@par Side Effects:\n"
+# will allow you to put the command \sideeffect (or @sideeffect) in the
+# documentation, which will result in a user-defined paragraph with heading
+# "Side Effects:". You can put \n's in the value part of an alias to insert
+# newlines.
+
+ALIASES                =
+
+# This tag can be used to specify a number of word-keyword mappings (TCL only).
+# A mapping has the form "name=value". For example adding "class=itcl::class"
+# will allow you to use the command class in the itcl::class meaning.
+
+TCL_SUBST              =
+
+# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C sources
+# only. Doxygen will then generate output that is more tailored for C. For
+# instance, some of the names that are used will be different. The list of all
+# members will be omitted, etc.
+# The default value is: NO.
+
+OPTIMIZE_OUTPUT_FOR_C  = NO
+
+# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java or
+# Python sources only. Doxygen will then generate output that is more tailored
+# for that language. For instance, namespaces will be presented as packages,
+# qualified scopes will look different, etc.
+# The default value is: NO.
+
+OPTIMIZE_OUTPUT_JAVA   = NO
+
+# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran
+# sources. Doxygen will then generate output that is tailored for Fortran.
+# The default value is: NO.
+
+OPTIMIZE_FOR_FORTRAN   = NO
+
+# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL
+# sources. Doxygen will then generate output that is tailored for VHDL.
+# The default value is: NO.
+
+OPTIMIZE_OUTPUT_VHDL   = NO
+
+# Doxygen selects the parser to use depending on the extension of the files it
+# parses. With this tag you can assign which parser to use for a given
+# extension. Doxygen has a built-in mapping, but you can override or extend it
+# using this tag. The format is ext=language, where ext is a file extension, and
+# language is one of the parsers supported by doxygen: IDL, Java, Javascript,
+# C#, C, C++, D, PHP, Objective-C, Python, Fortran, VHDL. For instance to make
+# doxygen treat .inc files as Fortran files (default is PHP), and .f files as C
+# (default is Fortran), use: inc=Fortran f=C.
+#
+# Note For files without extension you can use no_extension as a placeholder.
+#
+# Note that for custom extensions you also need to set FILE_PATTERNS otherwise
+# the files are not read by doxygen.
+
+EXTENSION_MAPPING      =
+
+# If the MARKDOWN_SUPPORT tag is enabled then doxygen pre-processes all comments
+# according to the Markdown format, which allows for more readable
+# documentation. See http://daringfireball.net/projects/markdown/ for details.
+# The output of markdown processing is further processed by doxygen, so you can
+# mix doxygen, HTML, and XML commands with Markdown formatting. Disable only in
+# case of backward compatibilities issues.
+# The default value is: YES.
+
+MARKDOWN_SUPPORT       = YES
+
+# When enabled doxygen tries to link words that correspond to documented
+# classes, or namespaces to their corresponding documentation. Such a link can
+# be prevented in individual cases by by putting a % sign in front of the word
+# or globally by setting AUTOLINK_SUPPORT to NO.
+# The default value is: YES.
+
+AUTOLINK_SUPPORT       = YES
+
+# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want
+# to include (a tag file for) the STL sources as input, then you should set this
+# tag to YES in order to let doxygen match functions declarations and
+# definitions whose arguments contain STL classes (e.g. func(std::string);
+# versus func(std::string) {}). This also make the inheritance and collaboration
+# diagrams that involve STL classes more complete and accurate.
+# The default value is: NO.
+
+BUILTIN_STL_SUPPORT    = NO
+
+# If you use Microsoft's C++/CLI language, you should set this option to YES to
+# enable parsing support.
+# The default value is: NO.
+
+CPP_CLI_SUPPORT        = NO
+
+# Set the SIP_SUPPORT tag to YES if your project consists of sip (see:
+# http://www.riverbankcomputing.co.uk/software/sip/intro) sources only. Doxygen
+# will parse them like normal C++ but will assume all classes use public instead
+# of private inheritance when no explicit protection keyword is present.
+# The default value is: NO.
+
+SIP_SUPPORT            = NO
+
+# For Microsoft's IDL there are propget and propput attributes to indicate
+# getter and setter methods for a property. Setting this option to YES will make
+# doxygen to replace the get and set methods by a property in the documentation.
+# This will only work if the methods are indeed getting or setting a simple
+# type. If this is not the case, or you want to show the methods anyway, you
+# should set this option to NO.
+# The default value is: YES.
+
+IDL_PROPERTY_SUPPORT   = YES
+
+# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC
+# tag is set to YES, then doxygen will reuse the documentation of the first
+# member in the group (if any) for the other members of the group. By default
+# all members of a group must be documented explicitly.
+# The default value is: NO.
+
+DISTRIBUTE_GROUP_DOC   = NO
+
+# Set the SUBGROUPING tag to YES to allow class member groups of the same type
+# (for instance a group of public functions) to be put as a subgroup of that
+# type (e.g. under the Public Functions section). Set it to NO to prevent
+# subgrouping. Alternatively, this can be done per class using the
+# \nosubgrouping command.
+# The default value is: YES.
+
+SUBGROUPING            = YES
+
+# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and unions
+# are shown inside the group in which they are included (e.g. using \ingroup)
+# instead of on a separate page (for HTML and Man pages) or section (for LaTeX
+# and RTF).
+#
+# Note that this feature does not work in combination with
+# SEPARATE_MEMBER_PAGES.
+# The default value is: NO.
+
+INLINE_GROUPED_CLASSES = NO
+
+# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and unions
+# with only public data fields or simple typedef fields will be shown inline in
+# the documentation of the scope in which they are defined (i.e. file,
+# namespace, or group documentation), provided this scope is documented. If set
+# to NO, structs, classes, and unions are shown on a separate page (for HTML and
+# Man pages) or section (for LaTeX and RTF).
+# The default value is: NO.
+
+INLINE_SIMPLE_STRUCTS  = NO
+
+# When TYPEDEF_HIDES_STRUCT tag is enabled, a typedef of a struct, union, or
+# enum is documented as struct, union, or enum with the name of the typedef. So
+# typedef struct TypeS {} TypeT, will appear in the documentation as a struct
+# with name TypeT. When disabled the typedef will appear as a member of a file,
+# namespace, or class. And the struct will be named TypeS. This can typically be
+# useful for C code in case the coding convention dictates that all compound
+# types are typedef'ed and only the typedef is referenced, never the tag name.
+# The default value is: NO.
+
+TYPEDEF_HIDES_STRUCT   = NO
+
+# The size of the symbol lookup cache can be set using LOOKUP_CACHE_SIZE. This
+# cache is used to resolve symbols given their name and scope. Since this can be
+# an expensive process and often the same symbol appears multiple times in the
+# code, doxygen keeps a cache of pre-resolved symbols. If the cache is too small
+# doxygen will become slower. If the cache is too large, memory is wasted. The
+# cache size is given by this formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range
+# is 0..9, the default is 0, corresponding to a cache size of 2^16=65536
+# symbols. At the end of a run doxygen will report the cache usage and suggest
+# the optimal cache size from a speed point of view.
+# Minimum value: 0, maximum value: 9, default value: 0.
+
+LOOKUP_CACHE_SIZE      = 0
+
+#---------------------------------------------------------------------------
+# Build related configuration options
+#---------------------------------------------------------------------------
+
+# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in
+# documentation are documented, even if no documentation was available. Private
+# class members and static file members will be hidden unless the
+# EXTRACT_PRIVATE respectively EXTRACT_STATIC tags are set to YES.
+# Note: This will also disable the warnings about undocumented members that are
+# normally produced when WARNINGS is set to YES.
+# The default value is: NO.
+
+EXTRACT_ALL            = NO
+
+# If the EXTRACT_PRIVATE tag is set to YES all private members of a class will
+# be included in the documentation.
+# The default value is: NO.
+
+EXTRACT_PRIVATE        = NO
+
+# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal
+# scope will be included in the documentation.
+# The default value is: NO.
+
+EXTRACT_PACKAGE        = NO
+
+# If the EXTRACT_STATIC tag is set to YES all static members of a file will be
+# included in the documentation.
+# The default value is: NO.
+
+EXTRACT_STATIC         = NO
+
+# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs) defined
+# locally in source files will be included in the documentation. If set to NO
+# only classes defined in header files are included. Does not have any effect
+# for Java sources.
+# The default value is: YES.
+
+EXTRACT_LOCAL_CLASSES  = YES
+
+# This flag is only useful for Objective-C code. When set to YES local methods,
+# which are defined in the implementation section but not in the interface are
+# included in the documentation. If set to NO only methods in the interface are
+# included.
+# The default value is: NO.
+
+EXTRACT_LOCAL_METHODS  = NO
+
+# If this flag is set to YES, the members of anonymous namespaces will be
+# extracted and appear in the documentation as a namespace called
+# 'anonymous_namespace{file}', where file will be replaced with the base name of
+# the file that contains the anonymous namespace. By default anonymous namespace
+# are hidden.
+# The default value is: NO.
+
+EXTRACT_ANON_NSPACES   = NO
+
+# If the HIDE_UNDOC_MEMBERS tag is set to YES, doxygen will hide all
+# undocumented members inside documented classes or files. If set to NO these
+# members will be included in the various overviews, but no documentation
+# section is generated. This option has no effect if EXTRACT_ALL is enabled.
+# The default value is: NO.
+
+HIDE_UNDOC_MEMBERS     = NO
+
+# If the HIDE_UNDOC_CLASSES tag is set to YES, doxygen will hide all
+# undocumented classes that are normally visible in the class hierarchy. If set
+# to NO these classes will be included in the various overviews. This option has
+# no effect if EXTRACT_ALL is enabled.
+# The default value is: NO.
+
+HIDE_UNDOC_CLASSES     = NO
+
+# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, doxygen will hide all friend
+# (class|struct|union) declarations. If set to NO these declarations will be
+# included in the documentation.
+# The default value is: NO.
+
+HIDE_FRIEND_COMPOUNDS  = NO
+
+# If the HIDE_IN_BODY_DOCS tag is set to YES, doxygen will hide any
+# documentation blocks found inside the body of a function. If set to NO these
+# blocks will be appended to the function's detailed documentation block.
+# The default value is: NO.
+
+HIDE_IN_BODY_DOCS      = NO
+
+# The INTERNAL_DOCS tag determines if documentation that is typed after a
+# \internal command is included. If the tag is set to NO then the documentation
+# will be excluded. Set it to YES to include the internal documentation.
+# The default value is: NO.
+
+INTERNAL_DOCS          = NO
+
+# If the CASE_SENSE_NAMES tag is set to NO then doxygen will only generate file
+# names in lower-case letters. If set to YES upper-case letters are also
+# allowed. This is useful if you have classes or files whose names only differ
+# in case and if your file system supports case sensitive file names. Windows
+# and Mac users are advised to set this option to NO.
+# The default value is: system dependent.
+
+CASE_SENSE_NAMES       = YES
+
+# If the HIDE_SCOPE_NAMES tag is set to NO then doxygen will show members with
+# their full class and namespace scopes in the documentation. If set to YES the
+# scope will be hidden.
+# The default value is: NO.
+
+HIDE_SCOPE_NAMES       = NO
+
+# If the SHOW_INCLUDE_FILES tag is set to YES then doxygen will put a list of
+# the files that are included by a file in the documentation of that file.
+# The default value is: YES.
+
+SHOW_INCLUDE_FILES     = YES
+
+# If the SHOW_GROUPED_MEMB_INC tag is set to YES then Doxygen will add for each
+# grouped member an include statement to the documentation, telling the reader
+# which file to include in order to use the member.
+# The default value is: NO.
+
+SHOW_GROUPED_MEMB_INC  = NO
+
+# If the FORCE_LOCAL_INCLUDES tag is set to YES then doxygen will list include
+# files with double quotes in the documentation rather than with sharp brackets.
+# The default value is: NO.
+
+FORCE_LOCAL_INCLUDES   = NO
+
+# If the INLINE_INFO tag is set to YES then a tag [inline] is inserted in the
+# documentation for inline members.
+# The default value is: YES.
+
+INLINE_INFO            = YES
+
+# If the SORT_MEMBER_DOCS tag is set to YES then doxygen will sort the
+# (detailed) documentation of file and class members alphabetically by member
+# name. If set to NO the members will appear in declaration order.
+# The default value is: YES.
+
+SORT_MEMBER_DOCS       = YES
+
+# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the brief
+# descriptions of file, namespace and class members alphabetically by member
+# name. If set to NO the members will appear in declaration order. Note that
+# this will also influence the order of the classes in the class list.
+# The default value is: NO.
+
+SORT_BRIEF_DOCS        = NO
+
+# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen will sort the
+# (brief and detailed) documentation of class members so that constructors and
+# destructors are listed first. If set to NO the constructors will appear in the
+# respective orders defined by SORT_BRIEF_DOCS and SORT_MEMBER_DOCS.
+# Note: If SORT_BRIEF_DOCS is set to NO this option is ignored for sorting brief
+# member documentation.
+# Note: If SORT_MEMBER_DOCS is set to NO this option is ignored for sorting
+# detailed member documentation.
+# The default value is: NO.
+
+SORT_MEMBERS_CTORS_1ST = NO
+
+# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the hierarchy
+# of group names into alphabetical order. If set to NO the group names will
+# appear in their defined order.
+# The default value is: NO.
+
+SORT_GROUP_NAMES       = NO
+
+# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be sorted by
+# fully-qualified names, including namespaces. If set to NO, the class list will
+# be sorted only by class name, not including the namespace part.
+# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES.
+# Note: This option applies only to the class list, not to the alphabetical
+# list.
+# The default value is: NO.
+
+SORT_BY_SCOPE_NAME     = NO
+
+# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to do proper
+# type resolution of all parameters of a function it will reject a match between
+# the prototype and the implementation of a member function even if there is
+# only one candidate or it is obvious which candidate to choose by doing a
+# simple string match. By disabling STRICT_PROTO_MATCHING doxygen will still
+# accept a match between prototype and implementation in such cases.
+# The default value is: NO.
+
+STRICT_PROTO_MATCHING  = NO
+
+# The GENERATE_TODOLIST tag can be used to enable ( YES) or disable ( NO) the
+# todo list. This list is created by putting \todo commands in the
+# documentation.
+# The default value is: YES.
+
+GENERATE_TODOLIST      = YES
+
+# The GENERATE_TESTLIST tag can be used to enable ( YES) or disable ( NO) the
+# test list. This list is created by putting \test commands in the
+# documentation.
+# The default value is: YES.
+
+GENERATE_TESTLIST      = YES
+
+# The GENERATE_BUGLIST tag can be used to enable ( YES) or disable ( NO) the bug
+# list. This list is created by putting \bug commands in the documentation.
+# The default value is: YES.
+
+GENERATE_BUGLIST       = YES
+
+# The GENERATE_DEPRECATEDLIST tag can be used to enable ( YES) or disable ( NO)
+# the deprecated list. This list is created by putting \deprecated commands in
+# the documentation.
+# The default value is: YES.
+
+GENERATE_DEPRECATEDLIST= YES
+
+# The ENABLED_SECTIONS tag can be used to enable conditional documentation
+# sections, marked by \if <section_label> ... \endif and \cond <section_label>
+# ... \endcond blocks.
+
+ENABLED_SECTIONS       =
+
+# The MAX_INITIALIZER_LINES tag determines the maximum number of lines that the
+# initial value of a variable or macro / define can have for it to appear in the
+# documentation. If the initializer consists of more lines than specified here
+# it will be hidden. Use a value of 0 to hide initializers completely. The
+# appearance of the value of individual variables and macros / defines can be
+# controlled using \showinitializer or \hideinitializer command in the
+# documentation regardless of this setting.
+# Minimum value: 0, maximum value: 10000, default value: 30.
+
+MAX_INITIALIZER_LINES  = 30
+
+# Set the SHOW_USED_FILES tag to NO to disable the list of files generated at
+# the bottom of the documentation of classes and structs. If set to YES the list
+# will mention the files that were used to generate the documentation.
+# The default value is: YES.
+
+SHOW_USED_FILES        = YES
+
+# Set the SHOW_FILES tag to NO to disable the generation of the Files page. This
+# will remove the Files entry from the Quick Index and from the Folder Tree View
+# (if specified).
+# The default value is: YES.
+
+SHOW_FILES             = YES
+
+# Set the SHOW_NAMESPACES tag to NO to disable the generation of the Namespaces
+# page. This will remove the Namespaces entry from the Quick Index and from the
+# Folder Tree View (if specified).
+# The default value is: YES.
+
+SHOW_NAMESPACES        = YES
+
+# The FILE_VERSION_FILTER tag can be used to specify a program or script that
+# doxygen should invoke to get the current version for each file (typically from
+# the version control system). Doxygen will invoke the program by executing (via
+# popen()) the command command input-file, where command is the value of the
+# FILE_VERSION_FILTER tag, and input-file is the name of an input file provided
+# by doxygen. Whatever the program writes to standard output is used as the file
+# version. For an example see the documentation.
+
+FILE_VERSION_FILTER    =
+
+# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed
+# by doxygen. The layout file controls the global structure of the generated
+# output files in an output format independent way. To create the layout file
+# that represents doxygen's defaults, run doxygen with the -l option. You can
+# optionally specify a file name after the option, if omitted DoxygenLayout.xml
+# will be used as the name of the layout file.
+#
+# Note that if you run doxygen from a directory containing a file called
+# DoxygenLayout.xml, doxygen will parse it automatically even if the LAYOUT_FILE
+# tag is left empty.
+
+LAYOUT_FILE            =
+
+# The CITE_BIB_FILES tag can be used to specify one or more bib files containing
+# the reference definitions. This must be a list of .bib files. The .bib
+# extension is automatically appended if omitted. This requires the bibtex tool
+# to be installed. See also http://en.wikipedia.org/wiki/BibTeX for more info.
+# For LaTeX the style of the bibliography can be controlled using
+# LATEX_BIB_STYLE. To use this feature you need bibtex and perl available in the
+# search path. Do not use file names with spaces, bibtex cannot handle them. See
+# also \cite for info how to create references.
+
+CITE_BIB_FILES         =
+
+#---------------------------------------------------------------------------
+# Configuration options related to warning and progress messages
+#---------------------------------------------------------------------------
+
+# The QUIET tag can be used to turn on/off the messages that are generated to
+# standard output by doxygen. If QUIET is set to YES this implies that the
+# messages are off.
+# The default value is: NO.
+
+QUIET                  = NO
+
+# The WARNINGS tag can be used to turn on/off the warning messages that are
+# generated to standard error ( stderr) by doxygen. If WARNINGS is set to YES
+# this implies that the warnings are on.
+#
+# Tip: Turn warnings on while writing the documentation.
+# The default value is: YES.
+
+WARNINGS               = YES
+
+# If the WARN_IF_UNDOCUMENTED tag is set to YES, then doxygen will generate
+# warnings for undocumented members. If EXTRACT_ALL is set to YES then this flag
+# will automatically be disabled.
+# The default value is: YES.
+
+WARN_IF_UNDOCUMENTED   = YES
+
+# If the WARN_IF_DOC_ERROR tag is set to YES, doxygen will generate warnings for
+# potential errors in the documentation, such as not documenting some parameters
+# in a documented function, or documenting parameters that don't exist or using
+# markup commands wrongly.
+# The default value is: YES.
+
+WARN_IF_DOC_ERROR      = YES
+
+# This WARN_NO_PARAMDOC option can be enabled to get warnings for functions that
+# are documented, but have no documentation for their parameters or return
+# value. If set to NO doxygen will only warn about wrong or incomplete parameter
+# documentation, but not about the absence of documentation.
+# The default value is: NO.
+
+WARN_NO_PARAMDOC       = NO
+
+# The WARN_FORMAT tag determines the format of the warning messages that doxygen
+# can produce. The string should contain the $file, $line, and $text tags, which
+# will be replaced by the file and line number from which the warning originated
+# and the warning text. Optionally the format may contain $version, which will
+# be replaced by the version of the file (if it could be obtained via
+# FILE_VERSION_FILTER)
+# The default value is: $file:$line: $text.
+
+WARN_FORMAT            = "$file:$line: $text"
+
+# The WARN_LOGFILE tag can be used to specify a file to which warning and error
+# messages should be written. If left blank the output is written to standard
+# error (stderr).
+
+WARN_LOGFILE           =
+
+#---------------------------------------------------------------------------
+# Configuration options related to the input files
+#---------------------------------------------------------------------------
+
+# The INPUT tag is used to specify the files and/or directories that contain
+# documented source files. You may enter file names like myfile.cpp or
+# directories like /usr/src/myproject. Separate the files or directories with
+# spaces.
+# Note: If this tag is empty the current directory is searched.
+
+INPUT                  =
+
+# This tag can be used to specify the character encoding of the source files
+# that doxygen parses. Internally doxygen uses the UTF-8 encoding. Doxygen uses
+# libiconv (or the iconv built into libc) for the transcoding. See the libiconv
+# documentation (see: http://www.gnu.org/software/libiconv) for the list of
+# possible encodings.
+# The default value is: UTF-8.
+
+INPUT_ENCODING         = UTF-8
+
+# If the value of the INPUT tag contains directories, you can use the
+# FILE_PATTERNS tag to specify one or more wildcard patterns (like *.cpp and
+# *.h) to filter out the source-files in the directories. If left blank the
+# following patterns are tested:*.c, *.cc, *.cxx, *.cpp, *.c++, *.java, *.ii,
+# *.ixx, *.ipp, *.i++, *.inl, *.idl, *.ddl, *.odl, *.h, *.hh, *.hxx, *.hpp,
+# *.h++, *.cs, *.d, *.php, *.php4, *.php5, *.phtml, *.inc, *.m, *.markdown,
+# *.md, *.mm, *.dox, *.py, *.f90, *.f, *.for, *.tcl, *.vhd, *.vhdl, *.ucf,
+# *.qsf, *.as and *.js.
+
+FILE_PATTERNS          =
+
+# The RECURSIVE tag can be used to specify whether or not subdirectories should
+# be searched for input files as well.
+# The default value is: NO.
+
+RECURSIVE              = YES
+
+# The EXCLUDE tag can be used to specify files and/or directories that should be
+# excluded from the INPUT source files. This way you can easily exclude a
+# subdirectory from a directory tree whose root is specified with the INPUT tag.
+#
+# Note that relative paths are relative to the directory from which doxygen is
+# run.
+
+EXCLUDE                =
+
+# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or
+# directories that are symbolic links (a Unix file system feature) are excluded
+# from the input.
+# The default value is: NO.
+
+EXCLUDE_SYMLINKS       = NO
+
+# If the value of the INPUT tag contains directories, you can use the
+# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude
+# certain files from those directories.
+#
+# Note that the wildcards are matched against the file with absolute path, so to
+# exclude all test directories for example use the pattern */test/*
+
+EXCLUDE_PATTERNS       =
+
+# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names
+# (namespaces, classes, functions, etc.) that should be excluded from the
+# output. The symbol name can be a fully qualified name, a word, or if the
+# wildcard * is used, a substring. Examples: ANamespace, AClass,
+# AClass::ANamespace, ANamespace::*Test
+#
+# Note that the wildcards are matched against the file with absolute path, so to
+# exclude all test directories use the pattern */test/*
+
+EXCLUDE_SYMBOLS        =
+
+# The EXAMPLE_PATH tag can be used to specify one or more files or directories
+# that contain example code fragments that are included (see the \include
+# command).
+
+EXAMPLE_PATH           =
+
+# If the value of the EXAMPLE_PATH tag contains directories, you can use the
+# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp and
+# *.h) to filter out the source-files in the directories. If left blank all
+# files are included.
+
+EXAMPLE_PATTERNS       =
+
+# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be
+# searched for input files to be used with the \include or \dontinclude commands
+# irrespective of the value of the RECURSIVE tag.
+# The default value is: NO.
+
+EXAMPLE_RECURSIVE      = NO
+
+# The IMAGE_PATH tag can be used to specify one or more files or directories
+# that contain images that are to be included in the documentation (see the
+# \image command).
+
+IMAGE_PATH             =
+
+# The INPUT_FILTER tag can be used to specify a program that doxygen should
+# invoke to filter for each input file. Doxygen will invoke the filter program
+# by executing (via popen()) the command:
+#
+# <filter> <input-file>
+#
+# where <filter> is the value of the INPUT_FILTER tag, and <input-file> is the
+# name of an input file. Doxygen will then use the output that the filter
+# program writes to standard output. If FILTER_PATTERNS is specified, this tag
+# will be ignored.
+#
+# Note that the filter must not add or remove lines; it is applied before the
+# code is scanned, but not when the output code is generated. If lines are added
+# or removed, the anchors will not be placed correctly.
+
+INPUT_FILTER           =
+
+# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern
+# basis. Doxygen will compare the file name with each pattern and apply the
+# filter if there is a match. The filters are a list of the form: pattern=filter
+# (like *.cpp=my_cpp_filter). See INPUT_FILTER for further information on how
+# filters are used. If the FILTER_PATTERNS tag is empty or if none of the
+# patterns match the file name, INPUT_FILTER is applied.
+
+FILTER_PATTERNS        =
+
+# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using
+# INPUT_FILTER ) will also be used to filter the input files that are used for
+# producing the source files to browse (i.e. when SOURCE_BROWSER is set to YES).
+# The default value is: NO.
+
+FILTER_SOURCE_FILES    = NO
+
+# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file
+# pattern. A pattern will override the setting for FILTER_PATTERN (if any) and
+# it is also possible to disable source filtering for a specific pattern using
+# *.ext= (so without naming a filter).
+# This tag requires that the tag FILTER_SOURCE_FILES is set to YES.
+
+FILTER_SOURCE_PATTERNS =
+
+# If the USE_MDFILE_AS_MAINPAGE tag refers to the name of a markdown file that
+# is part of the input, its contents will be placed on the main page
+# (index.html). This can be useful if you have a project on for instance GitHub
+# and want to reuse the introduction page also for the doxygen output.
+
+USE_MDFILE_AS_MAINPAGE =
+
+#---------------------------------------------------------------------------
+# Configuration options related to source browsing
+#---------------------------------------------------------------------------
+
+# If the SOURCE_BROWSER tag is set to YES then a list of source files will be
+# generated. Documented entities will be cross-referenced with these sources.
+#
+# Note: To get rid of all source code in the generated output, make sure that
+# also VERBATIM_HEADERS is set to NO.
+# The default value is: NO.
+
+SOURCE_BROWSER         = NO
+
+# Setting the INLINE_SOURCES tag to YES will include the body of functions,
+# classes and enums directly into the documentation.
+# The default value is: NO.
+
+INLINE_SOURCES         = NO
+
+# Setting the STRIP_CODE_COMMENTS tag to YES will instruct doxygen to hide any
+# special comment blocks from generated source code fragments. Normal C, C++ and
+# Fortran comments will always remain visible.
+# The default value is: YES.
+
+STRIP_CODE_COMMENTS    = YES
+
+# If the REFERENCED_BY_RELATION tag is set to YES then for each documented
+# function all documented functions referencing it will be listed.
+# The default value is: NO.
+
+REFERENCED_BY_RELATION = NO
+
+# If the REFERENCES_RELATION tag is set to YES then for each documented function
+# all documented entities called/used by that function will be listed.
+# The default value is: NO.
+
+REFERENCES_RELATION    = NO
+
+# If the REFERENCES_LINK_SOURCE tag is set to YES and SOURCE_BROWSER tag is set
+# to YES, then the hyperlinks from functions in REFERENCES_RELATION and
+# REFERENCED_BY_RELATION lists will link to the source code. Otherwise they will
+# link to the documentation.
+# The default value is: YES.
+
+REFERENCES_LINK_SOURCE = YES
+
+# If SOURCE_TOOLTIPS is enabled (the default) then hovering a hyperlink in the
+# source code will show a tooltip with additional information such as prototype,
+# brief description and links to the definition and documentation. Since this
+# will make the HTML file larger and loading of large files a bit slower, you
+# can opt to disable this feature.
+# The default value is: YES.
+# This tag requires that the tag SOURCE_BROWSER is set to YES.
+
+SOURCE_TOOLTIPS        = YES
+
+# If the USE_HTAGS tag is set to YES then the references to source code will
+# point to the HTML generated by the htags(1) tool instead of doxygen built-in
+# source browser. The htags tool is part of GNU's global source tagging system
+# (see http://www.gnu.org/software/global/global.html). You will need version
+# 4.8.6 or higher.
+#
+# To use it do the following:
+# - Install the latest version of global
+# - Enable SOURCE_BROWSER and USE_HTAGS in the config file
+# - Make sure the INPUT points to the root of the source tree
+# - Run doxygen as normal
+#
+# Doxygen will invoke htags (and that will in turn invoke gtags), so these
+# tools must be available from the command line (i.e. in the search path).
+#
+# The result: instead of the source browser generated by doxygen, the links to
+# source code will now point to the output of htags.
+# The default value is: NO.
+# This tag requires that the tag SOURCE_BROWSER is set to YES.
+
+USE_HTAGS              = NO
+
+# If the VERBATIM_HEADERS tag is set the YES then doxygen will generate a
+# verbatim copy of the header file for each class for which an include is
+# specified. Set to NO to disable this.
+# See also: Section \class.
+# The default value is: YES.
+
+VERBATIM_HEADERS       = YES
+
+#---------------------------------------------------------------------------
+# Configuration options related to the alphabetical class index
+#---------------------------------------------------------------------------
+
+# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index of all
+# compounds will be generated. Enable this if the project contains a lot of
+# classes, structs, unions or interfaces.
+# The default value is: YES.
+
+ALPHABETICAL_INDEX     = YES
+
+# The COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns in
+# which the alphabetical index list will be split.
+# Minimum value: 1, maximum value: 20, default value: 5.
+# This tag requires that the tag ALPHABETICAL_INDEX is set to YES.
+
+COLS_IN_ALPHA_INDEX    = 5
+
+# In case all classes in a project start with a common prefix, all classes will
+# be put under the same header in the alphabetical index. The IGNORE_PREFIX tag
+# can be used to specify a prefix (or a list of prefixes) that should be ignored
+# while generating the index headers.
+# This tag requires that the tag ALPHABETICAL_INDEX is set to YES.
+
+IGNORE_PREFIX          =
+
+#---------------------------------------------------------------------------
+# Configuration options related to the HTML output
+#---------------------------------------------------------------------------
+
+# If the GENERATE_HTML tag is set to YES doxygen will generate HTML output
+# The default value is: YES.
+
+GENERATE_HTML          = YES
+
+# The HTML_OUTPUT tag is used to specify where the HTML docs will be put. If a
+# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
+# it.
+# The default directory is: html.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_OUTPUT            = html
+
+# The HTML_FILE_EXTENSION tag can be used to specify the file extension for each
+# generated HTML page (for example: .htm, .php, .asp).
+# The default value is: .html.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_FILE_EXTENSION    = .html
+
+# The HTML_HEADER tag can be used to specify a user-defined HTML header file for
+# each generated HTML page. If the tag is left blank doxygen will generate a
+# standard header.
+#
+# To get valid HTML the header file that includes any scripts and style sheets
+# that doxygen needs, which is dependent on the configuration options used (e.g.
+# the setting GENERATE_TREEVIEW). It is highly recommended to start with a
+# default header using
+# doxygen -w html new_header.html new_footer.html new_stylesheet.css
+# YourConfigFile
+# and then modify the file new_header.html. See also section "Doxygen usage"
+# for information on how to generate the default header that doxygen normally
+# uses.
+# Note: The header is subject to change so you typically have to regenerate the
+# default header when upgrading to a newer version of doxygen. For a description
+# of the possible markers and block names see the documentation.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_HEADER            =
+
+# The HTML_FOOTER tag can be used to specify a user-defined HTML footer for each
+# generated HTML page. If the tag is left blank doxygen will generate a standard
+# footer. See HTML_HEADER for more information on how to generate a default
+# footer and what special commands can be used inside the footer. See also
+# section "Doxygen usage" for information on how to generate the default footer
+# that doxygen normally uses.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_FOOTER            =
+
+# The HTML_STYLESHEET tag can be used to specify a user-defined cascading style
+# sheet that is used by each HTML page. It can be used to fine-tune the look of
+# the HTML output. If left blank doxygen will generate a default style sheet.
+# See also section "Doxygen usage" for information on how to generate the style
+# sheet that doxygen normally uses.
+# Note: It is recommended to use HTML_EXTRA_STYLESHEET instead of this tag, as
+# it is more robust and this tag (HTML_STYLESHEET) will in the future become
+# obsolete.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_STYLESHEET        =
+
+# The HTML_EXTRA_STYLESHEET tag can be used to specify an additional user-
+# defined cascading style sheet that is included after the standard style sheets
+# created by doxygen. Using this option one can overrule certain style aspects.
+# This is preferred over using HTML_STYLESHEET since it does not replace the
+# standard style sheet and is therefor more robust against future updates.
+# Doxygen will copy the style sheet file to the output directory. For an example
+# see the documentation.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_EXTRA_STYLESHEET  =
+
+# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or
+# other source files which should be copied to the HTML output directory. Note
+# that these files will be copied to the base HTML output directory. Use the
+# $relpath^ marker in the HTML_HEADER and/or HTML_FOOTER files to load these
+# files. In the HTML_STYLESHEET file, use the file name only. Also note that the
+# files will be copied as-is; there are no commands or markers available.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_EXTRA_FILES       =
+
+# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output. Doxygen
+# will adjust the colors in the stylesheet and background images according to
+# this color. Hue is specified as an angle on a colorwheel, see
+# http://en.wikipedia.org/wiki/Hue for more information. For instance the value
+# 0 represents red, 60 is yellow, 120 is green, 180 is cyan, 240 is blue, 300
+# purple, and 360 is red again.
+# Minimum value: 0, maximum value: 359, default value: 220.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_COLORSTYLE_HUE    = 220
+
+# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of the colors
+# in the HTML output. For a value of 0 the output will use grayscales only. A
+# value of 255 will produce the most vivid colors.
+# Minimum value: 0, maximum value: 255, default value: 100.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_COLORSTYLE_SAT    = 100
+
+# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to the
+# luminance component of the colors in the HTML output. Values below 100
+# gradually make the output lighter, whereas values above 100 make the output
+# darker. The value divided by 100 is the actual gamma applied, so 80 represents
+# a gamma of 0.8, The value 220 represents a gamma of 2.2, and 100 does not
+# change the gamma.
+# Minimum value: 40, maximum value: 240, default value: 80.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_COLORSTYLE_GAMMA  = 80
+
+# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML
+# page will contain the date and time when the page was generated. Setting this
+# to NO can help when comparing the output of multiple runs.
+# The default value is: YES.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_TIMESTAMP         = YES
+
+# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML
+# documentation will contain sections that can be hidden and shown after the
+# page has loaded.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_DYNAMIC_SECTIONS  = NO
+
+# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of entries
+# shown in the various tree structured indices initially; the user can expand
+# and collapse entries dynamically later on. Doxygen will expand the tree to
+# such a level that at most the specified number of entries are visible (unless
+# a fully collapsed tree already exceeds this amount). So setting the number of
+# entries 1 will produce a full collapsed tree by default. 0 is a special value
+# representing an infinite number of entries and will result in a full expanded
+# tree by default.
+# Minimum value: 0, maximum value: 9999, default value: 100.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+HTML_INDEX_NUM_ENTRIES = 100
+
+# If the GENERATE_DOCSET tag is set to YES, additional index files will be
+# generated that can be used as input for Apple's Xcode 3 integrated development
+# environment (see: http://developer.apple.com/tools/xcode/), introduced with
+# OSX 10.5 (Leopard). To create a documentation set, doxygen will generate a
+# Makefile in the HTML output directory. Running make will produce the docset in
+# that directory and running make install will install the docset in
+# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find it at
+# startup. See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html
+# for more information.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+GENERATE_DOCSET        = NO
+
+# This tag determines the name of the docset feed. A documentation feed provides
+# an umbrella under which multiple documentation sets from a single provider
+# (such as a company or product suite) can be grouped.
+# The default value is: Doxygen generated docs.
+# This tag requires that the tag GENERATE_DOCSET is set to YES.
+
+DOCSET_FEEDNAME        = "Doxygen generated docs"
+
+# This tag specifies a string that should uniquely identify the documentation
+# set bundle. This should be a reverse domain-name style string, e.g.
+# com.mycompany.MyDocSet. Doxygen will append .docset to the name.
+# The default value is: org.doxygen.Project.
+# This tag requires that the tag GENERATE_DOCSET is set to YES.
+
+DOCSET_BUNDLE_ID       = org.doxygen.Project
+
+# The DOCSET_PUBLISHER_ID tag specifies a string that should uniquely identify
+# the documentation publisher. This should be a reverse domain-name style
+# string, e.g. com.mycompany.MyDocSet.documentation.
+# The default value is: org.doxygen.Publisher.
+# This tag requires that the tag GENERATE_DOCSET is set to YES.
+
+DOCSET_PUBLISHER_ID    = org.doxygen.Publisher
+
+# The DOCSET_PUBLISHER_NAME tag identifies the documentation publisher.
+# The default value is: Publisher.
+# This tag requires that the tag GENERATE_DOCSET is set to YES.
+
+DOCSET_PUBLISHER_NAME  = Publisher
+
+# If the GENERATE_HTMLHELP tag is set to YES then doxygen generates three
+# additional HTML index files: index.hhp, index.hhc, and index.hhk. The
+# index.hhp is a project file that can be read by Microsoft's HTML Help Workshop
+# (see: http://www.microsoft.com/en-us/download/details.aspx?id=21138) on
+# Windows.
+#
+# The HTML Help Workshop contains a compiler that can convert all HTML output
+# generated by doxygen into a single compiled HTML file (.chm). Compiled HTML
+# files are now used as the Windows 98 help format, and will replace the old
+# Windows help format (.hlp) on all Windows platforms in the future. Compressed
+# HTML files also contain an index, a table of contents, and you can search for
+# words in the documentation. The HTML workshop also contains a viewer for
+# compressed HTML files.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+GENERATE_HTMLHELP      = NO
+
+# The CHM_FILE tag can be used to specify the file name of the resulting .chm
+# file. You can add a path in front of the file if the result should not be
+# written to the html output directory.
+# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
+
+CHM_FILE               =
+
+# The HHC_LOCATION tag can be used to specify the location (absolute path
+# including file name) of the HTML help compiler ( hhc.exe). If non-empty
+# doxygen will try to run the HTML help compiler on the generated index.hhp.
+# The file has to be specified with full path.
+# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
+
+HHC_LOCATION           =
+
+# The GENERATE_CHI flag controls if a separate .chi index file is generated (
+# YES) or that it should be included in the master .chm file ( NO).
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
+
+GENERATE_CHI           = NO
+
+# The CHM_INDEX_ENCODING is used to encode HtmlHelp index ( hhk), content ( hhc)
+# and project file content.
+# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
+
+CHM_INDEX_ENCODING     =
+
+# The BINARY_TOC flag controls whether a binary table of contents is generated (
+# YES) or a normal table of contents ( NO) in the .chm file.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
+
+BINARY_TOC             = NO
+
+# The TOC_EXPAND flag can be set to YES to add extra items for group members to
+# the table of contents of the HTML help documentation and to the tree view.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTMLHELP is set to YES.
+
+TOC_EXPAND             = NO
+
+# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and
+# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated that
+# can be used as input for Qt's qhelpgenerator to generate a Qt Compressed Help
+# (.qch) of the generated HTML documentation.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+GENERATE_QHP           = NO
+
+# If the QHG_LOCATION tag is specified, the QCH_FILE tag can be used to specify
+# the file name of the resulting .qch file. The path specified is relative to
+# the HTML output folder.
+# This tag requires that the tag GENERATE_QHP is set to YES.
+
+QCH_FILE               =
+
+# The QHP_NAMESPACE tag specifies the namespace to use when generating Qt Help
+# Project output. For more information please see Qt Help Project / Namespace
+# (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#namespace).
+# The default value is: org.doxygen.Project.
+# This tag requires that the tag GENERATE_QHP is set to YES.
+
+QHP_NAMESPACE          = org.doxygen.Project
+
+# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating Qt
+# Help Project output. For more information please see Qt Help Project / Virtual
+# Folders (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#virtual-
+# folders).
+# The default value is: doc.
+# This tag requires that the tag GENERATE_QHP is set to YES.
+
+QHP_VIRTUAL_FOLDER     = doc
+
+# If the QHP_CUST_FILTER_NAME tag is set, it specifies the name of a custom
+# filter to add. For more information please see Qt Help Project / Custom
+# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom-
+# filters).
+# This tag requires that the tag GENERATE_QHP is set to YES.
+
+QHP_CUST_FILTER_NAME   =
+
+# The QHP_CUST_FILTER_ATTRS tag specifies the list of the attributes of the
+# custom filter to add. For more information please see Qt Help Project / Custom
+# Filters (see: http://qt-project.org/doc/qt-4.8/qthelpproject.html#custom-
+# filters).
+# This tag requires that the tag GENERATE_QHP is set to YES.
+
+QHP_CUST_FILTER_ATTRS  =
+
+# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this
+# project's filter section matches. Qt Help Project / Filter Attributes (see:
+# http://qt-project.org/doc/qt-4.8/qthelpproject.html#filter-attributes).
+# This tag requires that the tag GENERATE_QHP is set to YES.
+
+QHP_SECT_FILTER_ATTRS  =
+
+# The QHG_LOCATION tag can be used to specify the location of Qt's
+# qhelpgenerator. If non-empty doxygen will try to run qhelpgenerator on the
+# generated .qhp file.
+# This tag requires that the tag GENERATE_QHP is set to YES.
+
+QHG_LOCATION           =
+
+# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files will be
+# generated, together with the HTML files, they form an Eclipse help plugin. To
+# install this plugin and make it available under the help contents menu in
+# Eclipse, the contents of the directory containing the HTML and XML files needs
+# to be copied into the plugins directory of eclipse. The name of the directory
+# within the plugins directory should be the same as the ECLIPSE_DOC_ID value.
+# After copying Eclipse needs to be restarted before the help appears.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+GENERATE_ECLIPSEHELP   = NO
+
+# A unique identifier for the Eclipse help plugin. When installing the plugin
+# the directory name containing the HTML and XML files should also have this
+# name. Each documentation set should have its own identifier.
+# The default value is: org.doxygen.Project.
+# This tag requires that the tag GENERATE_ECLIPSEHELP is set to YES.
+
+ECLIPSE_DOC_ID         = org.doxygen.Project
+
+# If you want full control over the layout of the generated HTML pages it might
+# be necessary to disable the index and replace it with your own. The
+# DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs) at top
+# of each HTML page. A value of NO enables the index and the value YES disables
+# it. Since the tabs in the index contain the same information as the navigation
+# tree, you can set this option to YES if you also set GENERATE_TREEVIEW to YES.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+DISABLE_INDEX          = YES
+
+# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index
+# structure should be generated to display hierarchical information. If the tag
+# value is set to YES, a side panel will be generated containing a tree-like
+# index structure (just like the one that is generated for HTML Help). For this
+# to work a browser that supports JavaScript, DHTML, CSS and frames is required
+# (i.e. any modern browser). Windows users are probably better off using the
+# HTML help feature. Via custom stylesheets (see HTML_EXTRA_STYLESHEET) one can
+# further fine-tune the look of the index. As an example, the default style
+# sheet generated by doxygen has an example that shows how to put an image at
+# the root of the tree instead of the PROJECT_NAME. Since the tree basically has
+# the same information as the tab index, you could consider setting
+# DISABLE_INDEX to YES when enabling this option.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+GENERATE_TREEVIEW      = YES
+
+# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values that
+# doxygen will group on one line in the generated HTML documentation.
+#
+# Note that a value of 0 will completely suppress the enum values from appearing
+# in the overview section.
+# Minimum value: 0, maximum value: 20, default value: 4.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+ENUM_VALUES_PER_LINE   = 4
+
+# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be used
+# to set the initial width (in pixels) of the frame in which the tree is shown.
+# Minimum value: 0, maximum value: 1500, default value: 250.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+TREEVIEW_WIDTH         = 250
+
+# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open links to
+# external symbols imported via tag files in a separate window.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+EXT_LINKS_IN_WINDOW    = NO
+
+# Use this tag to change the font size of LaTeX formulas included as images in
+# the HTML documentation. When you change the font size after a successful
+# doxygen run you need to manually remove any form_*.png images from the HTML
+# output directory to force them to be regenerated.
+# Minimum value: 8, maximum value: 50, default value: 10.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+FORMULA_FONTSIZE       = 10
+
+# Use the FORMULA_TRANPARENT tag to determine whether or not the images
+# generated for formulas are transparent PNGs. Transparent PNGs are not
+# supported properly for IE 6.0, but are supported on all modern browsers.
+#
+# Note that when changing this option you need to delete any form_*.png files in
+# the HTML output directory before the changes have effect.
+# The default value is: YES.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+FORMULA_TRANSPARENT    = YES
+
+# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax (see
+# http://www.mathjax.org) which uses client side Javascript for the rendering
+# instead of using prerendered bitmaps. Use this if you do not have LaTeX
+# installed or if you want to formulas look prettier in the HTML output. When
+# enabled you may also need to install MathJax separately and configure the path
+# to it using the MATHJAX_RELPATH option.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+USE_MATHJAX            = NO
+
+# When MathJax is enabled you can set the default output format to be used for
+# the MathJax output. See the MathJax site (see:
+# http://docs.mathjax.org/en/latest/output.html) for more details.
+# Possible values are: HTML-CSS (which is slower, but has the best
+# compatibility), NativeMML (i.e. MathML) and SVG.
+# The default value is: HTML-CSS.
+# This tag requires that the tag USE_MATHJAX is set to YES.
+
+MATHJAX_FORMAT         = HTML-CSS
+
+# When MathJax is enabled you need to specify the location relative to the HTML
+# output directory using the MATHJAX_RELPATH option. The destination directory
+# should contain the MathJax.js script. For instance, if the mathjax directory
+# is located at the same level as the HTML output directory, then
+# MATHJAX_RELPATH should be ../mathjax. The default value points to the MathJax
+# Content Delivery Network so you can quickly see the result without installing
+# MathJax. However, it is strongly recommended to install a local copy of
+# MathJax from http://www.mathjax.org before deployment.
+# The default value is: http://cdn.mathjax.org/mathjax/latest.
+# This tag requires that the tag USE_MATHJAX is set to YES.
+
+MATHJAX_RELPATH        = http://cdn.mathjax.org/mathjax/latest
+
+# The MATHJAX_EXTENSIONS tag can be used to specify one or more MathJax
+# extension names that should be enabled during MathJax rendering. For example
+# MATHJAX_EXTENSIONS = TeX/AMSmath TeX/AMSsymbols
+# This tag requires that the tag USE_MATHJAX is set to YES.
+
+MATHJAX_EXTENSIONS     =
+
+# The MATHJAX_CODEFILE tag can be used to specify a file with javascript pieces
+# of code that will be used on startup of the MathJax code. See the MathJax site
+# (see: http://docs.mathjax.org/en/latest/output.html) for more details. For an
+# example see the documentation.
+# This tag requires that the tag USE_MATHJAX is set to YES.
+
+MATHJAX_CODEFILE       =
+
+# When the SEARCHENGINE tag is enabled doxygen will generate a search box for
+# the HTML output. The underlying search engine uses javascript and DHTML and
+# should work on any modern browser. Note that when using HTML help
+# (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets (GENERATE_DOCSET)
+# there is already a search function so this one should typically be disabled.
+# For large projects the javascript based search engine can be slow, then
+# enabling SERVER_BASED_SEARCH may provide a better solution. It is possible to
+# search using the keyboard; to jump to the search box use <access key> + S
+# (what the <access key> is depends on the OS and browser, but it is typically
+# <CTRL>, <ALT>/<option>, or both). Inside the search box use the <cursor down
+# key> to jump into the search results window, the results can be navigated
+# using the <cursor keys>. Press <Enter> to select an item or <escape> to cancel
+# the search. The filter options can be selected when the cursor is inside the
+# search box by pressing <Shift>+<cursor down>. Also here use the <cursor keys>
+# to select a filter and <Enter> or <escape> to activate or cancel the filter
+# option.
+# The default value is: YES.
+# This tag requires that the tag GENERATE_HTML is set to YES.
+
+SEARCHENGINE           = YES
+
+# When the SERVER_BASED_SEARCH tag is enabled the search engine will be
+# implemented using a web server instead of a web client using Javascript. There
+# are two flavours of web server based searching depending on the
+# EXTERNAL_SEARCH setting. When disabled, doxygen will generate a PHP script for
+# searching and an index file used by the script. When EXTERNAL_SEARCH is
+# enabled the indexing and searching needs to be provided by external tools. See
+# the section "External Indexing and Searching" for details.
+# The default value is: NO.
+# This tag requires that the tag SEARCHENGINE is set to YES.
+
+SERVER_BASED_SEARCH    = NO
+
+# When EXTERNAL_SEARCH tag is enabled doxygen will no longer generate the PHP
+# script for searching. Instead the search results are written to an XML file
+# which needs to be processed by an external indexer. Doxygen will invoke an
+# external search engine pointed to by the SEARCHENGINE_URL option to obtain the
+# search results.
+#
+# Doxygen ships with an example indexer ( doxyindexer) and search engine
+# (doxysearch.cgi) which are based on the open source search engine library
+# Xapian (see: http://xapian.org/).
+#
+# See the section "External Indexing and Searching" for details.
+# The default value is: NO.
+# This tag requires that the tag SEARCHENGINE is set to YES.
+
+EXTERNAL_SEARCH        = NO
+
+# The SEARCHENGINE_URL should point to a search engine hosted by a web server
+# which will return the search results when EXTERNAL_SEARCH is enabled.
+#
+# Doxygen ships with an example indexer ( doxyindexer) and search engine
+# (doxysearch.cgi) which are based on the open source search engine library
+# Xapian (see: http://xapian.org/). See the section "External Indexing and
+# Searching" for details.
+# This tag requires that the tag SEARCHENGINE is set to YES.
+
+SEARCHENGINE_URL       =
+
+# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the unindexed
+# search data is written to a file for indexing by an external tool. With the
+# SEARCHDATA_FILE tag the name of this file can be specified.
+# The default file is: searchdata.xml.
+# This tag requires that the tag SEARCHENGINE is set to YES.
+
+SEARCHDATA_FILE        = searchdata.xml
+
+# When SERVER_BASED_SEARCH and EXTERNAL_SEARCH are both enabled the
+# EXTERNAL_SEARCH_ID tag can be used as an identifier for the project. This is
+# useful in combination with EXTRA_SEARCH_MAPPINGS to search through multiple
+# projects and redirect the results back to the right project.
+# This tag requires that the tag SEARCHENGINE is set to YES.
+
+EXTERNAL_SEARCH_ID     =
+
+# The EXTRA_SEARCH_MAPPINGS tag can be used to enable searching through doxygen
+# projects other than the one defined by this configuration file, but that are
+# all added to the same external search index. Each project needs to have a
+# unique id set via EXTERNAL_SEARCH_ID. The search mapping then maps the id of
+# to a relative location where the documentation can be found. The format is:
+# EXTRA_SEARCH_MAPPINGS = tagname1=loc1 tagname2=loc2 ...
+# This tag requires that the tag SEARCHENGINE is set to YES.
+
+EXTRA_SEARCH_MAPPINGS  =
+
+#---------------------------------------------------------------------------
+# Configuration options related to the LaTeX output
+#---------------------------------------------------------------------------
+
+# If the GENERATE_LATEX tag is set to YES doxygen will generate LaTeX output.
+# The default value is: YES.
+
+GENERATE_LATEX         = YES
+
+# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put. If a
+# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
+# it.
+# The default directory is: latex.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_OUTPUT           = latex
+
+# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be
+# invoked.
+#
+# Note that when enabling USE_PDFLATEX this option is only used for generating
+# bitmaps for formulas in the HTML output, but not in the Makefile that is
+# written to the output directory.
+# The default file is: latex.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_CMD_NAME         = latex
+
+# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to generate
+# index for LaTeX.
+# The default file is: makeindex.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+MAKEINDEX_CMD_NAME     = makeindex
+
+# If the COMPACT_LATEX tag is set to YES doxygen generates more compact LaTeX
+# documents. This may be useful for small projects and may help to save some
+# trees in general.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+COMPACT_LATEX          = NO
+
+# The PAPER_TYPE tag can be used to set the paper type that is used by the
+# printer.
+# Possible values are: a4 (210 x 297 mm), letter (8.5 x 11 inches), legal (8.5 x
+# 14 inches) and executive (7.25 x 10.5 inches).
+# The default value is: a4.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+PAPER_TYPE             = a4
+
+# The EXTRA_PACKAGES tag can be used to specify one or more LaTeX package names
+# that should be included in the LaTeX output. To get the times font for
+# instance you can specify
+# EXTRA_PACKAGES=times
+# If left blank no extra packages will be included.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+EXTRA_PACKAGES         =
+
+# The LATEX_HEADER tag can be used to specify a personal LaTeX header for the
+# generated LaTeX document. The header should contain everything until the first
+# chapter. If it is left blank doxygen will generate a standard header. See
+# section "Doxygen usage" for information on how to let doxygen write the
+# default header to a separate file.
+#
+# Note: Only use a user-defined header if you know what you are doing! The
+# following commands have a special meaning inside the header: $title,
+# $datetime, $date, $doxygenversion, $projectname, $projectnumber. Doxygen will
+# replace them by respectively the title of the page, the current date and time,
+# only the current date, the version number of doxygen, the project name (see
+# PROJECT_NAME), or the project number (see PROJECT_NUMBER).
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_HEADER           =
+
+# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for the
+# generated LaTeX document. The footer should contain everything after the last
+# chapter. If it is left blank doxygen will generate a standard footer.
+#
+# Note: Only use a user-defined footer if you know what you are doing!
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_FOOTER           =
+
+# The LATEX_EXTRA_FILES tag can be used to specify one or more extra images or
+# other source files which should be copied to the LATEX_OUTPUT output
+# directory. Note that the files will be copied as-is; there are no commands or
+# markers available.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_EXTRA_FILES      =
+
+# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated is
+# prepared for conversion to PDF (using ps2pdf or pdflatex). The PDF file will
+# contain links (just like the HTML output) instead of page references. This
+# makes the output suitable for online browsing using a PDF viewer.
+# The default value is: YES.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+PDF_HYPERLINKS         = YES
+
+# If the LATEX_PDFLATEX tag is set to YES, doxygen will use pdflatex to generate
+# the PDF file directly from the LaTeX files. Set this option to YES to get a
+# higher quality PDF documentation.
+# The default value is: YES.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+USE_PDFLATEX           = YES
+
+# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \batchmode
+# command to the generated LaTeX files. This will instruct LaTeX to keep running
+# if errors occur, instead of asking the user for help. This option is also used
+# when generating formulas in HTML.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_BATCHMODE        = NO
+
+# If the LATEX_HIDE_INDICES tag is set to YES then doxygen will not include the
+# index chapters (such as File Index, Compound Index, etc.) in the output.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_HIDE_INDICES     = NO
+
+# If the LATEX_SOURCE_CODE tag is set to YES then doxygen will include source
+# code with syntax highlighting in the LaTeX output.
+#
+# Note that which sources are shown also depends on other settings such as
+# SOURCE_BROWSER.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_SOURCE_CODE      = NO
+
+# The LATEX_BIB_STYLE tag can be used to specify the style to use for the
+# bibliography, e.g. plainnat, or ieeetr. See
+# http://en.wikipedia.org/wiki/BibTeX and \cite for more info.
+# The default value is: plain.
+# This tag requires that the tag GENERATE_LATEX is set to YES.
+
+LATEX_BIB_STYLE        = plain
+
+#---------------------------------------------------------------------------
+# Configuration options related to the RTF output
+#---------------------------------------------------------------------------
+
+# If the GENERATE_RTF tag is set to YES doxygen will generate RTF output. The
+# RTF output is optimized for Word 97 and may not look too pretty with other RTF
+# readers/editors.
+# The default value is: NO.
+
+GENERATE_RTF           = NO
+
+# The RTF_OUTPUT tag is used to specify where the RTF docs will be put. If a
+# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
+# it.
+# The default directory is: rtf.
+# This tag requires that the tag GENERATE_RTF is set to YES.
+
+RTF_OUTPUT             = rtf
+
+# If the COMPACT_RTF tag is set to YES doxygen generates more compact RTF
+# documents. This may be useful for small projects and may help to save some
+# trees in general.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_RTF is set to YES.
+
+COMPACT_RTF            = NO
+
+# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated will
+# contain hyperlink fields. The RTF file will contain links (just like the HTML
+# output) instead of page references. This makes the output suitable for online
+# browsing using Word or some other Word compatible readers that support those
+# fields.
+#
+# Note: WordPad (write) and others do not support links.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_RTF is set to YES.
+
+RTF_HYPERLINKS         = NO
+
+# Load stylesheet definitions from file. Syntax is similar to doxygen's config
+# file, i.e. a series of assignments. You only have to provide replacements,
+# missing definitions are set to their default value.
+#
+# See also section "Doxygen usage" for information on how to generate the
+# default style sheet that doxygen normally uses.
+# This tag requires that the tag GENERATE_RTF is set to YES.
+
+RTF_STYLESHEET_FILE    =
+
+# Set optional variables used in the generation of an RTF document. Syntax is
+# similar to doxygen's config file. A template extensions file can be generated
+# using doxygen -e rtf extensionFile.
+# This tag requires that the tag GENERATE_RTF is set to YES.
+
+RTF_EXTENSIONS_FILE    =
+
+#---------------------------------------------------------------------------
+# Configuration options related to the man page output
+#---------------------------------------------------------------------------
+
+# If the GENERATE_MAN tag is set to YES doxygen will generate man pages for
+# classes and files.
+# The default value is: NO.
+
+GENERATE_MAN           = NO
+
+# The MAN_OUTPUT tag is used to specify where the man pages will be put. If a
+# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
+# it. A directory man3 will be created inside the directory specified by
+# MAN_OUTPUT.
+# The default directory is: man.
+# This tag requires that the tag GENERATE_MAN is set to YES.
+
+MAN_OUTPUT             = man
+
+# The MAN_EXTENSION tag determines the extension that is added to the generated
+# man pages. In case the manual section does not start with a number, the number
+# 3 is prepended. The dot (.) at the beginning of the MAN_EXTENSION tag is
+# optional.
+# The default value is: .3.
+# This tag requires that the tag GENERATE_MAN is set to YES.
+
+MAN_EXTENSION          = .3
+
+# If the MAN_LINKS tag is set to YES and doxygen generates man output, then it
+# will generate one additional man file for each entity documented in the real
+# man page(s). These additional files only source the real man page, but without
+# them the man command would be unable to find the correct page.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_MAN is set to YES.
+
+MAN_LINKS              = NO
+
+#---------------------------------------------------------------------------
+# Configuration options related to the XML output
+#---------------------------------------------------------------------------
+
+# If the GENERATE_XML tag is set to YES doxygen will generate an XML file that
+# captures the structure of the code including all documentation.
+# The default value is: NO.
+
+GENERATE_XML           = NO
+
+# The XML_OUTPUT tag is used to specify where the XML pages will be put. If a
+# relative path is entered the value of OUTPUT_DIRECTORY will be put in front of
+# it.
+# The default directory is: xml.
+# This tag requires that the tag GENERATE_XML is set to YES.
+
+XML_OUTPUT             = xml
+
+# The XML_SCHEMA tag can be used to specify a XML schema, which can be used by a
+# validating XML parser to check the syntax of the XML files.
+# This tag requires that the tag GENERATE_XML is set to YES.
+
+XML_SCHEMA             =
+
+# The XML_DTD tag can be used to specify a XML DTD, which can be used by a
+# validating XML parser to check the syntax of the XML files.
+# This tag requires that the tag GENERATE_XML is set to YES.
+
+XML_DTD                =
+
+# If the XML_PROGRAMLISTING tag is set to YES doxygen will dump the program
+# listings (including syntax highlighting and cross-referencing information) to
+# the XML output. Note that enabling this will significantly increase the size
+# of the XML output.
+# The default value is: YES.
+# This tag requires that the tag GENERATE_XML is set to YES.
+
+XML_PROGRAMLISTING     = YES
+
+#---------------------------------------------------------------------------
+# Configuration options related to the DOCBOOK output
+#---------------------------------------------------------------------------
+
+# If the GENERATE_DOCBOOK tag is set to YES doxygen will generate Docbook files
+# that can be used to generate PDF.
+# The default value is: NO.
+
+GENERATE_DOCBOOK       = NO
+
+# The DOCBOOK_OUTPUT tag is used to specify where the Docbook pages will be put.
+# If a relative path is entered the value of OUTPUT_DIRECTORY will be put in
+# front of it.
+# The default directory is: docbook.
+# This tag requires that the tag GENERATE_DOCBOOK is set to YES.
+
+DOCBOOK_OUTPUT         = docbook
+
+#---------------------------------------------------------------------------
+# Configuration options for the AutoGen Definitions output
+#---------------------------------------------------------------------------
+
+# If the GENERATE_AUTOGEN_DEF tag is set to YES doxygen will generate an AutoGen
+# Definitions (see http://autogen.sf.net) file that captures the structure of
+# the code including all documentation. Note that this feature is still
+# experimental and incomplete at the moment.
+# The default value is: NO.
+
+GENERATE_AUTOGEN_DEF   = NO
+
+#---------------------------------------------------------------------------
+# Configuration options related to the Perl module output
+#---------------------------------------------------------------------------
+
+# If the GENERATE_PERLMOD tag is set to YES doxygen will generate a Perl module
+# file that captures the structure of the code including all documentation.
+#
+# Note that this feature is still experimental and incomplete at the moment.
+# The default value is: NO.
+
+GENERATE_PERLMOD       = NO
+
+# If the PERLMOD_LATEX tag is set to YES doxygen will generate the necessary
+# Makefile rules, Perl scripts and LaTeX code to be able to generate PDF and DVI
+# output from the Perl module output.
+# The default value is: NO.
+# This tag requires that the tag GENERATE_PERLMOD is set to YES.
+
+PERLMOD_LATEX          = NO
+
+# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be nicely
+# formatted so it can be parsed by a human reader. This is useful if you want to
+# understand what is going on. On the other hand, if this tag is set to NO the
+# size of the Perl module output will be much smaller and Perl will parse it
+# just the same.
+# The default value is: YES.
+# This tag requires that the tag GENERATE_PERLMOD is set to YES.
+
+PERLMOD_PRETTY         = YES
+
+# The names of the make variables in the generated doxyrules.make file are
+# prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX. This is useful
+# so different doxyrules.make files included by the same Makefile don't
+# overwrite each other's variables.
+# This tag requires that the tag GENERATE_PERLMOD is set to YES.
+
+PERLMOD_MAKEVAR_PREFIX =
+
+#---------------------------------------------------------------------------
+# Configuration options related to the preprocessor
+#---------------------------------------------------------------------------
+
+# If the ENABLE_PREPROCESSING tag is set to YES doxygen will evaluate all
+# C-preprocessor directives found in the sources and include files.
+# The default value is: YES.
+
+ENABLE_PREPROCESSING   = YES
+
+# If the MACRO_EXPANSION tag is set to YES doxygen will expand all macro names
+# in the source code. If set to NO only conditional compilation will be
+# performed. Macro expansion can be done in a controlled way by setting
+# EXPAND_ONLY_PREDEF to YES.
+# The default value is: NO.
+# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
+
+MACRO_EXPANSION        = NO
+
+# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES then
+# the macro expansion is limited to the macros specified with the PREDEFINED and
+# EXPAND_AS_DEFINED tags.
+# The default value is: NO.
+# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
+
+EXPAND_ONLY_PREDEF     = NO
+
+# If the SEARCH_INCLUDES tag is set to YES the includes files in the
+# INCLUDE_PATH will be searched if a #include is found.
+# The default value is: YES.
+# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
+
+SEARCH_INCLUDES        = YES
+
+# The INCLUDE_PATH tag can be used to specify one or more directories that
+# contain include files that are not input files but should be processed by the
+# preprocessor.
+# This tag requires that the tag SEARCH_INCLUDES is set to YES.
+
+INCLUDE_PATH           =
+
+# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard
+# patterns (like *.h and *.hpp) to filter out the header-files in the
+# directories. If left blank, the patterns specified with FILE_PATTERNS will be
+# used.
+# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
+
+INCLUDE_FILE_PATTERNS  =
+
+# The PREDEFINED tag can be used to specify one or more macro names that are
+# defined before the preprocessor is started (similar to the -D option of e.g.
+# gcc). The argument of the tag is a list of macros of the form: name or
+# name=definition (no spaces). If the definition and the "=" are omitted, "=1"
+# is assumed. To prevent a macro definition from being undefined via #undef or
+# recursively expanded use the := operator instead of the = operator.
+# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
+
+PREDEFINED             =
+
+# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then this
+# tag can be used to specify a list of macro names that should be expanded. The
+# macro definition that is found in the sources will be used. Use the PREDEFINED
+# tag if you want to use a different macro definition that overrules the
+# definition found in the source code.
+# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
+
+EXPAND_AS_DEFINED      =
+
+# If the SKIP_FUNCTION_MACROS tag is set to YES then doxygen's preprocessor will
+# remove all refrences to function-like macros that are alone on a line, have an
+# all uppercase name, and do not end with a semicolon. Such function macros are
+# typically used for boiler-plate code, and will confuse the parser if not
+# removed.
+# The default value is: YES.
+# This tag requires that the tag ENABLE_PREPROCESSING is set to YES.
+
+SKIP_FUNCTION_MACROS   = YES
+
+#---------------------------------------------------------------------------
+# Configuration options related to external references
+#---------------------------------------------------------------------------
+
+# The TAGFILES tag can be used to specify one or more tag files. For each tag
+# file the location of the external documentation should be added. The format of
+# a tag file without this location is as follows:
+# TAGFILES = file1 file2 ...
+# Adding location for the tag files is done as follows:
+# TAGFILES = file1=loc1 "file2 = loc2" ...
+# where loc1 and loc2 can be relative or absolute paths or URLs. See the
+# section "Linking to external documentation" for more information about the use
+# of tag files.
+# Note: Each tag file must have an unique name (where the name does NOT include
+# the path). If a tag file is not located in the directory in which doxygen is
+# run, you must also specify the path to the tagfile here.
+
+TAGFILES               =
+
+# When a file name is specified after GENERATE_TAGFILE, doxygen will create a
+# tag file that is based on the input files it reads. See section "Linking to
+# external documentation" for more information about the usage of tag files.
+
+GENERATE_TAGFILE       =
+
+# If the ALLEXTERNALS tag is set to YES all external class will be listed in the
+# class index. If set to NO only the inherited external classes will be listed.
+# The default value is: NO.
+
+ALLEXTERNALS           = NO
+
+# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed in
+# the modules index. If set to NO, only the current project's groups will be
+# listed.
+# The default value is: YES.
+
+EXTERNAL_GROUPS        = YES
+
+# If the EXTERNAL_PAGES tag is set to YES all external pages will be listed in
+# the related pages index. If set to NO, only the current project's pages will
+# be listed.
+# The default value is: YES.
+
+EXTERNAL_PAGES         = YES
+
+# The PERL_PATH should be the absolute path and name of the perl script
+# interpreter (i.e. the result of 'which perl').
+# The default file (with absolute path) is: /usr/bin/perl.
+
+PERL_PATH              = /usr/bin/perl
+
+#---------------------------------------------------------------------------
+# Configuration options related to the dot tool
+#---------------------------------------------------------------------------
+
+# If the CLASS_DIAGRAMS tag is set to YES doxygen will generate a class diagram
+# (in HTML and LaTeX) for classes with base or super classes. Setting the tag to
+# NO turns the diagrams off. Note that this option also works with HAVE_DOT
+# disabled, but it is recommended to install and use dot, since it yields more
+# powerful graphs.
+# The default value is: YES.
+
+CLASS_DIAGRAMS         = YES
+
+# You can define message sequence charts within doxygen comments using the \msc
+# command. Doxygen will then run the mscgen tool (see:
+# http://www.mcternan.me.uk/mscgen/)) to produce the chart and insert it in the
+# documentation. The MSCGEN_PATH tag allows you to specify the directory where
+# the mscgen tool resides. If left empty the tool is assumed to be found in the
+# default search path.
+
+MSCGEN_PATH            =
+
+# You can include diagrams made with dia in doxygen documentation. Doxygen will
+# then run dia to produce the diagram and insert it in the documentation. The
+# DIA_PATH tag allows you to specify the directory where the dia binary resides.
+# If left empty dia is assumed to be found in the default search path.
+
+DIA_PATH               =
+
+# If set to YES, the inheritance and collaboration graphs will hide inheritance
+# and usage relations if the target is undocumented or is not a class.
+# The default value is: YES.
+
+HIDE_UNDOC_RELATIONS   = YES
+
+# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is
+# available from the path. This tool is part of Graphviz (see:
+# http://www.graphviz.org/), a graph visualization toolkit from AT&T and Lucent
+# Bell Labs. The other options in this section have no effect if this option is
+# set to NO
+# The default value is: NO.
+
+HAVE_DOT               = NO
+
+# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is allowed
+# to run in parallel. When set to 0 doxygen will base this on the number of
+# processors available in the system. You can set it explicitly to a value
+# larger than 0 to get control over the balance between CPU load and processing
+# speed.
+# Minimum value: 0, maximum value: 32, default value: 0.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_NUM_THREADS        = 0
+
+# When you want a differently looking font n the dot files that doxygen
+# generates you can specify the font name using DOT_FONTNAME. You need to make
+# sure dot is able to find the font, which can be done by putting it in a
+# standard location or by setting the DOTFONTPATH environment variable or by
+# setting DOT_FONTPATH to the directory containing the font.
+# The default value is: Helvetica.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_FONTNAME           = Helvetica
+
+# The DOT_FONTSIZE tag can be used to set the size (in points) of the font of
+# dot graphs.
+# Minimum value: 4, maximum value: 24, default value: 10.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_FONTSIZE           = 10
+
+# By default doxygen will tell dot to use the default font as specified with
+# DOT_FONTNAME. If you specify a different font using DOT_FONTNAME you can set
+# the path where dot can find it using this tag.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_FONTPATH           =
+
+# If the CLASS_GRAPH tag is set to YES then doxygen will generate a graph for
+# each documented class showing the direct and indirect inheritance relations.
+# Setting this tag to YES will force the CLASS_DIAGRAMS tag to NO.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+CLASS_GRAPH            = YES
+
+# If the COLLABORATION_GRAPH tag is set to YES then doxygen will generate a
+# graph for each documented class showing the direct and indirect implementation
+# dependencies (inheritance, containment, and class references variables) of the
+# class with other documented classes.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+COLLABORATION_GRAPH    = YES
+
+# If the GROUP_GRAPHS tag is set to YES then doxygen will generate a graph for
+# groups, showing the direct groups dependencies.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+GROUP_GRAPHS           = YES
+
+# If the UML_LOOK tag is set to YES doxygen will generate inheritance and
+# collaboration diagrams in a style similar to the OMG's Unified Modeling
+# Language.
+# The default value is: NO.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+UML_LOOK               = NO
+
+# If the UML_LOOK tag is enabled, the fields and methods are shown inside the
+# class node. If there are many fields or methods and many nodes the graph may
+# become too big to be useful. The UML_LIMIT_NUM_FIELDS threshold limits the
+# number of items for each type to make the size more manageable. Set this to 0
+# for no limit. Note that the threshold may be exceeded by 50% before the limit
+# is enforced. So when you set the threshold to 10, up to 15 fields may appear,
+# but if the number exceeds 15, the total amount of fields shown is limited to
+# 10.
+# Minimum value: 0, maximum value: 100, default value: 10.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+UML_LIMIT_NUM_FIELDS   = 10
+
+# If the TEMPLATE_RELATIONS tag is set to YES then the inheritance and
+# collaboration graphs will show the relations between templates and their
+# instances.
+# The default value is: NO.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+TEMPLATE_RELATIONS     = NO
+
+# If the INCLUDE_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES tags are set to
+# YES then doxygen will generate a graph for each documented file showing the
+# direct and indirect include dependencies of the file with other documented
+# files.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+INCLUDE_GRAPH          = YES
+
+# If the INCLUDED_BY_GRAPH, ENABLE_PREPROCESSING and SEARCH_INCLUDES tags are
+# set to YES then doxygen will generate a graph for each documented file showing
+# the direct and indirect include dependencies of the file with other documented
+# files.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+INCLUDED_BY_GRAPH      = YES
+
+# If the CALL_GRAPH tag is set to YES then doxygen will generate a call
+# dependency graph for every global function or class method.
+#
+# Note that enabling this option will significantly increase the time of a run.
+# So in most cases it will be better to enable call graphs for selected
+# functions only using the \callgraph command.
+# The default value is: NO.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+CALL_GRAPH             = NO
+
+# If the CALLER_GRAPH tag is set to YES then doxygen will generate a caller
+# dependency graph for every global function or class method.
+#
+# Note that enabling this option will significantly increase the time of a run.
+# So in most cases it will be better to enable caller graphs for selected
+# functions only using the \callergraph command.
+# The default value is: NO.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+CALLER_GRAPH           = NO
+
+# If the GRAPHICAL_HIERARCHY tag is set to YES then doxygen will graphical
+# hierarchy of all classes instead of a textual one.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+GRAPHICAL_HIERARCHY    = YES
+
+# If the DIRECTORY_GRAPH tag is set to YES then doxygen will show the
+# dependencies a directory has on other directories in a graphical way. The
+# dependency relations are determined by the #include relations between the
+# files in the directories.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DIRECTORY_GRAPH        = YES
+
+# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images
+# generated by dot.
+# Note: If you choose svg you need to set HTML_FILE_EXTENSION to xhtml in order
+# to make the SVG files visible in IE 9+ (other browsers do not have this
+# requirement).
+# Possible values are: png, jpg, gif and svg.
+# The default value is: png.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_IMAGE_FORMAT       = png
+
+# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to
+# enable generation of interactive SVG images that allow zooming and panning.
+#
+# Note that this requires a modern browser other than Internet Explorer. Tested
+# and working are Firefox, Chrome, Safari, and Opera.
+# Note: For IE 9+ you need to set HTML_FILE_EXTENSION to xhtml in order to make
+# the SVG files visible. Older versions of IE do not have SVG support.
+# The default value is: NO.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+INTERACTIVE_SVG        = NO
+
+# The DOT_PATH tag can be used to specify the path where the dot tool can be
+# found. If left blank, it is assumed the dot tool can be found in the path.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_PATH               =
+
+# The DOTFILE_DIRS tag can be used to specify one or more directories that
+# contain dot files that are included in the documentation (see the \dotfile
+# command).
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOTFILE_DIRS           =
+
+# The MSCFILE_DIRS tag can be used to specify one or more directories that
+# contain msc files that are included in the documentation (see the \mscfile
+# command).
+
+MSCFILE_DIRS           =
+
+# The DIAFILE_DIRS tag can be used to specify one or more directories that
+# contain dia files that are included in the documentation (see the \diafile
+# command).
+
+DIAFILE_DIRS           =
+
+# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of nodes
+# that will be shown in the graph. If the number of nodes in a graph becomes
+# larger than this value, doxygen will truncate the graph, which is visualized
+# by representing a node as a red box. Note that doxygen if the number of direct
+# children of the root node in a graph is already larger than
+# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note that
+# the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH.
+# Minimum value: 0, maximum value: 10000, default value: 50.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_GRAPH_MAX_NODES    = 50
+
+# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the graphs
+# generated by dot. A depth value of 3 means that only nodes reachable from the
+# root by following a path via at most 3 edges will be shown. Nodes that lay
+# further from the root node will be omitted. Note that setting this option to 1
+# or 2 may greatly reduce the computation time needed for large code bases. Also
+# note that the size of a graph can be further restricted by
+# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction.
+# Minimum value: 0, maximum value: 1000, default value: 0.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+MAX_DOT_GRAPH_DEPTH    = 0
+
+# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent
+# background. This is disabled by default, because dot on Windows does not seem
+# to support this out of the box.
+#
+# Warning: Depending on the platform used, enabling this option may lead to
+# badly anti-aliased labels on the edges of a graph (i.e. they become hard to
+# read).
+# The default value is: NO.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_TRANSPARENT        = NO
+
+# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output
+# files in one run (i.e. multiple -o and -T options on the command line). This
+# makes dot run faster, but since only newer versions of dot (>1.8.10) support
+# this, this feature is disabled by default.
+# The default value is: NO.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_MULTI_TARGETS      = YES
+
+# If the GENERATE_LEGEND tag is set to YES doxygen will generate a legend page
+# explaining the meaning of the various boxes and arrows in the dot generated
+# graphs.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+GENERATE_LEGEND        = YES
+
+# If the DOT_CLEANUP tag is set to YES doxygen will remove the intermediate dot
+# files that are used to generate the various graphs.
+# The default value is: YES.
+# This tag requires that the tag HAVE_DOT is set to YES.
+
+DOT_CLEANUP            = YES
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/scripts/frcgazebo b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/scripts/frcgazebo
new file mode 100644
index 0000000..d0e9a75
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/scripts/frcgazebo
@@ -0,0 +1,63 @@
+#!/bin/bash
+#---------------------------------------------------------------------------
+# 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.
+#----------------------------------------------------------------------------
+
+#----------------------------------------------------------------------------
+#  Invoke gazebo, giving it the environment variables
+#   it needs to find the FRC plugins and models.
+#----------------------------------------------------------------------------
+usage() {
+    echo $1:  Invoke Gazebo for FRC
+    echo Usage:
+    echo "  $1 name-of-world-file"
+}
+
+d=`dirname "$0"`
+fulldir=`(cd "$d"; pwd)`
+sharedir=/usr/share/frcgazebo
+if [ -d "$fulldir/../share" ] ; then
+    sharedir=`(cd "$fulldir/../share/frcgazebo"; pwd)`
+fi
+
+# While we wait for the frc gazebo models to have a proper
+#  home, we require the user to make them accessible
+if [ ! -d "$sharedir" ] ; then
+    cravedir=`(cd "$fulldir/../"; pwd)`
+    echo Error: you must manually place the models and world into $cravedir/share/frcgazebo
+    exit 2
+fi
+
+libsdir=/invalid/directory
+if [ -d "$fulldir/../libs" ] ; then
+    libsdir=`(cd "$fulldir/../libs"; pwd)`
+fi
+
+#  Use exactly the file they gave us, or find it in ../share/frcgazebo/worlds,
+#    or find it there by adding a .world extension
+world="$1"
+if [ ! -f "$world" ] ; then
+    world="$sharedir/worlds/$1"
+fi
+if [ ! -f "$world" ] ; then
+    world="$sharedir/worlds/$1.world"
+fi
+
+if [ $# -ne 1 -o "x${1:0:1}" = "x-" ] ; then
+    usage `basename $0`
+    exit 1
+fi
+if [ ! -f "$world" ] ; then
+    echo Could not find $1 directly or in $sharedir/worlds
+    exit 2
+fi
+
+export GAZEBO_MODEL_PATH="$sharedir/models":$GAZEBO_MODEL_PATH
+for x in `find "$libsdir" -type d -name shared` ; do
+    export GAZEBO_PLUGIN_PATH="$x:$GAZEBO_PLUGIN_PATH"
+done
+
+gazebo "$world"
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clock/cpp/clock.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clock/cpp/clock.cpp
new file mode 100644
index 0000000..c7440eb
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clock/cpp/clock.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "clock.h"
+
+#include <boost/algorithm/string/replace.hpp>
+
+GZ_REGISTER_MODEL_PLUGIN(Clock)
+
+void Clock::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+
+  // Parse SDF properties
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  gzmsg << "Initializing clock: " << topic << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  pub = node->Advertise<gazebo::msgs::Float64>(topic);
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&Clock::Update, this, _1));
+}
+
+void Clock::Update(const gazebo::common::UpdateInfo& info) {
+  gazebo::msgs::Float64 msg;
+  msg.set_data(info.simTime.Double());
+  pub->Publish(msg);
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clock/headers/clock.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clock/headers/clock.h
new file mode 100644
index 0000000..fcdc2bd
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clock/headers/clock.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/**
+ * \brief Plugin for publishing the simulation time.
+ *
+ * This plugin publishes the simualtaion time in seconds every physics
+ * update.
+ *
+ * To add a clock to your robot, add the following XML to your robot
+ * model:
+ *
+ *     <plugin name="my_clock" filename="libclock.so">
+ *       <topic>~/my/topic</topic>
+ *     </plugin>
+ *
+ * - `topic`: Optional. Message will be published as a gazebo.msgs.Float64.
+ *
+ * \todo Make WorldPlugin?
+ */
+class Clock : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the clock and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Sends out time each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Publish the time on this topic.
+  std::string topic;
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer to the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Publisher handle.
+  gazebo::transport::PublisherPtr pub;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clockTest/cpp/clockTest.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clockTest/cpp/clockTest.cpp
new file mode 100644
index 0000000..275425c
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clockTest/cpp/clockTest.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <simulation/gz_msgs/msgs.h>
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/gazebo_client.hh>
+#include <gazebo/msgs/msgs.hh>
+#include <gazebo/sensors/sensors.hh>
+#include <gazebo/transport/transport.hh>
+
+#include "gtest/gtest.h"
+
+using namespace testing;
+
+static char* library;
+static char* world_sdf;
+static double latest_time;
+
+void cb(gazebo::msgs::ConstFloat64Ptr& msg) { latest_time = msg->data(); }
+
+TEST(ClockTests, test_clock) {
+  gazebo::physics::WorldPtr world;
+
+  ASSERT_TRUE(library);
+  ASSERT_TRUE(!access(library, X_OK | R_OK));
+  ASSERT_TRUE(world_sdf);
+  ASSERT_TRUE(!access(world_sdf, R_OK));
+
+  gazebo::addPlugin(library);
+  ASSERT_TRUE(gazebo::setupServer());
+
+  world = gazebo::loadWorld(world_sdf);
+  ASSERT_TRUE(world != NULL);
+
+  ASSERT_TRUE(gazebo::client::setup());
+
+  gazebo::transport::NodePtr node(new gazebo::transport::Node());
+  node->Init();
+
+  gazebo::transport::SubscriberPtr sub =
+      node->Subscribe("/gazebo/frc/time", cb);
+
+  gazebo::sensors::run_once(true);
+  gazebo::sensors::run_threads();
+  gazebo::common::Time::MSleep(1);
+
+  double start = latest_time;
+
+  for (unsigned int i = 0; i < 1000; ++i) {
+    gazebo::runWorld(world, 1);
+    gazebo::sensors::run_once();
+    gazebo::common::Time::MSleep(1);
+  }
+
+  double end = latest_time;
+
+  ASSERT_TRUE(end > start);
+  ASSERT_TRUE(gazebo::client::shutdown());
+  ASSERT_TRUE(gazebo::shutdown());
+}
+
+int main(int argc, char** argv) {
+  testing::InitGoogleTest(&argc, argv);
+
+  if (argc >= 1) library = argv[1];
+
+  if (argc >= 2) world_sdf = argv[2];
+
+  return RUN_ALL_TESTS();
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clockTest/world/clockTest.world b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clockTest/world/clockTest.world
new file mode 100644
index 0000000..e6f7cfd
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/clockTest/world/clockTest.world
@@ -0,0 +1,17 @@
+<?xml version="1.0" ?>
+<sdf version="1.5">
+    <world name="default">
+        <scene>
+            <ambient>0.2 0.2 0.2 1</ambient>
+            <background>1 1 1 1</background>
+            <shadows>false</shadows>
+            <grid>false</grid>
+            <origin_visual>false</origin_visual>
+        </scene>
+        <model name='Clock'>
+            <plugin name='clock' filename='libclock.so'>
+                <topic>/gazebo/frc/time</topic>
+            </plugin>
+        </model>
+    </world>
+</sdf>
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/dc_motor/cpp/dc_motor.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/dc_motor/cpp/dc_motor.cpp
new file mode 100644
index 0000000..8cc3039
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/dc_motor/cpp/dc_motor.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "dc_motor.h"
+
+#include <boost/algorithm/string/replace.hpp>
+
+GZ_REGISTER_MODEL_PLUGIN(DCMotor)
+
+void DCMotor::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+  signal = 0;
+
+  // Parse SDF properties
+  joint = model->GetJoint(sdf->Get<std::string>("joint"));
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  if (sdf->HasElement("multiplier")) {
+    multiplier = sdf->Get<double>("multiplier");
+  } else {
+    multiplier = 1;
+  }
+
+  gzmsg << "Initializing motor: " << topic << " joint=" << joint->GetName()
+        << " multiplier=" << multiplier << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  sub = node->Subscribe(topic, &DCMotor::Callback, this);
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&DCMotor::Update, this, _1));
+}
+
+void DCMotor::Update(const gazebo::common::UpdateInfo& info) {
+  joint->SetForce(0, signal * multiplier);
+}
+
+void DCMotor::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
+  signal = msg->data();
+  if (signal < -1) {
+    signal = -1;
+  } else if (signal > 1) {
+    signal = 1;
+  }
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/dc_motor/headers/dc_motor.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/dc_motor/headers/dc_motor.h
new file mode 100644
index 0000000..f9c2523
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/dc_motor/headers/dc_motor.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/**
+ * \brief Plugin for controlling a joint with a DC motor.
+ *
+ * This plugin subscribes to a topic to get a signal in the range
+ * [-1,1]. Every physics update the joint's torque is set as
+ * multiplier*signal.
+ *
+ * To add a DC motor to your robot, add the following XML to your
+ * robot model:
+ *
+ *     <plugin name="my_motor" filename="libdc_motor.so">
+ *       <joint>Joint Name</joint>
+ *       <topic>~/my/topic</topic>
+ *       <multiplier>Number</multiplier>
+ *     </plugin>
+ *
+ * - `joint`: Name of the joint this Dc motor is attached to.
+ * - `topic`: Optional. Message type should be gazebo.msgs.Float64.
+ * - `multiplier`: Optional. Defaults to 1.
+ */
+class DCMotor : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the dc motor and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Update the torque on the joint from the dc motor each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Topic to read control signal from.
+  std::string topic;
+
+  /// \brief The pwm signal limited to the range [-1,1].
+  double signal;
+
+  /// \brief The magic torque multiplier. torque=multiplier*signal
+  double multiplier;
+
+  /// \brief The joint that this dc motor drives.
+  gazebo::physics::JointPtr joint;
+
+  /// \brief Callback for receiving msgs and storing the signal.
+  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer toe the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Subscriber handle.
+  gazebo::transport::SubscriberPtr sub;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/drive_motor/cpp/drive_motor.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/drive_motor/cpp/drive_motor.cpp
new file mode 100644
index 0000000..e6511bb
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/drive_motor/cpp/drive_motor.cpp
@@ -0,0 +1,134 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "drive_motor.h"
+
+#include <boost/algorithm/string/replace.hpp>
+
+GZ_REGISTER_MODEL_PLUGIN(DriveMotor)
+
+void DriveMotor::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+  signal = 0;
+
+  // Parse SDF properties
+  joint = model->GetJoint(sdf->Get<std::string>("joint"));
+  if (!joint) {
+    gzerr << "Error initializing drive motor: could not get joint";
+    return;
+  }
+
+  parent = joint->GetParent();
+  if (!parent) {
+    gzerr << "Error initializing drive motor: could not get parent";
+    return;
+  }
+
+  child = joint->GetChild();
+  if (!child) {
+    gzerr << "Error initializing drive motor: could not get child";
+    return;
+  }
+
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  if (sdf->HasElement("max_speed")) {
+    maxSpeed = sdf->Get<double>("max_speed");
+  } else {
+    maxSpeed = 0;
+  }
+
+  if (sdf->HasElement("multiplier")) {
+    multiplier = sdf->Get<double>("multiplier");
+  } else {
+    multiplier = 1;
+  }
+
+  if (sdf->HasElement("dx")) {
+    dx = sdf->Get<double>("dx");
+  } else {
+    dx = 0;
+  }
+
+  if (sdf->HasElement("dy")) {
+    dy = sdf->Get<double>("dy");
+  } else {
+    dy = 0;
+  }
+
+  if (sdf->HasElement("dz")) {
+    dz = sdf->Get<double>("dz");
+  } else {
+    dz = 0;
+  }
+
+  gzmsg << "Initializing drive motor: " << topic
+        << " parent=" << parent->GetName() << " directions=" << dx << " " << dy
+        << " " << dz << " multiplier=" << multiplier << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  sub = node->Subscribe(topic, &DriveMotor::Callback, this);
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&DriveMotor::Update, this, _1));
+}
+
+static double computeForce(double input, double velocity, double max) {
+  double output = input;
+  if (max == 0.0) return output;
+  if (std::fabs(velocity) >= max) {
+    output = 0;
+  } else {
+    double reduce = (max - std::fabs(velocity)) / max;
+    output *= reduce;
+  }
+  return output;
+}
+
+void DriveMotor::Update(const gazebo::common::UpdateInfo& info) {
+#if GAZEBO_MAJOR_VERSION >= 8
+  ignition::math::Vector3d velocity = parent->RelativeLinearVel();
+#else
+  ignition::math::Vector3d velocity = parent->GetRelativeLinearVel().Ign();
+#endif
+
+  if (signal == 0) return;
+
+  double x = computeForce(signal * dx * multiplier, velocity.X(),
+                          std::fabs(maxSpeed * dx));
+  double y = computeForce(signal * dy * multiplier, velocity.Y(),
+                          std::fabs(maxSpeed * dy));
+  double z = computeForce(signal * dz * multiplier, velocity.Z(),
+                          std::fabs(maxSpeed * dz));
+
+  ignition::math::Vector3d force(x, y, z);
+#if GAZEBO_MAJOR_VERSION >= 8
+  parent->AddLinkForce(force, child->RelativePose().Pos());
+#else
+  parent->AddLinkForce(force, child->GetRelativePose().Ign().Pos());
+#endif
+}
+
+void DriveMotor::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
+  signal = msg->data();
+  if (signal < -1) {
+    signal = -1;
+  } else if (signal > 1) {
+    signal = 1;
+  }
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/drive_motor/headers/drive_motor.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/drive_motor/headers/drive_motor.h
new file mode 100644
index 0000000..2033223
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/drive_motor/headers/drive_motor.h
@@ -0,0 +1,126 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/**
+ * \brief Plugin for simulating a drive motor
+ *
+ * This plugin attempts to overcome a limitation in gazebo.
+ * That is, most normal FRC robots rely on wheels that have good
+ * traction in one direction, and less traction in the opposite
+ * direction.
+ *
+ * Gazebo does not model that well (in fact, drive wheels are
+ * quite hard to simulate).
+ *
+ * So this plugin subscribes to a PWM output signal and applies
+ * a force to the chassis at the proscribed point in hopefully
+ * the correct direction.  The SDF model can then have lower friction,
+ * and it should turn more naturally.
+ *
+ * This plugin also attempts to simulate the limitations of a drive
+ * motor, most notably the maximum speed any given motor can spin at.
+ * The initial implemention is quite naive; just a linear reduction
+ * in force as a product of velocity/max velocity.
+ *
+ * Nicely, this plugin let's you generate a force in any of
+ * three axes.  That is helpful for simulating a mecanum drive.
+ *
+ * This plugin subscribes to a topic to get a signal in the range
+ * [-1,1]. Every physics update the joint's torque is set as
+ * multiplier*signal*direction.
+ *
+ * To add a drive motor to your robot, add the following XML to your
+ * robot model:
+ *
+ *     <plugin name="my_motor" filename="libdrive_motor.so">
+ *       <joint>Joint Name</joint>
+ *       <topic>~/my/topic</topic>
+ *       <multiplier>Number</multiplier>
+ *       <max_speed>Number</max_speed>
+ *       <dx>-1, 0, or 1</dx>
+ *       <dy>-1, 0, or 1</dy>
+ *       <dz>-1, 0, or 1</dz>
+ *     </plugin>
+ *
+ * - `joint`: Name of the joint this Dc motor is attached to.
+ * - `topic`: Optional. Message type should be gazebo.msgs.Float64.
+ *            A typical topic looks like this:
+ *              /gazebo/frc/simulator/pwm/<n>
+ * - `multiplier`: Optional. Defaults to 1.  Force applied by this motor.
+ *            This is force in Newtons.
+ * - `max_speed`:  Optional. Defaults to no maximum.
+ *            This is, in theory, meters/second.  Note that friction
+ *            and other forces will also slow down a robot.
+ *            In practice, this term can be tuned until the robot feels right.
+ * - `dx`:  These three constants must be set to either -1, 0, or 1
+ * - `dy`:  This controls whether or not the motor produces force
+ * - `dz`:  along a given axis, and what direction.  Each defaults to 0.
+ *          These are relative to the frame of the parent link of the joint.
+ *          So they are usually relative to a chassis.
+ *          The force is applied at the point that the joint connects to
+ *          the parent link.
+ */
+class DriveMotor : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the dc motor and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Update the force on the parent of the joint from each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Topic to read control signal from.
+  std::string topic;
+
+  /// \brief The pwm signal limited to the range [-1,1].
+  double signal;
+
+  /// \brief The robot's maximum speed
+  double maxSpeed;
+
+  /// \brief The magic drive force multipliers. force=multiplier*signal
+  double multiplier;
+
+  /// \brief The directional constants limited to -1, 0, or 1.
+  double dx;
+  double dy;
+  double dz;
+
+  /// \brief The joint that this motor drives.
+  gazebo::physics::JointPtr joint;
+
+  /// \brief The parent of this joint; usually a chassis
+  gazebo::physics::LinkPtr parent;
+
+  /// \brief The child of this joint; usually a wheel
+  gazebo::physics::LinkPtr child;
+
+  /// \brief Callback for receiving msgs and storing the signal.
+  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer toe the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Subscriber handle.
+  gazebo::transport::SubscriberPtr sub;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/encoder/cpp/encoder.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/encoder/cpp/encoder.cpp
new file mode 100644
index 0000000..37551f2
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/encoder/cpp/encoder.cpp
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "encoder.h"
+
+#include <boost/algorithm/string/replace.hpp>
+
+GZ_REGISTER_MODEL_PLUGIN(Encoder)
+
+void Encoder::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+
+  // Parse SDF properties
+  joint = model->GetJoint(sdf->Get<std::string>("joint"));
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  if (sdf->HasElement("units")) {
+    radians = sdf->Get<std::string>("units") != "degrees";
+  } else {
+    radians = true;
+  }
+  multiplier = 1.0;
+  zero = GetAngle();
+  stopped = true;
+  stop_value = 0;
+
+  if (sdf->HasElement("multiplier"))
+    multiplier = sdf->Get<double>("multiplier");
+
+  gzmsg << "Initializing encoder: " << topic << " joint=" << joint->GetName()
+        << " radians=" << radians << " multiplier=" << multiplier << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  command_sub = node->Subscribe(topic + "/control", &Encoder::Callback, this);
+  pos_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/position");
+  vel_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/velocity");
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&Encoder::Update, this, _1));
+}
+
+void Encoder::Update(const gazebo::common::UpdateInfo& info) {
+  gazebo::msgs::Float64 pos_msg, vel_msg;
+  if (stopped) {
+    pos_msg.set_data(stop_value * multiplier);
+    pos_pub->Publish(pos_msg);
+    vel_msg.set_data(0);
+    vel_pub->Publish(vel_msg);
+  } else {
+    pos_msg.set_data((GetAngle() - zero) * multiplier);
+    pos_pub->Publish(pos_msg);
+    vel_msg.set_data(GetVelocity() * multiplier);
+    vel_pub->Publish(vel_msg);
+  }
+}
+
+void Encoder::Callback(const gazebo::msgs::ConstStringPtr& msg) {
+  std::string command = msg->data();
+  if (command == "reset") {
+    zero = GetAngle();
+  } else if (command == "start") {
+    stopped = false;
+    zero = (GetAngle() - stop_value);
+  } else if (command == "stop") {
+    stopped = true;
+    stop_value = GetAngle();
+  } else {
+    gzerr << "WARNING: Encoder got unknown command '" << command << "'."
+          << std::endl;
+  }
+}
+
+double Encoder::GetAngle() {
+  if (radians) {
+    return joint->Position(0);
+  } else {
+    return joint->Position(0) * (180.0 / M_PI);
+  }
+}
+
+double Encoder::GetVelocity() {
+  if (radians) {
+    return joint->GetVelocity(0);
+  } else {
+    return joint->GetVelocity(0) * (180.0 / M_PI);
+  }
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/encoder/headers/encoder.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/encoder/headers/encoder.h
new file mode 100644
index 0000000..c33f708
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/encoder/headers/encoder.h
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/**
+ * \brief Plugin for reading the speed and relative angle of a joint.
+ *
+ * This plugin publishes the angle since last reset and the speed of a
+ * given joint to subtopics of the given topic every physics
+ * update. There is also a control subtopic that takes three commands:
+ * "start", "stop" and "reset":
+ *
+ * - "start": Start counting ticks from the current count.
+ * - "stop":  Stop counting ticks, pauses updates.
+ * - "reset": Set the current angle to zero.
+ *
+ * To add a encoder to your robot, add the following XML to your
+ * robot model:
+ *
+ *     <plugin name="my_encoder" filename="libencoder.so">
+ *       <joint>Joint Name</joint>
+ *       <topic>~/my/topic</topic>
+ *       <units>{degrees, radians}</units>
+ *       <multiplier>Number</multiplier>
+ *     </plugin>
+ *
+ * - `joint`: Name of the joint this encoder is attached to.
+ * - `topic`: Optional. Used as the root for subtopics. `topic`/position
+ * (gazebo.msgs.Float64),
+ *            `topic`/velocity (gazebo.msgs.Float64), `topic`/control
+ * (gazebo.msgs.String)
+ *    The suggested value for topic is of the form
+ *       ~/simulator/encoder/dio/<n>
+ *    where <n> is the number of the first digital input channel
+ *    used to formulate the encoder
+ *
+ * - `units`: Optional. Defaults to radians.
+ * - `multiplier`: Optional. Defaults to 1.
+ *     This can be used to make the simulated encoder
+ *     return a comparable number of ticks to a 'real' encoder
+ *     Useful facts:  A 'degrees' encoder will report 360 ticks/revolution.
+ *     The k4X encoder type can add another multiple of 4 into the mix.
+ */
+class Encoder : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the encoder and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Sends out the encoder reading each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Root topic for subtopics on this topic.
+  std::string topic;
+
+  /// \brief Whether or not this encoder measures radians or degrees.
+  bool radians;
+
+  /// \brief A factor to mulitply this output by.
+  double multiplier;
+
+  /// \brief Whether or not the encoder has been stopped.
+  bool stopped;
+
+  /// \brief The zero value of the encoder.
+  double zero;
+
+  /// \brief The value the encoder stopped counting at
+  double stop_value;
+
+  /// \brief The joint that this encoder measures
+  gazebo::physics::JointPtr joint;
+
+  /// \brief Callback for handling control data
+  void Callback(const gazebo::msgs::ConstStringPtr& msg);
+
+  /// \brief Gets the current angle, taking into account whether to
+  ///        return radians or degrees.
+  double GetAngle();
+
+  /// \brief Gets the current velocity, taking into account whether to
+  ///        return radians/second or degrees/second.
+  double GetVelocity();
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer to the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Subscriber handle.
+  gazebo::transport::SubscriberPtr command_sub;
+
+  /// \brief Publisher handles.
+  gazebo::transport::PublisherPtr pos_pub, vel_pub;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/gyro/cpp/gyro.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/gyro/cpp/gyro.cpp
new file mode 100644
index 0000000..65d42b7
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/gyro/cpp/gyro.cpp
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "gyro.h"
+
+#include <boost/algorithm/string/replace.hpp>
+
+GZ_REGISTER_MODEL_PLUGIN(Gyro)
+
+void Gyro::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+
+  // Parse SDF properties
+  link = model->GetLink(sdf->Get<std::string>("link"));
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  std::string axisString = sdf->Get<std::string>("axis");
+  if (axisString == "roll") axis = Roll;
+  if (axisString == "pitch") axis = Pitch;
+  if (axisString == "yaw") axis = Yaw;
+
+  if (sdf->HasElement("units")) {
+    radians = sdf->Get<std::string>("units") != "degrees";
+  } else {
+    radians = true;
+  }
+  zero = GetAngle();
+
+  gzmsg << "Initializing gyro: " << topic << " link=" << link->GetName()
+        << " axis=" << axis << " radians=" << radians << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  command_sub = node->Subscribe(topic + "/control", &Gyro::Callback, this);
+  pos_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/position");
+  vel_pub = node->Advertise<gazebo::msgs::Float64>(topic + "/velocity");
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&Gyro::Update, this, _1));
+}
+
+void Gyro::Update(const gazebo::common::UpdateInfo& info) {
+  gazebo::msgs::Float64 pos_msg, vel_msg;
+  pos_msg.set_data(Limit(GetAngle() - zero));
+  pos_pub->Publish(pos_msg);
+  vel_msg.set_data(GetVelocity());
+  vel_pub->Publish(vel_msg);
+}
+
+void Gyro::Callback(const gazebo::msgs::ConstStringPtr& msg) {
+  std::string command = msg->data();
+  if (command == "reset") {
+    zero = GetAngle();
+  } else {
+    gzerr << "WARNING: Gyro got unknown command '" << command << "'."
+          << std::endl;
+  }
+}
+
+double Gyro::GetAngle() {
+  if (radians) {
+    return link->WorldCoGPose().Rot().Euler()[axis];
+  } else {
+    return link->WorldCoGPose().Rot().Euler()[axis] * (180.0 / M_PI);
+  }
+}
+
+double Gyro::GetVelocity() {
+  if (radians) {
+    return link->RelativeAngularVel()[axis];
+  } else {
+    return link->RelativeAngularVel()[axis] * (180.0 / M_PI);
+  }
+}
+
+double Gyro::Limit(double value) {
+  if (radians) {
+    while (true) {
+      if (value < -M_PI)
+        value += 2 * M_PI;
+      else if (value > M_PI)
+        value -= 2 * M_PI;
+      else
+        break;
+    }
+  } else {
+    while (true) {
+      if (value < -180)
+        value += 360;
+      else if (value > 180)
+        value -= 360;
+      else
+        break;
+    }
+  }
+  return value;
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/gyro/headers/gyro.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/gyro/headers/gyro.h
new file mode 100644
index 0000000..3faa144
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/gyro/headers/gyro.h
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/// \brief The axis about which to measure rotation.
+typedef enum { Roll /*X*/, Pitch /*Y*/, Yaw /*Z*/ } ROTATION;
+
+/**
+ * \brief Plugin for reading the speed and relative angle of a link.
+ *
+ * This plugin publishes the angle since last reset and the speed
+ * which a link is rotating about some axis to subtopics of the given
+ * topic every physics update. There is also a control topic that
+ * takes one command: "reset", which sets the current angle as zero.
+ *
+ * To add a gyro to your robot, add the following XML to your robot
+ * model:
+ *
+ *     <plugin name="my_gyro" filename="libgyro.so">
+ *       <link>Joint Name</link>
+ *       <topic>~/my/topic</topic>
+ *       <units>{degrees, radians}</units>
+ *     </plugin>
+ *
+ * - `link`: Name of the link this potentiometer is attached to.
+ * - `topic`: Optional. Used as the root for subtopics. `topic`/position
+ * (gazebo.msgs.Float64),
+ *            `topic`/velocity (gazebo.msgs.Float64), `topic`/control
+ * (gazebo.msgs.String)
+ * - `units`; Optional, defaults to radians.
+ */
+class Gyro : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the gyro and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Sends out the gyro reading each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Publish the angle on this topic.
+  std::string topic;
+
+  /// \brief Whether or not this gyro measures radians or degrees.
+  bool radians;
+
+  /// \brief The axis to measure rotation about.
+  ROTATION axis;
+
+  /// \brief The zero value of the gyro.
+  double zero;
+
+  /// \brief The link that this gyro measures
+  gazebo::physics::LinkPtr link;
+
+  /// \brief Callback for handling control data
+  void Callback(const gazebo::msgs::ConstStringPtr& msg);
+
+  /// \brief Gets the current angle, taking into account whether to
+  ///        return radians or degrees.
+  double GetAngle();
+
+  /// \brief Gets the current velocity, taking into account whether to
+  ///        return radians/second or degrees/second.
+  double GetVelocity();
+
+  /// \brief Limit the value to either [-180,180] or [-PI,PI]
+  ///       depending on whether or radians or degrees are being used.
+  double Limit(double value);
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer to the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Subscriber handle.
+  gazebo::transport::SubscriberPtr command_sub;
+
+  /// \brief Publisher handles.
+  gazebo::transport::PublisherPtr pos_pub, vel_pub;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/external_limit_switch.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/external_limit_switch.cpp
new file mode 100644
index 0000000..c5780ae
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/external_limit_switch.cpp
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "external_limit_switch.h"
+
+#include <string>
+
+ExternalLimitSwitch::ExternalLimitSwitch(sdf::ElementPtr sdf) {
+  sensor = std::dynamic_pointer_cast<gazebo::sensors::ContactSensor>(
+      gazebo::sensors::get_sensor(sdf->Get<std::string>("sensor")));
+
+  gzmsg << "\texternal limit switch: "
+        << " sensor=" << sensor->Name() << std::endl;
+}
+
+bool ExternalLimitSwitch::Get() {
+  return sensor->Contacts().contact().size() > 0;
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/internal_limit_switch.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/internal_limit_switch.cpp
new file mode 100644
index 0000000..adfd860
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/internal_limit_switch.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "internal_limit_switch.h"
+
+#include <string>
+
+InternalLimitSwitch::InternalLimitSwitch(gazebo::physics::ModelPtr model,
+                                         sdf::ElementPtr sdf) {
+  joint = model->GetJoint(sdf->Get<std::string>("joint"));
+  min = sdf->Get<double>("min");
+  max = sdf->Get<double>("max");
+
+  if (sdf->HasElement("units")) {
+    radians = sdf->Get<std::string>("units") != "degrees";
+  } else {
+    radians = true;
+  }
+
+  gzmsg << "\tinternal limit switch: "
+        << " type=" << joint->GetName() << " range=[" << min << "," << max
+        << "] radians=" << radians << std::endl;
+}
+
+bool InternalLimitSwitch::Get() {
+  double value;
+  if (radians) {
+    value = joint->Position(0);
+  } else {
+    value = joint->Position(0) * (180.0 / M_PI);
+  }
+  return value >= min && value <= max;
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/limit_switch.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/limit_switch.cpp
new file mode 100644
index 0000000..34b7ae3
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/cpp/limit_switch.cpp
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "limit_switch.h"
+
+#include <boost/algorithm/string/replace.hpp>
+
+GZ_REGISTER_MODEL_PLUGIN(LimitSwitch)
+
+void LimitSwitch::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+
+  // Parse SDF properties
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+  invert = sdf->HasElement("invert");
+  std::string type = sdf->Get<std::string>("type");
+
+  gzmsg << "Initializing limit switch: " << topic << " type=" << type
+        << std::endl;
+  if (type == "internal") {
+    ls = new InternalLimitSwitch(model, sdf);
+  } else if (type == "external") {
+    ls = new ExternalLimitSwitch(sdf);
+  } else {
+    gzerr << "WARNING: unsupported limit switch type " << type;
+  }
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  pub = node->Advertise<gazebo::msgs::Bool>(topic);
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&LimitSwitch::Update, this, _1));
+}
+
+void LimitSwitch::Update(const gazebo::common::UpdateInfo& info) {
+  gazebo::msgs::Bool msg;
+  if (invert)
+    msg.set_data(!ls->Get());
+  else
+    msg.set_data(ls->Get());
+  pub->Publish(msg);
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/external_limit_switch.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/external_limit_switch.h
new file mode 100644
index 0000000..2114b71
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/external_limit_switch.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <boost/pointer_cast.hpp>
+#include <gazebo/gazebo.hh>
+#include <gazebo/sensors/sensors.hh>
+
+#ifdef _WIN32
+#include <Winsock2.h>
+#endif
+
+#include "switch.h"
+
+class ExternalLimitSwitch : public Switch {
+ public:
+  explicit ExternalLimitSwitch(sdf::ElementPtr sdf);
+
+  /// \brief Returns true when the switch is triggered.
+  virtual bool Get();
+
+ private:
+  gazebo::sensors::ContactSensorPtr sensor;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/internal_limit_switch.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/internal_limit_switch.h
new file mode 100644
index 0000000..870e8e3
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/internal_limit_switch.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/physics/physics.hh>
+
+#ifdef _WIN32
+#include <Winsock2.h>
+#endif
+
+#include "switch.h"
+
+class InternalLimitSwitch : public Switch {
+ public:
+  InternalLimitSwitch(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Returns true when the switch is triggered.
+  virtual bool Get();
+
+ private:
+  gazebo::physics::JointPtr joint;
+  double min, max;
+  bool radians;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/limit_switch.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/limit_switch.h
new file mode 100644
index 0000000..23ae2cc
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/limit_switch.h
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#include "external_limit_switch.h"
+#include "internal_limit_switch.h"
+#include "simulation/gz_msgs/msgs.h"
+#include "switch.h"
+
+/**
+ * \brief Plugin for reading limit switches.
+ *
+ * This plugin publishes whether or not the limit switch has been
+ * triggered every physics update. There are two types of limit switches:
+ *
+ * - Internal: Measure joint limits. Triggerd if the joint is within
+ *             some range.
+ * - External: Measure interactions with the outside world. Triggerd
+ *             if some link is in collision.
+ *
+ * To add a limit swithch to your robot, add the following XML to your
+ * robot model.
+ *
+ * Internal:
+ *
+ *     <plugin name="my_limit_switch" filename="liblimit_switch.so">
+ *       <topic>~/my/topic</topic>
+ *       <type>internal</type>
+ *       <joint>Joint Name</joint>
+ *       <units>{degrees, radians}</units>
+ *       <min>Number</min>
+ *       <max>Number</max>
+ *     </plugin>
+ *
+ * External:
+ *
+ *     <plugin name="my_limit_switch" filename="liblimit_switch.so">
+ *       <topic>~/my/topic</topic>
+ *       <type>external</type>
+ *       <sensor>Sensor Name</sensor>
+ *     </plugin>
+ *
+ * Common:
+ * - `topic`: Optional. Message will be published as a gazebo.msgs.Bool.
+ *            Recommended values are of the form:
+ *              /gazebo/frc/simulator/dio/n
+ * - `type`: Required. The type of limit switch that this is
+ * - `invert`: Optional. If given, the output meaning will be inverted
+ *
+ * Internal
+ * - `joint`: Name of the joint this potentiometer is attached to.
+ * - `units`: Optional. Defaults to radians.
+ * - `min`: Minimum angle considered triggered.
+ * - `max`: Maximum angle considered triggered.
+ *
+ * External
+ * - `sensor`: Name of the contact sensor that this limit switch uses.
+ */
+class LimitSwitch : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the limit switch and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Sends out the limit switch reading each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Publish the limit switch value on this topic.
+  std::string topic;
+
+  /// \brief LimitSwitch object, currently internal or external.
+  Switch* ls;
+
+  /// \brief Indicate if we should invert the output
+  bool invert;
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer to the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Publisher handle.
+  gazebo::transport::PublisherPtr pub;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/switch.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/switch.h
new file mode 100644
index 0000000..0387647
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/limit_switch/headers/switch.h
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+class Switch {
+ public:
+  virtual ~Switch() = default;
+
+  /// \brief Returns true when the switch is triggered.
+  virtual bool Get() = 0;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/pneumatic_piston/cpp/pneumatic_piston.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/pneumatic_piston/cpp/pneumatic_piston.cpp
new file mode 100644
index 0000000..f0e4c7e
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/pneumatic_piston/cpp/pneumatic_piston.cpp
@@ -0,0 +1,95 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "pneumatic_piston.h"
+
+#include <boost/algorithm/string/replace.hpp>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#ifdef _WIN32
+// Ensure that Winsock2.h is included before Windows.h, which can get
+// pulled in by anybody (e.g., Boost).
+#include <Winsock2.h>
+#endif
+
+GZ_REGISTER_MODEL_PLUGIN(PneumaticPiston)
+
+void PneumaticPiston::Load(gazebo::physics::ModelPtr model,
+                           sdf::ElementPtr sdf) {
+  this->model = model;
+  forward_signal = reverse_signal = false;
+
+  // Parse SDF properties
+  joint = model->GetJoint(sdf->Get<std::string>("joint"));
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  if (sdf->HasElement("reverse-topic")) {
+    reverse_topic = sdf->Get<std::string>("reverse-topic");
+  } else {
+    reverse_topic.clear();
+  }
+
+  forward_force = sdf->Get<double>("forward-force");
+  if (sdf->HasElement("reverse-force"))
+    reverse_force = -1.0 * sdf->Get<double>("reverse-force");
+
+  if (sdf->HasElement("direction") &&
+      sdf->Get<std::string>("direction") == "reversed") {
+    forward_force = -forward_force;
+    reverse_force = -reverse_force;
+  }
+
+  gzmsg << "Initializing piston: " << topic << " joint=" << joint->GetName()
+        << " forward_force=" << forward_force
+        << " reverse_force=" << reverse_force << std::endl;
+  if (!reverse_topic.empty())
+    gzmsg << "Reversing on topic " << reverse_topic << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  sub = node->Subscribe(topic, &PneumaticPiston::ForwardCallback, this);
+  if (!reverse_topic.empty())
+    sub_reverse =
+        node->Subscribe(reverse_topic, &PneumaticPiston::ReverseCallback, this);
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&PneumaticPiston::Update, this, _1));
+}
+
+void PneumaticPiston::Update(const gazebo::common::UpdateInfo& info) {
+  double force = 0.0;
+  if (forward_signal) {
+    force = forward_force;
+  } else {
+    /* For DoubleSolenoids, the second signal must be present
+       for us to apply the reverse force.  For SingleSolenoids,
+       the lack of the forward signal suffices.
+       Note that a true simulation would not allow a SingleSolenoid to
+       have reverse force, but we put that in the hands of the model builder.*/
+    if (reverse_topic.empty() || reverse_signal) force = reverse_force;
+  }
+  joint->SetForce(0, force);
+}
+
+void PneumaticPiston::ForwardCallback(const gazebo::msgs::ConstBoolPtr& msg) {
+  forward_signal = msg->data();
+}
+
+void PneumaticPiston::ReverseCallback(const gazebo::msgs::ConstBoolPtr& msg) {
+  reverse_signal = msg->data();
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/pneumatic_piston/headers/pneumatic_piston.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/pneumatic_piston/headers/pneumatic_piston.h
new file mode 100644
index 0000000..ba8becf
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/pneumatic_piston/headers/pneumatic_piston.h
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/**
+ * \brief Plugin for controlling a joint with a pneumatic piston.
+ *
+ * This plugin subscribes to topics to get the solenoid state for a piston
+ *    It needs one signal for the forward signal.  For a double solenoid,
+ *    a second signal can be sent.
+ *    Each signal is a boolean.
+ *
+ * Every physics update the joint's torque is set to reflect the
+ * signal, using the configured force
+ *
+ * To add a pneumatic piston to your robot, add the following XML to
+ * your robot model:
+ *
+ *     <plugin name="my_piston" filename="libpneumatic_piston.so">
+ *       <joint>Joint Name</joint>
+ *       <topic>/gazebo/frc/simulator/pneumatics/1/1</topic>
+ *       <reverse-topic>/gazebo/frc/simulator/pneumatics/1/2</reverse-topic>
+ *       <direction>{forward, reversed}</direction>
+ *       <forward-force>Number</forward-force>
+ *       <reverse-force>Number</reverse-force>
+ *     </plugin>
+ *
+ * - `joint`: Name of the joint this piston is attached to.
+ * - `topic`: Optional. Forward Solenoid signal name. type gazebo.msgs.Bool.
+ *            If not given, the name given for the plugin will be used.
+ *            A pattern of /gazebo/frc/simulator/pneumatics/1/n is good.
+ *            The first number represents the PCM module.  Only 1 is supported.
+ *            The second number represents the channel on the PCM.
+ * - `topic-reverse`: Optional. If given, represents the reverse channel.
+ *            Message type should be gazebo.msgs.Bool.
+ * - `direction`: Optional. Defaults to forward. Reversed if the piston
+ *                pushes in the opposite direction of the joint axis.
+ * - `forward-force`: Force to apply in the forward direction.
+ * - `reverse-force`: Force to apply in the reverse direction.
+ *                    For a single solenoid, you would expect '0',
+ *                    but we allow model builders to provide a value.
+ *
+ */
+class PneumaticPiston : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the pneumatic piston and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Updat the force the piston applies on the joint.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Topic to read forward control signal from.
+  std::string topic;
+
+  /// \brief Topic to read reverse control signal from.
+  std::string reverse_topic;
+
+  /// \brief Whether the solenoid to open forward is on
+  bool forward_signal;
+
+  /// \brief Whether the solenoid to open in reverse is on
+  bool reverse_signal;
+
+  /// \brief The magic force multipliers for each direction.
+  double forward_force, reverse_force;
+
+  /// \brief The joint that this pneumatic piston actuates.
+  gazebo::physics::JointPtr joint;
+
+  /// \brief Callback for receiving msgs and updating the solenoid state
+  void ForwardCallback(const gazebo::msgs::ConstBoolPtr& msg);
+
+  /// \brief Callback for receiving msgs and updating the reverse solenoid state
+  void ReverseCallback(const gazebo::msgs::ConstBoolPtr& msg);
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer to the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Subscriber handle.
+  gazebo::transport::SubscriberPtr sub;
+
+  /// \brief Subscriber handle for reverse topic
+  gazebo::transport::SubscriberPtr sub_reverse;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/potentiometer/cpp/potentiometer.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/potentiometer/cpp/potentiometer.cpp
new file mode 100644
index 0000000..140afd1
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/potentiometer/cpp/potentiometer.cpp
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "potentiometer.h"
+
+#include <boost/algorithm/string/replace.hpp>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#ifdef _WIN32
+// Ensure that Winsock2.h is included before Windows.h, which can get
+// pulled in by anybody (e.g., Boost).
+#include <Winsock2.h>
+#endif
+
+GZ_REGISTER_MODEL_PLUGIN(Potentiometer)
+
+void Potentiometer::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+
+  // Parse SDF properties
+  joint = model->GetJoint(sdf->Get<std::string>("joint"));
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  if (sdf->HasElement("units")) {
+    radians = sdf->Get<std::string>("units") != "degrees";
+  } else {
+    radians = true;
+  }
+
+  multiplier = 1.0;
+  if (sdf->HasElement("multiplier"))
+    multiplier = sdf->Get<double>("multiplier");
+
+  gzmsg << "Initializing potentiometer: " << topic
+        << " joint=" << joint->GetName() << " radians=" << radians
+        << " multiplier=" << multiplier << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  pub = node->Advertise<gazebo::msgs::Float64>(topic);
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&Potentiometer::Update, this, _1));
+}
+
+void Potentiometer::Update(const gazebo::common::UpdateInfo& info) {
+  gazebo::msgs::Float64 msg;
+  if (radians) {
+    msg.set_data(joint->Position(0) * multiplier);
+  } else {
+    msg.set_data(joint->Position(0) * (180.0 / M_PI) * multiplier);
+  }
+  pub->Publish(msg);
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/potentiometer/headers/potentiometer.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/potentiometer/headers/potentiometer.h
new file mode 100644
index 0000000..f9111cb
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/potentiometer/headers/potentiometer.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/**
+ * \brief Plugin for reading the angle of a joint.
+ *
+ * This plugin publishes the angle of a joint to the topic every
+ * physics update. Supports reading in either radians or degrees.
+ *
+ * To add a potentiometer to your robot, add the following XML to your
+ * robot model:
+ *
+ *     <plugin name="my_pot" filename="libpotentiometer.so">
+ *       <joint>Joint Name</joint>
+ *       <topic>~/my/topic</topic>
+ *       <units>{degrees, radians}</units>
+ *     </plugin>
+ *
+ * - `joint`: Name of the joint this potentiometer is attached to.
+ * - `topic`: Optional. Message will be published as a gazebo.msgs.Float64.
+ *            The default topic name will be the plugin name.
+ *            Recommended topic names are of the form:
+ *              /gazebo/frc/simulator/analog/n
+ *            where n is the analog channel for the pot.
+ * - `multiplier`: Optional.  Amount to multiply output with.
+ *            Useful when a rotary pot returns something other than an angle
+ * - `units`: Optional. Defaults to radians.
+ */
+class Potentiometer : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the potentiometer and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Sends out the potentiometer reading each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Publish the angle on this topic.
+  std::string topic;
+
+  /// \brief Whether or not this potentiometer measures radians or degrees.
+  bool radians;
+
+  /// \brief A scaling factor to apply to this potentiometer.
+  double multiplier;
+
+  /// \brief The joint that this potentiometer measures
+  gazebo::physics::JointPtr joint;
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer to the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Publisher handle.
+  gazebo::transport::PublisherPtr pub;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/rangefinder/cpp/rangefinder.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/rangefinder/cpp/rangefinder.cpp
new file mode 100644
index 0000000..a01f10f
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/rangefinder/cpp/rangefinder.cpp
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "rangefinder.h"
+
+#include <boost/algorithm/string/replace.hpp>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/sensors/sensors.hh>
+#include <gazebo/transport/transport.hh>
+
+#ifdef _WIN32
+// Ensure that Winsock2.h is included before Windows.h, which can get
+// pulled in by anybody (e.g., Boost).
+#include <Winsock2.h>
+#endif
+
+GZ_REGISTER_MODEL_PLUGIN(Rangefinder)
+
+void Rangefinder::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+
+  // Parse SDF properties
+  sensor = std::dynamic_pointer_cast<gazebo::sensors::SonarSensor>(
+      gazebo::sensors::get_sensor(sdf->Get<std::string>("sensor")));
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  gzmsg << "Initializing rangefinder: " << topic << " sensor=" << sensor->Name()
+        << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  pub = node->Advertise<gazebo::msgs::Float64>(topic);
+
+  // Connect to the world update event.
+  // This will trigger the Update function every Gazebo iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&Rangefinder::Update, this, _1));
+}
+
+void Rangefinder::Update(const gazebo::common::UpdateInfo& info) {
+  gazebo::msgs::Float64 msg;
+  msg.set_data(sensor->Range());
+  pub->Publish(msg);
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/rangefinder/headers/rangefinder.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/rangefinder/headers/rangefinder.h
new file mode 100644
index 0000000..6a395b6
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/rangefinder/headers/rangefinder.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/**
+ * \brief Plugin for reading the range of obstacles.
+ *
+ * This plugin publishes the range of obstacles detected by a sonar
+ * rangefinder every physics update.
+ *
+ * To add a rangefinder to your robot, add the following XML to your
+ * robot model:
+ *
+ *     <plugin name="my_rangefinder" filename="librangefinder.so">
+ *       <sensor>Sensor Name</sensor>
+ *       <topic>~/my/topic</topic>
+ *     </plugin>
+ *
+ * - `sensor`: Name of the sonar sensor that this rangefinder uses.
+ * - `topic`: Optional. Message will be published as a gazebo.msgs.Float64.
+ */
+class Rangefinder : public gazebo::ModelPlugin {
+ public:
+  /// \brief Load the rangefinder and configures it according to the sdf.
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Sends out the rangefinder reading each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Publish the range on this topic.
+  std::string topic;
+
+  /// \brief The sonar sensor that this rangefinder uses
+  gazebo::sensors::SonarSensorPtr sensor;
+
+  /// \brief The model to which this is attached.
+  gazebo::physics::ModelPtr model;
+
+  /// \brief Pointer to the world update function.
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising.
+  gazebo::transport::NodePtr node;
+
+  /// \brief Publisher handle.
+  gazebo::transport::PublisherPtr pub;
+};
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/servo/cpp/servo.cpp b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/servo/cpp/servo.cpp
new file mode 100644
index 0000000..ca9d361
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/servo/cpp/servo.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "servo.h"
+
+#include <boost/algorithm/string/replace.hpp>
+#include <gazebo/physics/physics.hh>
+#include <gazebo/transport/transport.hh>
+
+#ifdef _WIN32
+// Ensure that Winsock2.h is included before Windows.h, which can get
+// pulled in by anybody (e.g., Boost).
+#include <Winsock2.h>
+#endif
+
+GZ_REGISTER_MODEL_PLUGIN(Servo)
+
+void Servo::Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf) {
+  this->model = model;
+  signal = 0;
+
+  // parse SDF Properries
+  joint = model->GetJoint(sdf->Get<std::string>("joint"));
+  if (sdf->HasElement("topic")) {
+    topic = sdf->Get<std::string>("topic");
+  } else {
+    topic = "~/" + sdf->GetAttribute("name")->GetAsString();
+  }
+
+  if (sdf->HasElement("torque")) {
+    torque = sdf->Get<double>("torque");
+  } else {
+    torque = 5;
+  }
+
+  gzmsg << "initializing servo: " << topic << " joint=" << joint->GetName()
+        << " torque=" << torque << std::endl;
+
+  // Connect to Gazebo transport for messaging
+  std::string scoped_name =
+      model->GetWorld()->Name() + "::" + model->GetScopedName();
+  boost::replace_all(scoped_name, "::", "/");
+  node = gazebo::transport::NodePtr(new gazebo::transport::Node());
+  node->Init(scoped_name);
+  sub = node->Subscribe(topic, &Servo::Callback, this);
+
+  // connect to the world update event
+  // this will call update every iteration
+  updateConn = gazebo::event::Events::ConnectWorldUpdateBegin(
+      boost::bind(&Servo::Update, this, _1));
+}
+
+void Servo::Update(const gazebo::common::UpdateInfo& info) {
+  // torque is in kg*cm
+  // joint->SetAngle(0,signal*180);
+  if (joint->Position(0) < signal) {
+    joint->SetForce(0, torque);
+  } else if (joint->Position(0) > signal) {
+    joint->SetForce(0, torque);
+  }
+  joint->SetForce(0, 0);
+}
+
+void Servo::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
+  signal = msg->data();
+  if (signal < -1) {
+    signal = -1;
+  } else if (signal > 1) {
+    signal = 1;
+  }
+}
diff --git a/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/servo/headers/servo.h b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/servo/headers/servo.h
new file mode 100644
index 0000000..6d8ab08
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/frc_gazebo_plugins/src/servo/headers/servo.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo.hh>
+
+#include "simulation/gz_msgs/msgs.h"
+
+/**
+ * \brief Plugin for controlling a servo.
+ *
+ * This plugin subscribes to a topic to get a signal in the range
+ * [-1,1]. Every physics update the joint's torque is set as
+ * multiplier*signal.
+ *
+ * To add a servo to your robot, add the following XML to your robot
+ * model:
+ *
+ *     <plugin name="my_servo" filename="libservo.so">
+ *       <joint>Joint Name</joint>
+ *       <topic>/gzebo/frc/simulator/pwm/1</topic>
+ *       <zero_position>0</zero_position>
+ *     </plugin>
+ *
+ * - `link`: Name of the link the servo is attached to.
+ * - `topic`: Optional. Message type should be gazebo.msgs.Float64.
+ */
+class Servo : public gazebo::ModelPlugin {
+ public:
+  /// \brief load the servo and configure it according to the sdf
+  void Load(gazebo::physics::ModelPtr model, sdf::ElementPtr sdf);
+
+  /// \brief Update the torque on the joint from the dc motor each timestep.
+  void Update(const gazebo::common::UpdateInfo& info);
+
+ private:
+  /// \brief Topic to read control signal from.
+  std::string topic;
+
+  /// \brief the pwm signal limited to the range [-1,1]
+  double signal;
+
+  /// \brief the torque of the motor in kg/cm
+  double torque;
+
+  /// \brief the joint that this servo moves
+  gazebo::physics::JointPtr joint;
+
+  /// \brief Callback for receiving msgs and storing the signal
+  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
+
+  /// \brief The model to which this is attached
+  gazebo::physics::ModelPtr model;
+
+  /// \brief The pointer to the world update function
+  gazebo::event::ConnectionPtr updateConn;
+
+  /// \brief The node on which we're advertising torque
+  gazebo::transport::NodePtr node;
+
+  /// \brief The subscriber for the PWM signal
+  gazebo::transport::SubscriberPtr sub;
+};
diff --git a/third_party/allwpilib_2019/simulation/gz_msgs/README.md b/third_party/allwpilib_2019/simulation/gz_msgs/README.md
new file mode 100644
index 0000000..7df7a79
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/gz_msgs/README.md
@@ -0,0 +1,12 @@
+gz_msgs
+=======
+gz_msgs is a library that allows the transmission of messages
+to and from Java and C++ programs.
+
+gz_msgs currently requires libprotobuf-dev on Debian like systems.
+
+If it's not found via pkg-config, then it's build is diabled.
+
+You can force it by specifying -PmakeSim on the gradle command line.
+
+If you are installing FRCSim with the script, then this *should* have be done for you.
diff --git a/third_party/allwpilib_2019/simulation/gz_msgs/build.gradle b/third_party/allwpilib_2019/simulation/gz_msgs/build.gradle
new file mode 100644
index 0000000..8264ceb
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/gz_msgs/build.gradle
@@ -0,0 +1,95 @@
+plugins {
+    id 'cpp'
+    id 'java'
+    id 'com.google.protobuf' version '0.8.6'
+    id 'edu.wpi.first.NativeUtils'
+}
+
+description = "A C++ and Java library to pass FRC Simulation Messages in and out of Gazebo."
+
+/* The simulation does not run on real hardware; so we always skip Athena */
+ext.skipAthena = true
+ext.skipRaspbian = true
+apply from: "${rootDir}/shared/config.gradle"
+
+/* Use a sort of poor man's autoconf to find the protobuf development
+   files; on Debian, those are supplied by libprotobuf-dev.
+
+   This should get skipped on Windows.
+
+   TODO:  Add Windows support for the simulation code */
+
+def protobuf_version = ""
+try {
+    protobuf_version = "pkg-config --modversion protobuf".execute().text.trim()
+    println "Protobuf version is [${protobuf_version}]"
+} catch(Exception ex) {
+}
+
+if (!protobuf_version?.trim()) {
+    println "Protobuf is not available. (pkg-config --modversion protobuf failed)"
+    protobuf_version = "+"
+    if (project.hasProperty("makeSim")) {
+        /* Force the build even though we did not find protobuf. */
+        println "makeSim set. Forcing build - failure likely."
+    }
+    else {
+        ext.skip_gz_msgs = true
+        println "Skipping gz_msgs."
+    }
+}
+
+tasks.whenTaskAdded { task ->
+    task.onlyIf { !project.hasProperty('skip_gz_msgs') }
+}
+
+dependencies {
+      compile "com.google.protobuf:protobuf-java:${protobuf_version}"
+      compile "com.google.protobuf:protoc:${protobuf_version}"
+}
+
+/* There is a nice gradle plugin for protobuf, and the protoc tool
+   is included; using it simplifies our build process.
+   The trick is that we have to use the same version as the system
+   copy of libprotobuf-dev */
+protobuf {
+    protoc {
+        artifact = "com.google.protobuf:protoc:${protobuf_version}"
+    }
+
+    generatedFilesBaseDir = "$buildDir/generated"
+    generateProtoTasks {
+        all().each { task ->
+            task.builtins {
+                cpp {
+                    outputSubDir = 'simulation/gz_msgs'
+                }
+            }
+        }
+    }
+}
+
+model {
+    components {
+        gz_msgs(NativeLibrarySpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDir "$buildDir/generated/main/simulation/gz_msgs"
+                        builtBy tasks.generateProto
+                    }
+                    exportedHeaders {
+                        srcDir "src/include"
+                        srcDir "$buildDir/generated/main"
+                    }
+                }
+            }
+            /* We must compile with -fPIC to link the static library into an so */
+            binaries {
+                all {
+                    cppCompiler.args "-fPIC"
+                }
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/simulation/gz_msgs/src/include/simulation/gz_msgs/msgs.h b/third_party/allwpilib_2019/simulation/gz_msgs/src/include/simulation/gz_msgs/msgs.h
new file mode 100644
index 0000000..e953ad5
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/gz_msgs/src/include/simulation/gz_msgs/msgs.h
@@ -0,0 +1,47 @@
+/* This was originally auto generated by cmake.
+   However, it changes infrequently enough that it makes
+   sense to simply revise it by hand any time we change
+   the protobuf messages expressed in the .proto files */
+
+#ifndef _FRC_MSGS_H_
+#define _FRC_MSGS_H_
+
+#ifdef _WIN32
+  //include this before anything else includes windows.h
+  //putting this here saves putting it in more files
+  #include <Winsock2.h>
+#endif
+
+
+ #include "simulation/gz_msgs/bool.pb.h"
+ #include "simulation/gz_msgs/driver-station.pb.h"
+ #include "simulation/gz_msgs/float64.pb.h"
+ #include "simulation/gz_msgs/frc_joystick.pb.h"
+
+
+#include <gazebo/msgs/msgs.hh>
+#include <boost/shared_ptr.hpp>
+
+namespace gazebo {
+  namespace msgs {
+
+    typedef GzString String;
+
+    typedef boost::shared_ptr< gazebo::msgs::String > StringPtr;
+    typedef const boost::shared_ptr< const gazebo::msgs::String > ConstStringPtr;
+
+    typedef boost::shared_ptr< msgs::Float64 > Float64Ptr;
+    typedef const boost::shared_ptr< const msgs::Float64 > ConstFloat64Ptr;
+
+    typedef boost::shared_ptr< msgs::Bool > BoolPtr;
+    typedef const boost::shared_ptr< const msgs::Bool > ConstBoolPtr;
+
+    typedef boost::shared_ptr< msgs::FRCJoystick > FRCJoystickPtr;
+    typedef const boost::shared_ptr< const msgs::FRCJoystick > ConstFRCJoystickPtr;
+
+    typedef boost::shared_ptr< msgs::DriverStation > DriverStationPtr;
+    typedef const boost::shared_ptr< const msgs::DriverStation > ConstDriverStationPtr;
+  }
+}
+
+#endif /* _FRC_MSGS_H_ */
diff --git a/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/bool.proto b/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/bool.proto
new file mode 100644
index 0000000..90ab7fa
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/bool.proto
@@ -0,0 +1,15 @@
+package gazebo.msgs;
+
+/// \ingroup gazebo_msgs
+/// \interface Bool
+/// \brief A message for boolean data
+/// \verbatim
+
+option java_outer_classname = "GzBool";
+
+message Bool
+{
+  required bool data = 1;
+}
+
+/// \endverbatim
diff --git a/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/driver-station.proto b/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/driver-station.proto
new file mode 100644
index 0000000..187e056
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/driver-station.proto
@@ -0,0 +1,21 @@
+package gazebo.msgs;
+
+/// \ingroup gazebo_msgs
+/// \interface DriverStation
+/// \brief A message for DriverStation data
+/// \verbatim
+
+option java_outer_classname = "GzDriverStation";
+
+message DriverStation
+{
+  required bool enabled = 1;
+  enum State {
+    AUTO = 0;
+    TELEOP = 1;
+    TEST = 2;
+  }
+  required State state = 2;
+}
+
+/// \endverbatim
diff --git a/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/float64.proto b/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/float64.proto
new file mode 100644
index 0000000..dd3ddcc
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/float64.proto
@@ -0,0 +1,15 @@
+package gazebo.msgs;
+
+/// \ingroup gazebo_msgs
+/// \interface Float64
+/// \brief A message for floating point data
+/// \verbatim
+
+option java_outer_classname = "GzFloat64";
+
+message Float64
+{
+  required double data = 1;
+}
+
+/// \endverbatim
diff --git a/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/frc_joystick.proto b/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/frc_joystick.proto
new file mode 100644
index 0000000..ec98aba
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/gz_msgs/src/main/proto/frc_joystick.proto
@@ -0,0 +1,16 @@
+package gazebo.msgs;
+
+/// \ingroup gazebo_msgs
+/// \interface Joystick
+/// \brief A message for joystick data
+/// \verbatim
+
+option java_outer_classname = "GzFRCJoystick";
+
+message FRCJoystick
+{
+  repeated double axes = 1;
+  repeated bool buttons = 2;
+}
+
+/// \endverbatim
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/build.gradle b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/build.gradle
new file mode 100644
index 0000000..c9f754d
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/build.gradle
@@ -0,0 +1,198 @@
+apply plugin: 'cpp'
+apply plugin: 'google-test-test-suite'
+apply plugin: 'visual-studio'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: SingleNativeBuild
+apply plugin: ExtraTasks
+
+ext {
+    nativeName = 'halsim_adx_gyro_accelerometer'
+}
+
+apply from: "${rootDir}/shared/config.gradle"
+
+if (!project.hasProperty('onlyAthena')) {
+
+    ext {
+        sharedCvConfigs = [halsim_adx_gyro_accelerometerTest: []]
+        staticCvConfigs = [:]
+        useJava = false
+        useCpp = true
+    }
+    apply from: "${rootDir}/shared/opencv.gradle"
+
+    ext {
+        staticGtestConfigs = [:]
+    }
+    staticGtestConfigs["${nativeName}Test"] = []
+    apply from: "${rootDir}/shared/googletest.gradle"
+
+    project(':').libraryBuild.dependsOn build
+
+    ext {
+        chipObjectComponents = ["$nativeName".toString(), "${nativeName}Base".toString(), "${nativeName}Dev".toString(), "${nativeName}Test".toString()]
+        netCommComponents = ["$nativeName".toString(), "${nativeName}Base".toString(), "${nativeName}Dev".toString(), "${nativeName}Test".toString()]
+        useNiJava = false
+    }
+
+    apply from: "${rootDir}/shared/nilibraries.gradle"
+
+    model {
+        exportsConfigs {
+            halsim_adx_gyro_accelerometer(ExportsConfig) {
+                x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                     '_CT??_R0?AVbad_cast',
+                                     '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                     '_TI5?AVfailure']
+                x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                     '_CT??_R0?AVbad_cast',
+                                     '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                     '_TI5?AVfailure']
+            }
+        }
+        components {
+            "${nativeName}Base"(NativeLibrarySpec) {
+                sources {
+                    cpp {
+                        source {
+                            srcDirs = ['src/main/native/cpp']
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/native/include'
+                        }
+                    }
+                }
+                binaries.all {
+                    if (it instanceof SharedLibraryBinarySpec) {
+                        it.buildable = false
+                        return
+                    }
+                    if (it.targetPlatform.architecture.name == 'athena') {
+                        it.buildable = false
+                        return
+                    }
+                    project(':hal').addHalDependency(it, 'shared')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                }
+            }
+            "${nativeName}"(NativeLibrarySpec) {
+                sources {
+                    cpp {
+                        source {
+                            srcDirs "${rootDir}/shared/singlelib"
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/native/include'
+                        }
+                    }
+                }
+                binaries.all {
+                    if (it.targetPlatform.architecture.name == 'athena') {
+                        it.buildable = false
+                        return
+                    }
+                    project(':hal').addHalDependency(it, 'shared')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                }
+            }
+            // By default, a development executable will be generated. This is to help the case of
+            // testing specific functionality of the library.
+            "${nativeName}Dev"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'src/dev/native/cpp'
+                            include '**/*.cpp'
+                            lib library: "${nativeName}"
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/dev/native/include'
+                        }
+                    }
+                }
+                binaries.all {
+                    if (it.targetPlatform.architecture.name == 'athena') {
+                        it.buildable = false
+                        return
+                    }
+                    project(':hal').addHalDependency(it, 'shared')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib library: nativeName, linkage: 'shared'
+                }
+            }
+        }
+        binaries {
+            withType(GoogleTestTestSuiteBinarySpec) {
+                if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                    project(':hal').addHalDependency(it, 'shared')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                    lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                    lib library: nativeName, linkage: 'shared'
+                } else {
+                    it.buildable = false
+                }
+            }
+        }
+    }
+
+    apply from: "publish.gradle"
+}
+
+model {
+
+    testSuites {
+        if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+            "${nativeName}Test"(GoogleTestTestSuiteSpec) {
+                for(NativeComponentSpec c : $.components) {
+                    if (c.name == nativeName) {
+                        testing c
+                        break
+                    }
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'src/test/native/cpp'
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/test/native/include', 'src/main/native/cpp'
+                        }
+                    }
+                }
+            }
+        }
+    }
+    tasks {
+        def c = $.components
+        project.tasks.create('runCpp', Exec) {
+            def found = false
+            c.each {
+                if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
+                    it.binaries.each {
+                        if (!found) {
+                            def arch = it.targetPlatform.architecture.name
+                            if (arch == 'x86-64' || arch == 'x86') {
+                                dependsOn it.tasks.install
+								commandLine it.tasks.install.runScriptFile.get().asFile.toString()
+
+                                found = true
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+tasks.withType(RunTestExecutable) {
+    args "--gtest_output=xml:test_detail.xml"
+    outputs.dir outputDir
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/publish.gradle b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/publish.gradle
new file mode 100644
index 0000000..11feda5
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/publish.gradle
@@ -0,0 +1,70 @@
+apply plugin: 'maven-publish'
+
+def pubVersion = ''
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseArtifactId = nativeName
+def artifactGroupId = 'edu.wpi.first.halsim'
+def zipBaseName = "_GROUP_edu_wpi_first_halsim_ID_${nativeName}_CLS"
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task cppSourcesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "sources"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/cpp') {
+        into '/'
+    }
+}
+
+task cppHeadersZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "headers"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/include') {
+        into '/'
+    }
+}
+
+build.dependsOn cppSourcesZip
+build.dependsOn cppHeadersZip
+
+addTaskToCopyAllOutputs(cppSourcesZip)
+addTaskToCopyAllOutputs(cppHeadersZip)
+
+model {
+    publishing {
+        def halsim_adx_gyro_accelerometerTaskList = createComponentZipTasks($.components, [nativeName], zipBaseName, Zip, project, includeStandardZipFormat)
+
+        publications {
+            cpp(MavenPublication) {
+                halsim_adx_gyro_accelerometerTaskList.each {
+                    artifact it
+                }
+
+                artifact cppHeadersZip
+                artifact cppSourcesZip
+
+
+                artifactId = baseArtifactId
+                groupId artifactGroupId
+                version pubVersion
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..e324b44
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/dev/native/cpp/main.cpp
@@ -0,0 +1,8 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+int main() {}
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL345_I2CAccelerometerData.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL345_I2CAccelerometerData.cpp
new file mode 100644
index 0000000..f0650db
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL345_I2CAccelerometerData.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ADXL345_I2CAccelerometerData.h"
+
+#include <cstring>
+
+#include <mockdata/I2CData.h>
+
+using namespace hal;
+
+const double ADXL345_I2CData::LSB = 1 / 0.00390625;
+
+static void ADXL345I2C_ReadBufferCallback(const char* name, void* param,
+                                          uint8_t* buffer, uint32_t count) {
+  ADXL345_I2CData* sim = static_cast<ADXL345_I2CData*>(param);
+  sim->HandleRead(buffer, count);
+}
+
+static void ADXL345I2C_WriteBufferCallback(const char* name, void* param,
+                                           const uint8_t* buffer,
+                                           uint32_t count) {
+  ADXL345_I2CData* sim = static_cast<ADXL345_I2CData*>(param);
+  sim->HandleWrite(buffer, count);
+}
+
+ADXL345_I2CData::ADXL345_I2CData(int port) : m_port(port) {
+  m_readCallbackId =
+      HALSIM_RegisterI2CReadCallback(port, ADXL345I2C_ReadBufferCallback, this);
+  m_writeCallbackId = HALSIM_RegisterI2CWriteCallback(
+      port, ADXL345I2C_WriteBufferCallback, this);
+}
+
+ADXL345_I2CData::~ADXL345_I2CData() {
+  HALSIM_CancelI2CReadCallback(m_port, m_readCallbackId);
+  HALSIM_CancelI2CWriteCallback(m_port, m_writeCallbackId);
+}
+
+bool ADXL345_I2CData::GetInitialized() const {
+  return HALSIM_GetI2CInitialized(m_port);
+}
+
+void ADXL345_I2CData::ADXL345_I2CData::HandleWrite(const uint8_t* buffer,
+                                                   uint32_t count) {
+  m_lastWriteAddress = buffer[0];
+}
+
+void ADXL345_I2CData::HandleRead(uint8_t* buffer, uint32_t count) {
+  bool writeAll = count == 6;
+  int byteIndex = 0;
+
+  if (writeAll || m_lastWriteAddress == 0x32) {
+    int16_t val = static_cast<int16_t>(GetX() * LSB);
+    std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+    byteIndex += sizeof(val);
+  }
+
+  if (writeAll || m_lastWriteAddress == 0x34) {
+    int16_t val = static_cast<int16_t>(GetY() * LSB);
+    std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+    byteIndex += sizeof(val);
+  }
+
+  if (writeAll || m_lastWriteAddress == 0x36) {
+    int16_t val = static_cast<int16_t>(GetZ() * LSB);
+    std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+    byteIndex += sizeof(val);
+  }
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL345_SpiAccelerometerData.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL345_SpiAccelerometerData.cpp
new file mode 100644
index 0000000..e60f4a7
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL345_SpiAccelerometerData.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ADXL345_SpiAccelerometerData.h"
+
+#include <cstring>
+
+#include <mockdata/SPIData.h>
+
+using namespace hal;
+
+const double ADXL345_SpiAccelerometer::LSB = 1 / 0.00390625;
+
+static void ADXL345SPI_ReadBufferCallback(const char* name, void* param,
+                                          uint8_t* buffer, uint32_t count) {
+  ADXL345_SpiAccelerometer* sim = static_cast<ADXL345_SpiAccelerometer*>(param);
+  sim->HandleRead(buffer, count);
+}
+
+static void ADXL345SPI_WriteBufferCallback(const char* name, void* param,
+                                           const uint8_t* buffer,
+                                           uint32_t count) {
+  ADXL345_SpiAccelerometer* sim = static_cast<ADXL345_SpiAccelerometer*>(param);
+  sim->HandleWrite(buffer, count);
+}
+
+ADXL345_SpiAccelerometer::ADXL345_SpiAccelerometer(int port) : m_port(port) {
+  m_readCallbackId =
+      HALSIM_RegisterSPIReadCallback(port, ADXL345SPI_ReadBufferCallback, this);
+  m_writeCallbackId = HALSIM_RegisterSPIWriteCallback(
+      port, ADXL345SPI_WriteBufferCallback, this);
+}
+
+ADXL345_SpiAccelerometer::~ADXL345_SpiAccelerometer() {
+  HALSIM_CancelSPIReadCallback(m_port, m_readCallbackId);
+  HALSIM_CancelSPIWriteCallback(m_port, m_writeCallbackId);
+}
+
+bool ADXL345_SpiAccelerometer::GetInitialized() const {
+  return HALSIM_GetSPIInitialized(m_port);
+}
+
+void ADXL345_SpiAccelerometer::HandleWrite(const uint8_t* buffer,
+                                           uint32_t count) {
+  m_lastWriteAddress = buffer[0] & 0xF;
+}
+
+void ADXL345_SpiAccelerometer::HandleRead(uint8_t* buffer, uint32_t count) {
+  bool writeAll = count == 7;
+  int byteIndex = 1;
+
+  if (writeAll || m_lastWriteAddress == 0x02) {
+    int16_t val = static_cast<int16_t>(GetX() * LSB);
+    std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+    byteIndex += sizeof(val);
+  }
+
+  if (writeAll || m_lastWriteAddress == 0x04) {
+    int16_t val = static_cast<int16_t>(GetY() * LSB);
+    std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+    byteIndex += sizeof(val);
+  }
+
+  if (writeAll || m_lastWriteAddress == 0x06) {
+    int16_t val = static_cast<int16_t>(GetZ() * LSB);
+    std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+    byteIndex += sizeof(val);
+  }
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL362_SpiAccelerometerData.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL362_SpiAccelerometerData.cpp
new file mode 100644
index 0000000..306be89
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXL362_SpiAccelerometerData.cpp
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ADXL362_SpiAccelerometerData.h"
+
+#include <cstring>
+
+#include <mockdata/SPIData.h>
+
+using namespace hal;
+
+const double ADXL362_SpiAccelerometer::LSB = 1 / 0.001;
+
+static void ADXL362SPI_ReadBufferCallback(const char* name, void* param,
+                                          uint8_t* buffer, uint32_t count) {
+  ADXL362_SpiAccelerometer* sim = static_cast<ADXL362_SpiAccelerometer*>(param);
+  sim->HandleRead(buffer, count);
+}
+
+static void ADXL362SPI_WriteBufferCallback(const char* name, void* param,
+                                           const uint8_t* buffer,
+                                           uint32_t count) {
+  ADXL362_SpiAccelerometer* sim = static_cast<ADXL362_SpiAccelerometer*>(param);
+  sim->HandleWrite(buffer, count);
+}
+
+ADXL362_SpiAccelerometer::ADXL362_SpiAccelerometer(int port) : m_port(port) {
+  m_readCallbackId =
+      HALSIM_RegisterSPIReadCallback(port, ADXL362SPI_ReadBufferCallback, this);
+  m_writeCallbackId = HALSIM_RegisterSPIWriteCallback(
+      port, ADXL362SPI_WriteBufferCallback, this);
+}
+
+ADXL362_SpiAccelerometer::~ADXL362_SpiAccelerometer() {
+  HALSIM_CancelSPIReadCallback(m_port, m_readCallbackId);
+  HALSIM_CancelSPIWriteCallback(m_port, m_writeCallbackId);
+}
+bool ADXL362_SpiAccelerometer::GetInitialized() const {
+  return HALSIM_GetSPIInitialized(m_port);
+}
+
+void ADXL362_SpiAccelerometer::HandleWrite(const uint8_t* buffer,
+                                           uint32_t count) {
+  m_lastWriteAddress = buffer[1];
+}
+
+void ADXL362_SpiAccelerometer::HandleRead(uint8_t* buffer, uint32_t count) {
+  // Init check
+  if (m_lastWriteAddress == 0x02) {
+    uint32_t numToPut = 0xF20000;
+    std::memcpy(&buffer[0], &numToPut, sizeof(numToPut));
+  } else {
+    // Get Accelerations
+    bool writeAll = count == 8;
+    int byteIndex = 2;
+
+    if (writeAll || m_lastWriteAddress == 0x0E) {
+      int16_t val = static_cast<int16_t>(GetX() * LSB);
+      std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+      byteIndex += sizeof(val);
+    }
+
+    if (writeAll || m_lastWriteAddress == 0x10) {
+      int16_t val = static_cast<int16_t>(GetY() * LSB);
+      std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+      byteIndex += sizeof(val);
+    }
+
+    if (writeAll || m_lastWriteAddress == 0x12) {
+      int16_t val = static_cast<int16_t>(GetZ() * LSB);
+      std::memcpy(&buffer[byteIndex], &val, sizeof(val));
+      byteIndex += sizeof(val);
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXRS450_SpiGyroWrapperData.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXRS450_SpiGyroWrapperData.cpp
new file mode 100644
index 0000000..5658b30
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ADXRS450_SpiGyroWrapperData.cpp
@@ -0,0 +1,132 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ADXRS450_SpiGyroWrapperData.h"
+
+#include <algorithm>
+#include <cmath>
+#include <cstring>
+
+#include <hal/HALBase.h>
+#include <mockdata/SPIData.h>
+
+#ifdef _WIN32
+#include "Winsock2.h"
+#pragma comment(lib, "ws2_32.lib")
+#else
+#include <arpa/inet.h>
+#endif
+
+using namespace hal;
+
+static constexpr double kSamplePeriod = 0.0005;
+
+const double ADXRS450_SpiGyroWrapper::kAngleLsb = 1 / 0.0125 / kSamplePeriod;
+const double ADXRS450_SpiGyroWrapper::kMaxAngleDeltaPerMessage = 0.1875;
+const int ADXRS450_SpiGyroWrapper::kPacketSize = 4 + 1;  // +1 for timestamp
+
+template <class T>
+constexpr const T& clamp(const T& value, const T& low, const T& high) {
+  return std::max(low, std::min(value, high));
+}
+
+static void ADXRS450SPI_ReadBufferCallback(const char* name, void* param,
+                                           uint8_t* buffer, uint32_t count) {
+  auto sim = static_cast<ADXRS450_SpiGyroWrapper*>(param);
+  sim->HandleRead(buffer, count);
+}
+
+static void ADXRS450SPI_ReadAutoReceivedData(const char* name, void* param,
+                                             uint32_t* buffer,
+                                             int32_t numToRead,
+                                             int32_t* outputCount) {
+  auto sim = static_cast<ADXRS450_SpiGyroWrapper*>(param);
+  sim->HandleAutoReceiveData(buffer, numToRead, *outputCount);
+}
+
+ADXRS450_SpiGyroWrapper::ADXRS450_SpiGyroWrapper(int port) : m_port(port) {
+  m_readCallbackId = HALSIM_RegisterSPIReadCallback(
+      port, ADXRS450SPI_ReadBufferCallback, this);
+  m_autoReceiveReadCallbackId = HALSIM_RegisterSPIReadAutoReceivedDataCallback(
+      port, ADXRS450SPI_ReadAutoReceivedData, this);
+}
+
+ADXRS450_SpiGyroWrapper::~ADXRS450_SpiGyroWrapper() {
+  HALSIM_CancelSPIReadCallback(m_port, m_readCallbackId);
+  HALSIM_CancelSPIReadAutoReceivedDataCallback(m_port,
+                                               m_autoReceiveReadCallbackId);
+}
+bool ADXRS450_SpiGyroWrapper::GetInitialized() const {
+  return HALSIM_GetSPIInitialized(m_port);
+}
+
+void ADXRS450_SpiGyroWrapper::ResetData() {
+  std::lock_guard<wpi::recursive_spinlock> lock(m_angle.GetMutex());
+  m_angle.Reset(0.0);
+  m_angleDiff = 0;
+}
+
+void ADXRS450_SpiGyroWrapper::HandleRead(uint8_t* buffer, uint32_t count) {
+  int returnCode = 0x00400AE0;
+  std::memcpy(&buffer[0], &returnCode, sizeof(returnCode));
+}
+
+void ADXRS450_SpiGyroWrapper::HandleAutoReceiveData(uint32_t* buffer,
+                                                    int32_t numToRead,
+                                                    int32_t& outputCount) {
+  std::lock_guard<wpi::recursive_spinlock> lock(m_angle.GetMutex());
+  int32_t messagesToSend =
+      1 + std::abs(m_angleDiff > 0
+                       ? std::ceil(m_angleDiff / kMaxAngleDeltaPerMessage)
+                       : std::floor(m_angleDiff / kMaxAngleDeltaPerMessage));
+
+  // Zero gets passed in during the "How much data do I need to read" step.
+  // Else it is actually reading the accumulator
+  if (numToRead == 0) {
+    outputCount = messagesToSend * kPacketSize;
+    return;
+  }
+
+  int valuesToRead = numToRead / kPacketSize;
+  std::memset(&buffer[0], 0, numToRead * sizeof(uint32_t));
+
+  int32_t status = 0;
+  uint32_t timestamp = HAL_GetFPGATime(&status);
+
+  for (int msgCtr = 0; msgCtr < valuesToRead; ++msgCtr) {
+    // force the first message to be a rate of 0 to init the timestamp
+    double cappedDiff = (msgCtr == 0)
+                            ? 0
+                            : clamp(m_angleDiff, -kMaxAngleDeltaPerMessage,
+                                    kMaxAngleDeltaPerMessage);
+
+    // first word is timestamp
+    buffer[msgCtr * kPacketSize] = timestamp;
+
+    int32_t valueToSend =
+        ((static_cast<int32_t>(cappedDiff * kAngleLsb) << 10) & (~0x0C00000E)) |
+        0x04000000;
+
+    // following words have byte in LSB, in big endian order
+    for (int i = 4; i >= 1; --i) {
+      buffer[msgCtr * kPacketSize + i] =
+          static_cast<uint32_t>(valueToSend) & 0xffu;
+      valueToSend >>= 8;
+    }
+
+    m_angleDiff -= cappedDiff;
+    timestamp += kSamplePeriod * 1e6;  // fpga time is in us
+  }
+}
+
+void ADXRS450_SpiGyroWrapper::SetAngle(double angle) {
+  std::lock_guard<wpi::recursive_spinlock> lock(m_angle.GetMutex());
+  if (m_angle != angle) {
+    m_angleDiff += angle - m_angle;
+    m_angle = angle;
+  }
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ThreeAxisAccelerometerData.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ThreeAxisAccelerometerData.cpp
new file mode 100644
index 0000000..f2483af
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/cpp/ThreeAxisAccelerometerData.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ThreeAxisAccelerometerData.h"
+
+using namespace hal;
+
+ThreeAxisAccelerometerData::ThreeAxisAccelerometerData() {}
+
+ThreeAxisAccelerometerData::~ThreeAxisAccelerometerData() {}
+void ThreeAxisAccelerometerData::ResetData() {
+  x.Reset(0.0);
+  y.Reset(0.0);
+  z.Reset(0.0);
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL345_I2CAccelerometerData.h b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL345_I2CAccelerometerData.h
new file mode 100644
index 0000000..a08e9f2
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL345_I2CAccelerometerData.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ThreeAxisAccelerometerData.h"
+
+namespace hal {
+class ADXL345_I2CData : public ThreeAxisAccelerometerData {
+ public:
+  explicit ADXL345_I2CData(int port);
+  virtual ~ADXL345_I2CData();
+
+  bool GetInitialized() const override;
+
+  void HandleWrite(const uint8_t* buffer, uint32_t count);
+  void HandleRead(uint8_t* buffer, uint32_t count);
+
+ private:
+  int m_port;
+  int m_writeCallbackId;
+  int m_readCallbackId;
+
+  int m_lastWriteAddress;
+
+  static const double LSB;
+};
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL345_SpiAccelerometerData.h b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL345_SpiAccelerometerData.h
new file mode 100644
index 0000000..23140cb
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL345_SpiAccelerometerData.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ThreeAxisAccelerometerData.h"
+
+namespace hal {
+class ADXL345_SpiAccelerometer : public ThreeAxisAccelerometerData {
+ public:
+  explicit ADXL345_SpiAccelerometer(int port);
+  virtual ~ADXL345_SpiAccelerometer();
+
+  bool GetInitialized() const override;
+
+  void HandleWrite(const uint8_t* buffer, uint32_t count);
+  void HandleRead(uint8_t* buffer, uint32_t count);
+
+ private:
+  int m_port;
+  int m_writeCallbackId;
+  int m_readCallbackId;
+
+  int m_lastWriteAddress;
+
+  static const double LSB;
+};
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL362_SpiAccelerometerData.h b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL362_SpiAccelerometerData.h
new file mode 100644
index 0000000..258efb8
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXL362_SpiAccelerometerData.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ThreeAxisAccelerometerData.h"
+
+namespace hal {
+class ADXL362_SpiAccelerometer : public ThreeAxisAccelerometerData {
+ public:
+  explicit ADXL362_SpiAccelerometer(int port);
+  virtual ~ADXL362_SpiAccelerometer();
+
+  bool GetInitialized() const override;
+
+  void HandleWrite(const uint8_t* buffer, uint32_t count);
+  void HandleRead(uint8_t* buffer, uint32_t count);
+
+ private:
+  int m_port;
+  int m_writeCallbackId;
+  int m_readCallbackId;
+
+  int m_lastWriteAddress;
+
+  static const double LSB;
+};
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXRS450_SpiGyroWrapperData.h b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXRS450_SpiGyroWrapperData.h
new file mode 100644
index 0000000..25e8376
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ADXRS450_SpiGyroWrapperData.h
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <mockdata/SimDataValue.h>
+
+namespace hal {
+class ADXRS450_SpiGyroWrapper {
+ public:
+  explicit ADXRS450_SpiGyroWrapper(int port);
+  virtual ~ADXRS450_SpiGyroWrapper();
+
+  bool GetInitialized() const;
+
+  void HandleRead(uint8_t* buffer, uint32_t count);
+  void HandleAutoReceiveData(uint32_t* buffer, int32_t numToRead,
+                             int32_t& outputCount);
+
+  int32_t RegisterAngleCallback(HAL_NotifyCallback callback, void* param,
+                                HAL_Bool initialNotify) {
+    return m_angle.RegisterCallback(callback, param, initialNotify);
+  }
+  void CancelAngleCallback(int32_t uid) { m_angle.CancelCallback(uid); }
+  double GetAngle() { return m_angle; }
+  void SetAngle(double angle);
+
+  virtual void ResetData();
+
+ private:
+  int m_port;
+  int m_readCallbackId;
+  int m_autoReceiveReadCallbackId;
+
+  HAL_SIMDATAVALUE_DEFINE_NAME(Angle)
+
+  SimDataValue<double, MakeDouble, GetAngleName> m_angle{0.0};
+  double m_angleDiff = 0.0;
+
+  static const double kAngleLsb;
+  // The maximum difference that can fit inside of the shifted and masked data
+  // field, per transaction
+  static const double kMaxAngleDeltaPerMessage;
+  static const int kPacketSize;
+};
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ThreeAxisAccelerometerData.h b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ThreeAxisAccelerometerData.h
new file mode 100644
index 0000000..67412e5
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/main/native/include/ThreeAxisAccelerometerData.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <mockdata/SimDataValue.h>
+
+namespace hal {
+class ThreeAxisAccelerometerData {
+  HAL_SIMDATAVALUE_DEFINE_NAME(X);
+  HAL_SIMDATAVALUE_DEFINE_NAME(Y);
+  HAL_SIMDATAVALUE_DEFINE_NAME(Z);
+
+ public:
+  ThreeAxisAccelerometerData();
+  virtual ~ThreeAxisAccelerometerData();
+
+  virtual bool GetInitialized() const = 0;
+
+  double GetX() { return x; }
+  void SetX(double x_) { x = x_; }
+
+  double GetY() { return y; }
+  void SetY(double y_) { y = y_; }
+
+  double GetZ() { return z; }
+  void SetZ(double z_) { z = z_; }
+
+  SimDataValue<double, MakeDouble, GetXName> x{0.0};
+  SimDataValue<double, MakeDouble, GetYName> y{0.0};
+  SimDataValue<double, MakeDouble, GetZName> z{0.0};
+
+  virtual void ResetData();
+};
+}  // namespace hal
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL345_I2CAccelerometerTest.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL345_I2CAccelerometerTest.cpp
new file mode 100644
index 0000000..aa58861
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL345_I2CAccelerometerTest.cpp
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXL345_I2CAccelerometerData.h"
+#include "frc/ADXL345_I2C.h"
+#include "gtest/gtest.h"
+
+class ADXL345_I2CAccelerometerTest
+    : public ::testing::TestWithParam<frc::I2C::Port> {};
+
+TEST_P(ADXL345_I2CAccelerometerTest, TestAccelerometer) {
+  const double EPSILON = 1 / 256.0;
+
+  frc::I2C::Port port = GetParam();
+
+  hal::ADXL345_I2CData sim{port};
+  frc::ADXL345_I2C accel{port};
+
+  EXPECT_NEAR(0, sim.GetX(), EPSILON);
+  EXPECT_NEAR(0, sim.GetY(), EPSILON);
+  EXPECT_NEAR(0, sim.GetZ(), EPSILON);
+
+  EXPECT_NEAR(0, accel.GetX(), EPSILON);
+  EXPECT_NEAR(0, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0, accel.GetZ(), EPSILON);
+
+  sim.SetX(1.56);
+  sim.SetY(-.653);
+  sim.SetZ(0.11);
+
+  EXPECT_NEAR(1.56, sim.GetX(), EPSILON);
+  EXPECT_NEAR(-.653, sim.GetY(), EPSILON);
+  EXPECT_NEAR(0.11, sim.GetZ(), EPSILON);
+
+  EXPECT_NEAR(1.56, accel.GetX(), EPSILON);
+  EXPECT_NEAR(-.653, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0.11, accel.GetZ(), EPSILON);
+}
+
+INSTANTIATE_TEST_CASE_P(ADXL345_I2CAccelerometerTest,
+                        ADXL345_I2CAccelerometerTest,
+                        ::testing::Values(frc::I2C::kOnboard,
+                                          frc::I2C::kMXP), );
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL345_SpiAccelerometerTest.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL345_SpiAccelerometerTest.cpp
new file mode 100644
index 0000000..548240d
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL345_SpiAccelerometerTest.cpp
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXL345_SpiAccelerometerData.h"
+#include "frc/ADXL345_SPI.h"
+#include "gtest/gtest.h"
+
+class ADXL345_SpiAccelerometerTest
+    : public ::testing::TestWithParam<frc::SPI::Port> {};
+
+TEST_P(ADXL345_SpiAccelerometerTest, TestAccelerometer) {
+  const double EPSILON = 1 / 256.0;
+
+  frc::SPI::Port port = GetParam();
+
+  hal::ADXL345_SpiAccelerometer sim{port};
+  frc::ADXL345_SPI accel{port};
+
+  EXPECT_NEAR(0, sim.GetX(), EPSILON);
+  EXPECT_NEAR(0, sim.GetY(), EPSILON);
+  EXPECT_NEAR(0, sim.GetZ(), EPSILON);
+
+  EXPECT_NEAR(0, accel.GetX(), EPSILON);
+  EXPECT_NEAR(0, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0, accel.GetZ(), EPSILON);
+
+  sim.SetX(1.56);
+  sim.SetY(-.653);
+  sim.SetZ(0.11);
+
+  EXPECT_NEAR(1.56, sim.GetX(), EPSILON);
+  EXPECT_NEAR(-.653, sim.GetY(), EPSILON);
+  EXPECT_NEAR(0.11, sim.GetZ(), EPSILON);
+
+  EXPECT_NEAR(1.56, accel.GetX(), EPSILON);
+  EXPECT_NEAR(-.653, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0.11, accel.GetZ(), EPSILON);
+}
+
+INSTANTIATE_TEST_CASE_P(
+    ADXL345_SpiAccelerometerTest, ADXL345_SpiAccelerometerTest,
+    ::testing::Values(frc::SPI::kOnboardCS0, frc::SPI::kOnboardCS1,
+                      frc::SPI::kOnboardCS2, frc::SPI::kOnboardCS3,
+                      frc::SPI::kMXP), );
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL362_SpiAccelerometerTest.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL362_SpiAccelerometerTest.cpp
new file mode 100644
index 0000000..67efd18
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXL362_SpiAccelerometerTest.cpp
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXL362_SpiAccelerometerData.h"
+#include "frc/ADXL362.h"
+#include "gtest/gtest.h"
+
+class ADXL362_SpiAccelerometerTest
+    : public ::testing::TestWithParam<frc::SPI::Port> {};
+
+TEST_P(ADXL362_SpiAccelerometerTest, TestAccelerometer) {
+  const double EPSILON = 1 / 256.0;
+
+  frc::SPI::Port port = GetParam();
+
+  hal::ADXL362_SpiAccelerometer sim{port};
+  frc::ADXL362 accel{port};
+
+  EXPECT_NEAR(0, sim.GetX(), EPSILON);
+  EXPECT_NEAR(0, sim.GetY(), EPSILON);
+  EXPECT_NEAR(0, sim.GetZ(), EPSILON);
+
+  EXPECT_NEAR(0, accel.GetX(), EPSILON);
+  EXPECT_NEAR(0, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0, accel.GetZ(), EPSILON);
+
+  sim.SetX(1.56);
+  sim.SetY(-.653);
+  sim.SetZ(0.11);
+
+  EXPECT_NEAR(1.56, sim.GetX(), EPSILON);
+  EXPECT_NEAR(-.653, sim.GetY(), EPSILON);
+  EXPECT_NEAR(0.11, sim.GetZ(), EPSILON);
+
+  EXPECT_NEAR(1.56, accel.GetX(), EPSILON);
+  EXPECT_NEAR(-.653, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0.11, accel.GetZ(), EPSILON);
+}
+
+INSTANTIATE_TEST_CASE_P(
+    ADXL362_SpiAccelerometerTest, ADXL362_SpiAccelerometerTest,
+    ::testing::Values(frc::SPI::kOnboardCS0, frc::SPI::kOnboardCS1,
+                      frc::SPI::kOnboardCS2, frc::SPI::kOnboardCS3,
+                      frc::SPI::kMXP), );
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXRS450_SpiGyroWrapperTest.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXRS450_SpiGyroWrapperTest.cpp
new file mode 100644
index 0000000..f1c14ca
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/ADXRS450_SpiGyroWrapperTest.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 "ADXRS450_SpiGyroWrapperData.h"
+#include "frc/ADXRS450_Gyro.h"
+#include "gtest/gtest.h"
+
+class ADXRS450_SpiGyroWrapperTest
+    : public ::testing::TestWithParam<frc::SPI::Port> {};
+
+TEST_P(ADXRS450_SpiGyroWrapperTest, TestAccelerometer) {
+#ifdef __APPLE__
+  // Disable test on mac, because of unknown failures
+  // TODO: Finally figure out the isse.
+  return;
+#else
+  const double EPSILON = .000001;
+
+  frc::SPI::Port port = GetParam();
+
+  hal::ADXRS450_SpiGyroWrapper sim{port};
+  frc::ADXRS450_Gyro gyro{port};
+
+  EXPECT_NEAR(0, sim.GetAngle(), EPSILON);
+  EXPECT_NEAR(0, gyro.GetAngle(), EPSILON);
+
+  sim.SetAngle(32.56);
+  EXPECT_NEAR(32.56, sim.GetAngle(), EPSILON);
+  EXPECT_NEAR(32.56, gyro.GetAngle(), EPSILON);
+#endif
+}
+
+INSTANTIATE_TEST_CASE_P(
+    ADXRS450_SpiGyroWrapperTest, ADXRS450_SpiGyroWrapperTest,
+    ::testing::Values(frc::SPI::kOnboardCS0, frc::SPI::kOnboardCS1,
+                      frc::SPI::kOnboardCS2, frc::SPI::kOnboardCS3,
+                      frc::SPI::kMXP), );
diff --git a/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..0e00efa
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_adx_gyro_accelerometer/src/test/native/cpp/main.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <hal/HAL.h>
+
+#include "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  HAL_Initialize(500, 0);
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_nt/build.gradle b/third_party/allwpilib_2019/simulation/halsim_ds_nt/build.gradle
new file mode 100644
index 0000000..fa02630
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_nt/build.gradle
@@ -0,0 +1,9 @@
+description = "A simulation shared object that uses NetworkTables to act as a stand-in for the FRC Driver Station"
+
+ext {
+    includeNtCore = true
+    includeWpiutil = true
+    pluginName = 'halsim_ds_nt'
+}
+
+apply from: "${rootDir}/shared/plugins/setupBuild.gradle"
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..e324b44
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/dev/native/cpp/main.cpp
@@ -0,0 +1,8 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+int main() {}
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/cpp/HALSimDsNt.cpp b/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/cpp/HALSimDsNt.cpp
new file mode 100644
index 0000000..ef510e4
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/cpp/HALSimDsNt.cpp
@@ -0,0 +1,194 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "HALSimDsNt.h"
+
+void HALSimDSNT::Initialize() {
+  rootTable =
+      nt::NetworkTableInstance::GetDefault().GetTable("sim")->GetSubTable(
+          "DS_CONTROL");  // Not to be confused with sim::DriverStation from
+                          // HALSim LowFi
+
+  // LOOP TIMING //
+
+  auto timinghz = rootTable->GetEntry("timing_hz");
+  timinghz.ForceSetDouble(50);
+  timinghz.AddListener(
+      [this](const nt::EntryNotification& ev) -> void {
+        double valIn = ev.value->GetDouble();
+        double val = 0;
+        val = (valIn < 1 ? 1 : valIn > 100 ? 100 : valIn);
+
+        if (val != valIn) {
+          this->rootTable->GetEntry("timing_hz").ForceSetDouble(val);
+          Flush();
+        }
+
+        this->timingHz = val;
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  // MODES //
+
+  modeTable = rootTable->GetSubTable("mode");
+  auto mtele = modeTable->GetEntry("teleop?");
+  auto mauto = modeTable->GetEntry("auto?");
+  auto mtest = modeTable->GetEntry("test?");
+  auto enabled = modeTable->GetEntry("enabled?");
+  auto estop = modeTable->GetEntry("estop?");
+
+  mtele.ForceSetBoolean(true);
+  mauto.ForceSetBoolean(false);
+  mtest.ForceSetBoolean(false);
+  enabled.ForceSetBoolean(false);
+  estop.ForceSetBoolean(false);
+
+  mtele.AddListener(
+      [this](const nt::EntryNotification& ev) -> void {
+        this->HandleModePress(HALSimDSNT_Mode::teleop, ev.value->GetBoolean());
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  mauto.AddListener(
+      [this](const nt::EntryNotification& ev) -> void {
+        this->HandleModePress(HALSimDSNT_Mode::auton, ev.value->GetBoolean());
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  mtest.AddListener(
+      [this](const nt::EntryNotification& ev) -> void {
+        this->HandleModePress(HALSimDSNT_Mode::test, ev.value->GetBoolean());
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  enabled.AddListener(
+      [this](const nt::EntryNotification& ev) -> void {
+        std::lock_guard<wpi::mutex> lock(modeMutex);
+        if (!this->isEstop) {
+          this->isEnabled = ev.value->GetBoolean();
+        } else {
+          this->isEnabled = false;
+        }
+        this->DoModeUpdate();
+        this->UpdateModeButtons();
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  estop.AddListener(
+      [this](const nt::EntryNotification& ev) -> void {
+        std::lock_guard<wpi::mutex> lock(modeMutex);
+        this->isEstop = ev.value->GetBoolean();
+        if (this->isEstop) {
+          this->isEnabled = false;
+        }
+        this->DoModeUpdate();
+        this->UpdateModeButtons();
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  // ALLIANCES //
+
+  allianceTable = rootTable->GetSubTable("alliance");
+  auto allianceStation = allianceTable->GetEntry("station");
+  auto allianceColorRed = allianceTable->GetEntry("red?");
+
+  allianceStation.ForceSetDouble(1);
+  allianceColorRed.ForceSetBoolean(true);
+
+  allianceStation.AddListener(
+      [this](const nt::EntryNotification& ev) -> void {
+        double stnIn = ev.value->GetDouble();
+        double stn = 0;
+        stn = (stnIn > 3 ? 3 : stnIn < 1 ? 1 : stnIn);
+
+        if (stn != stnIn) {
+          this->allianceTable->GetEntry("station").ForceSetDouble(stn);
+          Flush();
+        }
+
+        this->allianceStation = stn;
+        this->DoAllianceUpdate();
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  allianceColorRed.AddListener(
+      [this](const nt::EntryNotification& ev) -> void {
+        this->isAllianceRed = ev.value->GetBoolean();
+        this->DoAllianceUpdate();
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  // FINAL LOGIC //
+
+  Flush();
+
+  loopThread = std::thread([this]() -> void {
+    this->running = true;
+    this->LoopFunc();
+  });
+  loopThread.detach();
+}
+
+void HALSimDSNT::HandleModePress(enum HALSimDSNT_Mode mode, bool isPressed) {
+  if (isPressed) {
+    if (mode != currentMode) {
+      std::lock_guard<wpi::mutex> lock(modeMutex);
+      currentMode = mode;
+      isEnabled = false;
+      this->DoModeUpdate();
+    }
+  }
+
+  this->UpdateModeButtons();
+}
+
+void HALSimDSNT::UpdateModeButtons() {
+  modeTable->GetEntry("teleop?").ForceSetBoolean(currentMode ==
+                                                 HALSimDSNT_Mode::teleop);
+  modeTable->GetEntry("auto?").ForceSetBoolean(currentMode ==
+                                               HALSimDSNT_Mode::auton);
+  modeTable->GetEntry("test?").ForceSetBoolean(currentMode ==
+                                               HALSimDSNT_Mode::test);
+  modeTable->GetEntry("enabled?").ForceSetBoolean(isEnabled);
+  Flush();
+}
+
+void HALSimDSNT::DoModeUpdate() {
+  HALSIM_SetDriverStationAutonomous(currentMode == HALSimDSNT_Mode::auton);
+  HALSIM_SetDriverStationTest(currentMode == HALSimDSNT_Mode::test);
+  HALSIM_SetDriverStationEnabled(isEnabled);
+  if (isEnabled && !lastIsEnabled) {
+    currentMatchTime = 0;
+  }
+  lastIsEnabled = isEnabled;
+  HALSIM_SetDriverStationEStop(isEstop);
+  HALSIM_SetDriverStationFmsAttached(false);
+  HALSIM_SetDriverStationDsAttached(true);
+  HALSIM_NotifyDriverStationNewData();
+}
+
+void HALSimDSNT::DoAllianceUpdate() {
+  HALSIM_SetDriverStationAllianceStationId(static_cast<HAL_AllianceStationID>(
+      (isAllianceRed ? HAL_AllianceStationID_kRed1
+                     : HAL_AllianceStationID_kBlue1) +
+      (static_cast<int32_t>(allianceStation) - 1)));
+}
+
+void HALSimDSNT::LoopFunc() {
+  while (running) {
+    double dt = 1000 / timingHz;
+    std::this_thread::sleep_for(
+        std::chrono::milliseconds(static_cast<int64_t>(dt)));
+    if (isEnabled) {
+      currentMatchTime = currentMatchTime + dt;
+      HALSIM_SetDriverStationMatchTime(currentMatchTime);
+    }
+    HALSIM_NotifyDriverStationNewData();
+  }
+}
+
+void HALSimDSNT::Flush() { rootTable->GetInstance().Flush(); }
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/cpp/main.cpp
new file mode 100644
index 0000000..7090de9
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/cpp/main.cpp
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include <HALSimDsNt.h>
+
+static HALSimDSNT dsnt;
+
+extern "C" {
+#if defined(WIN32) || defined(_WIN32)
+__declspec(dllexport)
+#endif
+    int HALSIM_InitExtension(void) {
+  std::cout << "DriverStationNT Initializing." << std::endl;
+
+  dsnt.Initialize();
+
+  std::cout << "DriverStationNT Initialized!" << std::endl;
+  return 0;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/include/HALSimDsNt.h b/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/include/HALSimDsNt.h
new file mode 100644
index 0000000..21d19ee
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_nt/src/main/native/include/HALSimDsNt.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <memory>
+#include <thread>
+
+#include <mockdata/DriverStationData.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/mutex.h>
+
+enum HALSimDSNT_Mode { teleop, auton, test };
+
+class HALSimDSNT {
+ public:
+  std::shared_ptr<nt::NetworkTable> rootTable, modeTable, allianceTable;
+  enum HALSimDSNT_Mode currentMode;
+  bool isEnabled, lastIsEnabled, isEstop;
+  std::atomic<bool> isAllianceRed, running;
+  std::atomic<double> currentMatchTime, timingHz, allianceStation;
+  std::thread loopThread;
+  wpi::mutex modeMutex;
+
+  void Initialize();
+  void HandleModePress(enum HALSimDSNT_Mode mode, bool isPressed);
+  void UpdateModeButtons();
+  void DoModeUpdate();
+  void DoAllianceUpdate();
+  void LoopFunc();
+  void Flush();
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_socket/build.gradle b/third_party/allwpilib_2019/simulation/halsim_ds_socket/build.gradle
new file mode 100644
index 0000000..0200980
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/build.gradle
@@ -0,0 +1,58 @@
+description = "A plugin that listens on a socket so that you can use the real Driver Station software to connect to the simulation"
+
+ext {
+    includeWpiutil = true
+    pluginName = 'halsim_ds_socket'
+}
+
+apply plugin: 'google-test-test-suite'
+
+
+ext {
+    staticGtestConfigs = [:]
+}
+
+staticGtestConfigs["${pluginName}Test"] = []
+apply from: "${rootDir}/shared/googletest.gradle"
+
+apply from: "${rootDir}/shared/plugins/setupBuild.gradle"
+
+
+model {
+    testSuites {
+        def comps = $.components
+        if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+            "${pluginName}Test"(GoogleTestTestSuiteSpec) {
+                for(NativeComponentSpec c : comps) {
+                    if (c.name == pluginName) {
+                        testing c
+                        break
+                    }
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'src/test/native/cpp'
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/test/native/include', 'src/main/native/cpp'
+                        }
+                    }
+                }
+            }
+        }
+    }
+    binaries {
+        withType(GoogleTestTestSuiteBinarySpec) {
+            project(':hal').addHalDependency(it, 'shared')
+            lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            lib library: pluginName, linkage: 'shared'
+        }
+    }
+}
+
+tasks.withType(RunTestExecutable) {
+    args "--gtest_output=xml:test_detail.xml"
+    outputs.dir outputDir
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..aba88fb
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/dev/native/cpp/main.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <thread>
+
+#include <hal/HAL.h>
+#include <wpi/Format.h>
+#include <wpi/raw_ostream.h>
+
+extern "C" int HALSIM_InitExtension(void);
+
+int main() {
+  HAL_Initialize(500, 0);
+  HALSIM_InitExtension();
+
+  HAL_ObserveUserProgramStarting();
+
+  while (true) {
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+  }
+}
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
new file mode 100644
index 0000000..92f1720
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp
@@ -0,0 +1,312 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DSCommPacket.h"
+
+#include <algorithm>
+#include <chrono>
+#include <cstring>
+#include <iostream>
+#include <thread>
+#include <vector>
+
+#include <mockdata/DriverStationData.h>
+#include <mockdata/MockHooks.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/Format.h>
+
+using namespace halsim;
+
+DSCommPacket::DSCommPacket() {
+  for (auto& i : m_joystick_packets) {
+    i.ResetTcp();
+    i.ResetUdp();
+  }
+  matchInfo.gameSpecificMessageSize = 0;
+}
+
+/*----------------------------------------------------------------------------
+**  The following methods help parse and hold information about the
+**   driver station and it's joysticks.
+**--------------------------------------------------------------------------*/
+
+void DSCommPacket::SetControl(uint8_t control, uint8_t request) {
+  std::memset(&m_control_word, 0, sizeof(m_control_word));
+  m_control_word.enabled = (control & kEnabled) != 0;
+  m_control_word.autonomous = (control & kAutonomous) != 0;
+  m_control_word.test = (control & kTest) != 0;
+  m_control_word.eStop = (control & kEmergencyStop) != 0;
+  m_control_word.fmsAttached = (control & kFMS_Attached) != 0;
+  m_control_word.dsAttached = (request & kRequestNormalMask) != 0;
+
+  m_control_sent = control;
+}
+
+void DSCommPacket::SetAlliance(uint8_t station_code) {
+  m_alliance_station = static_cast<HAL_AllianceStationID>(station_code);
+}
+
+void DSCommPacket::ReadMatchtimeTag(wpi::ArrayRef<uint8_t> tagData) {
+  if (tagData.size() < 6) return;
+
+  uint32_t store = tagData[2] << 24;
+  store |= tagData[3] << 16;
+  store |= tagData[4] << 8;
+  store |= tagData[5];
+
+  static_assert(sizeof(uint32_t) == sizeof(float), "float must be 32 bits");
+
+  float matchTime = 0;
+
+  std::memcpy(&matchTime, &store, sizeof(float));
+  m_match_time = matchTime;
+}
+
+void DSCommPacket::ReadJoystickTag(wpi::ArrayRef<uint8_t> dataInput,
+                                   int index) {
+  DSCommJoystickPacket& stick = m_joystick_packets[index];
+  stick.ResetUdp();
+
+  if (dataInput.size() == 2) {
+    return;
+  }
+
+  dataInput = dataInput.slice(2);
+
+  // Read axes
+  int axesLength = dataInput[0];
+  for (int i = 0; i < axesLength; i++) {
+    int8_t value = dataInput[1 + i];
+    if (value < 0) {
+      stick.axes.axes[i] = value / 128.0;
+    } else {
+      stick.axes.axes[i] = value / 127.0;
+    }
+  }
+  stick.axes.count = axesLength;
+
+  dataInput = dataInput.slice(1 + axesLength);
+
+  // Read Buttons
+  int buttonCount = dataInput[0];
+  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.count = buttonCount;
+
+  dataInput = dataInput.slice(1 + numBytes);
+
+  int povsLength = dataInput[0];
+  for (int i = 0; i < povsLength * 2; i += 2) {
+    stick.povs.povs[i] = (dataInput[1 + i] << 8) | dataInput[2 + i];
+  }
+
+  stick.povs.count = povsLength;
+
+  return;
+}
+
+/*----------------------------------------------------------------------------
+**  Communication methods
+**--------------------------------------------------------------------------*/
+void DSCommPacket::DecodeTCP(wpi::ArrayRef<uint8_t> packet) {
+  // No header
+  while (!packet.empty()) {
+    int tagLength = packet[0] << 8 | packet[1];
+    auto tagPacket = packet.slice(0, tagLength + 2);
+
+    if (tagLength == 0) {
+      return;
+    }
+
+    switch (packet[2]) {
+      case kJoystickNameTag:
+        ReadJoystickDescriptionTag(tagPacket);
+        break;
+      case kGameDataTag:
+        ReadGameSpecificMessageTag(tagPacket);
+        break;
+      case kMatchInfoTag:
+        ReadNewMatchInfoTag(tagPacket);
+        break;
+    }
+    packet = packet.slice(tagLength + 2);
+  }
+}
+
+void DSCommPacket::DecodeUDP(wpi::ArrayRef<uint8_t> packet) {
+  if (packet.size() < 6) return;
+  // Decode fixed header
+  m_hi = packet[0];
+  m_lo = packet[1];
+  // Comm Version is packet 2, ignore
+  SetControl(packet[3], packet[4]);
+  SetAlliance(packet[5]);
+
+  // Return if packet finished
+  if (packet.size() == 6) return;
+
+  // Else, handle tagged data
+  packet = packet.slice(6);
+
+  int joystickNum = 0;
+
+  // Loop to handle multiple tags
+  while (!packet.empty()) {
+    auto tagLength = packet[0];
+    auto tagPacket = packet.slice(0, tagLength + 1);
+
+    switch (packet[1]) {
+      case kJoystickDataTag:
+        ReadJoystickTag(tagPacket, joystickNum);
+        joystickNum++;
+        break;
+      case kMatchTimeTag:
+        ReadMatchtimeTag(tagPacket);
+        break;
+    }
+    packet = packet.slice(tagLength + 1);
+  }
+}
+
+void DSCommPacket::ReadNewMatchInfoTag(wpi::ArrayRef<uint8_t> data) {
+  // Size 2 bytes, tag 1 byte
+  if (data.size() <= 3) return;
+
+  int nameLength = std::min<size_t>(data[3], sizeof(matchInfo.eventName) - 1);
+
+  for (int i = 0; i < nameLength; i++) {
+    matchInfo.eventName[i] = data[4 + i];
+  }
+
+  matchInfo.eventName[nameLength] = '\0';
+
+  data = data.slice(4 + nameLength);
+
+  if (data.size() < 4) return;
+
+  matchInfo.matchType = static_cast<HAL_MatchType>(
+      data[0]);  // None, Practice, Qualification, Elimination, Test
+  matchInfo.matchNumber = (data[1] << 8) | data[2];
+  matchInfo.replayNumber = data[3];
+
+  HALSIM_SetMatchInfo(&matchInfo);
+}
+
+void DSCommPacket::ReadGameSpecificMessageTag(wpi::ArrayRef<uint8_t> data) {
+  // Size 2 bytes, tag 1 byte
+  if (data.size() <= 3) return;
+
+  int length = std::min<size_t>(((data[0] << 8) | data[1]) - 1,
+                                sizeof(matchInfo.gameSpecificMessage));
+  for (int i = 0; i < length; i++) {
+    matchInfo.gameSpecificMessage[i] = data[3 + i];
+  }
+
+  matchInfo.gameSpecificMessageSize = length;
+
+  HALSIM_SetMatchInfo(&matchInfo);
+}
+void DSCommPacket::ReadJoystickDescriptionTag(wpi::ArrayRef<uint8_t> data) {
+  if (data.size() < 3) return;
+  data = data.slice(3);
+  int joystickNum = data[0];
+  DSCommJoystickPacket& packet = m_joystick_packets[joystickNum];
+  packet.ResetTcp();
+  packet.descriptor.isXbox = data[1] != 0 ? 1 : 0;
+  packet.descriptor.type = data[2];
+  int nameLength =
+      std::min<size_t>(data[3], (sizeof(packet.descriptor.name) - 1));
+  for (int i = 0; i < nameLength; i++) {
+    packet.descriptor.name[i] = data[4 + i];
+  }
+  data = data.slice(4 + nameLength);
+  packet.descriptor.name[nameLength] = '\0';
+  int axesCount = data[0];
+  packet.descriptor.axisCount = axesCount;
+  for (int i = 0; i < axesCount; i++) {
+    packet.descriptor.axisTypes[i] = data[1 + i];
+  }
+  data = data.slice(1 + axesCount);
+
+  packet.descriptor.buttonCount = data[0];
+  packet.descriptor.povCount = data[1];
+}
+
+void DSCommPacket::SendJoysticks(void) {
+  for (int i = 0; i < HAL_kMaxJoysticks; i++) {
+    DSCommJoystickPacket& packet = m_joystick_packets[i];
+    HALSIM_SetJoystickAxes(i, &packet.axes);
+    HALSIM_SetJoystickPOVs(i, &packet.povs);
+    HALSIM_SetJoystickButtons(i, &packet.buttons);
+    HALSIM_SetJoystickDescriptor(i, &packet.descriptor);
+  }
+}
+
+void DSCommPacket::SetupSendBuffer(wpi::raw_uv_ostream& buf) {
+  SetupSendHeader(buf);
+  SetupJoystickTag(buf);
+}
+
+void DSCommPacket::SetupSendHeader(wpi::raw_uv_ostream& buf) {
+  static constexpr uint8_t kCommVersion = 0x01;
+
+  // High low packet index, comm version
+  buf << m_hi << m_lo << kCommVersion;
+
+  // Control word and status check
+  buf << m_control_sent
+      << static_cast<uint8_t>(HALSIM_GetProgramStarted() ? kRobotHasCode : 0);
+
+  // Battery voltage high and low
+  buf << static_cast<uint8_t>(12) << static_cast<uint8_t>(0);
+
+  // Request (Always 0)
+  buf << static_cast<uint8_t>(0);
+}
+
+void DSCommPacket::SetupJoystickTag(wpi::raw_uv_ostream& buf) {
+  static constexpr uint8_t kHIDTag = 0x01;
+
+  // HID tags are sent 1 per device
+  int64_t outputs;
+  int32_t rightRumble;
+  int32_t leftRumble;
+  for (size_t i = 0; i < m_joystick_packets.size(); i++) {
+    // Length is 9, 1 tag and 8 data.
+    buf << static_cast<uint8_t>(9) << kHIDTag;
+    HALSIM_GetJoystickOutputs(i, &outputs, &leftRumble, &rightRumble);
+    auto op = static_cast<uint32_t>(outputs);
+    auto rr = static_cast<uint16_t>(rightRumble);
+    auto lr = static_cast<uint16_t>(leftRumble);
+    buf.write((op >> 24 & 0xFF));
+    buf.write((op >> 16 & 0xFF));
+    buf.write((op >> 8 & 0xFF));
+    buf.write((op & 0xFF));
+    buf.write((rr >> 8 & 0xFF));
+    buf.write((rr & 0xFF));
+    buf.write((lr >> 8 & 0xFF));
+    buf.write((lr & 0xFF));
+  }
+}
+
+void DSCommPacket::SendUDPToHALSim(void) {
+  SendJoysticks();
+
+  HALSIM_SetDriverStationMatchTime(m_match_time);
+  HALSIM_SetDriverStationEnabled(m_control_word.enabled);
+  HALSIM_SetDriverStationAutonomous(m_control_word.autonomous);
+  HALSIM_SetDriverStationTest(m_control_word.test);
+  HALSIM_SetDriverStationEStop(m_control_word.eStop);
+  HALSIM_SetDriverStationFmsAttached(m_control_word.fmsAttached);
+  HALSIM_SetDriverStationDsAttached(m_control_word.dsAttached);
+  HALSIM_SetDriverStationAllianceStationId(m_alliance_station);
+
+  HALSIM_NotifyDriverStationNewData();
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp
new file mode 100644
index 0000000..12cbf74
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp
@@ -0,0 +1,190 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*----------------------------------------------------------------------------
+**  This extension reimplements enough of the FRC_Network layer to enable the
+**    simulator to communicate with a driver station.  That includes a
+**    simple udp layer for communication.
+**  The protocol does not appear to be well documented; this implementation
+**    is based in part on the Toast ds_comms.cpp by Jaci and in part
+**    by the protocol specification given by QDriverStation.
+**--------------------------------------------------------------------------*/
+
+#include <sys/types.h>
+
+#include <cstring>
+#include <iostream>
+
+#include <DSCommPacket.h>
+#include <wpi/EventLoopRunner.h>
+#include <wpi/StringRef.h>
+#include <wpi/raw_ostream.h>
+#include <wpi/raw_uv_ostream.h>
+#include <wpi/uv/Tcp.h>
+#include <wpi/uv/Timer.h>
+#include <wpi/uv/Udp.h>
+#include <wpi/uv/util.h>
+
+#if defined(Win32) || defined(_WIN32)
+#pragma comment(lib, "Ws2_32.lib")
+#endif
+
+using namespace wpi::uv;
+
+static std::unique_ptr<Buffer> singleByte;
+
+namespace {
+struct DataStore {
+  wpi::SmallVector<uint8_t, 128> m_frame;
+  size_t m_frameSize = std::numeric_limits<size_t>::max();
+  halsim::DSCommPacket* dsPacket;
+};
+}  // namespace
+
+static SimpleBufferPool<4>& GetBufferPool() {
+  static SimpleBufferPool<4> bufferPool;
+  return bufferPool;
+}
+
+static void HandleTcpDataStream(Buffer& buf, size_t size, DataStore& store) {
+  wpi::StringRef data{buf.base, size};
+  while (!data.empty()) {
+    if (store.m_frameSize == std::numeric_limits<size_t>::max()) {
+      if (store.m_frame.size() < 2u) {
+        size_t toCopy = std::min(2u - store.m_frame.size(), data.size());
+        store.m_frame.append(data.bytes_begin(), data.bytes_begin() + toCopy);
+        data = data.drop_front(toCopy);
+        if (store.m_frame.size() < 2u) return;  // need more data
+      }
+      store.m_frameSize = (static_cast<uint16_t>(store.m_frame[0]) << 8) |
+                          static_cast<uint16_t>(store.m_frame[1]);
+    }
+    if (store.m_frameSize != std::numeric_limits<size_t>::max()) {
+      size_t need = store.m_frameSize - (store.m_frame.size() - 2);
+      size_t toCopy = std::min(need, data.size());
+      store.m_frame.append(data.bytes_begin(), data.bytes_begin() + toCopy);
+      data = data.drop_front(toCopy);
+      need -= toCopy;
+      if (need == 0) {
+        auto ds = store.dsPacket;
+        ds->DecodeTCP(store.m_frame);
+        store.m_frame.clear();
+        store.m_frameSize = std::numeric_limits<size_t>::max();
+      }
+    }
+  }
+}
+
+static void SetupTcp(wpi::uv::Loop& loop) {
+  auto tcp = Tcp::Create(loop);
+  auto tcpWaitTimer = Timer::Create(loop);
+
+  auto recStore = std::make_shared<DataStore>();
+  recStore->dsPacket = loop.GetData<halsim::DSCommPacket>().get();
+
+  tcp->SetData(recStore);
+
+  tcp->Bind("0.0.0.0", 1740);
+
+  tcp->Listen([t = tcp.get()] {
+    auto client = t->Accept();
+
+    client->data.connect([t](Buffer& buf, size_t len) {
+      HandleTcpDataStream(buf, len, *t->GetData<DataStore>());
+    });
+    client->StartRead();
+    client->end.connect([c = client.get()] { c->Close(); });
+  });
+}
+
+static void SetupUdp(wpi::uv::Loop& loop) {
+  auto udp = wpi::uv::Udp::Create(loop);
+  udp->Bind("0.0.0.0", 1110);
+
+  // Simulation mode packet
+  auto simLoopTimer = Timer::Create(loop);
+  struct sockaddr_in simAddr;
+  NameToAddr("127.0.0.1", 1135, &simAddr);
+  simLoopTimer->timeout.connect([ udpLocal = udp.get(), simAddr ] {
+    udpLocal->Send(simAddr, wpi::ArrayRef<Buffer>{singleByte.get(), 1},
+                   [](auto buf, Error err) {
+                     if (err) {
+                       wpi::errs() << err.str() << "\n";
+                       wpi::errs().flush();
+                     }
+                   });
+  });
+  simLoopTimer->Start(Timer::Time{100}, Timer::Time{100});
+
+  // UDP Receive then send
+  udp->received.connect([udpLocal = udp.get()](
+      Buffer & buf, size_t len, const sockaddr& recSock, unsigned int port) {
+    auto ds = udpLocal->GetLoop()->GetData<halsim::DSCommPacket>();
+    ds->DecodeUDP(
+        wpi::ArrayRef<uint8_t>{reinterpret_cast<uint8_t*>(buf.base), len});
+
+    struct sockaddr_in outAddr;
+    std::memcpy(&outAddr, &recSock, sizeof(sockaddr_in));
+    outAddr.sin_family = PF_INET;
+    outAddr.sin_port = htons(1150);
+
+    wpi::SmallVector<wpi::uv::Buffer, 4> sendBufs;
+    wpi::raw_uv_ostream stream{sendBufs, GetBufferPool()};
+    ds->SetupSendBuffer(stream);
+
+    udpLocal->Send(outAddr, sendBufs, [](auto bufs, Error err) {
+      GetBufferPool().Release(bufs);
+      if (err) {
+        wpi::errs() << err.str() << "\n";
+        wpi::errs().flush();
+      }
+    });
+    ds->SendUDPToHALSim();
+  });
+
+  udp->StartRecv();
+}
+
+static void SetupEventLoop(wpi::uv::Loop& loop) {
+  auto loopData = std::make_shared<halsim::DSCommPacket>();
+  loop.SetData(loopData);
+  SetupUdp(loop);
+  SetupTcp(loop);
+}
+
+static std::unique_ptr<wpi::EventLoopRunner> eventLoopRunner;
+
+/*----------------------------------------------------------------------------
+** Main entry point.  We will start listen threads going, processing
+**  against our driver station packet
+**--------------------------------------------------------------------------*/
+extern "C" {
+#if defined(WIN32) || defined(_WIN32)
+__declspec(dllexport)
+#endif
+    int HALSIM_InitExtension(void) {
+  static bool once = false;
+
+  if (once) {
+    std::cerr << "Error: cannot invoke HALSIM_InitExtension twice."
+              << std::endl;
+    return -1;
+  }
+  once = true;
+
+  std::cout << "DriverStationSocket Initializing." << std::endl;
+
+  singleByte = std::make_unique<Buffer>("0");
+
+  eventLoopRunner = std::make_unique<wpi::EventLoopRunner>();
+
+  eventLoopRunner->ExecAsync(SetupEventLoop);
+
+  std::cout << "DriverStationSocket Initialized!" << std::endl;
+  return 0;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/include/DSCommJoystickPacket.h b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/include/DSCommJoystickPacket.h
new file mode 100644
index 0000000..6f7e0bf
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/include/DSCommJoystickPacket.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cstring>
+
+#include <hal/DriverStationTypes.h>
+
+namespace halsim {
+
+typedef struct {
+  HAL_JoystickAxes axes;
+  HAL_JoystickButtons buttons;
+  HAL_JoystickPOVs povs;
+  HAL_JoystickDescriptor descriptor;
+
+  void ResetUdp() {
+    std::memset(&axes, 0, sizeof(axes));
+    std::memset(&buttons, 0, sizeof(buttons));
+    std::memset(&povs, 0, sizeof(povs));
+  }
+
+  void ResetTcp() { std::memset(&descriptor, 0, sizeof(descriptor)); }
+} DSCommJoystickPacket;
+
+}  // namespace halsim
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h
new file mode 100644
index 0000000..ebe36e4
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/main/native/include/DSCommPacket.h
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+
+#include <DSCommJoystickPacket.h>
+#include <mockdata/DriverStationData.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/raw_uv_ostream.h>
+
+class DSCommPacketTest;
+
+namespace halsim {
+
+class DSCommPacket {
+  friend class ::DSCommPacketTest;
+
+ public:
+  DSCommPacket(void);
+  void DecodeTCP(wpi::ArrayRef<uint8_t> packet);
+  void DecodeUDP(wpi::ArrayRef<uint8_t> packet);
+  void SendUDPToHALSim(void);
+  void SetupSendBuffer(wpi::raw_uv_ostream& buf);
+
+  /* TCP Tags */
+  static const uint8_t kGameDataTag = 0x0e;
+  static const uint8_t kJoystickNameTag = 0x02;
+  static const uint8_t kMatchInfoTag = 0x07;
+
+  /* UDP Tags*/
+  static const uint8_t kJoystickDataTag = 0x0c;
+  static const uint8_t kMatchTimeTag = 0x07;
+
+  /* Control word bits */
+  static const uint8_t kTest = 0x01;
+  static const uint8_t kEnabled = 0x04;
+  static const uint8_t kAutonomous = 0x02;
+  static const uint8_t kFMS_Attached = 0x08;
+  static const uint8_t kEmergencyStop = 0x80;
+
+  /* Control request bitmask */
+  static const uint8_t kRequestNormalMask = 0xF0;
+
+  /* Status bits */
+  static const uint8_t kRobotHasCode = 0x20;
+
+ private:
+  void SendJoysticks(void);
+  void SetControl(uint8_t control, uint8_t request);
+  void SetAlliance(uint8_t station_code);
+  void SetupSendHeader(wpi::raw_uv_ostream& buf);
+  void SetupJoystickTag(wpi::raw_uv_ostream& buf);
+  void ReadMatchtimeTag(wpi::ArrayRef<uint8_t> tagData);
+  void ReadJoystickTag(wpi::ArrayRef<uint8_t> data, int index);
+  void ReadNewMatchInfoTag(wpi::ArrayRef<uint8_t> data);
+  void ReadGameSpecificMessageTag(wpi::ArrayRef<uint8_t> data);
+  void ReadJoystickDescriptionTag(wpi::ArrayRef<uint8_t> data);
+
+  uint8_t m_hi;
+  uint8_t m_lo;
+  uint8_t m_control_sent;
+  HAL_ControlWord m_control_word;
+  HAL_AllianceStationID m_alliance_station;
+  HAL_MatchInfo matchInfo;
+  std::array<DSCommJoystickPacket, HAL_kMaxJoysticks> m_joystick_packets;
+  double m_match_time;
+};
+
+}  // namespace halsim
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
new file mode 100644
index 0000000..a72aafc
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/test/native/cpp/DSCommPacketTest.cpp
@@ -0,0 +1,146 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "DSCommPacket.h"
+#include "gtest/gtest.h"
+
+class DSCommPacketTest : public ::testing::Test {
+ public:
+  DSCommPacketTest() {}
+
+  void SendJoysticks() { commPacket.SendJoysticks(); }
+
+  halsim::DSCommJoystickPacket& ReadJoystickTag(wpi::ArrayRef<uint8_t> data,
+                                                int index) {
+    commPacket.ReadJoystickTag(data, index);
+    return commPacket.m_joystick_packets[index];
+  }
+
+  halsim::DSCommJoystickPacket& ReadDescriptorTag(wpi::ArrayRef<uint8_t> data) {
+    commPacket.ReadJoystickDescriptionTag(data);
+    return commPacket.m_joystick_packets[data[3]];
+  }
+
+  HAL_MatchInfo& ReadNewMatchInfoTag(wpi::ArrayRef<uint8_t> data) {
+    commPacket.ReadNewMatchInfoTag(data);
+    return commPacket.matchInfo;
+  }
+
+  HAL_MatchInfo& ReadGameSpecificTag(wpi::ArrayRef<uint8_t> data) {
+    commPacket.ReadGameSpecificMessageTag(data);
+    return commPacket.matchInfo;
+  }
+
+ protected:
+  halsim::DSCommPacket commPacket;
+};
+
+TEST_F(DSCommPacketTest, EmptyJoystickTag) {
+  for (int i = 0; i < HAL_kMaxJoysticks; i++) {
+    uint8_t arr[2];
+    auto& data = ReadJoystickTag(arr, 0);
+    ASSERT_EQ(data.axes.count, 0);
+    ASSERT_EQ(data.povs.count, 0);
+    ASSERT_EQ(data.buttons.count, 0);
+  }
+}
+
+TEST_F(DSCommPacketTest, BlankJoystickTag) {
+  for (int i = 0; i < HAL_kMaxJoysticks; i++) {
+    uint8_t arr[5];
+    arr[0] = 4;
+    arr[1] = 2;
+    arr[2] = 0;
+    arr[3] = 0;
+    arr[4] = 0;
+    auto& data = ReadJoystickTag(arr, 0);
+    ASSERT_EQ(data.axes.count, 0);
+    ASSERT_EQ(data.povs.count, 0);
+    ASSERT_EQ(data.buttons.count, 0);
+  }
+}
+
+TEST_F(DSCommPacketTest, MainJoystickTag) {
+  for (int i = 0; i < HAL_kMaxJoysticks; i++) {
+    // 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,
+                                  // POVs
+                                  3, 0, 50, 0, 100, 0x0F, 0x00};
+
+    auto& data = ReadJoystickTag(arr, 0);
+    ASSERT_EQ(data.axes.count, 4);
+    ASSERT_EQ(data.povs.count, 3);
+    ASSERT_EQ(data.buttons.count, 12);
+  }
+}
+
+TEST_F(DSCommPacketTest, DescriptorTag) {
+  for (int i = 0; i < HAL_kMaxJoysticks; i++) {
+    uint8_t arr[] = {// Size (2), tag
+                     0, 0, 7,
+                     // Joystick index, Is Xbox, Type
+                     static_cast<uint8_t>(i), 1, 0,
+                     // NameLen, Name (Not null terminated)
+                     11, 'H', 'e', 'l', 'l', 'o', ' ', 'W', 'o', 'r', 'l', 'd',
+                     // Axes count, Axes types
+                     4, 1, 2, 3, 4,
+                     // Button count, pov count,
+                     12, 3};
+    arr[1] = sizeof(arr) - 2;
+    auto& data = ReadDescriptorTag(arr);
+    ASSERT_EQ(data.descriptor.isXbox, 1);
+    ASSERT_EQ(data.descriptor.type, 0);
+    ASSERT_STREQ(data.descriptor.name, "Hello World");
+    ASSERT_EQ(data.descriptor.axisCount, 4);
+    for (int i = 0; i < 4; i++) {
+      ASSERT_EQ(data.descriptor.axisTypes[i], i + 1);
+    }
+    ASSERT_EQ(data.descriptor.buttonCount, 12);
+    ASSERT_EQ(data.descriptor.povCount, 3);
+  }
+}
+
+TEST_F(DSCommPacketTest, MatchInfoTag) {
+  uint8_t arr[]{// Size (2), tag
+                0, 0, 8,
+                // Event Name Len, Event Name
+                4, 'W', 'C', 'B', 'C',
+                // Match type, Match num (2), replay num
+                2, 0, 18, 1};
+  arr[1] = sizeof(arr) - 2;
+  auto& matchInfo = ReadNewMatchInfoTag(arr);
+  ASSERT_STREQ(matchInfo.eventName, "WCBC");
+  ASSERT_EQ(matchInfo.matchType, HAL_MatchType::HAL_kMatchType_qualification);
+  ASSERT_EQ(matchInfo.matchNumber, 18);
+  ASSERT_EQ(matchInfo.replayNumber, 1);
+}
+
+TEST_F(DSCommPacketTest, GameDataTag) {
+  uint8_t arr[]{
+      // Size (2), tag
+      0,
+      0,
+      17,
+      // Match data (length is taglength - 1)
+      'W',
+      'C',
+      'B',
+      'C',
+  };
+  arr[1] = sizeof(arr) - 2;
+  auto& matchInfo = ReadGameSpecificTag(arr);
+  ASSERT_EQ(matchInfo.gameSpecificMessageSize, 4);
+  ASSERT_EQ(matchInfo.gameSpecificMessage[0], 'W');
+  ASSERT_EQ(matchInfo.gameSpecificMessage[1], 'C');
+  ASSERT_EQ(matchInfo.gameSpecificMessage[2], 'B');
+  ASSERT_EQ(matchInfo.gameSpecificMessage[3], 'C');
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..aa4f4b0
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_ds_socket/src/test/native/cpp/main.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/

+/* Copyright (c) 2015-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 <hal/HAL.h>

+

+#include "gtest/gtest.h"

+

+int main(int argc, char** argv) {

+  HAL_Initialize(500, 0);

+  ::testing::InitGoogleTest(&argc, argv);

+  int ret = RUN_ALL_TESTS();

+  return ret;

+}

diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/build.gradle b/third_party/allwpilib_2019/simulation/halsim_gazebo/build.gradle
new file mode 100644
index 0000000..d9c2217
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/build.gradle
@@ -0,0 +1,57 @@
+description = "A shared object library that will interface between a robot and the Gazebo plugins."
+
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: 'cpp'
+
+ext.skipAthena = true
+ext.skipRaspbian = true
+ext.pluginName = 'halsim_gazebo'
+
+/* If gz_msgs or gazebo is not available, do not attempt a build */
+def gazebo_version = ""
+def gazebo_cppflags = ""
+def gazebo_linker_args = ""
+
+try {
+    gazebo_version = "pkg-config --modversion gazebo".execute().text.trim()
+    println "Gazebo version is [${gazebo_version}]"
+    gazebo_cppflags = "pkg-config --cflags gazebo".execute().text.split()
+    gazebo_linker_args = "pkg-config --libs gazebo protobuf".execute().text.split()
+} catch(Exception ex) { }
+
+if (!gazebo_version?.trim()) {
+    println "Gazebo development files are not available. (pkg-config --modversion gazebo failed)"
+    if (project.hasProperty("makeSim")) {
+        /* Force the build even though we did not find protobuf. */
+        println "makeSim set. Forcing build - failure likely."
+    }
+    else {
+        ext.skip_frc_plugins = true
+        println "Skipping FRC Plugins."
+    }
+}
+
+evaluationDependsOn(":simulation:gz_msgs")
+def gz_msgs_project = project(":simulation:gz_msgs")
+
+if (!gz_msgs_project.hasProperty('skip_gz_msgs') && !project.hasProperty('skip_frc_plugins')) {
+
+    apply from: "${rootDir}/shared/plugins/setupBuild.gradle"
+
+}
+
+model {
+    binaries {
+        all {
+            if (it instanceof StaticLibraryBinarySpec) {
+                it.buildable = false
+                return
+            }
+            linker.args gazebo_linker_args
+            cppCompiler.args gazebo_cppflags
+            lib project: ":simulation:gz_msgs", library: "gz_msgs", linkage: "static"
+        }
+    }
+}
+
+/* TODO: Publish this library */
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboAnalogIn.cpp b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboAnalogIn.cpp
new file mode 100644
index 0000000..60700c2
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboAnalogIn.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "GazeboAnalogIn.h"
+
+#include <string>
+
+#include <hal/Power.h>
+#include <mockdata/AnalogInData.h>
+#include <mockdata/HAL_Value.h>
+#include <mockdata/NotifyListener.h>
+
+static void init_callback(const char* name, void* param,
+                          const struct HAL_Value* value) {
+  GazeboAnalogIn* ain = static_cast<GazeboAnalogIn*>(param);
+  ain->SetInitialized(value->data.v_boolean);
+  if (ain->IsInitialized()) {
+    ain->Listen();
+  }
+}
+
+GazeboAnalogIn::GazeboAnalogIn(int index, HALSimGazebo* halsim) {
+  m_index = index;
+  m_halsim = halsim;
+  m_sub = NULL;
+  HALSIM_RegisterAnalogInInitializedCallback(index, init_callback, this, true);
+}
+
+void GazeboAnalogIn::Listen() {
+  if (!m_sub)
+    m_sub = m_halsim->node.Subscribe<gazebo::msgs::Float64>(
+        "~/simulator/analog/" + std::to_string(m_index),
+        &GazeboAnalogIn::Callback, this);
+}
+
+void GazeboAnalogIn::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
+  /* This value is going to be divided by the 5V rail in the HAL, so
+     we multiply by that value to make the change neutral */
+  int32_t status;
+  HALSIM_SetAnalogInVoltage(m_index,
+                            msg->data() * HAL_GetUserVoltage5V(&status));
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboDIO.cpp b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboDIO.cpp
new file mode 100644
index 0000000..02f8387
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboDIO.cpp
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "GazeboDIO.h"
+
+#include <string>
+
+#include <mockdata/DIOData.h>
+#include <mockdata/HAL_Value.h>
+#include <mockdata/NotifyListener.h>
+
+static void init_callback(const char* name, void* param,
+                          const struct HAL_Value* value) {
+  GazeboDIO* dio = static_cast<GazeboDIO*>(param);
+  dio->SetInitialized(value->data.v_boolean);
+  if (dio->IsInitialized()) {
+    dio->Listen();
+  }
+}
+
+GazeboDIO::GazeboDIO(int index, HALSimGazebo* halsim) {
+  m_index = index;
+  m_halsim = halsim;
+  m_sub = NULL;
+  HALSIM_RegisterDIOInitializedCallback(index, init_callback, this, true);
+}
+
+void GazeboDIO::Listen() {
+  if (!m_sub)
+    m_sub = m_halsim->node.Subscribe<gazebo::msgs::Bool>(
+        "~/simulator/dio/" + std::to_string(m_index), &GazeboDIO::Callback,
+        this);
+}
+
+void GazeboDIO::Callback(const gazebo::msgs::ConstBoolPtr& msg) {
+  HALSIM_SetDIOValue(m_index, msg->data());
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboEncoder.cpp b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboEncoder.cpp
new file mode 100644
index 0000000..778df7a
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboEncoder.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "GazeboEncoder.h"
+
+#include <string>
+
+#include <mockdata/EncoderData.h>
+#include <mockdata/HAL_Value.h>
+#include <mockdata/NotifyListener.h>
+
+static void encoder_init_callback(const char* name, void* param,
+                                  const struct HAL_Value* value) {
+  GazeboEncoder* encoder = static_cast<GazeboEncoder*>(param);
+  encoder->SetInitialized(value->data.v_boolean);
+  if (encoder->IsInitialized()) {
+    encoder->Control("start");
+    encoder->Listen();
+  }
+}
+
+static void encoder_reset_callback(const char* name, void* param,
+                                   const struct HAL_Value* value) {
+  GazeboEncoder* encoder = static_cast<GazeboEncoder*>(param);
+  if (encoder->IsInitialized() && value->data.v_boolean)
+    encoder->Control("reset");
+}
+
+static void encoder_reverse_callback(const char* name, void* param,
+                                     const struct HAL_Value* value) {
+  GazeboEncoder* encoder = static_cast<GazeboEncoder*>(param);
+  if (encoder->IsInitialized()) encoder->SetReverse(value->data.v_boolean);
+}
+
+GazeboEncoder::GazeboEncoder(int index, HALSimGazebo* halsim) {
+  m_index = index;
+  m_halsim = halsim;
+  m_reverse = false;
+  m_pub = NULL;
+  m_sub = NULL;
+  HALSIM_RegisterEncoderInitializedCallback(index, encoder_init_callback, this,
+                                            true);
+  HALSIM_RegisterEncoderResetCallback(index, encoder_reset_callback, this,
+                                      true);
+  HALSIM_RegisterEncoderReverseDirectionCallback(
+      index, encoder_reverse_callback, this, true);
+}
+
+void GazeboEncoder::Control(const char* command) {
+  if (!m_pub) {
+    m_pub = m_halsim->node.Advertise<gazebo::msgs::String>(
+        "~/simulator/encoder/dio/" +
+        std::to_string(HALSIM_GetDigitalChannelA(m_index)) + "/control");
+    m_pub->WaitForConnection(gazebo::common::Time(1, 0));
+  }
+  gazebo::msgs::String msg;
+  msg.set_data(command);
+  if (m_pub) m_pub->Publish(msg);
+}
+
+void GazeboEncoder::Listen() {
+  if (!m_sub)
+    m_sub = m_halsim->node.Subscribe<gazebo::msgs::Float64>(
+        "~/simulator/encoder/dio/" +
+            std::to_string(HALSIM_GetDigitalChannelA(m_index)) + "/position",
+        &GazeboEncoder::Callback, this);
+}
+
+void GazeboEncoder::Callback(const gazebo::msgs::ConstFloat64Ptr& msg) {
+  HALSIM_SetEncoderCount(m_index, msg->data() * (m_reverse ? -1 : 1));
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboNode.cpp b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboNode.cpp
new file mode 100644
index 0000000..13103b7
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboNode.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "GazeboNode.h"
+
+bool GazeboNode::Connect() {
+  bool success = gazebo::client::setup();
+
+  if (success) {
+    main = gazebo::transport::NodePtr(new gazebo::transport::Node());
+    main->Init("frc");
+    gazebo::transport::run();
+  }
+
+  return success;
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboPCM.cpp b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboPCM.cpp
new file mode 100644
index 0000000..de4188c
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboPCM.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "GazeboPCM.h"
+
+#include <string>
+
+#include <mockdata/HAL_Value.h>
+#include <mockdata/NotifyListener.h>
+#include <mockdata/PCMData.h>
+
+#include "simulation/gz_msgs/msgs.h"
+
+static void init_callback(const char* name, void* param,
+                          const struct HAL_Value* value) {
+  GazeboPCM* pcm = static_cast<GazeboPCM*>(param);
+  pcm->SetInitialized(value->data.v_boolean);
+}
+
+static void output_callback(const char* name, void* param,
+                            const struct HAL_Value* value) {
+  GazeboPCM* pcm = static_cast<GazeboPCM*>(param);
+  if (pcm->IsInitialized()) pcm->Publish(value->data.v_boolean);
+}
+
+GazeboPCM::GazeboPCM(int index, int channel, HALSimGazebo* halsim) {
+  m_index = index;
+  m_channel = channel;
+  m_halsim = halsim;
+  m_pub = NULL;
+  HALSIM_RegisterPCMSolenoidInitializedCallback(index, channel, init_callback,
+                                                this, true);
+  HALSIM_RegisterPCMSolenoidOutputCallback(index, channel, output_callback,
+                                           this, true);
+}
+
+void GazeboPCM::Publish(bool value) {
+  if (!m_pub) {
+    m_pub = m_halsim->node.Advertise<gazebo::msgs::Bool>(
+        "~/simulator/pneumatic/" + std::to_string(m_index + 1) + "/" +
+        std::to_string(m_channel));
+    m_pub->WaitForConnection(gazebo::common::Time(1, 0));
+  }
+  gazebo::msgs::Bool msg;
+  msg.set_data(value);
+  if (m_pub) m_pub->Publish(msg);
+}
+
+void GazeboPCM_SetPressureSwitch(int index, bool value) {
+  HALSIM_SetPCMPressureSwitch(index, value);
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboPWM.cpp b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboPWM.cpp
new file mode 100644
index 0000000..1d07832
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/GazeboPWM.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "GazeboPWM.h"
+
+#include <string>
+
+#include <mockdata/HAL_Value.h>
+#include <mockdata/NotifyListener.h>
+#include <mockdata/PWMData.h>
+
+#include "simulation/gz_msgs/msgs.h"
+
+static void init_callback(const char* name, void* param,
+                          const struct HAL_Value* value) {
+  GazeboPWM* pwm = static_cast<GazeboPWM*>(param);
+  pwm->SetInitialized(value->data.v_boolean);
+}
+
+static void speed_callback(const char* name, void* param,
+                           const struct HAL_Value* value) {
+  GazeboPWM* pwm = static_cast<GazeboPWM*>(param);
+  if (pwm->IsInitialized()) pwm->Publish(value->data.v_double);
+}
+
+GazeboPWM::GazeboPWM(int port, HALSimGazebo* halsim) {
+  m_port = port;
+  m_halsim = halsim;
+  HALSIM_RegisterPWMInitializedCallback(port, init_callback, this, true);
+  HALSIM_RegisterPWMSpeedCallback(port, speed_callback, this, true);
+}
+
+void GazeboPWM::Publish(double value) {
+  if (!m_pub) {
+    m_pub = m_halsim->node.Advertise<gazebo::msgs::Float64>(
+        "~/simulator/pwm/" + std::to_string(m_port));
+    m_pub->WaitForConnection(gazebo::common::Time(1, 0));
+  }
+  gazebo::msgs::Float64 msg;
+  msg.set_data(value);
+  if (m_pub) m_pub->Publish(msg);
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/main.cpp
new file mode 100644
index 0000000..fa1c85a
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/cpp/main.cpp
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <iostream>
+
+#include <hal/Ports.h>
+
+#include "GazeboAnalogIn.h"
+#include "GazeboDIO.h"
+#include "GazeboEncoder.h"
+#include "GazeboPCM.h"
+#include "GazeboPWM.h"
+#include "HALSimGazebo.h"
+
+/* Currently, robots never terminate, so we keep a single static object
+   to access Gazebo with and it is never properly released or cleaned up. */
+static HALSimGazebo halsim;
+
+extern "C" {
+int HALSIM_InitExtension(void) {
+  std::cout << "Gazebo Simulator Initializing." << std::endl;
+
+  if (!halsim.node.Connect()) {
+    std::cerr << "Error: unable to connect to Gazebo.  Is it running?."
+              << std::endl;
+    return -1;
+  }
+  std::cout << "Gazebo Simulator Connected." << std::endl;
+
+  for (int i = 0; i < HALSimGazebo::kPWMCount; i++)
+    halsim.pwms[i] = new GazeboPWM(i, &halsim);
+
+  for (int i = 0; i < HALSimGazebo::kPCMCount; i++)
+    halsim.pcms[i] = new GazeboPCM(0, i, &halsim);
+  GazeboPCM_SetPressureSwitch(0, true);
+
+  for (int i = 0; i < HALSimGazebo::kEncoderCount; i++)
+    halsim.encoders[i] = new GazeboEncoder(i, &halsim);
+
+  int analog_in_count = HAL_GetNumAnalogInputs();
+  for (int i = 0; i < analog_in_count; i++)
+    halsim.analog_inputs.push_back(new GazeboAnalogIn(i, &halsim));
+
+  int dio_count = HAL_GetNumDigitalChannels();
+  for (int i = 0; i < dio_count; i++)
+    halsim.dios.push_back(new GazeboDIO(i, &halsim));
+
+  return 0;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboAnalogIn.h b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboAnalogIn.h
new file mode 100644
index 0000000..9b1bbde
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboAnalogIn.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HALSimGazebo.h"
+#include "simulation/gz_msgs/msgs.h"
+
+class GazeboAnalogIn {
+ public:
+  GazeboAnalogIn(int index, HALSimGazebo* halsim);
+  void SetInitialized(bool value) { m_initialized = value; }
+  bool IsInitialized(void) { return m_initialized; }
+  void Listen(void);
+
+ private:
+  HALSimGazebo* m_halsim;
+  int m_index;
+  bool m_initialized;
+  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
+  gazebo::transport::SubscriberPtr m_sub;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboDIO.h b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboDIO.h
new file mode 100644
index 0000000..e96650e
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboDIO.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HALSimGazebo.h"
+#include "simulation/gz_msgs/msgs.h"
+
+class GazeboDIO {
+ public:
+  GazeboDIO(int index, HALSimGazebo* halsim);
+  void SetInitialized(bool value) { m_initialized = value; }
+  bool IsInitialized(void) { return m_initialized; }
+  void Listen(void);
+
+ private:
+  HALSimGazebo* m_halsim;
+  int m_index;
+  bool m_initialized;
+  void Callback(const gazebo::msgs::ConstBoolPtr& msg);
+  gazebo::transport::SubscriberPtr m_sub;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboEncoder.h b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboEncoder.h
new file mode 100644
index 0000000..fafeb6a
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboEncoder.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HALSimGazebo.h"
+#include "simulation/gz_msgs/msgs.h"
+
+class GazeboEncoder {
+ public:
+  GazeboEncoder(int index, HALSimGazebo* halsim);
+  void SetInitialized(bool value) { m_initialized = value; }
+  bool IsInitialized(void) { return m_initialized; }
+  void SetReverse(bool value) { m_reverse = value; }
+  void Control(const char* command);
+  void Listen(void);
+
+ private:
+  HALSimGazebo* m_halsim;
+  int m_index;
+  bool m_initialized;
+  bool m_reverse;
+
+  void Callback(const gazebo::msgs::ConstFloat64Ptr& msg);
+
+  gazebo::transport::PublisherPtr m_pub;
+  gazebo::transport::SubscriberPtr m_sub;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboNode.h b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboNode.h
new file mode 100644
index 0000000..cc68599
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboNode.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <gazebo/gazebo_client.hh>
+#include <gazebo/transport/transport.hh>
+
+class GazeboNode {
+ public:
+  bool Connect();
+
+  template <typename M>
+  gazebo::transport::PublisherPtr Advertise(const std::string& topic,
+                                            int queueLimit = 10,
+                                            bool latch = false) {
+    return main->Advertise<M>(topic, queueLimit, latch);
+  }
+
+  template <typename M, typename T>
+  gazebo::transport::SubscriberPtr Subscribe(
+      const std::string& topic,
+      void (T::*fp)(const boost::shared_ptr<M const>&), T* obj,
+      bool latching = false) {
+    return main->Subscribe(topic, fp, obj, latching);
+  }
+
+  template <typename M>
+  gazebo::transport::SubscriberPtr Subscribe(
+      const std::string& topic, void (*fp)(const boost::shared_ptr<M const>&),
+      bool latching = false) {
+    return main->Subscribe(topic, fp, latching);
+  }
+
+ private:
+  gazebo::transport::NodePtr main;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboPCM.h b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboPCM.h
new file mode 100644
index 0000000..d74b20f
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboPCM.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HALSimGazebo.h"
+
+class GazeboPCM {
+ public:
+  GazeboPCM(int index, int channel, HALSimGazebo* halsim);
+  void Publish(bool value);
+  void SetInitialized(bool value) { m_initialized = value; }
+  bool IsInitialized(void) { return m_initialized; }
+
+ private:
+  HALSimGazebo* m_halsim;
+  int m_index;
+  int m_channel;
+
+  bool m_initialized;
+
+  gazebo::transport::PublisherPtr m_pub;
+};
+
+void GazeboPCM_SetPressureSwitch(int index, bool value);
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboPWM.h b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboPWM.h
new file mode 100644
index 0000000..1321e8a
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/GazeboPWM.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HALSimGazebo.h"
+
+class GazeboPWM {
+ public:
+  GazeboPWM(int port, HALSimGazebo* halsim);
+  void SetInitialized(bool value) { m_initialized = value; }
+  bool IsInitialized(void) { return m_initialized; }
+  void Publish(double value);
+
+ private:
+  HALSimGazebo* m_halsim;
+  gazebo::transport::PublisherPtr m_pub;
+  bool m_initialized;
+  int m_port;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/HALSimGazebo.h b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/HALSimGazebo.h
new file mode 100644
index 0000000..f7d8193
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_gazebo/src/main/native/include/HALSimGazebo.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <vector>
+
+#include "GazeboNode.h"
+
+class GazeboPWM;
+class GazeboPCM;
+class GazeboEncoder;
+class GazeboAnalogIn;
+class GazeboDIO;
+
+class HALSimGazebo {
+ public:
+  static const int kPWMCount = 20;
+  static const int kPCMCount = 8;
+  static const int kEncoderCount = 8;
+
+  GazeboNode node;
+  GazeboPWM* pwms[kPWMCount];
+  GazeboPCM* pcms[kPCMCount];
+  GazeboEncoder* encoders[kEncoderCount];
+  std::vector<GazeboAnalogIn*> analog_inputs;
+  std::vector<GazeboDIO*> dios;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/build.gradle b/third_party/allwpilib_2019/simulation/halsim_lowfi/build.gradle
new file mode 100644
index 0000000..549a43c
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/build.gradle
@@ -0,0 +1,9 @@
+description = "A simulation shared object that publishes basic robot I/O to NetworkTables."
+
+ext {
+    includeNtCore = true
+    includeWpiutil = true
+    pluginName = 'halsim_lowfi'
+}
+
+apply from: "${rootDir}/shared/plugins/setupBuild.gradle"
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..e324b44
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/dev/native/cpp/main.cpp
@@ -0,0 +1,8 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+int main() {}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/HALSimLowFi.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/HALSimLowFi.cpp
new file mode 100644
index 0000000..f82efb7
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/HALSimLowFi.cpp
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "HALSimLowFi.h"
+
+#include <wpi/Twine.h>
+
+void HALSimLowFi::Initialize() {
+  table = nt::NetworkTableInstance::GetDefault().GetTable("sim");
+}
+
+void HALSimNTProvider::Inject(std::shared_ptr<HALSimLowFi> parentArg,
+                              std::string tableNameArg) {
+  parent = parentArg;
+  tableName = std::move(tableNameArg);
+  table = parent->table->GetSubTable(tableName);
+
+  this->Initialize();
+}
+
+void NTProviderBaseCallback(const char* name, void* param,
+                            const struct HAL_Value* value) {
+  auto info =
+      static_cast<struct HALSimNTProvider::NTProviderCallbackInfo*>(param);
+  uint32_t chan = static_cast<uint32_t>(info->channel);
+  auto provider = info->provider;
+  auto table = info->table;
+  provider->OnCallback(chan, table);
+}
+
+void HALSimNTProvider::InitializeDefault(
+    int numChannels, HALCbRegisterIndexedFunc registerFunc) {
+  this->numChannels = numChannels;
+  cbInfos.reserve(numChannels);
+  for (int i = 0; i < numChannels; i++) {
+    struct NTProviderCallbackInfo info = {
+        this, table->GetSubTable(tableName + wpi::Twine(i)), i};
+    cbInfos.emplace_back(info);
+  }
+
+  for (auto& info : cbInfos) {
+    registerFunc(info.channel, NTProviderBaseCallback, &info, true);
+    OnInitializedChannel(info.channel, info.table);
+  }
+}
+
+void HALSimNTProvider::InitializeDefaultSingle(
+    HALCbRegisterSingleFunc registerFunc) {
+  struct NTProviderCallbackInfo info = {this, table, 0};
+  cbInfos.push_back(info);
+
+  for (auto& info : cbInfos) {
+    registerFunc(NTProviderBaseCallback, &info, true);
+  }
+}
+
+void HALSimNTProvider::OnInitializedChannel(
+    uint32_t channel, std::shared_ptr<nt::NetworkTable> table) {}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Analog.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Analog.cpp
new file mode 100644
index 0000000..2d35c57
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Analog.cpp
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "NTProvider_Analog.h"
+
+#include <hal/Ports.h>
+#include <mockdata/AnalogInData.h>
+#include <mockdata/AnalogOutData.h>
+
+void HALSimNTProviderAnalogIn::Initialize() {
+  InitializeDefault(HAL_GetNumAnalogInputs(),
+                    HALSIM_RegisterAnalogInAllCallbacks);
+}
+
+void HALSimNTProviderAnalogIn::OnCallback(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("init?").SetBoolean(HALSIM_GetAnalogInInitialized(chan));
+  table->GetEntry("avg_bits").SetDouble(HALSIM_GetAnalogInAverageBits(chan));
+  table->GetEntry("oversample_bits")
+      .SetDouble(HALSIM_GetAnalogInOversampleBits(chan));
+  table->GetEntry("voltage").SetDouble(HALSIM_GetAnalogInVoltage(chan));
+
+  auto accum = table->GetSubTable("accum");
+  accum->GetEntry("init?").SetBoolean(
+      HALSIM_GetAnalogInAccumulatorInitialized(chan));
+  accum->GetEntry("value").SetDouble(HALSIM_GetAnalogInAccumulatorValue(chan));
+  accum->GetEntry("count").SetDouble(HALSIM_GetAnalogInAccumulatorCount(chan));
+  accum->GetEntry("center").SetDouble(
+      HALSIM_GetAnalogInAccumulatorCenter(chan));
+  accum->GetEntry("deadband")
+      .SetDouble(HALSIM_GetAnalogInAccumulatorDeadband(chan));
+}
+
+void HALSimNTProviderAnalogIn::OnInitializedChannel(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("voltage").AddListener(
+      [=](const nt::EntryNotification& ev) -> void {
+        HALSIM_SetAnalogInVoltage(chan, ev.value->GetDouble());
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+}
+
+void HALSimNTProviderAnalogOut::Initialize() {
+  InitializeDefault(HAL_GetNumAnalogOutputs(),
+                    HALSIM_RegisterAnalogOutAllCallbacks);
+}
+
+void HALSimNTProviderAnalogOut::OnCallback(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("init?").SetBoolean(HALSIM_GetAnalogOutInitialized(chan));
+  table->GetEntry("voltage").SetDouble(HALSIM_GetAnalogOutVoltage(chan));
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_DIO.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_DIO.cpp
new file mode 100644
index 0000000..f4ed9d6
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_DIO.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "NTProvider_DIO.h"
+
+#include <hal/Ports.h>
+#include <mockdata/DIOData.h>
+
+void HALSimNTProviderDIO::Initialize() {
+  InitializeDefault(HAL_GetNumDigitalChannels(),
+                    HALSIM_RegisterDIOAllCallbacks);
+}
+
+void HALSimNTProviderDIO::OnCallback(uint32_t chan,
+                                     std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("init?").SetBoolean(HALSIM_GetDIOInitialized(chan));
+  table->GetEntry("value").SetBoolean(HALSIM_GetDIOValue(chan));
+  table->GetEntry("pulse_length").SetDouble(HALSIM_GetDIOPulseLength(chan));
+  table->GetEntry("input?").SetBoolean(HALSIM_GetDIOIsInput(chan));
+}
+
+void HALSimNTProviderDIO::OnInitializedChannel(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("value").AddListener(
+      [=](const nt::EntryNotification& ev) -> void {
+        if (HALSIM_GetDIOIsInput(chan)) {
+          HALSIM_SetDIOValue(chan, ev.value->GetBoolean());
+        }
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_DriverStation.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_DriverStation.cpp
new file mode 100644
index 0000000..e02d646
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_DriverStation.cpp
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "NTProvider_DriverStation.h"
+
+#include <hal/Ports.h>
+#include <mockdata/DriverStationData.h>
+
+void HALSimNTProviderDriverStation::Initialize() {
+  InitializeDefaultSingle(HALSIM_RegisterDriverStationAllCallbacks);
+}
+
+void HALSimNTProviderDriverStation::OnCallback(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  bool auton = HALSIM_GetDriverStationAutonomous(),
+       test = HALSIM_GetDriverStationTest(),
+       enabled = HALSIM_GetDriverStationEnabled();
+
+  bool teleop = (!auton && !test && enabled);
+
+  table->GetEntry("enabled?").SetBoolean(enabled);
+  table->GetEntry("autonomous?").SetBoolean(auton);
+  table->GetEntry("test?").SetBoolean(test);
+  table->GetEntry("teleop?").SetBoolean(teleop);
+  table->GetEntry("estop?").SetBoolean(HALSIM_GetDriverStationEStop());
+  table->GetEntry("fms?").SetBoolean(HALSIM_GetDriverStationFmsAttached());
+  table->GetEntry("ds?").SetBoolean(HALSIM_GetDriverStationDsAttached());
+  table->GetEntry("match_time").SetDouble(HALSIM_GetDriverStationMatchTime());
+
+  // TODO: Joysticks
+
+  auto alliance = table->GetSubTable("alliance");
+  auto allianceValue = HALSIM_GetDriverStationAllianceStationId();
+  alliance->GetEntry("color").SetString(
+      (allianceValue == HAL_AllianceStationID_kRed1 ||
+       allianceValue == HAL_AllianceStationID_kRed2 ||
+       allianceValue == HAL_AllianceStationID_kRed3)
+          ? "red"
+          : "blue");
+  int station = 0;
+
+  switch (allianceValue) {
+    case HAL_AllianceStationID_kRed1:
+    case HAL_AllianceStationID_kBlue1:
+      station = 1;
+      break;
+    case HAL_AllianceStationID_kRed2:
+    case HAL_AllianceStationID_kBlue2:
+      station = 2;
+      break;
+    case HAL_AllianceStationID_kRed3:
+    case HAL_AllianceStationID_kBlue3:
+      station = 3;
+      break;
+  }
+  alliance->GetEntry("station").SetDouble(station);
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Encoder.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Encoder.cpp
new file mode 100644
index 0000000..ca012ab
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Encoder.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "NTProvider_Encoder.h"
+
+#include <hal/Ports.h>
+#include <mockdata/EncoderData.h>
+
+void HALSimNTProviderEncoder::Initialize() {
+  InitializeDefault(HAL_GetNumEncoders(), HALSIM_RegisterEncoderAllCallbacks);
+}
+
+void HALSimNTProviderEncoder::OnCallback(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("init?").SetBoolean(HALSIM_GetEncoderInitialized(chan));
+  table->GetEntry("count").SetDouble(HALSIM_GetEncoderCount(chan));
+  table->GetEntry("period").SetDouble(HALSIM_GetEncoderPeriod(chan));
+  table->GetEntry("reset?").SetBoolean(HALSIM_GetEncoderReset(chan));
+  table->GetEntry("max_period").SetDouble(HALSIM_GetEncoderMaxPeriod(chan));
+  table->GetEntry("direction").SetBoolean(HALSIM_GetEncoderDirection(chan));
+  table->GetEntry("reverse_direction?")
+      .SetBoolean(HALSIM_GetEncoderReverseDirection(chan));
+  table->GetEntry("samples_to_avg")
+      .SetDouble(HALSIM_GetEncoderSamplesToAverage(chan));
+}
+
+void HALSimNTProviderEncoder::OnInitializedChannel(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("count").AddListener(
+      [=](const nt::EntryNotification& ev) -> void {
+        HALSIM_SetEncoderCount(chan,
+                               static_cast<int32_t>(ev.value->GetDouble()));
+      },
+      NT_NotifyKind::NT_NOTIFY_UPDATE);
+
+  table->GetEntry("direction")
+      .AddListener(
+          [=](const nt::EntryNotification& ev) -> void {
+            HALSIM_SetEncoderDirection(chan, ev.value->GetBoolean());
+          },
+          NT_NotifyKind::NT_NOTIFY_UPDATE);
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_PWM.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_PWM.cpp
new file mode 100644
index 0000000..5786eee
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_PWM.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "NTProvider_PWM.h"
+
+#include <hal/Ports.h>
+#include <mockdata/PWMData.h>
+
+void HALSimNTProviderPWM::Initialize() {
+  InitializeDefault(HAL_GetNumPWMChannels(), HALSIM_RegisterPWMAllCallbacks);
+}
+
+void HALSimNTProviderPWM::OnCallback(uint32_t chan,
+                                     std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("init?").SetBoolean(HALSIM_GetPWMInitialized(chan));
+  table->GetEntry("speed").SetDouble(HALSIM_GetPWMSpeed(chan));
+  table->GetEntry("position").SetDouble(HALSIM_GetPWMPosition(chan));
+  table->GetEntry("raw").SetDouble(HALSIM_GetPWMRawValue(chan));
+  table->GetEntry("period_scale").SetDouble(HALSIM_GetPWMPeriodScale(chan));
+  table->GetEntry("zero_latch?").SetBoolean(HALSIM_GetPWMZeroLatch(chan));
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Relay.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Relay.cpp
new file mode 100644
index 0000000..249a1c3
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_Relay.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "NTProvider_Relay.h"
+
+#include <hal/Ports.h>
+#include <mockdata/RelayData.h>
+
+void HALSimNTProviderRelay::Initialize() {
+  InitializeDefault(HAL_GetNumRelayHeaders(), HALSIM_RegisterRelayAllCallbacks);
+}
+
+void HALSimNTProviderRelay::OnCallback(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("init_fwd?")
+      .SetBoolean(HALSIM_GetRelayInitializedForward(chan));
+  table->GetEntry("init_rvs?")
+      .SetBoolean(HALSIM_GetRelayInitializedReverse(chan));
+  table->GetEntry("fwd?").SetBoolean(HALSIM_GetRelayForward(chan));
+  table->GetEntry("rvs?").SetBoolean(HALSIM_GetRelayReverse(chan));
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_RoboRIO.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_RoboRIO.cpp
new file mode 100644
index 0000000..c3eaa25
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_RoboRIO.cpp
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "NTProvider_RoboRIO.h"
+
+#include <hal/Ports.h>
+#include <mockdata/RoboRioData.h>
+
+void HALSimNTProviderRoboRIO::Initialize() {
+  InitializeDefault(1, HALSIM_RegisterRoboRioAllCallbacks);
+}
+
+void HALSimNTProviderRoboRIO::OnCallback(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("fpga_button?").SetBoolean(HALSIM_GetRoboRioFPGAButton(chan));
+
+  table->GetEntry("vin_voltage").SetDouble(HALSIM_GetRoboRioVInVoltage(chan));
+  table->GetEntry("vin_current").SetDouble(HALSIM_GetRoboRioVInCurrent(chan));
+
+  auto t6v = table->GetSubTable("6V");
+  t6v->GetEntry("voltage").SetDouble(HALSIM_GetRoboRioUserVoltage6V(chan));
+  t6v->GetEntry("current").SetDouble(HALSIM_GetRoboRioUserCurrent6V(chan));
+  t6v->GetEntry("active?").SetBoolean(HALSIM_GetRoboRioUserActive6V(chan));
+  t6v->GetEntry("faults").SetDouble(HALSIM_GetRoboRioUserFaults6V(chan));
+
+  auto t5v = table->GetSubTable("5V");
+  t5v->GetEntry("voltage").SetDouble(HALSIM_GetRoboRioUserVoltage5V(chan));
+  t5v->GetEntry("current").SetDouble(HALSIM_GetRoboRioUserCurrent5V(chan));
+  t5v->GetEntry("active?").SetBoolean(HALSIM_GetRoboRioUserActive5V(chan));
+  t5v->GetEntry("faults").SetDouble(HALSIM_GetRoboRioUserFaults5V(chan));
+
+  auto t3v3 = table->GetSubTable("3V3");
+  t3v3->GetEntry("voltage").SetDouble(HALSIM_GetRoboRioUserVoltage3V3(chan));
+  t3v3->GetEntry("current").SetDouble(HALSIM_GetRoboRioUserCurrent3V3(chan));
+  t3v3->GetEntry("active?").SetBoolean(HALSIM_GetRoboRioUserActive3V3(chan));
+  t3v3->GetEntry("faults").SetDouble(HALSIM_GetRoboRioUserFaults3V3(chan));
+}
+
+void HALSimNTProviderRoboRIO::OnInitializedChannel(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("fpga_button?")
+      .AddListener(
+          [=](const nt::EntryNotification& ev) -> void {
+            HALSIM_SetRoboRioFPGAButton(chan, ev.value->GetBoolean());
+          },
+          NT_NotifyKind::NT_NOTIFY_UPDATE);
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_dPWM.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_dPWM.cpp
new file mode 100644
index 0000000..e2bb74a
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/NTProvider_dPWM.cpp
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "NTProvider_dPWM.h"
+
+#include <hal/Ports.h>
+#include <mockdata/DigitalPWMData.h>
+
+void HALSimNTProviderDigitalPWM::Initialize() {
+  InitializeDefault(HAL_GetNumDigitalPWMOutputs(),
+                    HALSIM_RegisterDigitalPWMAllCallbacks);
+}
+
+void HALSimNTProviderDigitalPWM::OnCallback(
+    uint32_t chan, std::shared_ptr<nt::NetworkTable> table) {
+  table->GetEntry("init?").SetBoolean(HALSIM_GetDigitalPWMInitialized(chan));
+  table->GetEntry("dio_pin").SetDouble(HALSIM_GetDigitalPWMPin(chan));
+  table->GetEntry("duty_cycle").SetDouble(HALSIM_GetDigitalPWMDutyCycle(chan));
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/main.cpp
new file mode 100644
index 0000000..b94a634
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/cpp/main.cpp
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include <HALSimLowFi.h>
+#include <NTProvider_Analog.h>
+#include <NTProvider_DIO.h>
+#include <NTProvider_DriverStation.h>
+#include <NTProvider_Encoder.h>
+#include <NTProvider_PWM.h>
+#include <NTProvider_Relay.h>
+#include <NTProvider_RoboRIO.h>
+#include <NTProvider_dPWM.h>
+
+static HALSimLowFi halsim_lowfi;
+
+static HALSimNTProviderPWM pwm_provider;
+static HALSimNTProviderDigitalPWM dpwm_provider;
+static HALSimNTProviderDIO dio_provider;
+static HALSimNTProviderAnalogIn ai_provider;
+static HALSimNTProviderAnalogOut ao_provider;
+static HALSimNTProviderDriverStation ds_provider;
+static HALSimNTProviderEncoder encoder_provider;
+static HALSimNTProviderRelay relay_provider;
+static HALSimNTProviderRoboRIO roborio_provider;
+
+extern "C" {
+#if defined(WIN32) || defined(_WIN32)
+__declspec(dllexport)
+#endif
+    int HALSIM_InitExtension(void) {
+  std::cout << "NetworkTables LowFi Simulator Initializing." << std::endl;
+  halsim_lowfi.Initialize();
+  halsim_lowfi.table->GetInstance().StartServer("networktables.ini");
+  halsim_lowfi.table->GetInstance().SetUpdateRate(0.05);
+  auto lowfi = std::make_shared<HALSimLowFi>(halsim_lowfi);
+
+  pwm_provider.Inject(lowfi, "PWM");
+  dpwm_provider.Inject(lowfi, "dPWM");
+  dio_provider.Inject(lowfi, "DIO");
+  ai_provider.Inject(lowfi, "AI");
+  ao_provider.Inject(lowfi, "AO");
+  ds_provider.Inject(lowfi, "DriverStation");
+  encoder_provider.Inject(lowfi, "Encoder");
+  relay_provider.Inject(lowfi, "Relay");
+  roborio_provider.Inject(lowfi, "RoboRIO");
+
+  std::cout << "NetworkTables LowFi Simulator Initialized!" << std::endl;
+  return 0;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/HALSimLowFi.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/HALSimLowFi.h
new file mode 100644
index 0000000..28faed0
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/HALSimLowFi.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cinttypes>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <mockdata/NotifyListener.h>
+#include <networktables/NetworkTableInstance.h>
+
+class HALSimLowFi {
+ public:
+  std::shared_ptr<nt::NetworkTable> table;
+  void Initialize();
+};
+
+typedef void (*HALCbRegisterIndexedFunc)(int32_t index,
+                                         HAL_NotifyCallback callback,
+                                         void* param, HAL_Bool initialNotify);
+typedef void (*HALCbRegisterSingleFunc)(HAL_NotifyCallback callback,
+                                        void* param, HAL_Bool initialNotify);
+
+void NTProviderBaseCallback(const char* name, void* param,
+                            const struct HAL_Value* value);
+
+class HALSimNTProvider {
+ public:
+  struct NTProviderCallbackInfo {
+    HALSimNTProvider* provider;
+    std::shared_ptr<nt::NetworkTable> table;
+    int channel;
+  };
+
+  void Inject(std::shared_ptr<HALSimLowFi> parent, std::string table);
+  // Initialize is called by inject.
+  virtual void Initialize() = 0;
+  virtual void InitializeDefault(int numChannels,
+                                 HALCbRegisterIndexedFunc registerFunc);
+  virtual void InitializeDefaultSingle(HALCbRegisterSingleFunc registerFunc);
+  virtual void OnCallback(uint32_t channel,
+                          std::shared_ptr<nt::NetworkTable> table) = 0;
+  virtual void OnInitializedChannel(uint32_t channel,
+                                    std::shared_ptr<nt::NetworkTable> table);
+
+  int numChannels;
+  std::string tableName;
+
+  std::shared_ptr<HALSimLowFi> parent;
+  std::shared_ptr<nt::NetworkTable> table;
+  std::vector<NTProviderCallbackInfo> cbInfos;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Analog.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Analog.h
new file mode 100644
index 0000000..8672b46
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Analog.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <HALSimLowFi.h>
+
+class HALSimNTProviderAnalogIn : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+  void OnInitializedChannel(uint32_t channel,
+                            std::shared_ptr<nt::NetworkTable> table) override;
+};
+
+class HALSimNTProviderAnalogOut : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_DIO.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_DIO.h
new file mode 100644
index 0000000..b584b48
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_DIO.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <HALSimLowFi.h>
+
+class HALSimNTProviderDIO : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+  void OnInitializedChannel(uint32_t channel,
+                            std::shared_ptr<nt::NetworkTable> table) override;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_DriverStation.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_DriverStation.h
new file mode 100644
index 0000000..5041b02
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_DriverStation.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <HALSimLowFi.h>
+
+class HALSimNTProviderDriverStation : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Encoder.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Encoder.h
new file mode 100644
index 0000000..f3ef70f
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Encoder.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <HALSimLowFi.h>
+
+class HALSimNTProviderEncoder : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+  void OnInitializedChannel(uint32_t channel,
+                            std::shared_ptr<nt::NetworkTable> table) override;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_PWM.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_PWM.h
new file mode 100644
index 0000000..47c416e
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_PWM.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <HALSimLowFi.h>
+
+class HALSimNTProviderPWM : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Relay.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Relay.h
new file mode 100644
index 0000000..cc8439a
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_Relay.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <HALSimLowFi.h>
+
+class HALSimNTProviderRelay : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_RoboRIO.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_RoboRIO.h
new file mode 100644
index 0000000..055b6e6
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_RoboRIO.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <HALSimLowFi.h>
+
+class HALSimNTProviderRoboRIO : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+  void OnInitializedChannel(uint32_t channel,
+                            std::shared_ptr<nt::NetworkTable> table) override;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_dPWM.h b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_dPWM.h
new file mode 100644
index 0000000..0af607f
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_lowfi/src/main/native/include/NTProvider_dPWM.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <HALSimLowFi.h>
+
+class HALSimNTProviderDigitalPWM : public HALSimNTProvider {
+ public:
+  void Initialize() override;
+  void OnCallback(uint32_t channel,
+                  std::shared_ptr<nt::NetworkTable> table) override;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_print/build.gradle b/third_party/allwpilib_2019/simulation/halsim_print/build.gradle
new file mode 100644
index 0000000..dd0a347
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_print/build.gradle
@@ -0,0 +1,7 @@
+description = "A simulation shared object that simply prints robot behaviors"
+
+ext {
+    pluginName = 'halsim_print'
+}
+
+apply from: "${rootDir}/shared/plugins/setupBuild.gradle"
diff --git a/third_party/allwpilib_2019/simulation/halsim_print/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_print/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..d9f92e9
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_print/src/dev/native/cpp/main.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <chrono>
+#include <thread>
+
+#include <hal/HAL.h>
+
+int main() {
+  HAL_Initialize(500, 0);
+  std::this_thread::sleep_for(std::chrono::seconds(2));
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/cpp/PrintPWM.cpp b/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/cpp/PrintPWM.cpp
new file mode 100644
index 0000000..fe82ccd
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/cpp/PrintPWM.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "PrintPWM.h"
+
+#include <iostream>
+
+#include <mockdata/HAL_Value.h>
+#include <mockdata/NotifyListener.h>
+#include <mockdata/PWMData.h>
+
+static void PWMCallback(const char* name, void* param,
+                        const struct HAL_Value* value) {
+  auto pwm = static_cast<PrintPWM*>(param);
+  pwm->Publish(value->data.v_double);
+}
+
+PrintPWM::PrintPWM(int port) {
+  m_port = port;
+  HALSIM_RegisterPWMSpeedCallback(port, PWMCallback, this, false);
+}
+
+void PrintPWM::Publish(double value) {
+  std::cout << "PWM " << m_port << ": " << value << std::endl;
+}
diff --git a/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/cpp/main.cpp
new file mode 100644
index 0000000..55327ee
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/cpp/main.cpp
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include <hal/Ports.h>
+
+#include "HALSimPrint.h"
+#include "PrintPWM.h"
+
+// Currently, robots never terminate, so we keep a single static object and it
+// is never properly released or cleaned up.
+static HALSimPrint halsim;
+
+extern "C" {
+#if defined(WIN32) || defined(_WIN32)
+__declspec(dllexport)
+#endif
+    int HALSIM_InitExtension(void) {
+  std::cout << "Print Simulator Initializing." << std::endl;
+
+  int pwmCount = HAL_GetNumPWMChannels();
+  halsim.m_pwms.reserve(pwmCount);
+  for (int i = 0; i < pwmCount; i++) halsim.m_pwms.emplace_back(i);
+
+  return 0;
+}
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/include/HALSimPrint.h b/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/include/HALSimPrint.h
new file mode 100644
index 0000000..69dafec
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/include/HALSimPrint.h
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <vector>
+
+class PrintPWM;
+
+class HALSimPrint {
+ public:
+  std::vector<PrintPWM> m_pwms;
+};
diff --git a/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/include/PrintPWM.h b/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/include/PrintPWM.h
new file mode 100644
index 0000000..98803ff
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/halsim_print/src/main/native/include/PrintPWM.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "HALSimPrint.h"
+
+class PrintPWM {
+ public:
+  explicit PrintPWM(int port);
+  void Publish(double value);
+
+ private:
+  int m_port;
+};
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/build.gradle b/third_party/allwpilib_2019/simulation/lowfi_simulation/build.gradle
new file mode 100644
index 0000000..2b97416
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/build.gradle
@@ -0,0 +1,201 @@
+apply plugin: 'cpp'
+apply plugin: 'google-test-test-suite'
+apply plugin: 'visual-studio'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: SingleNativeBuild
+apply plugin: ExtraTasks
+
+
+ext {
+    nativeName = 'lowfi_sim'
+}
+
+apply from: "${rootDir}/shared/config.gradle"
+
+if (!project.hasProperty('onlyAthena')) {
+
+    ext {
+        sharedCvConfigs = [lowfi_simTest: []]
+        staticCvConfigs = [:]
+        useJava = false
+        useCpp = true
+    }
+    apply from: "${rootDir}/shared/opencv.gradle"
+
+    ext {
+        staticGtestConfigs = [:]
+    }
+    staticGtestConfigs["${nativeName}Test"] = []
+    apply from: "${rootDir}/shared/googletest.gradle"
+
+    project(':').libraryBuild.dependsOn build
+
+    ext {
+        chipObjectComponents = ["$nativeName".toString(), "${nativeName}Dev".toString(), "${nativeName}Base".toString(),
+                                "${nativeName}Test".toString()]
+        netCommComponents = ["$nativeName".toString(), "${nativeName}Dev".toString(), "${nativeName}Base".toString(),
+                             "${nativeName}Test".toString()]
+        useNiJava = false
+    }
+
+    apply from: "${rootDir}/shared/nilibraries.gradle"
+
+    model {
+        exportsConfigs {
+            lowfi_sim(ExportsConfig) {
+                x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                     '_CT??_R0?AVbad_cast',
+                                     '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                     '_TI5?AVfailure']
+                x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                     '_CT??_R0?AVbad_cast',
+                                     '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                     '_TI5?AVfailure']
+            }
+        }
+        components {
+            "${nativeName}Base"(NativeLibrarySpec) {
+                sources {
+                    cpp {
+                        source {
+                            srcDirs = ['src/main/native/cpp']
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/native/include'
+                        }
+                    }
+                }
+                binaries.all {
+                    if (it instanceof SharedLibraryBinarySpec) {
+                        it.buildable = false
+                        return
+                    }
+                    if (it.targetPlatform.architecture.name == 'athena') {
+                        it.buildable = false
+                        return
+                    }
+                    project(':hal').addHalDependency(it, 'shared')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib project: ':simulation:halsim_adx_gyro_accelerometer', library: 'halsim_adx_gyro_accelerometer', linkage: 'shared'
+                }
+            }
+            "${nativeName}"(NativeLibrarySpec) {
+                sources {
+                    cpp {
+                        source {
+                            srcDirs "${rootDir}/shared/singlelib"
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/native/include'
+                        }
+                    }
+                }
+                binaries.all {
+                    if (it.targetPlatform.architecture.name == 'athena') {
+                        it.buildable = false
+                        return
+                    }
+                    project(':hal').addHalDependency(it, 'shared')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib project: ':simulation:halsim_adx_gyro_accelerometer', library: 'halsim_adx_gyro_accelerometer', linkage: 'shared'
+                }
+            }
+            // By default, a development executable will be generated. This is to help the case of
+            // testing specific functionality of the library.
+            "${nativeName}Dev"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'src/dev/native/cpp'
+                            include '**/*.cpp'
+                            lib library: "${nativeName}"
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/dev/native/include'
+                        }
+                    }
+                }
+                binaries.all {
+                    if (it.targetPlatform.architecture.name == 'athena') {
+                        it.buildable = false
+                        return
+                    }
+                    project(':hal').addHalDependency(it, 'shared')
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib project: ':simulation:halsim_adx_gyro_accelerometer', library: 'halsim_adx_gyro_accelerometer', linkage: 'shared'
+                    lib library: nativeName, linkage: 'shared'
+                }
+            }
+        }
+        binaries {
+            withType(GoogleTestTestSuiteBinarySpec) {
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                lib project: ':simulation:halsim_adx_gyro_accelerometer', library: 'halsim_adx_gyro_accelerometer', linkage: 'shared'
+                lib library: nativeName, linkage: 'shared'
+            }
+        }
+    }
+
+    apply from: "publish.gradle"
+}
+
+model {
+
+    testSuites {
+        if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+            "${nativeName}Test"(GoogleTestTestSuiteSpec) {
+                for(NativeComponentSpec c : $.components) {
+                    if (c.name == nativeName) {
+                        testing c
+                        break
+                    }
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'src/test/native/cpp'
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/test/native/include', 'src/main/native/cpp'
+                        }
+                    }
+                }
+            }
+        }
+    }
+    tasks {
+        def c = $.components
+        project.tasks.create('runCpp', Exec) {
+            def found = false
+            c.each {
+                if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
+                    it.binaries.each {
+                        if (!found) {
+                            def arch = it.targetPlatform.architecture.name
+                            if (arch == 'x86-64' || arch == 'x86') {
+                                dependsOn it.tasks.install
+								commandLine it.tasks.install.runScriptFile.get().asFile.toString()
+
+                                found = true
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+tasks.withType(RunTestExecutable) {
+    args "--gtest_output=xml:test_detail.xml"
+    outputs.dir outputDir
+}
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/publish.gradle b/third_party/allwpilib_2019/simulation/lowfi_simulation/publish.gradle
new file mode 100644
index 0000000..4143cd2
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/publish.gradle
@@ -0,0 +1,71 @@
+apply plugin: 'maven-publish'
+
+def pubVersion = ''
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseArtifactId = nativeName
+def artifactGroupId = 'edu.wpi.first.halsim'
+def zipBaseName = "_GROUP_edu_wpi_first_halsim_ID_${nativeName}_CLS"
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task cppSourcesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "sources"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/cpp') {
+        into '/'
+    }
+}
+
+task cppHeadersZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "headers"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/include') {
+        into '/'
+    }
+}
+
+build.dependsOn cppSourcesZip
+build.dependsOn cppHeadersZip
+
+addTaskToCopyAllOutputs(cppSourcesZip)
+addTaskToCopyAllOutputs(cppHeadersZip)
+
+
+model {
+    publishing {
+        def lowfiSimTaskList = createComponentZipTasks($.components, [nativeName], zipBaseName, Zip, project, includeStandardZipFormat)
+
+        publications {
+            cpp(MavenPublication) {
+                lowfiSimTaskList.each {
+                    artifact it
+                }
+
+                artifact cppHeadersZip
+                artifact cppSourcesZip
+
+
+                artifactId = baseArtifactId
+                groupId artifactGroupId
+                version pubVersion
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..4dc5f43
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/dev/native/cpp/main.cpp
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include <hal/HAL.h>
+
+int main() {
+  std::cout << "Hello World" << std::endl;
+  std::cout << HAL_GetRuntimeType() << std::endl;
+}
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/MotorEncoderConnector.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/MotorEncoderConnector.cpp
new file mode 100644
index 0000000..5e530e6
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/MotorEncoderConnector.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "lowfisim/MotorEncoderConnector.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+MotorEncoderConnector::MotorEncoderConnector(MotorSim& motorController,
+                                             EncoderSim& encoder)
+    : motorSimulator(motorController), encoderSimulator(encoder) {}
+
+void MotorEncoderConnector::Update() {
+  encoderSimulator.SetPosition(motorSimulator.GetPosition());
+  encoderSimulator.SetVelocity(motorSimulator.GetVelocity());
+}
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/SimulatorComponentBase.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/SimulatorComponentBase.cpp
new file mode 100644
index 0000000..a65de3b
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/SimulatorComponentBase.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "lowfisim/SimulatorComponentBase.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+const std::string& SimulatorComponentBase::GetDisplayName() const {
+  return m_name;
+}
+
+void SimulatorComponentBase::SetDisplayName(const std::string& displayName) {
+  m_name = displayName;
+}
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/motormodel/SimpleMotorModel.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/motormodel/SimpleMotorModel.cpp
new file mode 100644
index 0000000..226a836
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/motormodel/SimpleMotorModel.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "lowfisim/motormodel/SimpleMotorModel.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+SimpleMotorModel::SimpleMotorModel(double maxSpeed) : m_maxSpeed(maxSpeed) {}
+
+void SimpleMotorModel::Reset() {
+  m_position = 0;
+  m_velocity = 0;
+}
+
+void SimpleMotorModel::SetVoltage(double voltage) {
+  m_voltagePercentage = voltage / kMaxExpectedVoltage;
+}
+
+void SimpleMotorModel::Update(double elapsedTime) {
+  m_velocity = m_maxSpeed * m_voltagePercentage;
+  m_position += m_velocity * elapsedTime;
+}
+
+double SimpleMotorModel::GetPosition() const { return m_position; }
+
+double SimpleMotorModel::GetVelocity() const { return m_velocity; }
+
+double SimpleMotorModel::GetAcceleration() const { return 0; }
+
+double SimpleMotorModel::GetCurrent() const { return 0; }
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/ADXLThreeAxisAccelerometerSim.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/ADXLThreeAxisAccelerometerSim.cpp
new file mode 100644
index 0000000..915d838
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/ADXLThreeAxisAccelerometerSim.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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 "lowfisim/wpisimulators/ADXLThreeAxisAccelerometerSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+ADXLThreeAxisAccelerometerSim::ADXLThreeAxisAccelerometerSim(
+    hal::ThreeAxisAccelerometerData& accelerometerWrapper)
+    : m_accelerometerWrapper(accelerometerWrapper),
+      m_xWrapper(
+          [data = &m_accelerometerWrapper] { return data->GetInitialized(); },
+          [data = &m_accelerometerWrapper](double x) { data->x = x; },
+          [data = &m_accelerometerWrapper] { return data->GetX(); }),
+
+      m_yWrapper(
+          [data = &m_accelerometerWrapper] { return data->GetInitialized(); },
+          [data = &m_accelerometerWrapper](double y) { data->y = y; },
+          [data = &m_accelerometerWrapper] { return data->GetY(); }),
+
+      m_zWrapper(
+          [data = &m_accelerometerWrapper] { return data->GetInitialized(); },
+          [data = &m_accelerometerWrapper](double z) { data->z = z; },
+          [data = &m_accelerometerWrapper] { return data->GetZ(); }) {}
+
+AccelerometerSim& ADXLThreeAxisAccelerometerSim::GetXWrapper() {
+  return m_xWrapper;
+}
+
+AccelerometerSim& ADXLThreeAxisAccelerometerSim::GetYWrapper() {
+  return m_yWrapper;
+}
+
+AccelerometerSim& ADXLThreeAxisAccelerometerSim::GetZWrapper() {
+  return m_zWrapper;
+}
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/ADXRS450_SpiGyroSim.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/ADXRS450_SpiGyroSim.cpp
new file mode 100644
index 0000000..b1daf17
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/ADXRS450_SpiGyroSim.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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 "lowfisim/wpisimulators/ADXRS450_SpiGyroSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+ADXRS450_SpiGyroSim::ADXRS450_SpiGyroSim(int spiPort)
+    : m_gyroWrapper(spiPort) {}
+
+bool ADXRS450_SpiGyroSim::IsWrapperInitialized() const {
+  return m_gyroWrapper.GetInitialized();
+}
+
+void ADXRS450_SpiGyroSim::SetAngle(double angle) {
+  m_gyroWrapper.SetAngle(angle);
+}
+
+double ADXRS450_SpiGyroSim::GetAngle() { return m_gyroWrapper.GetAngle(); }
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiAnalogGyroSim.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiAnalogGyroSim.cpp
new file mode 100644
index 0000000..63619cc
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiAnalogGyroSim.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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 "lowfisim/wpisimulators/WpiAnalogGyroSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+WpiAnalogGyroSim::WpiAnalogGyroSim(int index) : m_gyroSimulator(index) {}
+
+bool WpiAnalogGyroSim::IsWrapperInitialized() const {
+  return m_gyroSimulator.GetInitialized();
+}
+
+void WpiAnalogGyroSim::SetAngle(double angle) {
+  m_gyroSimulator.SetAngle(angle);
+}
+
+double WpiAnalogGyroSim::GetAngle() { return m_gyroSimulator.GetAngle(); }
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiEncoderSim.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiEncoderSim.cpp
new file mode 100644
index 0000000..7425efe
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiEncoderSim.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "lowfisim/wpisimulators/WpiEncoderSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+WpiEncoderSim::WpiEncoderSim(int index) : m_encoderSimulator(index) {}
+
+bool WpiEncoderSim::IsWrapperInitialized() const {
+  return m_encoderSimulator.GetInitialized();
+}
+
+void WpiEncoderSim::SetPosition(double position) {
+  m_encoderSimulator.SetCount(
+      static_cast<int>(position / m_encoderSimulator.GetDistancePerPulse()));
+}
+
+void WpiEncoderSim::SetVelocity(double velocity) {
+  m_encoderSimulator.SetPeriod(1.0 / velocity);
+}
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiMotorSim.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiMotorSim.cpp
new file mode 100644
index 0000000..0b08cf2
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/cpp/lowfisim/wpisimulators/WpiMotorSim.cpp
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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 "lowfisim/wpisimulators/WpiMotorSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+WpiMotorSim::WpiMotorSim(int index, MotorModel& motorModelSimulator)
+    : m_motorModelSimulation(motorModelSimulator), m_pwmSimulator(index) {}
+
+void WpiMotorSim::Update(double elapsedTime) {
+  m_motorModelSimulation.SetVoltage(m_pwmSimulator.GetSpeed() *
+                                    kDefaultVoltage);
+  m_motorModelSimulation.Update(elapsedTime);
+}
+
+bool WpiMotorSim::IsWrapperInitialized() const {
+  return m_pwmSimulator.GetInitialized();
+}
+
+double WpiMotorSim::GetPosition() const {
+  return m_motorModelSimulation.GetPosition();
+}
+
+double WpiMotorSim::GetVelocity() const {
+  return m_motorModelSimulation.GetVelocity();
+}
+
+double WpiMotorSim::GetAcceleration() const {
+  return m_motorModelSimulation.GetAcceleration();
+}
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/AccelerometerSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/AccelerometerSim.h
new file mode 100644
index 0000000..fc9a456
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/AccelerometerSim.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "lowfisim/SimulatorComponent.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class AccelerometerSim : public virtual SimulatorComponent {
+ public:
+  virtual double GetAcceleration() = 0;
+  virtual void SetAcceleration(double acceleration) = 0;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/EncoderSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/EncoderSim.h
new file mode 100644
index 0000000..a16f94c
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/EncoderSim.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "lowfisim/SimulatorComponent.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class EncoderSim : public virtual SimulatorComponent {
+ public:
+  virtual void SetPosition(double position) = 0;
+  virtual void SetVelocity(double velocity) = 0;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/GyroSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/GyroSim.h
new file mode 100644
index 0000000..dcaa28f
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/GyroSim.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "lowfisim/SimulatorComponent.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class GyroSim : public virtual SimulatorComponent {
+ public:
+  virtual void SetAngle(double angle) = 0;
+  virtual double GetAngle() = 0;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/MotorEncoderConnector.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/MotorEncoderConnector.h
new file mode 100644
index 0000000..0cf4873
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/MotorEncoderConnector.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "EncoderSim.h"
+#include "MotorSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class MotorEncoderConnector {
+ public:
+  MotorEncoderConnector(MotorSim& motorController, EncoderSim& encoder);
+
+  void Update();
+
+ private:
+  MotorSim& motorSimulator;
+  EncoderSim& encoderSimulator;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/MotorSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/MotorSim.h
new file mode 100644
index 0000000..e880048
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/MotorSim.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "lowfisim/SimulatorComponent.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class MotorSim : public virtual SimulatorComponent {
+ public:
+  virtual double GetPosition() const = 0;
+  virtual double GetVelocity() const = 0;
+  virtual double GetAcceleration() const = 0;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimpleAccelerometerSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimpleAccelerometerSim.h
new file mode 100644
index 0000000..4c10cfe
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimpleAccelerometerSim.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+
+#include "lowfisim/AccelerometerSim.h"
+#include "lowfisim/SimulatorComponentBase.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class SimpleAccelerometerSim : public SimulatorComponentBase,
+                               public AccelerometerSim {
+ public:
+  using SimulatorComponentBase::GetDisplayName;
+
+  SimpleAccelerometerSim(const std::function<bool(void)>& initializedFunction,
+                         const std::function<void(double)>& setterFunction,
+                         const std::function<double(void)>& getterFunction)
+      : m_isInitializedFunction(initializedFunction),
+        m_setAccelerationFunction(setterFunction),
+        m_getAccelerationFunction(getterFunction) {}
+  double GetAcceleration() override { return m_getAccelerationFunction(); }
+
+  void SetAcceleration(double acceleration) override {
+    m_setAccelerationFunction(acceleration);
+  }
+
+  bool IsWrapperInitialized() const override {
+    return m_isInitializedFunction();
+  }
+
+ private:
+  std::function<bool(void)> m_isInitializedFunction;
+  std::function<void(double)> m_setAccelerationFunction;
+  std::function<double(void)> m_getAccelerationFunction;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimpleGyroSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimpleGyroSim.h
new file mode 100644
index 0000000..ea69247
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimpleGyroSim.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+
+#include "lowfisim/GyroSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class SimpleGyroSim : public GyroSim {
+ public:
+  SimpleGyroSim(std::function<void(double)>& setterFunction,
+                std::function<double(void)>& getterFunction)
+      : m_setAngleFunction(setterFunction),
+        m_getAngleFunction(getterFunction) {}
+  double GetAngle() override { return m_getAngleFunction(); }
+
+  void SetAngle(double angle) override { m_setAngleFunction(angle); }
+
+ private:
+  std::function<void(double)> m_setAngleFunction;
+  std::function<double(void)> m_getAngleFunction;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimulatorComponent.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimulatorComponent.h
new file mode 100644
index 0000000..4eb5e99
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimulatorComponent.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class SimulatorComponent {
+ public:
+  virtual ~SimulatorComponent() = default;
+
+  virtual bool IsWrapperInitialized() const = 0;
+
+  virtual const std::string& GetDisplayName() const = 0;
+
+  virtual void SetDisplayName(const std::string& displayName) = 0;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimulatorComponentBase.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimulatorComponentBase.h
new file mode 100644
index 0000000..c29e68c
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/SimulatorComponentBase.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include "lowfisim/SimulatorComponent.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class SimulatorComponentBase : public virtual SimulatorComponent {
+ public:
+  SimulatorComponentBase() = default;
+  virtual ~SimulatorComponentBase() = default;
+
+  const std::string& GetDisplayName() const override;
+
+  void SetDisplayName(const std::string& displayName) override;
+
+ private:
+  std::string m_name;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/motormodel/MotorModel.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/motormodel/MotorModel.h
new file mode 100644
index 0000000..aeffcb7
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/motormodel/MotorModel.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class MotorModel {
+ public:
+  virtual void Reset() = 0;
+  virtual void SetVoltage(double voltage) = 0;
+  virtual void Update(double elapsedTime) = 0;
+
+  virtual double GetPosition() const = 0;
+  virtual double GetVelocity() const = 0;
+  virtual double GetAcceleration() const = 0;
+  virtual double GetCurrent() const = 0;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/motormodel/SimpleMotorModel.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/motormodel/SimpleMotorModel.h
new file mode 100644
index 0000000..ccfc3b9
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/motormodel/SimpleMotorModel.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "lowfisim/motormodel/MotorModel.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class SimpleMotorModel : public MotorModel {
+ public:
+  explicit SimpleMotorModel(double maxSpeed);
+
+  void Reset() override;
+  void SetVoltage(double voltage) override;
+  void Update(double elapsedTime) override;
+
+  double GetPosition() const override;
+  double GetVelocity() const override;
+  double GetAcceleration() const override;
+  double GetCurrent() const override;
+
+ protected:
+  double m_maxSpeed;
+  double m_voltagePercentage{0};
+  double m_position{0};
+  double m_velocity{0};
+
+  static constexpr double kMaxExpectedVoltage = 12;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/ADXLThreeAxisAccelerometerSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/ADXLThreeAxisAccelerometerSim.h
new file mode 100644
index 0000000..0b63f2e
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/ADXLThreeAxisAccelerometerSim.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ThreeAxisAccelerometerData.h"
+#include "lowfisim/SimpleAccelerometerSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class ADXLThreeAxisAccelerometerSim {
+ public:
+  ADXLThreeAxisAccelerometerSim(
+      hal::ThreeAxisAccelerometerData& accelerometerWrapper);
+
+  AccelerometerSim& GetXWrapper();
+  AccelerometerSim& GetYWrapper();
+  AccelerometerSim& GetZWrapper();
+
+ protected:
+  hal::ThreeAxisAccelerometerData& m_accelerometerWrapper;
+  SimpleAccelerometerSim m_xWrapper;
+  SimpleAccelerometerSim m_yWrapper;
+  SimpleAccelerometerSim m_zWrapper;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/ADXRS450_SpiGyroSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/ADXRS450_SpiGyroSim.h
new file mode 100644
index 0000000..9b23320
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/ADXRS450_SpiGyroSim.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "ADXRS450_SpiGyroWrapperData.h"
+#include "lowfisim/GyroSim.h"
+#include "lowfisim/SimulatorComponentBase.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class ADXRS450_SpiGyroSim : public SimulatorComponentBase, public GyroSim {
+ public:
+  explicit ADXRS450_SpiGyroSim(int spiPort);
+
+  bool IsWrapperInitialized() const override;
+
+  void SetAngle(double angle) override;
+  double GetAngle() override;
+
+ protected:
+  hal::ADXRS450_SpiGyroWrapper m_gyroWrapper;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiAnalogGyroSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiAnalogGyroSim.h
new file mode 100644
index 0000000..8741cb2
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiAnalogGyroSim.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "lowfisim/GyroSim.h"
+#include "lowfisim/SimulatorComponentBase.h"
+#include "simulation/AnalogGyroSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class WpiAnalogGyroSim : public SimulatorComponentBase, public GyroSim {
+ public:
+  explicit WpiAnalogGyroSim(int index);
+
+  bool IsWrapperInitialized() const override;
+
+  void SetAngle(double angle) override;
+  double GetAngle() override;
+
+ protected:
+  frc::sim::AnalogGyroSim m_gyroSimulator;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiEncoderSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiEncoderSim.h
new file mode 100644
index 0000000..6460d8b
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiEncoderSim.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "lowfisim/EncoderSim.h"
+#include "lowfisim/SimulatorComponentBase.h"
+#include "simulation/EncoderSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class WpiEncoderSim : public SimulatorComponentBase, public EncoderSim {
+ public:
+  explicit WpiEncoderSim(int index);
+  bool IsWrapperInitialized() const override;
+
+  void SetPosition(double position) override;
+  void SetVelocity(double velocity) override;
+
+ protected:
+  frc::sim::EncoderSim m_encoderSimulator;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiMotorSim.h b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiMotorSim.h
new file mode 100644
index 0000000..d24e831
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/main/native/include/lowfisim/wpisimulators/WpiMotorSim.h
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "lowfisim/MotorSim.h"
+#include "lowfisim/SimulatorComponentBase.h"
+#include "lowfisim/motormodel/MotorModel.h"
+#include "simulation/PWMSim.h"
+
+namespace frc {
+namespace sim {
+namespace lowfi {
+
+class WpiMotorSim : public SimulatorComponentBase, public MotorSim {
+ public:
+  explicit WpiMotorSim(int index, MotorModel& motorModelSimulator);
+  bool IsWrapperInitialized() const override;
+
+  void Update(double elapsedTime);
+  double GetPosition() const override;
+  double GetVelocity() const override;
+  double GetAcceleration() const override;
+
+ private:
+  MotorModel& m_motorModelSimulation;
+  frc::sim::PWMSim m_pwmSimulator;
+
+  static constexpr double kDefaultVoltage = 12.0;
+};
+
+}  // namespace lowfi
+}  // namespace sim
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/AccelerometerSimulatorTest.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/AccelerometerSimulatorTest.cpp
new file mode 100644
index 0000000..b51a63a
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/AccelerometerSimulatorTest.cpp
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXL345_I2CAccelerometerData.h"
+#include "frc/ADXL345_I2C.h"
+#include "gtest/gtest.h"
+#include "lowfisim/wpisimulators/ADXLThreeAxisAccelerometerSim.h"
+
+TEST(AccelerometerTests, TestADXL345_I2CAccelerometerWrapper) {
+  const double EPSILON = 1 / 256.0;
+
+  frc::I2C::Port port = frc::I2C::kOnboard;
+
+  hal::ADXL345_I2CData rawAdxSim(port);
+  frc::sim::lowfi::ADXLThreeAxisAccelerometerSim accelerometerSim(rawAdxSim);
+  frc::sim::lowfi::AccelerometerSim& xWrapper = accelerometerSim.GetXWrapper();
+  frc::sim::lowfi::AccelerometerSim& yWrapper = accelerometerSim.GetYWrapper();
+  frc::sim::lowfi::AccelerometerSim& zWrapper = accelerometerSim.GetZWrapper();
+  EXPECT_FALSE(xWrapper.IsWrapperInitialized());
+  EXPECT_FALSE(yWrapper.IsWrapperInitialized());
+  EXPECT_FALSE(zWrapper.IsWrapperInitialized());
+
+  frc::ADXL345_I2C accel{port};
+  EXPECT_NEAR(0, accel.GetX(), EPSILON);
+  EXPECT_NEAR(0, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0, accel.GetZ(), EPSILON);
+  EXPECT_TRUE(xWrapper.IsWrapperInitialized());
+  EXPECT_TRUE(yWrapper.IsWrapperInitialized());
+  EXPECT_TRUE(zWrapper.IsWrapperInitialized());
+
+  xWrapper.SetAcceleration(1.45);
+  EXPECT_NEAR(1.45, accel.GetX(), EPSILON);
+  EXPECT_NEAR(0, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0, accel.GetZ(), EPSILON);
+  EXPECT_NEAR(1.45, xWrapper.GetAcceleration(), EPSILON);
+  EXPECT_NEAR(0, yWrapper.GetAcceleration(), EPSILON);
+  EXPECT_NEAR(0, zWrapper.GetAcceleration(), EPSILON);
+
+  yWrapper.SetAcceleration(-.67);
+  EXPECT_NEAR(1.45, accel.GetX(), EPSILON);
+  EXPECT_NEAR(-.67, accel.GetY(), EPSILON);
+  EXPECT_NEAR(0, accel.GetZ(), EPSILON);
+  EXPECT_NEAR(1.45, xWrapper.GetAcceleration(), EPSILON);
+  EXPECT_NEAR(-.67, yWrapper.GetAcceleration(), EPSILON);
+  EXPECT_NEAR(0, zWrapper.GetAcceleration(), EPSILON);
+
+  zWrapper.SetAcceleration(2.42);
+  EXPECT_NEAR(1.45, accel.GetX(), EPSILON);
+  EXPECT_NEAR(-.67, accel.GetY(), EPSILON);
+  EXPECT_NEAR(2.42, accel.GetZ(), EPSILON);
+  EXPECT_NEAR(1.45, xWrapper.GetAcceleration(), EPSILON);
+  EXPECT_NEAR(-.67, yWrapper.GetAcceleration(), EPSILON);
+  EXPECT_NEAR(2.42, zWrapper.GetAcceleration(), EPSILON);
+}
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/GyroSimulatorTest.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/GyroSimulatorTest.cpp
new file mode 100644
index 0000000..6cd0b2b
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/GyroSimulatorTest.cpp
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ADXRS450_SpiGyroWrapperData.h"
+#include "frc/ADXRS450_Gyro.h"
+#include "frc/AnalogGyro.h"
+#include "gtest/gtest.h"
+#include "lowfisim/wpisimulators/ADXRS450_SpiGyroSim.h"
+#include "lowfisim/wpisimulators/WpiAnalogGyroSim.h"
+
+void TestGyro(frc::sim::lowfi::GyroSim& sim, frc::Gyro& gyro) {
+  const double EPSILON = .00001;
+
+  EXPECT_NEAR(0, gyro.GetAngle(), EPSILON);
+  EXPECT_NEAR(0, sim.GetAngle(), EPSILON);
+
+  sim.SetAngle(45.13);
+  EXPECT_NEAR(45.13, gyro.GetAngle(), EPSILON);
+  EXPECT_NEAR(45.13, sim.GetAngle(), EPSILON);
+}
+
+TEST(GyroSimulatorTests, TestAnalogGyro) {
+  int port = 1;
+  frc::sim::lowfi::WpiAnalogGyroSim sim{port};
+  EXPECT_FALSE(sim.IsWrapperInitialized());
+
+  frc::AnalogGyro gyro{port};
+  EXPECT_TRUE(sim.IsWrapperInitialized());
+
+  TestGyro(sim, gyro);
+}
+
+TEST(GyroSimulatorTests, TestSpiGyro) {
+  frc::SPI::Port port = frc::SPI::kOnboardCS0;
+
+  frc::sim::lowfi::ADXRS450_SpiGyroSim sim{port};
+  EXPECT_FALSE(sim.IsWrapperInitialized());
+
+  frc::ADXRS450_Gyro gyro{port};
+  EXPECT_TRUE(sim.IsWrapperInitialized());
+
+  TestGyro(sim, gyro);
+}
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/MotorEncoderSimulatorTest.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/MotorEncoderSimulatorTest.cpp
new file mode 100644
index 0000000..83e9ddc
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/MotorEncoderSimulatorTest.cpp
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Encoder.h"
+#include "frc/Talon.h"
+#include "gtest/gtest.h"
+#include "lowfisim/MotorEncoderConnector.h"
+#include "lowfisim/motormodel/SimpleMotorModel.h"
+#include "lowfisim/wpisimulators/WpiEncoderSim.h"
+#include "lowfisim/wpisimulators/WpiMotorSim.h"
+
+TEST(MotorEncoderConnectorTest, TestWithoutDistancePerPulseFullSpeed) {
+  frc::sim::lowfi::SimpleMotorModel motorModelSim(6000);
+  frc::sim::lowfi::WpiMotorSim motorSim(3, motorModelSim);
+  frc::sim::lowfi::WpiEncoderSim encoderSim(0);
+  frc::sim::lowfi::MotorEncoderConnector connector(motorSim, encoderSim);
+
+  EXPECT_FALSE(motorSim.IsWrapperInitialized());
+  EXPECT_FALSE(encoderSim.IsWrapperInitialized());
+  frc::Talon talon{3};
+  frc::Encoder encoder{3, 1};
+  EXPECT_TRUE(motorSim.IsWrapperInitialized());
+  EXPECT_TRUE(encoderSim.IsWrapperInitialized());
+
+  talon.Set(-1);
+  motorSim.Update(1);
+  connector.Update();
+
+  // Position
+  EXPECT_EQ(-6000, encoder.Get());
+  EXPECT_DOUBLE_EQ(-6000, encoder.GetDistance());
+
+  // Velocity
+  EXPECT_DOUBLE_EQ(-1.0 / 6000, encoder.GetPeriod());
+  EXPECT_DOUBLE_EQ(-6000, encoder.GetRate());
+}
+
+TEST(MotorEncoderConnectorTest, TestWithoutDistancePerPulseRealisitcUpdate) {
+  frc::Talon talon{3};
+  frc::Encoder encoder{3, 1};
+
+  frc::sim::lowfi::SimpleMotorModel motorModelSim(6000);
+  frc::sim::lowfi::WpiMotorSim motorSim(3, motorModelSim);
+  frc::sim::lowfi::WpiEncoderSim encoderSim(0);
+  frc::sim::lowfi::MotorEncoderConnector connector(motorSim, encoderSim);
+
+  talon.Set(0.5);
+  motorSim.Update(.02);
+  connector.Update();
+
+  // Position
+  EXPECT_EQ(60, encoder.Get());
+  EXPECT_DOUBLE_EQ(60, encoder.GetDistance());
+
+  // Velocity
+  EXPECT_DOUBLE_EQ(1.0 / 3000, encoder.GetPeriod());
+  EXPECT_DOUBLE_EQ(3000, encoder.GetRate());
+}
+
+TEST(MotorEncoderConnectorTest, TestWithDistancePerPulseFullSpeed) {
+  frc::Talon talon{3};
+  frc::Encoder encoder{3, 1};
+  encoder.SetDistancePerPulse(.001);
+
+  frc::sim::lowfi::SimpleMotorModel motorModelSim(6000);
+  frc::sim::lowfi::WpiMotorSim motorSim(3, motorModelSim);
+  frc::sim::lowfi::WpiEncoderSim encoderSim(0);
+  frc::sim::lowfi::MotorEncoderConnector connector(motorSim, encoderSim);
+
+  talon.Set(-1);
+
+  motorSim.Update(1);
+  connector.Update();
+
+  // Position
+  EXPECT_EQ(-6000000, encoder.Get());
+  EXPECT_DOUBLE_EQ(-6000, encoder.GetDistance());
+
+  // Velocity
+  EXPECT_EQ(-1.0 / 6000, encoder.GetPeriod());
+  EXPECT_DOUBLE_EQ(-6, encoder.GetRate());
+}
+
+TEST(MotorEncoderConnectorTest, TestWithDistancePerPulseRealistic) {
+  frc::Talon talon{3};
+  frc::Encoder encoder{3, 1};
+  encoder.SetDistancePerPulse(.001);
+
+  frc::sim::lowfi::SimpleMotorModel motorModelSim(6000);
+  frc::sim::lowfi::WpiMotorSim motorSim(3, motorModelSim);
+  frc::sim::lowfi::WpiEncoderSim encoderSim(0);
+  frc::sim::lowfi::MotorEncoderConnector connector(motorSim, encoderSim);
+
+  talon.Set(0.5);
+
+  motorSim.Update(.02);
+  connector.Update();
+
+  // Position
+  EXPECT_EQ(60000, encoder.Get());
+  EXPECT_DOUBLE_EQ(60, encoder.GetDistance());
+
+  // Velocity
+  EXPECT_EQ(1.0 / 3000, encoder.GetPeriod());
+  EXPECT_DOUBLE_EQ(3, encoder.GetRate());
+}
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/motormodel/SimpleMotorModelSimulationTest.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/motormodel/SimpleMotorModelSimulationTest.cpp
new file mode 100644
index 0000000..e60cf1e
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/lowfisim/motormodel/SimpleMotorModelSimulationTest.cpp
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "gtest/gtest.h"
+#include "lowfisim/motormodel/SimpleMotorModel.h"
+
+TEST(SimpleMotorModelSimulationTest, TestSimpleModel) {
+  frc::sim::lowfi::SimpleMotorModel motorModelSim(200);
+
+  // Test forward voltage
+  motorModelSim.SetVoltage(6);
+  motorModelSim.Update(.5);
+
+  EXPECT_DOUBLE_EQ(50, motorModelSim.GetPosition());
+  EXPECT_DOUBLE_EQ(100, motorModelSim.GetVelocity());
+
+  // Test Reset
+  motorModelSim.Reset();
+  EXPECT_DOUBLE_EQ(0, motorModelSim.GetPosition());
+  EXPECT_DOUBLE_EQ(0, motorModelSim.GetVelocity());
+
+  // Test negative voltage
+  motorModelSim.Reset();
+  motorModelSim.SetVoltage(-3);
+  motorModelSim.Update(.06);
+
+  EXPECT_DOUBLE_EQ(-3, motorModelSim.GetPosition());
+  EXPECT_DOUBLE_EQ(-50, motorModelSim.GetVelocity());
+}
diff --git a/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..0e00efa
--- /dev/null
+++ b/third_party/allwpilib_2019/simulation/lowfi_simulation/src/test/native/cpp/main.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <hal/HAL.h>
+
+#include "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  HAL_Initialize(500, 0);
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/styleguide/checkstyle.xml b/third_party/allwpilib_2019/styleguide/checkstyle.xml
new file mode 100644
index 0000000..0a690b6
--- /dev/null
+++ b/third_party/allwpilib_2019/styleguide/checkstyle.xml
@@ -0,0 +1,293 @@
+<?xml version="1.0"?>
+<!DOCTYPE
+module PUBLIC "-//Puppy Crawl//DTD Check Configuration 1.3//EN"
+"http://www.puppycrawl.com/dtds/configuration_1_3.dtd">
+<!--
+    Checkstyle configuration that checks the Google coding conventions from Google Java Style
+    that can be found at https://google.github.io/styleguide/javaguide.html.
+
+    Checkstyle is very configurable. Be sure to read the documentation at
+    http://checkstyle.sf.net (or in your downloaded distribution).
+
+    To completely disable a check, just comment it out or delete it from the file.
+
+    Authors: Max Vetrenko, Ruslan Diachenko, Roman Ivanov.
+ -->
+<module name="Checker">
+  <property name="charset"
+            value="UTF-8" />
+  <property name="severity"
+            value="error" />
+  <module name="SuppressionFilter">
+    <property name="file"
+              value="${config_loc}/suppressions.xml" />
+  </module>
+  <property name="fileExtensions"
+            value="java, properties, xml" />
+  <!-- Checks for whitespace                               -->
+  <!-- See http://checkstyle.sf.net/config_whitespace.html -->
+  <module name="FileTabCharacter">
+    <property name="eachLine"
+              value="true" />
+  </module>
+  <module name="NewlineAtEndOfFile">
+    <property name="lineSeparator"
+              value="lf" />
+  </module>
+  <module name="SuppressWarningsFilter" />
+  <module name="TreeWalker">
+    <module name="SuppressWarningsHolder" />
+    <module name="OuterTypeFilename" />
+    <module name="IllegalTokenText">
+      <property name="tokens"
+                value="STRING_LITERAL, CHAR_LITERAL" />
+      <property name="format"
+                value="\\u00(08|09|0(a|A)|0(c|C)|0(d|D)|22|27|5(C|c))|\\(0(10|11|12|14|15|42|47)|134)" />
+      <property name="message"
+                value="Avoid using corresponding octal or Unicode escape." />
+    </module>
+    <module name="AvoidEscapedUnicodeCharacters">
+      <property name="allowEscapesForControlCharacters"
+                value="true" />
+      <property name="allowByTailComment"
+                value="true" />
+      <property name="allowNonPrintableEscapes"
+                value="true" />
+    </module>
+    <module name="LineLength">
+      <property name="max"
+                value="100" />
+      <property name="ignorePattern"
+                value="^package.*|^import.*|a href|href|http://|https://|ftp://" />
+    </module>
+    <module name="ImportOrder">
+      <property name="option"
+                value="bottom"/>
+      <property name="groups"
+                value="/^java\./,javax,com,org,/^edu\./,*,/^edu\.wpi\./,/^edu\.wpi\.first\.wpilibj\.examples\./"/>
+      <property name="separated"
+                value="true"/>
+      <property name="sortStaticImportsAlphabetically"
+                value="true"/>
+    </module>
+    <module name="AvoidStarImport" />
+    <module name="RedundantImport" />
+    <module name="UnusedImports" />
+    <module name="OneTopLevelClass" />
+    <module name="NoLineWrap" />
+    <module name="EmptyBlock">
+      <property name="option"
+                value="TEXT" />
+      <property name="tokens"
+                value="LITERAL_TRY, LITERAL_FINALLY, LITERAL_IF, LITERAL_ELSE, LITERAL_SWITCH" />
+    </module>
+    <module name="NeedBraces" />
+    <module name="LeftCurly" />
+    <module name="RightCurly" />
+    <module name="RightCurly">
+      <property name="option"
+                value="alone" />
+      <property name="tokens"
+                value="CLASS_DEF, METHOD_DEF, CTOR_DEF, LITERAL_FOR, LITERAL_WHILE, LITERAL_DO, STATIC_INIT, INSTANCE_INIT" />
+    </module>
+    <module name="WhitespaceAround">
+      <property name="allowEmptyConstructors"
+                value="true" />
+      <property name="allowEmptyMethods"
+                value="true" />
+      <property name="allowEmptyTypes"
+                value="true" />
+      <property name="allowEmptyLoops"
+                value="true" />
+      <message key="ws.notFollowed"
+               value="WhitespaceAround: ''{0}'' is not followed by whitespace. Empty blocks may only be represented as '{}' when not part of a multi-block statement (4.1.3)" />
+      <message key="ws.notPreceded"
+               value="WhitespaceAround: ''{0}'' is not preceded with whitespace." />
+    </module>
+    <module name="WhitespaceAfter" />
+    <module name="OneStatementPerLine" />
+    <module name="MultipleVariableDeclarations" />
+    <module name="ArrayTypeStyle" />
+    <module name="MissingSwitchDefault" />
+    <module name="FallThrough" />
+    <module name="SimplifyBooleanExpression" />
+    <module name="SimplifyBooleanReturn" />
+    <module name="StringLiteralEquality" />
+    <module name="UnnecessaryParentheses" />
+    <module name="UpperEll" />
+    <module name="ModifierOrder" />
+    <module name="RedundantModifier" />
+    <module name="EmptyLineSeparator">
+      <property name="allowNoEmptyLineBetweenFields"
+                value="true" />
+    </module>
+    <module name="SeparatorWrap">
+      <property name="tokens"
+                value="DOT" />
+      <property name="option"
+                value="nl" />
+    </module>
+    <module name="SeparatorWrap">
+      <property name="tokens"
+                value="COMMA" />
+      <property name="option"
+                value="EOL" />
+    </module>
+    <module name="PackageName">
+      <property name="format"
+                value="^[a-z]+(\.[a-z][a-z0-9]*)*$" />
+      <message key="name.invalidPattern"
+               value="Package name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="TypeName">
+      <message key="name.invalidPattern"
+               value="Type name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="MemberName">
+      <property name="format"
+                value="^m_[a-z][a-z0-9][a-zA-Z0-9]*$" />
+      <message key="name.invalidPattern"
+               value="Member name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="ParameterName">
+      <property name="format"
+                value="^[a-z][a-z0-9][a-zA-Z0-9]*$" />
+      <message key="name.invalidPattern"
+               value="Parameter name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="CatchParameterName">
+      <property name="format"
+                value="^[a-z][a-z0-9][a-zA-Z0-9]*$" />
+      <message key="name.invalidPattern"
+               value="Catch parameter name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="LocalVariableName">
+      <property name="tokens"
+                value="VARIABLE_DEF" />
+      <property name="format"
+                value="^[a-z][a-z0-9][a-zA-Z0-9]*$" />
+      <property name="allowOneCharVarInForLoop"
+                value="true" />
+      <message key="name.invalidPattern"
+               value="Local variable name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="ClassTypeParameterName">
+      <property name="format"
+                value="(^[A-Z][0-9]?)$|([A-Z][a-zA-Z0-9]*[T]$)" />
+      <message key="name.invalidPattern"
+               value="Class type name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="MethodTypeParameterName">
+      <property name="format"
+                value="(^[A-Z][0-9]?)$|([A-Z][a-zA-Z0-9]*[T]$)" />
+      <message key="name.invalidPattern"
+               value="Method type name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="InterfaceTypeParameterName">
+      <property name="format"
+                value="(^[A-Z][0-9]?)$|([A-Z][a-zA-Z0-9]*[T]$)" />
+      <message key="name.invalidPattern"
+               value="Interface type name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="NoFinalizer" />
+    <module name="GenericWhitespace">
+      <message key="ws.followed"
+               value="GenericWhitespace ''{0}'' is followed by whitespace." />
+      <message key="ws.preceded"
+               value="GenericWhitespace ''{0}'' is preceded with whitespace." />
+      <message key="ws.illegalFollow"
+               value="GenericWhitespace ''{0}'' should followed by whitespace." />
+      <message key="ws.notPreceded"
+               value="GenericWhitespace ''{0}'' is not preceded with whitespace." />
+    </module>
+    <module name="Indentation">
+      <property name="basicOffset"
+                value="2" />
+      <property name="braceAdjustment"
+                value="0" />
+      <property name="caseIndent"
+                value="2" />
+      <property name="throwsIndent"
+                value="4" />
+      <property name="lineWrappingIndentation"
+                value="4" />
+      <property name="arrayInitIndent"
+                value="2" />
+    </module>
+    <module name="AbbreviationAsWordInName">
+      <property name="ignoreFinal"
+                value="false" />
+      <property name="allowedAbbreviationLength"
+                value="3" />
+    </module>
+    <module name="OverloadMethodsDeclarationOrder" />
+    <module name="VariableDeclarationUsageDistance" />
+    <module name="MethodParamPad" />
+    <module name="TypecastParenPad" />
+    <module name="OperatorWrap">
+      <property name="option"
+                value="NL" />
+      <property name="tokens"
+                value="BAND, BOR, BSR, BXOR, DIV, EQUAL, GE, GT, LAND, LE, LITERAL_INSTANCEOF, LOR, LT, MINUS, MOD, NOT_EQUAL, PLUS, QUESTION, SL, SR, STAR " />
+    </module>
+    <module name="AnnotationLocation">
+      <property name="tokens"
+                value="CLASS_DEF, INTERFACE_DEF, ENUM_DEF, METHOD_DEF, CTOR_DEF" />
+    </module>
+    <module name="AnnotationLocation">
+      <property name="tokens"
+                value="VARIABLE_DEF" />
+      <property name="allowSamelineMultipleAnnotations"
+                value="true" />
+    </module>
+    <module name="MissingOverride" />
+    <module name="NonEmptyAtclauseDescription" />
+    <module name="JavadocTagContinuationIndentation" />
+    <module name="SummaryJavadoc">
+      <property name="forbiddenSummaryFragments"
+                value="^@return the *|^This method returns |^A [{]@code [a-zA-Z0-9]+[}]( is a )" />
+    </module>
+    <module name="JavadocParagraph" />
+    <module name="AtclauseOrder">
+      <property name="tagOrder"
+                value="@param, @return, @throws, @deprecated" />
+      <property name="target"
+                value="CLASS_DEF, INTERFACE_DEF, ENUM_DEF, METHOD_DEF, CTOR_DEF, VARIABLE_DEF" />
+    </module>
+    <module name="JavadocMethod">
+      <property name="scope"
+                value="public" />
+      <property name="allowMissingParamTags"
+                value="true" />
+      <property name="allowMissingThrowsTags"
+                value="true" />
+      <property name="allowMissingReturnTag"
+                value="true" />
+      <property name="minLineCount"
+                value="2" />
+      <property name="allowedAnnotations"
+                value="Override, Test, Before, After, BeforeClass, AfterClass, Parameters" />
+      <property name="allowUndeclaredRTE"
+                value="true" />
+      <property name="allowThrowsTagsForSubclasses"
+                value="true" />
+      <property name="suppressLoadErrors"
+                value="true" />
+    </module>
+    <module name="MethodName">
+      <property name="format"
+                value="^[a-z][a-z0-9][a-zA-Z0-9_]*$" />
+      <message key="name.invalidPattern"
+               value="Method name ''{0}'' must match pattern ''{1}''." />
+    </module>
+    <module name="SingleLineJavadoc">
+      <property name="ignoreInlineTags"
+                value="false" />
+    </module>
+    <module name="EmptyCatchBlock">
+      <property name="exceptionVariableName"
+                value="expected" />
+    </module>
+    <module name="CommentsIndentation" />
+  </module>
+</module>
diff --git a/third_party/allwpilib_2019/styleguide/pmd-ruleset.xml b/third_party/allwpilib_2019/styleguide/pmd-ruleset.xml
new file mode 100644
index 0000000..50f7cc7
--- /dev/null
+++ b/third_party/allwpilib_2019/styleguide/pmd-ruleset.xml
@@ -0,0 +1,104 @@
+<?xml version="1.0"?>
+<ruleset name="WPILibRuleset"
+         xmlns="http://pmd.sourceforge.net/ruleset/2.0.0"
+         xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance"
+         xsi:schemaLocation="http://pmd.sourceforge.net/ruleset/2.0.0 http://pmd.sourceforge.net/ruleset_2_0_0.xsd">
+
+  <description>PMD Ruleset for WPILib</description>
+
+  <exclude-pattern>.*/*JNI.*</exclude-pattern>
+  <exclude-pattern>.*/*IntegrationTests.*</exclude-pattern>
+
+  <rule ref="category/java/bestpractices.xml">
+    <exclude name="AccessorClassGeneration" />
+    <exclude name="AccessorMethodGeneration" />
+    <exclude name="AvoidPrintStackTrace" />
+    <exclude name="AvoidReassigningParameters" />
+    <exclude name="JUnitAssertionsShouldIncludeMessage" />
+    <exclude name="JUnitTestContainsTooManyAsserts" />
+    <exclude name="JUnit4TestShouldUseAfterAnnotation" />
+    <exclude name="JUnit4TestShouldUseBeforeAnnotation" />
+    <exclude name="JUnit4TestShouldUseTestAnnotation" />
+    <exclude name="ReplaceHashtableWithMap" />
+    <exclude name="ReplaceVectorWithList" />
+    <exclude name="SwitchStmtsShouldHaveDefault" />
+    <exclude name="SystemPrintln" />
+    <exclude name="UseVarargs" />
+  </rule>
+  <rule ref="category/java/bestpractices.xml/UnusedPrivateMethod">
+    <properties>
+      <property name="violationSuppressRegex"
+                value=".*'.*Arguments\(\)'.*" />
+    </properties>
+  </rule>
+
+  <rule ref="category/java/design.xml">
+    <exclude name="DataClass" />
+    <exclude name="LawOfDemeter" />
+    <exclude name="LoosePackageCoupling" />
+    <exclude name="NcssConstructorCount" />
+    <exclude name="NcssCount" />
+    <exclude name="NcssMethodCount" />
+  </rule>
+
+  <rule ref="category/java/errorprone.xml">
+    <exclude name="AssignmentToNonFinalStatic" />
+    <exclude name="AvoidDuplicateLiterals" />
+    <exclude name="AvoidLiteralsInIfCondition" />
+    <exclude name="BeanMembersShouldSerialize" />
+    <exclude name="ConstructorCallsOverridableMethod" />
+    <exclude name="DataflowAnomalyAnalysis" />
+    <exclude name="DoNotCallSystemExit" />
+    <exclude name="FinalizeDoesNotCallSuperFinalize" />
+    <exclude name="JUnitSpelling" />
+    <exclude name="MissingSerialVersionUID" />
+    <exclude name="NullAssignment" />
+  </rule>
+
+  <rule ref="category/java/multithreading.xml">
+    <exclude name="AvoidSynchronizedAtMethodLevel" />
+    <exclude name="AvoidUsingVolatile" />
+    <exclude name="DoNotUseThreads" />
+    <exclude name="UseConcurrentHashMap" />
+  </rule>
+
+  <rule ref="category/java/performance.xml">
+    <exclude name="AvoidUsingShortType" />
+  </rule>
+
+  <rule name="UnnecessaryCastRule"
+        language="java"
+        message="Avoid unnecessary casts"
+        class="net.sourceforge.pmd.lang.java.rule.migrating.UnnecessaryCastRule"
+        externalInfoUrl="https://github.com/pmd/pmd/blob/master/pmd-java/src/main/java/net/sourceforge/pmd/lang/java/rule/migrating/UnnecessaryCastRule.java" />
+
+  <!-- Custom Rules -->
+  <rule name="UseRequireNonNull"
+        message="Use Objects.requireNonNull() instead of throwing a NullPointerException yourself."
+        language="java"
+        class="net.sourceforge.pmd.lang.rule.XPathRule">
+    <description>Use Objects.requireNonNull() instead of throwing a
+    NullPointerException yourself.</description>
+    <properties>
+      <property name="xpath">
+        <value>
+          <![CDATA[
+            //IfStatement[child::Expression//NullLiteral]/Statement//ThrowStatement/Expression/PrimaryExpression/PrimaryPrefix/AllocationExpression/ClassOrInterfaceType[@Image='NullPointerException']
+          ]]>
+        </value>
+      </property>
+    </properties>
+    <priority>3</priority>
+    <example>
+<![CDATA[
+                public class Example {
+                    public Example(Object example) {
+                        if (example == null) {
+                            throw new NullPointerException();
+                        }
+                    }
+                }
+            ]]>
+    </example>
+  </rule>
+</ruleset>
diff --git a/third_party/allwpilib_2019/styleguide/suppressions.xml b/third_party/allwpilib_2019/styleguide/suppressions.xml
new file mode 100644
index 0000000..0c1d9f0
--- /dev/null
+++ b/third_party/allwpilib_2019/styleguide/suppressions.xml
@@ -0,0 +1,12 @@
+<?xml version="1.0"?>
+<!DOCTYPE
+suppressions PUBLIC "-//Puppy Crawl//DTD Suppressions 1.1//EN"
+"http://www.puppycrawl.com/dtds/suppressions_1_1.dtd">
+<suppressions>
+  <suppress files=".*sim.*"
+            checks="(LineLength|EmptyLineSeparator|ParameterName|ImportOrder|AbbreviationAsWordInName|JavadocMethod|NoFinalizer)" />
+  <suppress files=".*test.*"
+            checks="JavadocMethod" />
+  <suppress files=".*JNI.*"
+            checks="(LineLength|EmptyLineSeparator|ParameterName)" />
+</suppressions>
diff --git a/third_party/allwpilib_2019/test-scripts/.gitattributes b/third_party/allwpilib_2019/test-scripts/.gitattributes
new file mode 100644
index 0000000..cb5c152
--- /dev/null
+++ b/third_party/allwpilib_2019/test-scripts/.gitattributes
@@ -0,0 +1,4 @@
+# Set the default behavior, in case people don't have core.autocrlf set.
+* text=auto
+
+*.sh text eol=lf
diff --git a/third_party/allwpilib_2019/test-scripts/README.md b/third_party/allwpilib_2019/test-scripts/README.md
new file mode 100644
index 0000000..a96764e
--- /dev/null
+++ b/third_party/allwpilib_2019/test-scripts/README.md
@@ -0,0 +1,17 @@
+# WPILIB TEST SCRIPTS
+## Overview
+These test scripts are designed to allow the user of the WPILib test framework to quickly and easily deploy and run their tests on the WPI roboRIO.
+
+In order for the automated test system to work there is a driverstation onboard the roboRIO that handles a queue of users waiting to use the driver station. All of the interaction with this queue is handled internally by test scripts contained within this folder.
+
+If you deploy code to the test stand using the Eclipse plugins, you _must_ remove the build artifacts in `/home/lvuser`, or you will break tests.
+
+## roboRIO Setup
+The roboRIO on the test bench must be updated everytime NI releases a new image.
+
+1. [Use the roboRIO Imaging Tool to format the roboRIO with the lastest image.](https://wpilib.screenstepslive.com/s/4485/m/13503/l/144984-imaging-your-roborio)
+2. [Install Java on the roboRIO.](https://wpilib.screenstepslive.com/s/4485/m/13503/l/599747-installing-java-8-on-the-roborio-using-the-frc-roborio-java-installer-java-only)
+3. SFTP the [teststand, netconsole, and libstdc++ ipk files](https://users.wpi.edu/~phplenefisch/ipk/) on to the roboRIO.
+4. ssh on to the roboRIO as the admin user (ex: `ssh admin@roboRIO-190-FRC.local`)
+5. Use opkg to install the ipk files (ex: `opkg install teststand_1.2-1_armv7a-vfp.ipk`)
+6. Reboot the roboRIO
diff --git a/third_party/allwpilib_2019/test-scripts/config.sh b/third_party/allwpilib_2019/test-scripts/config.sh
new file mode 100755
index 0000000..48eeda4
--- /dev/null
+++ b/third_party/allwpilib_2019/test-scripts/config.sh
@@ -0,0 +1,40 @@
+#!/usr/bin/env bash
+#*----------------------------------------------------------------------------*#
+#* Copyright (c) FIRST 2014. 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.															      *#
+#*----------------------------------------------------------------------------*#
+
+# If this is changed, update the .gitignore
+# so that test results are not commited to the repo
+DEFAULT_LOCAL_TEST_RESULTS_DIR=../test-reports
+
+ROBOT_ADDRESS=admin@roboRIO-190-FRC.local
+ADMIN_ROBOT_ADDRESS=admin@roboRIO-190-FRC.local
+DEFAULT_LOCAL_RUN_TEST_SCRIPT="run-tests-on-robot.sh"
+
+DEFAULT_DESTINATION_DIR=/home/admin
+DEFAULT_TEST_SCP_DIR=${DEFAULT_DESTINATION_DIR}/deployedTests
+DEFAULT_DESTINATION_TEST_RESULTS_DIR=${DEFAULT_DESTINATION_DIR}/testResults
+
+# C++ test variables
+DEFAULT_CPP_TEST_NAME=FRCUserProgram
+DEFAULT_CPP_TEST_ARGS="--gtest_color=yes"
+DEFAULT_LOCAL_CPP_TEST_FILE=../build/integrationTestFiles/cpp/FRCUserProgram
+
+CPP_REPORT=cppreport.xml
+DEFAULT_LOCAL_CPP_TEST_RESULT=${DEFAULT_LOCAL_TEST_RESULTS_DIR}/${CPP_REPORT}
+DEFAULT_DESTINATION_CPP_TEST_RESULTS=${DEFAULT_DESTINATION_TEST_RESULTS_DIR}/${CPP_REPORT}
+
+# Java test variables
+DEFAULT_JAVA_TEST_NAME=FRCUserProgram.jar
+DEFAULT_JAVA_TEST_ARGS=""
+
+DEFAULT_LOCAL_JAVA_TEST_FILE=../build/integrationTestFiles/java/wpilibjIntegrationTests-all.jar
+
+JAVA_REPORT=javareport.xml
+DEFAULT_LIBRARY_NATIVE_FILES=../build/integrationTestFiles/libs
+DEFAULT_LIBRARY_NATIVE_DESTINATION=/usr/local/frc/lib
+DEFAULT_LOCAL_JAVA_TEST_RESULT=${DEFAULT_LOCAL_TEST_RESULTS_DIR}/${JAVA_REPORT}
+DEFAULT_DESTINATION_JAVA_TEST_RESULTS=${DEFAULT_DESTINATION_TEST_RESULTS_DIR}/AntReports/TEST-edu.wpi.first.wpilibj.test.TestSuite.xml
diff --git a/third_party/allwpilib_2019/test-scripts/deploy-and-run-test-on-robot.sh b/third_party/allwpilib_2019/test-scripts/deploy-and-run-test-on-robot.sh
new file mode 100755
index 0000000..f023a18
--- /dev/null
+++ b/third_party/allwpilib_2019/test-scripts/deploy-and-run-test-on-robot.sh
@@ -0,0 +1,89 @@
+#!/usr/bin/env bash
+#*----------------------------------------------------------------------------*#
+#* Copyright (c) FIRST 2014. 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.															      *#
+#*----------------------------------------------------------------------------*#
+
+# Configurable variables
+source config.sh
+
+# Java variables
+DEFAULT_DESTINATION_JAVA_TEST_FILE=${DEFAULT_TEST_SCP_DIR}/${DEFAULT_JAVA_TEST_NAME}
+
+# C++ Variables
+DEFAULT_DESTINATION_CPP_TEST_FILE=${DEFAULT_TEST_SCP_DIR}/${DEFAULT_CPP_TEST_NAME}
+
+DEFAULT_DESTINATION_RUN_TEST_SCRIPT=${DEFAULT_DESTINATION_DIR}/${DEFAULT_LOCAL_RUN_TEST_SCRIPT}
+
+usage="$(basename "$0") [-h] (java|cpp) [-A] [arg] [arg]...
+A script designed to run the integration tests.
+This script should only be run on the roborio.
+Where:
+    -h    Show this help text.
+    -A    Disable language recomended arguments.
+    arg   Additional arguments to be passed to test."
+
+
+# These variables are set when the language is selected
+LANGUAGE=none
+LOCAL_TEST_FILE=none
+DESTINATION_TEST_FILE=none
+LIBRARY_FILES=none
+TEST_RUN_ARGS=""
+
+# Begin searching for options from the third paramater on
+PARAM_ARGS=${@:2}
+
+if [[ "$1" = java ]]; then
+    LANGUAGE=$1
+    LOCAL_TEST_FILE=$DEFAULT_LOCAL_JAVA_TEST_FILE
+    DESTINATION_TEST_FILE=$DEFAULT_DESTINATION_JAVA_TEST_FILE
+elif [[ "$1" = cpp ]]; then
+    LANGUAGE=$1
+    LOCAL_TEST_FILE=$DEFAULT_LOCAL_CPP_TEST_FILE
+    DESTINATION_TEST_FILE=$DEFAULT_DESTINATION_CPP_TEST_FILE
+elif [[ "$1" = "-h" ]]; then
+    printf "Usage:\n"
+    echo "$usage"
+    exit
+else
+    printf "Invalid language selection: %s\n\n" "$1" >&2
+    echo "$usage" >&2
+    exit 1
+fi
+
+# Check if the test file to upload exists
+if [[ ! -e ${LOCAL_TEST_FILE} ]]; then
+    printf "The test file does not exist: %s\nAre you sure that you compiled the tests??\n\n" "${LOCAL_TEST_FILE}" >&2
+    echo "$usage" >&2
+    exit 1
+fi
+
+TEST_RUN_ARGS="${@:2}"
+
+shopt -s huponexit
+
+SCP_TEST_SCRIPT="scp config.sh ${DEFAULT_LOCAL_RUN_TEST_SCRIPT} ${ROBOT_ADDRESS}:/${DEFAULT_DESTINATION_DIR}"
+SSH_CHMOD_AND_MAKE_TEMP_TEST_DIR="ssh -t ${ROBOT_ADDRESS} \"chmod a+x ${DEFAULT_DESTINATION_RUN_TEST_SCRIPT}; mkdir ${DEFAULT_TEST_SCP_DIR}; touch ${DESTINATION_TEST_FILE}\""
+SCP_TEST_PROGRAM="scp ${LOCAL_TEST_FILE} ${ROBOT_ADDRESS}:${DESTINATION_TEST_FILE}"
+SSH_RUN_TESTS="ssh -t ${ROBOT_ADDRESS} ${DEFAULT_DESTINATION_RUN_TEST_SCRIPT} ${LANGUAGE} $(whoami) -d ${DEFAULT_TEST_SCP_DIR} ${TEST_RUN_ARGS}"
+SCP_NATIVE_LIBRARIES="scp ${DEFAULT_LIBRARY_NATIVE_FILES}/* ${ROBOT_ADDRESS}:${DEFAULT_LIBRARY_NATIVE_DESTINATION}"
+CONFIG_NATIVE_LIBRARIES="ssh -t ${ADMIN_ROBOT_ADDRESS} ldconfig"
+
+if [ $(which sshpass) ]; then
+    sshpass -p "" ${SCP_NATIVE_LIBRARIES}
+    sshpass -p "" ${CONFIG_NATIVE_LIBRARIES}
+    sshpass -p "" ${SCP_TEST_SCRIPT}
+    sshpass -p "" ${SSH_CHMOD_AND_MAKE_TEMP_TEST_DIR}
+    sshpass -p "" ${SCP_TEST_PROGRAM}
+    sshpass -p "" ${SSH_RUN_TESTS}
+else
+    eval ${SCP_NATIVE_LIBRARIES}
+    eval ${CONFIG_NATIVE_LIBRARIES}
+    eval ${SCP_TEST_SCRIPT}
+    eval ${SSH_CHMOD_AND_MAKE_TEMP_TEST_DIR}
+    eval ${SCP_TEST_PROGRAM}
+    eval ${SSH_RUN_TESTS}
+fi
diff --git a/third_party/allwpilib_2019/test-scripts/jenkins-run-tests-get-results.sh b/third_party/allwpilib_2019/test-scripts/jenkins-run-tests-get-results.sh
new file mode 100755
index 0000000..8981b4d
--- /dev/null
+++ b/third_party/allwpilib_2019/test-scripts/jenkins-run-tests-get-results.sh
@@ -0,0 +1,79 @@
+#!/usr/bin/env bash
+#*----------------------------------------------------------------------------*#
+#* Copyright (c) FIRST 2014. 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.															      *#
+#*----------------------------------------------------------------------------*#
+
+# Configurable variables
+source config.sh
+
+(
+# Wait for lock
+printf "Getting exclusive lock for RIO execution...\n"
+flock -x 200 || exit 1
+
+# Ensure the teststand is dead
+SSH_STOP_TESTSTAND="ssh -t ${ROBOT_ADDRESS} sh -c '/etc/init.d/teststand stop; sleep 1'"
+if [ $(which sshpass) ]; then
+    sshpass -p "" ${SSH_STOP_TESTSTAND}
+else
+    eval ${SSH_STOP_TESTSTAND}
+fi
+
+# If there are already test results in the repository then remove them
+if [[ -e ${DEFAULT_LOCAL_TEST_RESULTS_DIR} ]]; then
+    rm -R ${DEFAULT_LOCAL_TEST_RESULTS_DIR}
+fi
+
+# Make the directory where the tests should live
+mkdir ${DEFAULT_LOCAL_TEST_RESULTS_DIR} 2>/dev/null
+
+# Remove the preivous test results from the the robot
+SSH_REMOVE_OLD_TEST_RESULTS="ssh -t ${ROBOT_ADDRESS} rm -R ${DEFAULT_DESTINATION_TEST_RESULTS_DIR}; mkdir ${DEFAULT_DESTINATION_TEST_RESULTS_DIR}"
+if [ $(which sshpass) ]; then
+    sshpass -p "" ${SSH_REMOVE_OLD_TEST_RESULTS}
+else
+    eval ${SSH_REMOVE_OLD_TEST_RESULTS}
+fi
+
+printf "Running cpp test\n"
+
+# Run the C++ Tests
+./deploy-and-run-test-on-robot.sh cpp -A "--gtest_output=xml:${DEFAULT_DESTINATION_CPP_TEST_RESULTS}"
+
+# Retrive the C++ Test Results
+SCP_GET_CPP_TEST_RESULT="scp ${ROBOT_ADDRESS}:${DEFAULT_DESTINATION_CPP_TEST_RESULTS} ${DEFAULT_LOCAL_CPP_TEST_RESULT}"
+if [ $(which sshpass) ]; then
+    sshpass -p "" ${SCP_GET_CPP_TEST_RESULT}
+else
+    eval ${SCP_GET_CPP_TEST_RESULT}
+fi
+
+sleep 10
+
+# Run the Java Tests
+./deploy-and-run-test-on-robot.sh java
+
+# Retrive the Java Test Results
+SCP_GET_JAVA_TEST_RESULT="scp ${ROBOT_ADDRESS}:${DEFAULT_DESTINATION_JAVA_TEST_RESULTS} ${DEFAULT_LOCAL_JAVA_TEST_RESULT}"
+if [ $(which sshpass) ]; then
+    sshpass -p "" ${SCP_GET_JAVA_TEST_RESULT}
+else
+    eval ${SCP_GET_JAVA_TEST_RESULT}
+fi
+
+# Make sure that we got test results back.
+if [ ! -e ${DEFAULT_LOCAL_CPP_TEST_RESULT} ]; then
+  echo "There are no results from the C++ tests; they must have failed."
+  exit 100
+fi
+
+if [ ! -e ${DEFAULT_LOCAL_JAVA_TEST_RESULT} ]; then
+  echo "There are no results from the Java tests; they must have failed."
+  exit 101
+fi
+
+# The mutex is released when this program exits
+) 200>/var/lock/jenkins.rio.exclusivelock
diff --git a/third_party/allwpilib_2019/test-scripts/run-tests-on-robot.sh b/third_party/allwpilib_2019/test-scripts/run-tests-on-robot.sh
new file mode 100755
index 0000000..67d54f2
--- /dev/null
+++ b/third_party/allwpilib_2019/test-scripts/run-tests-on-robot.sh
@@ -0,0 +1,160 @@
+#!/usr/bin/env bash
+#*----------------------------------------------------------------------------*#
+#* Copyright (c) FIRST 2014. 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.															      *#
+#*----------------------------------------------------------------------------*#
+
+# This file is intended to be run in the DEFAULT_TEST_DIR on the roboRIO.
+# Do not attempt to run this file on your local system.
+# There is one file (delploy-and-run-test-on-robot.sh) that is designed to
+# deploy this file allong with the compiled tests for you.
+
+# Configurable variables
+source config.sh
+
+DEFAULT_TEST_DIR=${DEFAULT_DESTINATION_DIR}
+DEFAULT_PATH_TO_JRE=/usr/local/frc/JRE/bin/java
+
+usage="$(basename "$0") [-h] (java|cpp) name [-d test_dir] [-A] [arg] [arg]...
+A script designed to run the integration tests.
+This script should only be run on the roborio.
+Where:
+    -h    Show this help text
+    name  The name of the user trying to run the tests (used for driver station)
+    -d    The directory where the tests have been placed.
+          This is done to prevent overwriting an already running program.
+          This scrip will automatically move the test into the ${DEFAULT_TEST_DIR}
+          directory.
+          Default: Assumes the test is in the same directory as this scrip.
+    -A    Do not use the default arguments for the given language.
+    arg   The arguments to be passed to test."
+
+
+# Are you trying to run this program on a platform other than the roboRIO?
+if [[ ! -e "${DEFAULT_TEST_DIR}" ]]; then
+    printf "Failed to find %s\nAre you trying to run this file on your local computer?\n" "${DEFAULT_TEST_DIR}"
+    printf "This script should only be run on the roboRIO.\n\n"
+    echo "$usage"
+    exit 1
+fi
+
+LANGUAGE=none
+TEST_FILE=none
+NAME=$2
+TEST_DIR="$DEFAULT_TEST_DIR"
+# Begin searching for options from the third paramater on
+PARAM_ARGS=${@:3}
+# Where the test arguments start
+TEST_RUN_ARGS=${@:3}
+RUN_WITH_DEFAULT_ARGS=true
+DEFAULT_ARGS=""
+
+# Determine the language that we are attempting to run
+if [[ "$1" = java ]]; then
+    LANGUAGE=$1
+    TEST_FILE=$DEFAULT_JAVA_TEST_NAME
+    DEFAULT_ARGS=$DEFAULT_JAVA_TEST_ARGS
+elif [[ "$1" = cpp ]]; then
+    LANGUAGE=$1
+    TEST_FILE=$DEFAULT_CPP_TEST_NAME
+    DEFAULT_ARGS=$DEFAULT_CPP_TEST_ARGS
+elif [[ "$1" = "-h" ]]; then
+    #If the first argument is the help option
+    #Allow it to be searhced for in getopts
+    PARAM_ARGS=${@}
+else
+    printf "Invalid language selection: %s\n\n" "$1" >&2
+    echo "$usage" >&2
+    exit 1
+fi
+
+PARAM_COUNTER=2
+printf "Param Args ${PARAM_ARGS}\n"
+
+# Check for optional paramaters
+while  getopts ':hmd:A' option $PARAM_ARGS ; do
+    case "$option" in
+    h)
+        # Print the help message
+        printf "Usage:\n"
+        echo "$usage"
+        exit
+        ;;
+    A)
+        # Remove the default arguments
+        RUN_WITH_DEFAULT_ARGS=false
+        PARAM_COUNTER=$[$PARAM_COUNTER +1]
+        ;;
+    d)
+        TEST_DIR=$OPTARG
+        # Since we are selecting the directory the run args start from the 5th argument
+        PARAM_COUNTER=$[$PARAM_COUNTER +2]
+        ;;
+    ?)
+        # When an unknown param is found then we are done so break
+        break
+        ;;
+    esac
+done
+
+TEST_RUN_ARGS=${@:$[$PARAM_COUNTER +1]}
+
+if [[ "$RUN_WITH_DEFAULT_ARGS" == true ]]; then
+    TEST_RUN_ARGS="${DEFAULT_ARGS} ${TEST_RUN_ARGS}"
+fi
+
+# Make sure at least two paramaters are passed or four if running with -d option
+if [[ $# -lt $PARAM_COUNTER ]]; then
+    printf "Invalid arg count. Should be %s, was %s.\n" "${PARAM_COUNTER}" "$#"
+    echo "$usage"
+    exit 1
+fi
+
+# Make sure the webserver is disabled to save memory
+/usr/local/natinst/etc/init.d/systemWebServer stop
+
+# Kill all running robot programs
+killall java FRCUserProgram
+
+# If we are running with the -d argument move the test to the DEFAULT_TEST_DIR
+if [[ ! -e "${TEST_DIR}/${TEST_FILE}" ]]; then
+    printf "Failed to find %s.\nDid you copy the test file correctly?\n" "${TEST_DIR}/${TEST_FILE}"
+    echo "$usage"
+    exit 1
+elif [[ $TEST_DIR != "$DEFAULT_TEST_DIR" ]]; then
+    mv "${TEST_DIR}/${TEST_FILE}" "${DEFAULT_TEST_DIR}"
+fi
+
+# Make sure the excecutable file has permission to run
+
+# Get the serial number and FPGADeviceCode for this rio
+export serialnum=`/sbin/fw_printenv -n serial#`
+export eval `/sbin/fw_printenv DeviceCode FPGADeviceCode DeviceDesc TargetClass`
+
+# Store the run command for the language
+RUN_COMMAND=none
+if [[ ${LANGUAGE} = java ]]; then
+    chmod a+x ${DEFAULT_JAVA_TEST_NAME}
+    RUN_COMMAND="env LD_LIBRARY_PATH=/opt/GenICam_v3_0_NI/bin/Linux32_ARM/:/usr/local/frc/lib ${DEFAULT_PATH_TO_JRE} -ea -jar ${DEFAULT_JAVA_TEST_NAME} ${TEST_RUN_ARGS}"
+elif [[ ${LANGUAGE} = cpp ]]; then
+    chmod a+x ${DEFAULT_CPP_TEST_NAME}
+    RUN_COMMAND="./${DEFAULT_CPP_TEST_NAME} ${TEST_RUN_ARGS}"
+fi
+
+printf "Running: %s\n\n" "${RUN_COMMAND}"
+COREDUMP_DIR=${DEFAULT_DESTINATION_TEST_RESULTS_DIR}/coredump
+mkdir -p ${COREDUMP_DIR}
+CORE_LOCATION=${COREDUMP_DIR}/core
+echo ${CORE_LOCATION} > /proc/sys/kernel/core_pattern
+ulimit -c unlimited
+eval ${RUN_COMMAND}
+if [[ $? -gt 127 && -e ${CORE_LOCATION} ]]; then
+    mv ${CORE_LOCATION} ${COREDUMP_DIR}/core.${LANGUAGE}
+    if [[ ${LANGUAGE} = java ]]; then
+        cp -p ${DEFAULT_JAVA_TEST_NAME} ${COREDUMP_DIR}/
+    elif [[ ${LANGUAGE} = cpp ]]; then
+        cp -p ${DEFAULT_CPP_TEST_NAME} ${COREDUMP_DIR}/
+    fi
+fi
diff --git a/third_party/allwpilib_2019/tidy-html.conf b/third_party/allwpilib_2019/tidy-html.conf
new file mode 100644
index 0000000..23c4e73
--- /dev/null
+++ b/third_party/allwpilib_2019/tidy-html.conf
@@ -0,0 +1,3 @@
+indent: yes
+indent-spaces: 2
+wrap: 80
diff --git a/third_party/allwpilib_2019/tidy-xml.conf b/third_party/allwpilib_2019/tidy-xml.conf
new file mode 100644
index 0000000..0fb9bda
--- /dev/null
+++ b/third_party/allwpilib_2019/tidy-xml.conf
@@ -0,0 +1,4 @@
+indent: yes
+indent-spaces: 2
+indent-attributes: yes
+literal-attributes: yes
diff --git a/third_party/allwpilib_2019/wpilib-config.cmake.in b/third_party/allwpilib_2019/wpilib-config.cmake.in
new file mode 100644
index 0000000..445db82
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilib-config.cmake.in
@@ -0,0 +1,9 @@
+include(CMakeFindDependencyMacro)

+set(THREADS_PREFER_PTHREAD_FLAG ON)

+find_dependency(Threads)

+find_dependency(wpiutil)

+find_dependency(ntcore)

+@CSCORE_DEP_REPLACE@

+@CAMERASERVER_DEP_REPLACE@

+@HAL_DEP_REPLACE@

+@WPILIBC_DEP_REPLACE@

diff --git a/third_party/allwpilib_2019/wpilibc/CMakeLists.txt b/third_party/allwpilib_2019/wpilibc/CMakeLists.txt
new file mode 100644
index 0000000..da35871
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/CMakeLists.txt
@@ -0,0 +1,30 @@
+project(wpilibc)
+
+find_package( OpenCV REQUIRED )
+
+configure_file(src/generate/WPILibVersion.cpp.in WPILibVersion.cpp)
+
+file(GLOB_RECURSE
+    wpilibc_native_src src/main/native/cpp/*.cpp)
+
+add_library(wpilibc ${wpilibc_native_src} ${CMAKE_CURRENT_BINARY_DIR}/WPILibVersion.cpp)
+set_target_properties(wpilibc PROPERTIES DEBUG_POSTFIX "d")
+
+target_include_directories(wpilibc PUBLIC
+                $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpilibc>)
+target_link_libraries(wpilibc PUBLIC cameraserver hal ntcore cscore wpiutil ${OpenCV_LIBS})
+
+set_property(TARGET wpilibc PROPERTY FOLDER "libraries")
+
+install(TARGETS wpilibc EXPORT wpilibc DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpilibc")
+
+if (MSVC)
+    set (wpilibc_config_dir ${wpilib_dest})
+else()
+    set (wpilibc_config_dir share/wpilibc)
+endif()
+
+install(FILES wpilibc-config.cmake DESTINATION ${wpilibc_config_dir})
+install(EXPORT wpilibc DESTINATION ${wpilibc_config_dir})
diff --git a/third_party/allwpilib_2019/wpilibc/build.gradle b/third_party/allwpilib_2019/wpilibc/build.gradle
new file mode 100644
index 0000000..37ff6bd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/build.gradle
@@ -0,0 +1,250 @@
+apply plugin: 'cpp'
+apply plugin: 'c'
+apply plugin: 'google-test-test-suite'
+apply plugin: 'visual-studio'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: SingleNativeBuild
+apply plugin: ExtraTasks
+
+ext {
+    nativeName = 'wpilibc'
+}
+
+apply from: "${rootDir}/shared/config.gradle"
+
+def wpilibVersionFileInput = file("src/generate/WPILibVersion.cpp.in")
+def wpilibVersionFileOutput = file("$buildDir/generated/cpp/WPILibVersion.cpp")
+
+task generateCppVersion() {
+    description = 'Generates the wpilib version class'
+    group = 'WPILib'
+
+    outputs.file wpilibVersionFileOutput
+    inputs.file wpilibVersionFileInput
+
+    if (WPILibVersion.releaseType.toString().equalsIgnoreCase('official')) {
+        outputs.upToDateWhen { false }
+    }
+
+    // We follow a simple set of checks to determine whether we should generate a new version file:
+    // 1. If the release type is not development, we generate a new verison file
+    // 2. If there is no generated version number, we generate a new version file
+    // 3. If there is a generated build number, and the release type is development, then we will
+    //    only generate if the publish task is run.
+    doLast {
+        println "Writing version ${WPILibVersion.version} to $wpilibVersionFileOutput"
+
+        if (wpilibVersionFileOutput.exists()) {
+            wpilibVersionFileOutput.delete()
+        }
+        def read = wpilibVersionFileInput.text.replace('${wpilib_version}', WPILibVersion.version)
+        wpilibVersionFileOutput.write(read)
+    }
+}
+
+gradle.taskGraph.addTaskExecutionGraphListener { graph ->
+    def willPublish = graph.hasTask(publish)
+    if (willPublish) {
+        generateCppVersion.outputs.upToDateWhen { false }
+    }
+}
+
+ext {
+    sharedCvConfigs = [wpilibc    : [],
+                       wpilibcBase: [],
+                       wpilibcDev : [],
+                       wpilibcTest: []]
+    staticCvConfigs = [:]
+    useJava = false
+    useCpp = true
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+project(':').libraryBuild.dependsOn build
+
+ext {
+    staticGtestConfigs = [:]
+}
+
+staticGtestConfigs["${nativeName}Test"] = []
+
+apply from: "${rootDir}/shared/googletest.gradle"
+
+ext {
+    chipObjectComponents = ["$nativeName".toString(), "${nativeName}Dev".toString(), "${nativeName}Base".toString(),
+                            "${nativeName}Test".toString()]
+    netCommComponents = ["$nativeName".toString(), "${nativeName}Dev".toString(), "${nativeName}Base".toString(),
+                            "${nativeName}Test".toString()]
+    useNiJava = false
+}
+
+apply from: "${rootDir}/shared/nilibraries.gradle"
+
+model {
+    exportsConfigs {
+        wpilibc(ExportsConfig) {
+            x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVbad_cast',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure']
+            x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVbad_cast',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure']
+        }
+    }
+    components {
+        "${nativeName}Base"(NativeLibrarySpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDirs = ['src/main/native/cpp', "$buildDir/generated/cpp"]
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include'
+                    }
+                }
+            }
+            binaries.all {
+                if (it instanceof SharedLibraryBinarySpec) {
+                    it.buildable = false
+                    return
+                }
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+            }
+        }
+        "${nativeName}"(NativeLibrarySpec) {
+            sources {
+                cpp {
+                    source {
+                        srcDirs "${rootDir}/shared/singlelib"
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include'
+                    }
+                }
+            }
+            binaries.all {
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+            }
+            appendDebugPathToBinaries(binaries)
+        }
+        // By default, a development executable will be generated. This is to help the case of
+        // testing specific functionality of the library.
+        "${nativeName}Dev"(NativeExecutableSpec) {
+            targetBuildTypes 'debug'
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/dev/native/cpp'
+                        include '**/*.cpp'
+                        lib library: 'wpilibc'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/dev/native/include'
+                    }
+                }
+            }
+            binaries.all {
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+            }
+        }
+    }
+    testSuites {
+        "${nativeName}Test"(GoogleTestTestSuiteSpec) {
+            for(NativeComponentSpec c : $.components) {
+                if (c.name == nativeName) {
+                    testing c
+                    break
+                }
+            }
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/test/native/cpp'
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/test/native/include', 'src/main/native/cpp'
+                    }
+                }
+                c {
+                    source {
+                        srcDirs 'src/test/native/c'
+                        include '**/*.c'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/test/native/include', 'src/main/native/c'
+                    }
+                }
+            }
+        }
+    }
+    binaries {
+        all {
+            tasks.withType(CppCompile) {
+                dependsOn generateCppVersion
+            }
+        }
+        withType(GoogleTestTestSuiteBinarySpec) {
+            if (!project.hasProperty('onlyAthena') && !project.hasProperty('onlyRaspbian')) {
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                project(':hal').addHalDependency(it, 'shared')
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                lib library: nativeName, linkage: 'shared'
+            } else {
+                it.buildable = false
+            }
+        }
+    }
+    tasks {
+        def c = $.components
+        project.tasks.create('runCpp', Exec) {
+            def found = false
+            c.each {
+                if (it in NativeExecutableSpec && it.name == "${nativeName}Dev") {
+                    it.binaries.each {
+                        if (!found) {
+                            def arch = it.targetPlatform.architecture.name
+                            if (arch == 'x86-64' || arch == 'x86') {
+                                dependsOn it.tasks.install
+
+                                found = true
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+tasks.withType(RunTestExecutable) {
+    args "--gtest_output=xml:test_detail.xml"
+    outputs.dir outputDir
+}
+
+apply from: 'publish.gradle'
+
+def oldWpilibVersionFile = file('src/main/native/cpp/WPILibVersion.cpp')
+
+clean {
+    delete oldWpilibVersionFile
+}
diff --git a/third_party/allwpilib_2019/wpilibc/publish.gradle b/third_party/allwpilib_2019/wpilibc/publish.gradle
new file mode 100644
index 0000000..06f88df
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/publish.gradle
@@ -0,0 +1,74 @@
+apply plugin: 'maven-publish'
+
+def pubVersion = ''
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseArtifactId = 'wpilibc-cpp'
+def artifactGroupId = 'edu.wpi.first.wpilibc'
+def zipBaseName = '_GROUP_edu_wpi_first_wpilibc_ID_wpilibc-cpp_CLS'
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task cppSourcesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "sources"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/cpp') {
+        into '/'
+    }
+    from("$buildDir/generated/cpp") {
+        into '/'
+    }
+}
+
+cppSourcesZip.dependsOn generateCppVersion
+
+task cppHeadersZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = zipBaseName
+    classifier = "headers"
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/native/include') {
+        into '/'
+    }
+}
+
+build.dependsOn cppHeadersZip
+build.dependsOn cppSourcesZip
+
+addTaskToCopyAllOutputs(cppHeadersZip)
+addTaskToCopyAllOutputs(cppSourcesZip)
+
+model {
+    publishing {
+        def wpilibCTaskList = createComponentZipTasks($.components, ['wpilibc'], zipBaseName, Zip, project, includeStandardZipFormat)
+
+        publications {
+            cpp(MavenPublication) {
+                wpilibCTaskList.each {
+                    artifact it
+                }
+
+                artifact cppHeadersZip
+                artifact cppSourcesZip
+
+                artifactId = baseArtifactId
+                groupId artifactGroupId
+                version pubVersion
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/wpilibc/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..6e64d2b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/dev/native/cpp/main.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include <hal/HAL.h>
+
+#include "WPILibVersion.h"
+
+int main() {
+  std::cout << "Hello World" << std::endl;
+  std::cout << HAL_GetRuntimeType() << std::endl;
+  std::cout << GetWPILibVersion() << std::endl;
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/generate/WPILibVersion.cpp.in b/third_party/allwpilib_2019/wpilibc/src/generate/WPILibVersion.cpp.in
new file mode 100644
index 0000000..b0a4490
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/generate/WPILibVersion.cpp.in
@@ -0,0 +1,7 @@
+/*
+ * Autogenerated file! Do not manually edit this file. This version is regenerated
+ * any time the publish task is run, or when this file is deleted.
+ */
+const char* GetWPILibVersion() {
+  return "${wpilib_version}";
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp
new file mode 100644
index 0000000..71407da
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL345_I2C.cpp
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/ADXL345_I2C.h"
+
+#include <hal/HAL.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress)
+    : m_i2c(port, deviceAddress) {
+  // Turn on the measurements
+  m_i2c.Write(kPowerCtlRegister, kPowerCtl_Measure);
+  // Specify the data format to read
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL345,
+             HALUsageReporting::kADXL345_I2C, 0);
+  SetName("ADXL345_I2C", port);
+}
+
+void ADXL345_I2C::SetRange(Range range) {
+  m_i2c.Write(kDataFormatRegister,
+              kDataFormat_FullRes | static_cast<uint8_t>(range));
+}
+
+double ADXL345_I2C::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL345_I2C::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL345_I2C::GetZ() { return GetAcceleration(kAxis_Z); }
+
+double ADXL345_I2C::GetAcceleration(ADXL345_I2C::Axes axis) {
+  int16_t rawAccel = 0;
+  m_i2c.Read(kDataRegister + static_cast<int>(axis), sizeof(rawAccel),
+             reinterpret_cast<uint8_t*>(&rawAccel));
+  return rawAccel * kGsPerLSB;
+}
+
+ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() {
+  AllAxes data = AllAxes();
+  int16_t rawData[3];
+  m_i2c.Read(kDataRegister, sizeof(rawData),
+             reinterpret_cast<uint8_t*>(rawData));
+
+  data.XAxis = rawData[0] * kGsPerLSB;
+  data.YAxis = rawData[1] * kGsPerLSB;
+  data.ZAxis = rawData[2] * kGsPerLSB;
+  return data;
+}
+
+void ADXL345_I2C::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("3AxisAccelerometer");
+  auto x = builder.GetEntry("X").GetHandle();
+  auto y = builder.GetEntry("Y").GetHandle();
+  auto z = builder.GetEntry("Z").GetHandle();
+  builder.SetUpdateTable([=]() {
+    auto data = GetAccelerations();
+    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
+    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
+    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
+  });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp
new file mode 100644
index 0000000..738bc3e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL345_SPI.cpp
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/ADXL345_SPI.h"
+
+#include <hal/HAL.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+ADXL345_SPI::ADXL345_SPI(SPI::Port port, ADXL345_SPI::Range range)
+    : m_spi(port) {
+  m_spi.SetClockRate(500000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnTrailingEdge();
+  m_spi.SetClockActiveLow();
+  m_spi.SetChipSelectActiveHigh();
+
+  uint8_t commands[2];
+  // Turn on the measurements
+  commands[0] = kPowerCtlRegister;
+  commands[1] = kPowerCtl_Measure;
+  m_spi.Transaction(commands, commands, 2);
+
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL345,
+             HALUsageReporting::kADXL345_SPI);
+
+  SetName("ADXL345_SPI", port);
+}
+
+void ADXL345_SPI::SetRange(Range range) {
+  uint8_t commands[2];
+
+  // Specify the data format to read
+  commands[0] = kDataFormatRegister;
+  commands[1] = kDataFormat_FullRes | static_cast<uint8_t>(range & 0x03);
+  m_spi.Transaction(commands, commands, 2);
+}
+
+double ADXL345_SPI::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL345_SPI::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL345_SPI::GetZ() { return GetAcceleration(kAxis_Z); }
+
+double ADXL345_SPI::GetAcceleration(ADXL345_SPI::Axes axis) {
+  uint8_t buffer[3];
+  uint8_t command[3] = {0, 0, 0};
+  command[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister) +
+               static_cast<uint8_t>(axis);
+  m_spi.Transaction(command, buffer, 3);
+
+  // Sensor is little endian... swap bytes
+  int16_t rawAccel = buffer[2] << 8 | buffer[1];
+  return rawAccel * kGsPerLSB;
+}
+
+ADXL345_SPI::AllAxes ADXL345_SPI::GetAccelerations() {
+  AllAxes data = AllAxes();
+  uint8_t dataBuffer[7] = {0, 0, 0, 0, 0, 0, 0};
+  int16_t rawData[3];
+
+  // Select the data address.
+  dataBuffer[0] = (kAddress_Read | kAddress_MultiByte | kDataRegister);
+  m_spi.Transaction(dataBuffer, dataBuffer, 7);
+
+  for (int i = 0; i < 3; i++) {
+    // Sensor is little endian... swap bytes
+    rawData[i] = dataBuffer[i * 2 + 2] << 8 | dataBuffer[i * 2 + 1];
+  }
+
+  data.XAxis = rawData[0] * kGsPerLSB;
+  data.YAxis = rawData[1] * kGsPerLSB;
+  data.ZAxis = rawData[2] * kGsPerLSB;
+
+  return data;
+}
+
+void ADXL345_SPI::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("3AxisAccelerometer");
+  auto x = builder.GetEntry("X").GetHandle();
+  auto y = builder.GetEntry("Y").GetHandle();
+  auto z = builder.GetEntry("Z").GetHandle();
+  builder.SetUpdateTable([=]() {
+    auto data = GetAccelerations();
+    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
+    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
+    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
+  });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL362.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL362.cpp
new file mode 100644
index 0000000..d709ae4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXL362.cpp
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/ADXL362.h"
+
+#include <hal/HAL.h>
+
+#include "frc/DriverStation.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+static constexpr int kRegWrite = 0x0A;
+static constexpr int kRegRead = 0x0B;
+
+static constexpr int kPartIdRegister = 0x02;
+static constexpr int kDataRegister = 0x0E;
+static constexpr int kFilterCtlRegister = 0x2C;
+static constexpr int kPowerCtlRegister = 0x2D;
+
+// static constexpr int kFilterCtl_Range2G = 0x00;
+// static constexpr int kFilterCtl_Range4G = 0x40;
+// static constexpr int kFilterCtl_Range8G = 0x80;
+static constexpr int kFilterCtl_ODR_100Hz = 0x03;
+
+static constexpr int kPowerCtl_UltraLowNoise = 0x20;
+// static constexpr int kPowerCtl_AutoSleep = 0x04;
+static constexpr int kPowerCtl_Measure = 0x02;
+
+ADXL362::ADXL362(Range range) : ADXL362(SPI::Port::kOnboardCS1, range) {}
+
+ADXL362::ADXL362(SPI::Port port, Range range) : m_spi(port) {
+  m_spi.SetClockRate(3000000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnTrailingEdge();
+  m_spi.SetClockActiveLow();
+  m_spi.SetChipSelectActiveLow();
+
+  // Validate the part ID
+  uint8_t commands[3];
+  commands[0] = kRegRead;
+  commands[1] = kPartIdRegister;
+  commands[2] = 0;
+  m_spi.Transaction(commands, commands, 3);
+  if (commands[2] != 0xF2) {
+    DriverStation::ReportError("could not find ADXL362");
+    m_gsPerLSB = 0.0;
+    return;
+  }
+
+  SetRange(range);
+
+  // Turn on the measurements
+  commands[0] = kRegWrite;
+  commands[1] = kPowerCtlRegister;
+  commands[2] = kPowerCtl_Measure | kPowerCtl_UltraLowNoise;
+  m_spi.Write(commands, 3);
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXL362, port);
+
+  SetName("ADXL362", port);
+}
+
+void ADXL362::SetRange(Range range) {
+  if (m_gsPerLSB == 0.0) return;
+
+  uint8_t commands[3];
+
+  switch (range) {
+    case kRange_2G:
+      m_gsPerLSB = 0.001;
+      break;
+    case kRange_4G:
+      m_gsPerLSB = 0.002;
+      break;
+    case kRange_8G:
+    case kRange_16G:  // 16G not supported; treat as 8G
+      m_gsPerLSB = 0.004;
+      break;
+  }
+
+  // Specify the data format to read
+  commands[0] = kRegWrite;
+  commands[1] = kFilterCtlRegister;
+  commands[2] =
+      kFilterCtl_ODR_100Hz | static_cast<uint8_t>((range & 0x03) << 6);
+  m_spi.Write(commands, 3);
+}
+
+double ADXL362::GetX() { return GetAcceleration(kAxis_X); }
+
+double ADXL362::GetY() { return GetAcceleration(kAxis_Y); }
+
+double ADXL362::GetZ() { return GetAcceleration(kAxis_Z); }
+
+double ADXL362::GetAcceleration(ADXL362::Axes axis) {
+  if (m_gsPerLSB == 0.0) return 0.0;
+
+  uint8_t buffer[4];
+  uint8_t command[4] = {0, 0, 0, 0};
+  command[0] = kRegRead;
+  command[1] = kDataRegister + static_cast<uint8_t>(axis);
+  m_spi.Transaction(command, buffer, 4);
+
+  // Sensor is little endian... swap bytes
+  int16_t rawAccel = buffer[3] << 8 | buffer[2];
+  return rawAccel * m_gsPerLSB;
+}
+
+ADXL362::AllAxes ADXL362::GetAccelerations() {
+  AllAxes data = AllAxes();
+  if (m_gsPerLSB == 0.0) {
+    data.XAxis = data.YAxis = data.ZAxis = 0.0;
+    return data;
+  }
+
+  uint8_t dataBuffer[8] = {0, 0, 0, 0, 0, 0, 0, 0};
+  int16_t rawData[3];
+
+  // Select the data address.
+  dataBuffer[0] = kRegRead;
+  dataBuffer[1] = kDataRegister;
+  m_spi.Transaction(dataBuffer, dataBuffer, 8);
+
+  for (int i = 0; i < 3; i++) {
+    // Sensor is little endian... swap bytes
+    rawData[i] = dataBuffer[i * 2 + 3] << 8 | dataBuffer[i * 2 + 2];
+  }
+
+  data.XAxis = rawData[0] * m_gsPerLSB;
+  data.YAxis = rawData[1] * m_gsPerLSB;
+  data.ZAxis = rawData[2] * m_gsPerLSB;
+
+  return data;
+}
+
+void ADXL362::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("3AxisAccelerometer");
+  auto x = builder.GetEntry("X").GetHandle();
+  auto y = builder.GetEntry("Y").GetHandle();
+  auto z = builder.GetEntry("Z").GetHandle();
+  builder.SetUpdateTable([=]() {
+    auto data = GetAccelerations();
+    nt::NetworkTableEntry(x).SetDouble(data.XAxis);
+    nt::NetworkTableEntry(y).SetDouble(data.YAxis);
+    nt::NetworkTableEntry(z).SetDouble(data.ZAxis);
+  });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp
new file mode 100644
index 0000000..875f403
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ADXRS450_Gyro.cpp
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/ADXRS450_Gyro.h"
+
+#include <hal/HAL.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Timer.h"
+
+using namespace frc;
+
+static constexpr double kSamplePeriod = 0.0005;
+static constexpr double kCalibrationSampleTime = 5.0;
+static constexpr double kDegreePerSecondPerLSB = 0.0125;
+
+static constexpr int kRateRegister = 0x00;
+static constexpr int kTemRegister = 0x02;
+static constexpr int kLoCSTRegister = 0x04;
+static constexpr int kHiCSTRegister = 0x06;
+static constexpr int kQuadRegister = 0x08;
+static constexpr int kFaultRegister = 0x0A;
+static constexpr int kPIDRegister = 0x0C;
+static constexpr int kSNHighRegister = 0x0E;
+static constexpr int kSNLowRegister = 0x10;
+
+ADXRS450_Gyro::ADXRS450_Gyro() : ADXRS450_Gyro(SPI::kOnboardCS0) {}
+
+ADXRS450_Gyro::ADXRS450_Gyro(SPI::Port port) : m_spi(port) {
+  m_spi.SetClockRate(3000000);
+  m_spi.SetMSBFirst();
+  m_spi.SetSampleDataOnLeadingEdge();
+  m_spi.SetClockActiveHigh();
+  m_spi.SetChipSelectActiveLow();
+
+  // Validate the part ID
+  if ((ReadRegister(kPIDRegister) & 0xff00) != 0x5200) {
+    DriverStation::ReportError("could not find ADXRS450 gyro");
+    return;
+  }
+
+  m_spi.InitAccumulator(kSamplePeriod, 0x20000000u, 4, 0x0c00000eu, 0x04000000u,
+                        10u, 16u, true, true);
+
+  Calibrate();
+
+  HAL_Report(HALUsageReporting::kResourceType_ADXRS450, port);
+  SetName("ADXRS450_Gyro", port);
+}
+
+static bool CalcParity(int v) {
+  bool parity = false;
+  while (v != 0) {
+    parity = !parity;
+    v = v & (v - 1);
+  }
+  return parity;
+}
+
+static inline int BytesToIntBE(uint8_t* buf) {
+  int result = static_cast<int>(buf[0]) << 24;
+  result |= static_cast<int>(buf[1]) << 16;
+  result |= static_cast<int>(buf[2]) << 8;
+  result |= static_cast<int>(buf[3]);
+  return result;
+}
+
+uint16_t ADXRS450_Gyro::ReadRegister(int reg) {
+  int cmd = 0x80000000 | static_cast<int>(reg) << 17;
+  if (!CalcParity(cmd)) cmd |= 1u;
+
+  // big endian
+  uint8_t buf[4] = {static_cast<uint8_t>((cmd >> 24) & 0xff),
+                    static_cast<uint8_t>((cmd >> 16) & 0xff),
+                    static_cast<uint8_t>((cmd >> 8) & 0xff),
+                    static_cast<uint8_t>(cmd & 0xff)};
+
+  m_spi.Write(buf, 4);
+  m_spi.Read(false, buf, 4);
+  if ((buf[0] & 0xe0) == 0) return 0;  // error, return 0
+  return static_cast<uint16_t>((BytesToIntBE(buf) >> 5) & 0xffff);
+}
+
+double ADXRS450_Gyro::GetAngle() const {
+  return m_spi.GetAccumulatorIntegratedValue() * kDegreePerSecondPerLSB;
+}
+
+double ADXRS450_Gyro::GetRate() const {
+  return static_cast<double>(m_spi.GetAccumulatorLastValue()) *
+         kDegreePerSecondPerLSB;
+}
+
+void ADXRS450_Gyro::Reset() { m_spi.ResetAccumulator(); }
+
+void ADXRS450_Gyro::Calibrate() {
+  Wait(0.1);
+
+  m_spi.SetAccumulatorIntegratedCenter(0);
+  m_spi.ResetAccumulator();
+
+  Wait(kCalibrationSampleTime);
+
+  m_spi.SetAccumulatorIntegratedCenter(m_spi.GetAccumulatorIntegratedAverage());
+  m_spi.ResetAccumulator();
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp
new file mode 100644
index 0000000..3ae8e48
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogAccelerometer.cpp
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/AnalogAccelerometer.h"
+
+#include <hal/HAL.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+AnalogAccelerometer::AnalogAccelerometer(int channel)
+    : AnalogAccelerometer(std::make_shared<AnalogInput>(channel)) {
+  AddChild(m_analogInput);
+}
+
+AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel)
+    : m_analogInput(channel, NullDeleter<AnalogInput>()) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitAccelerometer();
+  }
+}
+
+AnalogAccelerometer::AnalogAccelerometer(std::shared_ptr<AnalogInput> channel)
+    : m_analogInput(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitAccelerometer();
+  }
+}
+
+double AnalogAccelerometer::GetAcceleration() const {
+  return (m_analogInput->GetAverageVoltage() - m_zeroGVoltage) / m_voltsPerG;
+}
+
+void AnalogAccelerometer::SetSensitivity(double sensitivity) {
+  m_voltsPerG = sensitivity;
+}
+
+void AnalogAccelerometer::SetZero(double zero) { m_zeroGVoltage = zero; }
+
+double AnalogAccelerometer::PIDGet() { return GetAcceleration(); }
+
+void AnalogAccelerometer::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Accelerometer");
+  builder.AddDoubleProperty("Value", [=]() { return GetAcceleration(); },
+                            nullptr);
+}
+
+void AnalogAccelerometer::InitAccelerometer() {
+  HAL_Report(HALUsageReporting::kResourceType_Accelerometer,
+             m_analogInput->GetChannel());
+  SetName("Accelerometer", m_analogInput->GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogGyro.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogGyro.cpp
new file mode 100644
index 0000000..5efe7b3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogGyro.cpp
@@ -0,0 +1,173 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/AnalogGyro.h"
+
+#include <climits>
+#include <utility>
+
+#include <hal/AnalogGyro.h>
+#include <hal/Errors.h>
+#include <hal/HAL.h>
+
+#include "frc/AnalogInput.h"
+#include "frc/Timer.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+AnalogGyro::AnalogGyro(int channel)
+    : AnalogGyro(std::make_shared<AnalogInput>(channel)) {
+  AddChild(m_analog);
+}
+
+AnalogGyro::AnalogGyro(AnalogInput* channel)
+    : AnalogGyro(
+          std::shared_ptr<AnalogInput>(channel, NullDeleter<AnalogInput>())) {}
+
+AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel)
+    : m_analog(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitGyro();
+    Calibrate();
+  }
+}
+
+AnalogGyro::AnalogGyro(int channel, int center, double offset)
+    : AnalogGyro(std::make_shared<AnalogInput>(channel), center, offset) {
+  AddChild(m_analog);
+}
+
+AnalogGyro::AnalogGyro(std::shared_ptr<AnalogInput> channel, int center,
+                       double offset)
+    : m_analog(channel) {
+  if (channel == nullptr) {
+    wpi_setWPIError(NullParameter);
+  } else {
+    InitGyro();
+    int32_t status = 0;
+    HAL_SetAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond,
+                                offset, center, &status);
+    if (status != 0) {
+      wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+    Reset();
+  }
+}
+
+AnalogGyro::~AnalogGyro() { HAL_FreeAnalogGyro(m_gyroHandle); }
+
+AnalogGyro::AnalogGyro(AnalogGyro&& rhs)
+    : GyroBase(std::move(rhs)), m_analog(std::move(rhs.m_analog)) {
+  std::swap(m_gyroHandle, rhs.m_gyroHandle);
+}
+
+AnalogGyro& AnalogGyro::operator=(AnalogGyro&& rhs) {
+  GyroBase::operator=(std::move(rhs));
+
+  m_analog = std::move(rhs.m_analog);
+  std::swap(m_gyroHandle, rhs.m_gyroHandle);
+
+  return *this;
+}
+
+double AnalogGyro::GetAngle() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroAngle(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+double AnalogGyro::GetRate() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroRate(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+int AnalogGyro::GetCenter() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogGyroCenter(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+double AnalogGyro::GetOffset() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetAnalogGyroOffset(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+void AnalogGyro::SetSensitivity(double voltsPerDegreePerSecond) {
+  int32_t status = 0;
+  HAL_SetAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle,
+                                           voltsPerDegreePerSecond, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void AnalogGyro::SetDeadband(double volts) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogGyroDeadband(m_gyroHandle, volts, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void AnalogGyro::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetAnalogGyro(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void AnalogGyro::InitGyro() {
+  if (StatusIsFatal()) return;
+  if (m_gyroHandle == HAL_kInvalidHandle) {
+    int32_t status = 0;
+    m_gyroHandle = HAL_InitializeAnalogGyro(m_analog->m_port, &status);
+    if (status == PARAMETER_OUT_OF_RANGE) {
+      wpi_setWPIErrorWithContext(ParameterOutOfRange,
+                                 " channel (must be accumulator channel)");
+      m_analog = nullptr;
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+    if (status != 0) {
+      wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+      m_analog = nullptr;
+      m_gyroHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+
+  int32_t status = 0;
+  HAL_SetupAnalogGyro(m_gyroHandle, &status);
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    m_analog = nullptr;
+    m_gyroHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_Gyro, m_analog->GetChannel());
+  SetName("AnalogGyro", m_analog->GetChannel());
+}
+
+void AnalogGyro::Calibrate() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_CalibrateAnalogGyro(m_gyroHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogInput.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogInput.cpp
new file mode 100644
index 0000000..52a55d3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogInput.cpp
@@ -0,0 +1,250 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/AnalogInput.h"
+
+#include <utility>
+
+#include <hal/AnalogAccumulator.h>
+#include <hal/AnalogInput.h>
+#include <hal/HAL.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/Timer.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+AnalogInput::AnalogInput(int channel) {
+  if (!SensorUtil::CheckAnalogInputChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Analog Input " + wpi::Twine(channel));
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_PortHandle port = HAL_GetPort(channel);
+  int32_t status = 0;
+  m_port = HAL_InitializeAnalogInputPort(port, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumAnalogInputs(), channel,
+                                 HAL_GetErrorMessage(status));
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogChannel, channel);
+  SetName("AnalogInput", channel);
+}
+
+AnalogInput::~AnalogInput() { HAL_FreeAnalogInputPort(m_port); }
+
+AnalogInput::AnalogInput(AnalogInput&& rhs)
+    : ErrorBase(std::move(rhs)),
+      SendableBase(std::move(rhs)),
+      PIDSource(std::move(rhs)),
+      m_channel(std::move(rhs.m_channel)),
+      m_accumulatorOffset(std::move(rhs.m_accumulatorOffset)) {
+  std::swap(m_port, rhs.m_port);
+}
+
+AnalogInput& AnalogInput::operator=(AnalogInput&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+  PIDSource::operator=(std::move(rhs));
+
+  m_channel = std::move(rhs.m_channel);
+  std::swap(m_port, rhs.m_port);
+  m_accumulatorOffset = std::move(rhs.m_accumulatorOffset);
+
+  return *this;
+}
+
+int AnalogInput::GetValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogValue(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+int AnalogInput::GetAverageValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetAnalogAverageValue(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+double AnalogInput::GetVoltage() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogVoltage(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return voltage;
+}
+
+double AnalogInput::GetAverageVoltage() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogAverageVoltage(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return voltage;
+}
+
+int AnalogInput::GetChannel() const {
+  if (StatusIsFatal()) return 0;
+  return m_channel;
+}
+
+void AnalogInput::SetAverageBits(int bits) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogAverageBits(m_port, bits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int AnalogInput::GetAverageBits() const {
+  int32_t status = 0;
+  int averageBits = HAL_GetAnalogAverageBits(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return averageBits;
+}
+
+void AnalogInput::SetOversampleBits(int bits) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogOversampleBits(m_port, bits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int AnalogInput::GetOversampleBits() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int oversampleBits = HAL_GetAnalogOversampleBits(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return oversampleBits;
+}
+
+int AnalogInput::GetLSBWeight() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int lsbWeight = HAL_GetAnalogLSBWeight(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return lsbWeight;
+}
+
+int AnalogInput::GetOffset() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int offset = HAL_GetAnalogOffset(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return offset;
+}
+
+bool AnalogInput::IsAccumulatorChannel() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool isAccum = HAL_IsAccumulatorChannel(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return isAccum;
+}
+
+void AnalogInput::InitAccumulator() {
+  if (StatusIsFatal()) return;
+  m_accumulatorOffset = 0;
+  int32_t status = 0;
+  HAL_InitAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void AnalogInput::SetAccumulatorInitialValue(int64_t initialValue) {
+  if (StatusIsFatal()) return;
+  m_accumulatorOffset = initialValue;
+}
+
+void AnalogInput::ResetAccumulator() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetAccumulator(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  if (!StatusIsFatal()) {
+    // Wait until the next sample, so the next call to GetAccumulator*()
+    // won't have old values.
+    const double sampleTime = 1.0 / GetSampleRate();
+    const double overSamples = 1 << GetOversampleBits();
+    const double averageSamples = 1 << GetAverageBits();
+    Wait(sampleTime * overSamples * averageSamples);
+  }
+}
+
+void AnalogInput::SetAccumulatorCenter(int center) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAccumulatorCenter(m_port, center, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void AnalogInput::SetAccumulatorDeadband(int deadband) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAccumulatorDeadband(m_port, deadband, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int64_t AnalogInput::GetAccumulatorValue() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int64_t value = HAL_GetAccumulatorValue(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value + m_accumulatorOffset;
+}
+
+int64_t AnalogInput::GetAccumulatorCount() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int64_t count = HAL_GetAccumulatorCount(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return count;
+}
+
+void AnalogInput::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_GetAccumulatorOutput(m_port, &value, &count, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  value += m_accumulatorOffset;
+}
+
+void AnalogInput::SetSampleRate(double samplesPerSecond) {
+  int32_t status = 0;
+  HAL_SetAnalogSampleRate(samplesPerSecond, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+double AnalogInput::GetSampleRate() {
+  int32_t status = 0;
+  double sampleRate = HAL_GetAnalogSampleRate(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return sampleRate;
+}
+
+double AnalogInput::PIDGet() {
+  if (StatusIsFatal()) return 0.0;
+  return GetAverageVoltage();
+}
+
+void AnalogInput::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Analog Input");
+  builder.AddDoubleProperty("Value", [=]() { return GetAverageVoltage(); },
+                            nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogOutput.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogOutput.cpp
new file mode 100644
index 0000000..b18af5b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogOutput.cpp
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/AnalogOutput.h"
+
+#include <limits>
+#include <utility>
+
+#include <hal/HAL.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+AnalogOutput::AnalogOutput(int channel) {
+  if (!SensorUtil::CheckAnalogOutputChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "analog output " + wpi::Twine(channel));
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_PortHandle port = HAL_GetPort(m_channel);
+  int32_t status = 0;
+  m_port = HAL_InitializeAnalogOutputPort(port, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumAnalogOutputs(), channel,
+                                 HAL_GetErrorMessage(status));
+    m_channel = std::numeric_limits<int>::max();
+    m_port = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogOutput, m_channel);
+  SetName("AnalogOutput", m_channel);
+}
+
+AnalogOutput::~AnalogOutput() { HAL_FreeAnalogOutputPort(m_port); }
+
+AnalogOutput::AnalogOutput(AnalogOutput&& rhs)
+    : ErrorBase(std::move(rhs)),
+      SendableBase(std::move(rhs)),
+      m_channel(std::move(rhs.m_channel)) {
+  std::swap(m_port, rhs.m_port);
+}
+
+AnalogOutput& AnalogOutput::operator=(AnalogOutput&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+
+  m_channel = std::move(rhs.m_channel);
+  std::swap(m_port, rhs.m_port);
+
+  return *this;
+}
+
+void AnalogOutput::SetVoltage(double voltage) {
+  int32_t status = 0;
+  HAL_SetAnalogOutput(m_port, voltage, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+double AnalogOutput::GetVoltage() const {
+  int32_t status = 0;
+  double voltage = HAL_GetAnalogOutput(m_port, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  return voltage;
+}
+
+int AnalogOutput::GetChannel() { return m_channel; }
+
+void AnalogOutput::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Analog Output");
+  builder.AddDoubleProperty("Value", [=]() { return GetVoltage(); },
+                            [=](double value) { SetVoltage(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp
new file mode 100644
index 0000000..6c42ff9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogPotentiometer.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/AnalogPotentiometer.h"
+
+#include "frc/RobotController.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange,
+                                         double offset)
+    : m_analog_input(std::make_shared<AnalogInput>(channel)),
+      m_fullRange(fullRange),
+      m_offset(offset) {
+  AddChild(m_analog_input);
+}
+
+AnalogPotentiometer::AnalogPotentiometer(AnalogInput* input, double fullRange,
+                                         double offset)
+    : m_analog_input(input, NullDeleter<AnalogInput>()),
+      m_fullRange(fullRange),
+      m_offset(offset) {}
+
+AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
+                                         double fullRange, double offset)
+    : m_analog_input(input), m_fullRange(fullRange), m_offset(offset) {}
+
+double AnalogPotentiometer::Get() const {
+  return (m_analog_input->GetVoltage() / RobotController::GetVoltage5V()) *
+             m_fullRange +
+         m_offset;
+}
+
+double AnalogPotentiometer::PIDGet() { return Get(); }
+
+void AnalogPotentiometer::InitSendable(SendableBuilder& builder) {
+  m_analog_input->InitSendable(builder);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogTrigger.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogTrigger.cpp
new file mode 100644
index 0000000..aeb58df
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogTrigger.cpp
@@ -0,0 +1,130 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/AnalogTrigger.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+
+#include "frc/AnalogInput.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+AnalogTrigger::AnalogTrigger(int channel)
+    : AnalogTrigger(new AnalogInput(channel)) {
+  m_ownsAnalog = true;
+  AddChild(m_analogInput);
+}
+
+AnalogTrigger::AnalogTrigger(AnalogInput* input) {
+  m_analogInput = input;
+  int32_t status = 0;
+  int index = 0;
+  m_trigger = HAL_InitializeAnalogTrigger(input->m_port, &index, &status);
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    m_index = std::numeric_limits<int>::max();
+    m_trigger = HAL_kInvalidHandle;
+    return;
+  }
+  m_index = index;
+
+  HAL_Report(HALUsageReporting::kResourceType_AnalogTrigger, input->m_channel);
+  SetName("AnalogTrigger", input->GetChannel());
+}
+
+AnalogTrigger::~AnalogTrigger() {
+  int32_t status = 0;
+  HAL_CleanAnalogTrigger(m_trigger, &status);
+
+  if (m_ownsAnalog) {
+    delete m_analogInput;
+  }
+}
+
+AnalogTrigger::AnalogTrigger(AnalogTrigger&& rhs)
+    : ErrorBase(std::move(rhs)),
+      SendableBase(std::move(rhs)),
+      m_index(std::move(rhs.m_index)) {
+  std::swap(m_trigger, rhs.m_trigger);
+  std::swap(m_analogInput, rhs.m_analogInput);
+  std::swap(m_ownsAnalog, rhs.m_ownsAnalog);
+}
+
+AnalogTrigger& AnalogTrigger::operator=(AnalogTrigger&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+
+  m_index = std::move(rhs.m_index);
+  std::swap(m_trigger, rhs.m_trigger);
+  std::swap(m_analogInput, rhs.m_analogInput);
+  std::swap(m_ownsAnalog, rhs.m_ownsAnalog);
+
+  return *this;
+}
+
+void AnalogTrigger::SetLimitsVoltage(double lower, double upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsVoltage(m_trigger, lower, upper, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void AnalogTrigger::SetLimitsRaw(int lower, int upper) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerLimitsRaw(m_trigger, lower, upper, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void AnalogTrigger::SetAveraged(bool useAveragedValue) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerAveraged(m_trigger, useAveragedValue, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void AnalogTrigger::SetFiltered(bool useFilteredValue) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetAnalogTriggerFiltered(m_trigger, useFilteredValue, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int AnalogTrigger::GetIndex() const {
+  if (StatusIsFatal()) return -1;
+  return m_index;
+}
+
+bool AnalogTrigger::GetInWindow() {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerInWindow(m_trigger, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return result;
+}
+
+bool AnalogTrigger::GetTriggerState() {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerTriggerState(m_trigger, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return result;
+}
+
+std::shared_ptr<AnalogTriggerOutput> AnalogTrigger::CreateOutput(
+    AnalogTriggerType type) const {
+  if (StatusIsFatal()) return nullptr;
+  return std::shared_ptr<AnalogTriggerOutput>(
+      new AnalogTriggerOutput(*this, type), NullDeleter<AnalogTriggerOutput>());
+}
+
+void AnalogTrigger::InitSendable(SendableBuilder& builder) {
+  if (m_ownsAnalog) m_analogInput->InitSendable(builder);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp
new file mode 100644
index 0000000..b2a8cd5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/AnalogTriggerOutput.cpp
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/AnalogTriggerOutput.h"
+
+#include <hal/HAL.h>
+
+#include "frc/AnalogTrigger.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+AnalogTriggerOutput::~AnalogTriggerOutput() {
+  if (m_interrupt != HAL_kInvalidHandle) {
+    int32_t status = 0;
+    HAL_CleanInterrupts(m_interrupt, &status);
+    // ignore status, as an invalid handle just needs to be ignored.
+    m_interrupt = HAL_kInvalidHandle;
+  }
+}
+
+bool AnalogTriggerOutput::Get() const {
+  int32_t status = 0;
+  bool result = HAL_GetAnalogTriggerOutput(
+      m_trigger.m_trigger, static_cast<HAL_AnalogTriggerType>(m_outputType),
+      &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return result;
+}
+
+HAL_Handle AnalogTriggerOutput::GetPortHandleForRouting() const {
+  return m_trigger.m_trigger;
+}
+
+AnalogTriggerType AnalogTriggerOutput::GetAnalogTriggerTypeForRouting() const {
+  return m_outputType;
+}
+
+bool AnalogTriggerOutput::IsAnalogTrigger() const { return true; }
+
+int AnalogTriggerOutput::GetChannel() const { return m_trigger.m_index; }
+
+void AnalogTriggerOutput::InitSendable(SendableBuilder&) {}
+
+AnalogTriggerOutput::AnalogTriggerOutput(const AnalogTrigger& trigger,
+                                         AnalogTriggerType outputType)
+    : m_trigger(trigger), m_outputType(outputType) {
+  HAL_Report(HALUsageReporting::kResourceType_AnalogTriggerOutput,
+             trigger.GetIndex(), static_cast<uint8_t>(outputType));
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp
new file mode 100644
index 0000000..8452e38
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/BuiltInAccelerometer.cpp
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/BuiltInAccelerometer.h"
+
+#include <hal/Accelerometer.h>
+#include <hal/HAL.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+BuiltInAccelerometer::BuiltInAccelerometer(Range range) {
+  SetRange(range);
+
+  HAL_Report(HALUsageReporting::kResourceType_Accelerometer, 0, 0,
+             "Built-in accelerometer");
+  SetName("BuiltInAccel", 0);
+}
+
+void BuiltInAccelerometer::SetRange(Range range) {
+  if (range == kRange_16G) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange, "16G range not supported (use k2G, k4G, or k8G)");
+  }
+
+  HAL_SetAccelerometerActive(false);
+  HAL_SetAccelerometerRange((HAL_AccelerometerRange)range);
+  HAL_SetAccelerometerActive(true);
+}
+
+double BuiltInAccelerometer::GetX() { return HAL_GetAccelerometerX(); }
+
+double BuiltInAccelerometer::GetY() { return HAL_GetAccelerometerY(); }
+
+double BuiltInAccelerometer::GetZ() { return HAL_GetAccelerometerZ(); }
+
+void BuiltInAccelerometer::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("3AxisAccelerometer");
+  builder.AddDoubleProperty("X", [=]() { return GetX(); }, nullptr);
+  builder.AddDoubleProperty("Y", [=]() { return GetY(); }, nullptr);
+  builder.AddDoubleProperty("Z", [=]() { return GetZ(); }, nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/CAN.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/CAN.cpp
new file mode 100644
index 0000000..f01eb3f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/CAN.cpp
@@ -0,0 +1,147 @@
+/*----------------------------------------------------------------------------*/
+/* 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/CAN.h"
+
+#include <utility>
+
+#include <hal/CAN.h>
+#include <hal/CANAPI.h>
+#include <hal/Errors.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+
+using namespace frc;
+
+CAN::CAN(int deviceId) {
+  int32_t status = 0;
+  m_handle =
+      HAL_InitializeCAN(kTeamManufacturer, deviceId, kTeamDeviceType, &status);
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_CAN, deviceId);
+}
+
+CAN::CAN(int deviceId, int deviceManufacturer, int deviceType) {
+  int32_t status = 0;
+  m_handle = HAL_InitializeCAN(
+      static_cast<HAL_CANManufacturer>(deviceManufacturer), deviceId,
+      static_cast<HAL_CANDeviceType>(deviceType), &status);
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_CAN, deviceId);
+}
+
+CAN::~CAN() {
+  if (StatusIsFatal()) return;
+  if (m_handle != HAL_kInvalidHandle) {
+    HAL_CleanCAN(m_handle);
+    m_handle = HAL_kInvalidHandle;
+  }
+}
+
+CAN::CAN(CAN&& rhs) : ErrorBase(std::move(rhs)) {
+  std::swap(m_handle, rhs.m_handle);
+}
+
+CAN& CAN::operator=(CAN&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+
+  std::swap(m_handle, rhs.m_handle);
+
+  return *this;
+}
+
+void CAN::WritePacket(const uint8_t* data, int length, int apiId) {
+  int32_t status = 0;
+  HAL_WriteCANPacket(m_handle, data, length, apiId, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void CAN::WritePacketRepeating(const uint8_t* data, int length, int apiId,
+                               int repeatMs) {
+  int32_t status = 0;
+  HAL_WriteCANPacketRepeating(m_handle, data, length, apiId, repeatMs, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void CAN::StopPacketRepeating(int apiId) {
+  int32_t status = 0;
+  HAL_StopCANPacketRepeating(m_handle, apiId, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+bool CAN::ReadPacketNew(int apiId, CANData* data) {
+  int32_t status = 0;
+  HAL_ReadCANPacketNew(m_handle, apiId, data->data, &data->length,
+                       &data->timestamp, &status);
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    return false;
+  } else {
+    return true;
+  }
+}
+
+bool CAN::ReadPacketLatest(int apiId, CANData* data) {
+  int32_t status = 0;
+  HAL_ReadCANPacketLatest(m_handle, apiId, data->data, &data->length,
+                          &data->timestamp, &status);
+  if (status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    return false;
+  } else {
+    return true;
+  }
+}
+
+bool CAN::ReadPacketTimeout(int apiId, int timeoutMs, CANData* data) {
+  int32_t status = 0;
+  HAL_ReadCANPacketTimeout(m_handle, apiId, data->data, &data->length,
+                           &data->timestamp, timeoutMs, &status);
+  if (status == HAL_CAN_TIMEOUT ||
+      status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    return false;
+  } else {
+    return true;
+  }
+}
+
+bool CAN::ReadPeriodicPacket(int apiId, int timeoutMs, int periodMs,
+                             CANData* data) {
+  int32_t status = 0;
+  HAL_ReadCANPeriodicPacket(m_handle, apiId, data->data, &data->length,
+                            &data->timestamp, timeoutMs, periodMs, &status);
+  if (status == HAL_CAN_TIMEOUT ||
+      status == HAL_ERR_CANSessionMux_MessageNotFound) {
+    return false;
+  }
+  if (status != 0) {
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+    return false;
+  } else {
+    return true;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Compressor.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Compressor.cpp
new file mode 100644
index 0000000..48e1ed6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Compressor.cpp
@@ -0,0 +1,218 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/Compressor.h"
+
+#include <hal/Compressor.h>
+#include <hal/HAL.h>
+#include <hal/Ports.h>
+#include <hal/Solenoid.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+Compressor::Compressor(int pcmID) : m_module(pcmID) {
+  int32_t status = 0;
+  m_compressorHandle = HAL_InitializeCompressor(m_module, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumPCMModules(), pcmID,
+                                 HAL_GetErrorMessage(status));
+    return;
+  }
+  SetClosedLoopControl(true);
+
+  HAL_Report(HALUsageReporting::kResourceType_Compressor, pcmID);
+  SetName("Compressor", pcmID);
+}
+
+void Compressor::Start() {
+  if (StatusIsFatal()) return;
+  SetClosedLoopControl(true);
+}
+
+void Compressor::Stop() {
+  if (StatusIsFatal()) return;
+  SetClosedLoopControl(false);
+}
+
+bool Compressor::Enabled() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressor(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetPressureSwitchValue() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorPressureSwitch(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+double Compressor::GetCompressorCurrent() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  double value;
+
+  value = HAL_GetCompressorCurrent(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+void Compressor::SetClosedLoopControl(bool on) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+
+  HAL_SetCompressorClosedLoopControl(m_compressorHandle, on, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+}
+
+bool Compressor::GetClosedLoopControl() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorClosedLoopControl(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorCurrentTooHighFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorCurrentTooHighFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorCurrentTooHighStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value =
+      HAL_GetCompressorCurrentTooHighStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorShortedStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorShortedStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorShortedFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorShortedFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorNotConnectedStickyFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorNotConnectedStickyFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+bool Compressor::GetCompressorNotConnectedFault() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value;
+
+  value = HAL_GetCompressorNotConnectedFault(m_compressorHandle, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+
+  return value;
+}
+
+void Compressor::ClearAllPCMStickyFaults() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+
+  HAL_ClearAllPCMStickyFaults(m_module, &status);
+
+  if (status) {
+    wpi_setWPIError(Timeout);
+  }
+}
+
+void Compressor::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Compressor");
+  builder.AddBooleanProperty("Enabled", [=]() { return Enabled(); },
+                             [=](bool value) {
+                               if (value)
+                                 Start();
+                               else
+                                 Stop();
+                             });
+  builder.AddBooleanProperty(
+      "Pressure switch", [=]() { return GetPressureSwitchValue(); }, nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ControllerPower.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ControllerPower.cpp
new file mode 100644
index 0000000..d3012ea
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ControllerPower.cpp
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/ControllerPower.h"
+
+#include <stdint.h>
+
+#include <hal/HAL.h>
+#include <hal/Power.h>
+
+#include "frc/ErrorBase.h"
+
+using namespace frc;
+
+double ControllerPower::GetInputVoltage() {
+  int32_t status = 0;
+  double retVal = HAL_GetVinVoltage(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double ControllerPower::GetInputCurrent() {
+  int32_t status = 0;
+  double retVal = HAL_GetVinCurrent(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double ControllerPower::GetVoltage3V3() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double ControllerPower::GetCurrent3V3() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+bool ControllerPower::GetEnabled3V3() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+int ControllerPower::GetFaultCount3V3() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double ControllerPower::GetVoltage5V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double ControllerPower::GetCurrent5V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+bool ControllerPower::GetEnabled5V() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+int ControllerPower::GetFaultCount5V() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double ControllerPower::GetVoltage6V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double ControllerPower::GetCurrent6V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+bool ControllerPower::GetEnabled6V() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+int ControllerPower::GetFaultCount6V() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Counter.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Counter.cpp
new file mode 100644
index 0000000..c97bbc5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Counter.cpp
@@ -0,0 +1,358 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Counter.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+
+#include "frc/AnalogTrigger.h"
+#include "frc/DigitalInput.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+Counter::Counter(Mode mode) {
+  int32_t status = 0;
+  m_counter = HAL_InitializeCounter((HAL_Counter_Mode)mode, &m_index, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  SetMaxPeriod(.5);
+
+  HAL_Report(HALUsageReporting::kResourceType_Counter, m_index, mode);
+  SetName("Counter", m_index);
+}
+
+Counter::Counter(int channel) : Counter(kTwoPulse) {
+  SetUpSource(channel);
+  ClearDownSource();
+}
+
+Counter::Counter(DigitalSource* source) : Counter(kTwoPulse) {
+  SetUpSource(source);
+  ClearDownSource();
+}
+
+Counter::Counter(std::shared_ptr<DigitalSource> source) : Counter(kTwoPulse) {
+  SetUpSource(source);
+  ClearDownSource();
+}
+
+Counter::Counter(const AnalogTrigger& trigger) : Counter(kTwoPulse) {
+  SetUpSource(trigger.CreateOutput(AnalogTriggerType::kState));
+  ClearDownSource();
+}
+
+Counter::Counter(EncodingType encodingType, DigitalSource* upSource,
+                 DigitalSource* downSource, bool inverted)
+    : Counter(encodingType,
+              std::shared_ptr<DigitalSource>(upSource,
+                                             NullDeleter<DigitalSource>()),
+              std::shared_ptr<DigitalSource>(downSource,
+                                             NullDeleter<DigitalSource>()),
+              inverted) {}
+
+Counter::Counter(EncodingType encodingType,
+                 std::shared_ptr<DigitalSource> upSource,
+                 std::shared_ptr<DigitalSource> downSource, bool inverted)
+    : Counter(kExternalDirection) {
+  if (encodingType != k1X && encodingType != k2X) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Counter only supports 1X and 2X quadrature decoding.");
+    return;
+  }
+  SetUpSource(upSource);
+  SetDownSource(downSource);
+  int32_t status = 0;
+
+  if (encodingType == k1X) {
+    SetUpSourceEdge(true, false);
+    HAL_SetCounterAverageSize(m_counter, 1, &status);
+  } else {
+    SetUpSourceEdge(true, true);
+    HAL_SetCounterAverageSize(m_counter, 2, &status);
+  }
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  SetDownSourceEdge(inverted, true);
+}
+
+Counter::~Counter() {
+  SetUpdateWhenEmpty(true);
+
+  int32_t status = 0;
+  HAL_FreeCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  m_counter = HAL_kInvalidHandle;
+}
+
+Counter::Counter(Counter&& rhs)
+    : ErrorBase(std::move(rhs)),
+      SendableBase(std::move(rhs)),
+      CounterBase(std::move(rhs)),
+      m_upSource(std::move(rhs.m_upSource)),
+      m_downSource(std::move(rhs.m_downSource)),
+      m_index(std::move(rhs.m_index)) {
+  std::swap(m_counter, rhs.m_counter);
+}
+
+Counter& Counter::operator=(Counter&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+  CounterBase::operator=(std::move(rhs));
+
+  m_upSource = std::move(rhs.m_upSource);
+  m_downSource = std::move(rhs.m_downSource);
+  std::swap(m_counter, rhs.m_counter);
+  m_index = std::move(rhs.m_index);
+
+  return *this;
+}
+
+void Counter::SetUpSource(int channel) {
+  if (StatusIsFatal()) return;
+  SetUpSource(std::make_shared<DigitalInput>(channel));
+  AddChild(m_upSource);
+}
+
+void Counter::SetUpSource(AnalogTrigger* analogTrigger,
+                          AnalogTriggerType triggerType) {
+  SetUpSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
+                                             NullDeleter<AnalogTrigger>()),
+              triggerType);
+}
+
+void Counter::SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                          AnalogTriggerType triggerType) {
+  if (StatusIsFatal()) return;
+  SetUpSource(analogTrigger->CreateOutput(triggerType));
+}
+
+void Counter::SetUpSource(DigitalSource* source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+void Counter::SetUpSource(std::shared_ptr<DigitalSource> source) {
+  if (StatusIsFatal()) return;
+  m_upSource = source;
+  if (m_upSource->StatusIsFatal()) {
+    CloneError(*m_upSource);
+  } else {
+    int32_t status = 0;
+    HAL_SetCounterUpSource(
+        m_counter, source->GetPortHandleForRouting(),
+        (HAL_AnalogTriggerType)source->GetAnalogTriggerTypeForRouting(),
+        &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  }
+}
+
+void Counter::SetUpSource(DigitalSource& source) {
+  SetUpSource(
+      std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
+}
+
+void Counter::SetUpSourceEdge(bool risingEdge, bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_upSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr UpSource before setting UpSourceEdge");
+  }
+  int32_t status = 0;
+  HAL_SetCounterUpSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::ClearUpSource() {
+  if (StatusIsFatal()) return;
+  m_upSource.reset();
+  int32_t status = 0;
+  HAL_ClearCounterUpSource(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetDownSource(int channel) {
+  if (StatusIsFatal()) return;
+  SetDownSource(std::make_shared<DigitalInput>(channel));
+  AddChild(m_downSource);
+}
+
+void Counter::SetDownSource(AnalogTrigger* analogTrigger,
+                            AnalogTriggerType triggerType) {
+  SetDownSource(std::shared_ptr<AnalogTrigger>(analogTrigger,
+                                               NullDeleter<AnalogTrigger>()),
+                triggerType);
+}
+
+void Counter::SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                            AnalogTriggerType triggerType) {
+  if (StatusIsFatal()) return;
+  SetDownSource(analogTrigger->CreateOutput(triggerType));
+}
+
+void Counter::SetDownSource(DigitalSource* source) {
+  SetDownSource(
+      std::shared_ptr<DigitalSource>(source, NullDeleter<DigitalSource>()));
+}
+
+void Counter::SetDownSource(DigitalSource& source) {
+  SetDownSource(
+      std::shared_ptr<DigitalSource>(&source, NullDeleter<DigitalSource>()));
+}
+
+void Counter::SetDownSource(std::shared_ptr<DigitalSource> source) {
+  if (StatusIsFatal()) return;
+  m_downSource = source;
+  if (m_downSource->StatusIsFatal()) {
+    CloneError(*m_downSource);
+  } else {
+    int32_t status = 0;
+    HAL_SetCounterDownSource(
+        m_counter, source->GetPortHandleForRouting(),
+        (HAL_AnalogTriggerType)source->GetAnalogTriggerTypeForRouting(),
+        &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  }
+}
+
+void Counter::SetDownSourceEdge(bool risingEdge, bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_downSource == nullptr) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "Must set non-nullptr DownSource before setting DownSourceEdge");
+  }
+  int32_t status = 0;
+  HAL_SetCounterDownSourceEdge(m_counter, risingEdge, fallingEdge, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::ClearDownSource() {
+  if (StatusIsFatal()) return;
+  m_downSource.reset();
+  int32_t status = 0;
+  HAL_ClearCounterDownSource(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetUpDownCounterMode() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterUpDownMode(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetExternalDirectionMode() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterExternalDirectionMode(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetSemiPeriodMode(bool highSemiPeriod) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterSemiPeriodMode(m_counter, highSemiPeriod, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetPulseLengthMode(double threshold) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterPulseLengthMode(m_counter, threshold, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetReverseDirection(bool reverseDirection) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterReverseDirection(m_counter, reverseDirection, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetSamplesToAverage(int samplesToAverage) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Average counter values must be between 1 and 127");
+  }
+  int32_t status = 0;
+  HAL_SetCounterSamplesToAverage(m_counter, samplesToAverage, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int Counter::GetSamplesToAverage() const {
+  int32_t status = 0;
+  int samples = HAL_GetCounterSamplesToAverage(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return samples;
+}
+
+int Counter::GetFPGAIndex() const { return m_index; }
+
+int Counter::Get() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+void Counter::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetCounter(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+double Counter::GetPeriod() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetCounterPeriod(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+void Counter::SetMaxPeriod(double maxPeriod) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterMaxPeriod(m_counter, maxPeriod, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Counter::SetUpdateWhenEmpty(bool enabled) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetCounterUpdateWhenEmpty(m_counter, enabled, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+bool Counter::GetStopped() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetCounterStopped(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+bool Counter::GetDirection() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetCounterDirection(m_counter, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+void Counter::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Counter");
+  builder.AddDoubleProperty("Value", [=]() { return Get(); }, nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DMC60.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DMC60.cpp
new file mode 100644
index 0000000..7dc2d8d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DMC60.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/DMC60.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+DMC60::DMC60(int channel) : PWMSpeedController(channel) {
+  /*
+   * Note that the DMC 60 uses the following bounds for PWM values. These
+   * values should work reasonably well for most controllers, but if users
+   * experience issues such as asymmetric behavior around the deadband or
+   * inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the DMC 60 User
+   * Manual available from Digilent.
+   *
+   *   2.004ms = full "forward"
+   *   1.52ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.48ms = the "low end" of the deadband range
+   *   0.997ms = full "reverse"
+   */
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_DigilentDMC60, GetChannel());
+  SetName("DMC60", GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp
new file mode 100644
index 0000000..71211b3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalGlitchFilter.cpp
@@ -0,0 +1,162 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/DigitalGlitchFilter.h"
+
+#include <algorithm>
+#include <array>
+#include <utility>
+
+#include <hal/Constants.h>
+#include <hal/DIO.h>
+#include <hal/HAL.h>
+
+#include "frc/Counter.h"
+#include "frc/Encoder.h"
+#include "frc/SensorUtil.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+std::array<bool, 3> DigitalGlitchFilter::m_filterAllocated = {
+    {false, false, false}};
+wpi::mutex DigitalGlitchFilter::m_mutex;
+
+DigitalGlitchFilter::DigitalGlitchFilter() {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  auto index =
+      std::find(m_filterAllocated.begin(), m_filterAllocated.end(), false);
+  wpi_assert(index != m_filterAllocated.end());
+
+  m_channelIndex = std::distance(m_filterAllocated.begin(), index);
+  *index = true;
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalGlitchFilter,
+             m_channelIndex);
+  SetName("DigitalGlitchFilter", m_channelIndex);
+}
+
+DigitalGlitchFilter::~DigitalGlitchFilter() {
+  if (m_channelIndex >= 0) {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_filterAllocated[m_channelIndex] = false;
+  }
+}
+
+DigitalGlitchFilter::DigitalGlitchFilter(DigitalGlitchFilter&& rhs)
+    : ErrorBase(std::move(rhs)), SendableBase(std::move(rhs)) {
+  std::swap(m_channelIndex, rhs.m_channelIndex);
+}
+
+DigitalGlitchFilter& DigitalGlitchFilter::operator=(DigitalGlitchFilter&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+
+  std::swap(m_channelIndex, rhs.m_channelIndex);
+
+  return *this;
+}
+
+void DigitalGlitchFilter::Add(DigitalSource* input) {
+  DoAdd(input, m_channelIndex + 1);
+}
+
+void DigitalGlitchFilter::DoAdd(DigitalSource* input, int requestedIndex) {
+  // Some sources from Counters and Encoders are null. By pushing the check
+  // here, we catch the issue more generally.
+  if (input) {
+    // We don't support GlitchFilters on AnalogTriggers.
+    if (input->IsAnalogTrigger()) {
+      wpi_setErrorWithContext(
+          -1, "Analog Triggers not supported for DigitalGlitchFilters");
+      return;
+    }
+    int32_t status = 0;
+    HAL_SetFilterSelect(input->GetPortHandleForRouting(), requestedIndex,
+                        &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+    // Validate that we set it correctly.
+    int actualIndex =
+        HAL_GetFilterSelect(input->GetPortHandleForRouting(), &status);
+    wpi_assertEqual(actualIndex, requestedIndex);
+
+    HAL_Report(HALUsageReporting::kResourceType_DigitalInput,
+               input->GetChannel());
+  }
+}
+
+void DigitalGlitchFilter::Add(Encoder* input) {
+  Add(input->m_aSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_bSource.get());
+}
+
+void DigitalGlitchFilter::Add(Counter* input) {
+  Add(input->m_upSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Add(input->m_downSource.get());
+}
+
+void DigitalGlitchFilter::Remove(DigitalSource* input) { DoAdd(input, 0); }
+
+void DigitalGlitchFilter::Remove(Encoder* input) {
+  Remove(input->m_aSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_bSource.get());
+}
+
+void DigitalGlitchFilter::Remove(Counter* input) {
+  Remove(input->m_upSource.get());
+  if (StatusIsFatal()) {
+    return;
+  }
+  Remove(input->m_downSource.get());
+}
+
+void DigitalGlitchFilter::SetPeriodCycles(int fpgaCycles) {
+  int32_t status = 0;
+  HAL_SetFilterPeriod(m_channelIndex, fpgaCycles, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DigitalGlitchFilter::SetPeriodNanoSeconds(uint64_t nanoseconds) {
+  int32_t status = 0;
+  int fpgaCycles =
+      nanoseconds * HAL_GetSystemClockTicksPerMicrosecond() / 4 / 1000;
+  HAL_SetFilterPeriod(m_channelIndex, fpgaCycles, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int DigitalGlitchFilter::GetPeriodCycles() {
+  int32_t status = 0;
+  int fpgaCycles = HAL_GetFilterPeriod(m_channelIndex, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  return fpgaCycles;
+}
+
+uint64_t DigitalGlitchFilter::GetPeriodNanoSeconds() {
+  int32_t status = 0;
+  int fpgaCycles = HAL_GetFilterPeriod(m_channelIndex, &status);
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  return static_cast<uint64_t>(fpgaCycles) * 1000L /
+         static_cast<uint64_t>(HAL_GetSystemClockTicksPerMicrosecond() / 4);
+}
+
+void DigitalGlitchFilter::InitSendable(SendableBuilder&) {}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalInput.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalInput.cpp
new file mode 100644
index 0000000..273e9b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalInput.cpp
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/DigitalInput.h"
+
+#include <limits>
+#include <utility>
+
+#include <hal/DIO.h>
+#include <hal/HAL.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+DigitalInput::DigitalInput(int channel) {
+  if (!SensorUtil::CheckDigitalChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Digital Channel " + wpi::Twine(channel));
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+  m_channel = channel;
+
+  int32_t status = 0;
+  m_handle = HAL_InitializeDIOPort(HAL_GetPort(channel), true, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumDigitalChannels(),
+                                 channel, HAL_GetErrorMessage(status));
+    m_handle = HAL_kInvalidHandle;
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalInput, channel);
+  SetName("DigitalInput", channel);
+}
+
+DigitalInput::~DigitalInput() {
+  if (StatusIsFatal()) return;
+  if (m_interrupt != HAL_kInvalidHandle) {
+    int32_t status = 0;
+    HAL_CleanInterrupts(m_interrupt, &status);
+    // Ignore status, as an invalid handle just needs to be ignored.
+    m_interrupt = HAL_kInvalidHandle;
+  }
+
+  HAL_FreeDIOPort(m_handle);
+}
+
+DigitalInput::DigitalInput(DigitalInput&& rhs)
+    : DigitalSource(std::move(rhs)), m_channel(std::move(rhs.m_channel)) {
+  std::swap(m_handle, rhs.m_handle);
+}
+
+DigitalInput& DigitalInput::operator=(DigitalInput&& rhs) {
+  DigitalSource::operator=(std::move(rhs));
+
+  m_channel = std::move(rhs.m_channel);
+  std::swap(m_handle, rhs.m_handle);
+
+  return *this;
+}
+
+bool DigitalInput::Get() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetDIO(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+HAL_Handle DigitalInput::GetPortHandleForRouting() const { return m_handle; }
+
+AnalogTriggerType DigitalInput::GetAnalogTriggerTypeForRouting() const {
+  return (AnalogTriggerType)0;
+}
+
+bool DigitalInput::IsAnalogTrigger() const { return false; }
+
+int DigitalInput::GetChannel() const { return m_channel; }
+
+void DigitalInput::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Digital Input");
+  builder.AddBooleanProperty("Value", [=]() { return Get(); }, nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalOutput.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalOutput.cpp
new file mode 100644
index 0000000..b05c6b1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DigitalOutput.cpp
@@ -0,0 +1,165 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/DigitalOutput.h"
+
+#include <limits>
+#include <utility>
+
+#include <hal/DIO.h>
+#include <hal/HAL.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+DigitalOutput::DigitalOutput(int channel) {
+  m_pwmGenerator = HAL_kInvalidHandle;
+  if (!SensorUtil::CheckDigitalChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Digital Channel " + wpi::Twine(channel));
+    m_channel = std::numeric_limits<int>::max();
+    return;
+  }
+  m_channel = channel;
+
+  int32_t status = 0;
+  m_handle = HAL_InitializeDIOPort(HAL_GetPort(channel), false, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumDigitalChannels(),
+                                 channel, HAL_GetErrorMessage(status));
+    m_channel = std::numeric_limits<int>::max();
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_DigitalOutput, channel);
+  SetName("DigitalOutput", channel);
+}
+
+DigitalOutput::~DigitalOutput() {
+  if (StatusIsFatal()) return;
+  // Disable the PWM in case it was running.
+  DisablePWM();
+
+  HAL_FreeDIOPort(m_handle);
+}
+
+DigitalOutput::DigitalOutput(DigitalOutput&& rhs)
+    : ErrorBase(std::move(rhs)),
+      SendableBase(std::move(rhs)),
+      m_channel(std::move(rhs.m_channel)),
+      m_pwmGenerator(std::move(rhs.m_pwmGenerator)) {
+  std::swap(m_handle, rhs.m_handle);
+}
+
+DigitalOutput& DigitalOutput::operator=(DigitalOutput&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+
+  m_channel = std::move(rhs.m_channel);
+  std::swap(m_handle, rhs.m_handle);
+  m_pwmGenerator = std::move(rhs.m_pwmGenerator);
+
+  return *this;
+}
+
+void DigitalOutput::Set(bool value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDIO(m_handle, value, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+bool DigitalOutput::Get() const {
+  if (StatusIsFatal()) return false;
+
+  int32_t status = 0;
+  bool val = HAL_GetDIO(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+int DigitalOutput::GetChannel() const { return m_channel; }
+
+void DigitalOutput::Pulse(double length) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_Pulse(m_handle, length, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+bool DigitalOutput::IsPulsing() const {
+  if (StatusIsFatal()) return false;
+
+  int32_t status = 0;
+  bool value = HAL_IsPulsing(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+void DigitalOutput::SetPWMRate(double rate) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDigitalPWMRate(rate, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DigitalOutput::EnablePWM(double initialDutyCycle) {
+  if (m_pwmGenerator != HAL_kInvalidHandle) return;
+
+  int32_t status = 0;
+
+  if (StatusIsFatal()) return;
+  m_pwmGenerator = HAL_AllocateDigitalPWM(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  if (StatusIsFatal()) return;
+  HAL_SetDigitalPWMDutyCycle(m_pwmGenerator, initialDutyCycle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  if (StatusIsFatal()) return;
+  HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, m_channel, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DigitalOutput::DisablePWM() {
+  if (StatusIsFatal()) return;
+  if (m_pwmGenerator == HAL_kInvalidHandle) return;
+
+  int32_t status = 0;
+
+  // Disable the output by routing to a dead bit.
+  HAL_SetDigitalPWMOutputChannel(m_pwmGenerator, SensorUtil::kDigitalChannels,
+                                 &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_FreeDigitalPWM(m_pwmGenerator, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  m_pwmGenerator = HAL_kInvalidHandle;
+}
+
+void DigitalOutput::UpdateDutyCycle(double dutyCycle) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetDigitalPWMDutyCycle(m_pwmGenerator, dutyCycle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void DigitalOutput::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Digital Output");
+  builder.AddBooleanProperty("Value", [=]() { return Get(); },
+                             [=](bool value) { Set(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp
new file mode 100644
index 0000000..86678aa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DoubleSolenoid.cpp
@@ -0,0 +1,186 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/DoubleSolenoid.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+#include <hal/Ports.h>
+#include <hal/Solenoid.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+DoubleSolenoid::DoubleSolenoid(int forwardChannel, int reverseChannel)
+    : DoubleSolenoid(SensorUtil::GetDefaultSolenoidModule(), forwardChannel,
+                     reverseChannel) {}
+
+DoubleSolenoid::DoubleSolenoid(int moduleNumber, int forwardChannel,
+                               int reverseChannel)
+    : SolenoidBase(moduleNumber),
+      m_forwardChannel(forwardChannel),
+      m_reverseChannel(reverseChannel) {
+  if (!SensorUtil::CheckSolenoidModule(m_moduleNumber)) {
+    wpi_setWPIErrorWithContext(ModuleIndexOutOfRange,
+                               "Solenoid Module " + wpi::Twine(m_moduleNumber));
+    return;
+  }
+  if (!SensorUtil::CheckSolenoidChannel(m_forwardChannel)) {
+    wpi_setWPIErrorWithContext(
+        ChannelIndexOutOfRange,
+        "Solenoid Channel " + wpi::Twine(m_forwardChannel));
+    return;
+  }
+  if (!SensorUtil::CheckSolenoidChannel(m_reverseChannel)) {
+    wpi_setWPIErrorWithContext(
+        ChannelIndexOutOfRange,
+        "Solenoid Channel " + wpi::Twine(m_reverseChannel));
+    return;
+  }
+  int32_t status = 0;
+  m_forwardHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, m_forwardChannel), &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumSolenoidChannels(),
+                                 forwardChannel, HAL_GetErrorMessage(status));
+    m_forwardHandle = HAL_kInvalidHandle;
+    m_reverseHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_reverseHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, m_reverseChannel), &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumSolenoidChannels(),
+                                 reverseChannel, HAL_GetErrorMessage(status));
+    // free forward solenoid
+    HAL_FreeSolenoidPort(m_forwardHandle);
+    m_forwardHandle = HAL_kInvalidHandle;
+    m_reverseHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_forwardMask = 1 << m_forwardChannel;
+  m_reverseMask = 1 << m_reverseChannel;
+
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_forwardChannel,
+             m_moduleNumber);
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_reverseChannel,
+             m_moduleNumber);
+  SetName("DoubleSolenoid", m_moduleNumber, m_forwardChannel);
+}
+
+DoubleSolenoid::~DoubleSolenoid() {
+  HAL_FreeSolenoidPort(m_forwardHandle);
+  HAL_FreeSolenoidPort(m_reverseHandle);
+}
+
+DoubleSolenoid::DoubleSolenoid(DoubleSolenoid&& rhs)
+    : SolenoidBase(std::move(rhs)),
+      m_forwardChannel(std::move(rhs.m_forwardChannel)),
+      m_reverseChannel(std::move(rhs.m_reverseChannel)),
+      m_forwardMask(std::move(rhs.m_forwardMask)),
+      m_reverseMask(std::move(rhs.m_reverseMask)) {
+  std::swap(m_forwardHandle, rhs.m_forwardHandle);
+  std::swap(m_reverseHandle, rhs.m_reverseHandle);
+}
+
+DoubleSolenoid& DoubleSolenoid::operator=(DoubleSolenoid&& rhs) {
+  SolenoidBase::operator=(std::move(rhs));
+
+  m_forwardChannel = std::move(rhs.m_forwardChannel);
+  m_reverseChannel = std::move(rhs.m_reverseChannel);
+  m_forwardMask = std::move(rhs.m_forwardMask);
+  m_reverseMask = std::move(rhs.m_reverseMask);
+  std::swap(m_forwardHandle, rhs.m_forwardHandle);
+  std::swap(m_reverseHandle, rhs.m_reverseHandle);
+
+  return *this;
+}
+
+void DoubleSolenoid::Set(Value value) {
+  if (StatusIsFatal()) return;
+
+  bool forward = false;
+  bool reverse = false;
+  switch (value) {
+    case kOff:
+      forward = false;
+      reverse = false;
+      break;
+    case kForward:
+      forward = true;
+      reverse = false;
+      break;
+    case kReverse:
+      forward = false;
+      reverse = true;
+      break;
+  }
+  int fstatus = 0;
+  HAL_SetSolenoid(m_forwardHandle, forward, &fstatus);
+  int rstatus = 0;
+  HAL_SetSolenoid(m_reverseHandle, reverse, &rstatus);
+
+  wpi_setErrorWithContext(fstatus, HAL_GetErrorMessage(fstatus));
+  wpi_setErrorWithContext(rstatus, HAL_GetErrorMessage(rstatus));
+}
+
+DoubleSolenoid::Value DoubleSolenoid::Get() const {
+  if (StatusIsFatal()) return kOff;
+  int fstatus = 0;
+  int rstatus = 0;
+  bool valueForward = HAL_GetSolenoid(m_forwardHandle, &fstatus);
+  bool valueReverse = HAL_GetSolenoid(m_reverseHandle, &rstatus);
+
+  wpi_setErrorWithContext(fstatus, HAL_GetErrorMessage(fstatus));
+  wpi_setErrorWithContext(rstatus, HAL_GetErrorMessage(rstatus));
+
+  if (valueForward) return kForward;
+  if (valueReverse) return kReverse;
+  return kOff;
+}
+
+bool DoubleSolenoid::IsFwdSolenoidBlackListed() const {
+  int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
+  return (blackList & m_forwardMask) != 0;
+}
+
+bool DoubleSolenoid::IsRevSolenoidBlackListed() const {
+  int blackList = GetPCMSolenoidBlackList(m_moduleNumber);
+  return (blackList & m_reverseMask) != 0;
+}
+
+void DoubleSolenoid::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Double Solenoid");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { Set(kOff); });
+  builder.AddSmallStringProperty(
+      "Value",
+      [=](wpi::SmallVectorImpl<char>& buf) -> wpi::StringRef {
+        switch (Get()) {
+          case kForward:
+            return "Forward";
+          case kReverse:
+            return "Reverse";
+          default:
+            return "Off";
+        }
+      },
+      [=](wpi::StringRef value) {
+        Value lvalue = kOff;
+        if (value == "Forward")
+          lvalue = kForward;
+        else if (value == "Reverse")
+          lvalue = kReverse;
+        Set(lvalue);
+      });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DriverStation.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DriverStation.cpp
new file mode 100644
index 0000000..3c274c6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/DriverStation.cpp
@@ -0,0 +1,621 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/DriverStation.h"
+
+#include <chrono>
+
+#include <hal/HAL.h>
+#include <hal/Power.h>
+#include <hal/cpp/Log.h>
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/SmallString.h>
+#include <wpi/StringRef.h>
+
+#include "frc/AnalogInput.h"
+#include "frc/MotorSafety.h"
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+namespace frc {
+
+class MatchDataSender {
+ public:
+  std::shared_ptr<nt::NetworkTable> table;
+  nt::NetworkTableEntry typeMetadata;
+  nt::NetworkTableEntry gameSpecificMessage;
+  nt::NetworkTableEntry eventName;
+  nt::NetworkTableEntry matchNumber;
+  nt::NetworkTableEntry replayNumber;
+  nt::NetworkTableEntry matchType;
+  nt::NetworkTableEntry alliance;
+  nt::NetworkTableEntry station;
+  nt::NetworkTableEntry controlWord;
+
+  MatchDataSender() {
+    table = nt::NetworkTableInstance::GetDefault().GetTable("FMSInfo");
+    typeMetadata = table->GetEntry(".type");
+    typeMetadata.ForceSetString("FMSInfo");
+    gameSpecificMessage = table->GetEntry("GameSpecificMessage");
+    gameSpecificMessage.ForceSetString("");
+    eventName = table->GetEntry("EventName");
+    eventName.ForceSetString("");
+    matchNumber = table->GetEntry("MatchNumber");
+    matchNumber.ForceSetDouble(0);
+    replayNumber = table->GetEntry("ReplayNumber");
+    replayNumber.ForceSetDouble(0);
+    matchType = table->GetEntry("MatchType");
+    matchType.ForceSetDouble(0);
+    alliance = table->GetEntry("IsRedAlliance");
+    alliance.ForceSetBoolean(true);
+    station = table->GetEntry("StationNumber");
+    station.ForceSetDouble(1);
+    controlWord = table->GetEntry("FMSControlData");
+    controlWord.ForceSetDouble(0);
+  }
+};
+}  // namespace frc
+
+using namespace frc;
+
+static constexpr double kJoystickUnpluggedMessageInterval = 1.0;
+
+DriverStation::~DriverStation() {
+  m_isRunning = false;
+  // Trigger a DS mutex release in case there is no driver station running.
+  HAL_ReleaseDSMutex();
+  m_dsThread.join();
+}
+
+DriverStation& DriverStation::GetInstance() {
+  static DriverStation instance;
+  return instance;
+}
+
+void DriverStation::ReportError(const wpi::Twine& error) {
+  wpi::SmallString<128> temp;
+  HAL_SendError(1, 1, 0, error.toNullTerminatedStringRef(temp).data(), "", "",
+                1);
+}
+
+void DriverStation::ReportWarning(const wpi::Twine& error) {
+  wpi::SmallString<128> temp;
+  HAL_SendError(0, 1, 0, error.toNullTerminatedStringRef(temp).data(), "", "",
+                1);
+}
+
+void DriverStation::ReportError(bool isError, int32_t code,
+                                const wpi::Twine& error,
+                                const wpi::Twine& location,
+                                const wpi::Twine& stack) {
+  wpi::SmallString<128> errorTemp;
+  wpi::SmallString<128> locationTemp;
+  wpi::SmallString<128> stackTemp;
+  HAL_SendError(isError, code, 0,
+                error.toNullTerminatedStringRef(errorTemp).data(),
+                location.toNullTerminatedStringRef(locationTemp).data(),
+                stack.toNullTerminatedStringRef(stackTemp).data(), 1);
+}
+
+bool DriverStation::GetStickButton(int stick, int button) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  if (button <= 0) {
+    ReportJoystickUnpluggedError(
+        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+    return false;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  if (button > buttons.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick Button missing, check if all controllers are plugged in");
+    return false;
+  }
+
+  return buttons.buttons & 1 << (button - 1);
+}
+
+bool DriverStation::GetStickButtonPressed(int stick, int button) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  if (button <= 0) {
+    ReportJoystickUnpluggedError(
+        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+    return false;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  if (button > buttons.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick Button missing, check if all controllers are plugged in");
+    return false;
+  }
+  std::unique_lock<wpi::mutex> lock(m_buttonEdgeMutex);
+  // If button was pressed, clear flag and return true
+  if (m_joystickButtonsPressed[stick] & 1 << (button - 1)) {
+    m_joystickButtonsPressed[stick] &= ~(1 << (button - 1));
+    return true;
+  } else {
+    return false;
+  }
+}
+
+bool DriverStation::GetStickButtonReleased(int stick, int button) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+  if (button <= 0) {
+    ReportJoystickUnpluggedError(
+        "ERROR: Button indexes begin at 1 in WPILib for C++ and Java");
+    return false;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  if (button > buttons.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick Button missing, check if all controllers are plugged in");
+    return false;
+  }
+  std::unique_lock<wpi::mutex> lock(m_buttonEdgeMutex);
+  // If button was released, clear flag and return true
+  if (m_joystickButtonsReleased[stick] & 1 << (button - 1)) {
+    m_joystickButtonsReleased[stick] &= ~(1 << (button - 1));
+    return true;
+  } else {
+    return false;
+  }
+}
+
+double DriverStation::GetStickAxis(int stick, int axis) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0.0;
+  }
+  if (axis < 0 || axis >= HAL_kMaxJoystickAxes) {
+    wpi_setWPIError(BadJoystickAxis);
+    return 0.0;
+  }
+
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(stick, &axes);
+
+  if (axis >= axes.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick Axis missing, check if all controllers are plugged in");
+    return 0.0;
+  }
+
+  return axes.axes[axis];
+}
+
+int DriverStation::GetStickPOV(int stick, int pov) {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+  if (pov < 0 || pov >= HAL_kMaxJoystickPOVs) {
+    wpi_setWPIError(BadJoystickAxis);
+    return -1;
+  }
+
+  HAL_JoystickPOVs povs;
+  HAL_GetJoystickPOVs(stick, &povs);
+
+  if (pov >= povs.count) {
+    ReportJoystickUnpluggedWarning(
+        "Joystick POV missing, check if all controllers are plugged in");
+    return -1;
+  }
+
+  return povs.povs[pov];
+}
+
+int DriverStation::GetStickButtons(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  return buttons.buttons;
+}
+
+int DriverStation::GetStickAxisCount(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  HAL_JoystickAxes axes;
+  HAL_GetJoystickAxes(stick, &axes);
+
+  return axes.count;
+}
+
+int DriverStation::GetStickPOVCount(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  HAL_JoystickPOVs povs;
+  HAL_GetJoystickPOVs(stick, &povs);
+
+  return povs.count;
+}
+
+int DriverStation::GetStickButtonCount(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return 0;
+  }
+
+  HAL_JoystickButtons buttons;
+  HAL_GetJoystickButtons(stick, &buttons);
+
+  return buttons.count;
+}
+
+bool DriverStation::GetJoystickIsXbox(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return false;
+  }
+
+  HAL_JoystickDescriptor descriptor;
+  HAL_GetJoystickDescriptor(stick, &descriptor);
+
+  return static_cast<bool>(descriptor.isXbox);
+}
+
+int DriverStation::GetJoystickType(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+
+  HAL_JoystickDescriptor descriptor;
+  HAL_GetJoystickDescriptor(stick, &descriptor);
+
+  return static_cast<int>(descriptor.type);
+}
+
+std::string DriverStation::GetJoystickName(int stick) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+  }
+
+  HAL_JoystickDescriptor descriptor;
+  HAL_GetJoystickDescriptor(stick, &descriptor);
+
+  return descriptor.name;
+}
+
+int DriverStation::GetJoystickAxisType(int stick, int axis) const {
+  if (stick < 0 || stick >= kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+    return -1;
+  }
+
+  HAL_JoystickDescriptor descriptor;
+  HAL_GetJoystickDescriptor(stick, &descriptor);
+
+  return static_cast<bool>(descriptor.axisTypes);
+}
+
+bool DriverStation::IsEnabled() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.enabled && controlWord.dsAttached;
+}
+
+bool DriverStation::IsDisabled() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return !(controlWord.enabled && controlWord.dsAttached);
+}
+
+bool DriverStation::IsAutonomous() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.autonomous;
+}
+
+bool DriverStation::IsOperatorControl() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return !(controlWord.autonomous || controlWord.test);
+}
+
+bool DriverStation::IsTest() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.test;
+}
+
+bool DriverStation::IsDSAttached() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.dsAttached;
+}
+
+bool DriverStation::IsNewControlData() const { return HAL_IsNewControlData(); }
+
+bool DriverStation::IsFMSAttached() const {
+  HAL_ControlWord controlWord;
+  HAL_GetControlWord(&controlWord);
+  return controlWord.fmsAttached;
+}
+
+bool DriverStation::IsSysActive() const {
+  int32_t status = 0;
+  bool retVal = HAL_GetSystemActive(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+bool DriverStation::IsBrownedOut() const {
+  int32_t status = 0;
+  bool retVal = HAL_GetBrownedOut(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+std::string DriverStation::GetGameSpecificMessage() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return std::string(reinterpret_cast<char*>(info.gameSpecificMessage),
+                     info.gameSpecificMessageSize);
+}
+
+std::string DriverStation::GetEventName() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return info.eventName;
+}
+
+DriverStation::MatchType DriverStation::GetMatchType() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return static_cast<DriverStation::MatchType>(info.matchType);
+}
+
+int DriverStation::GetMatchNumber() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return info.matchNumber;
+}
+
+int DriverStation::GetReplayNumber() const {
+  HAL_MatchInfo info;
+  HAL_GetMatchInfo(&info);
+  return info.replayNumber;
+}
+
+DriverStation::Alliance DriverStation::GetAlliance() const {
+  int32_t status = 0;
+  auto allianceStationID = HAL_GetAllianceStation(&status);
+  switch (allianceStationID) {
+    case HAL_AllianceStationID_kRed1:
+    case HAL_AllianceStationID_kRed2:
+    case HAL_AllianceStationID_kRed3:
+      return kRed;
+    case HAL_AllianceStationID_kBlue1:
+    case HAL_AllianceStationID_kBlue2:
+    case HAL_AllianceStationID_kBlue3:
+      return kBlue;
+    default:
+      return kInvalid;
+  }
+}
+
+int DriverStation::GetLocation() const {
+  int32_t status = 0;
+  auto allianceStationID = HAL_GetAllianceStation(&status);
+  switch (allianceStationID) {
+    case HAL_AllianceStationID_kRed1:
+    case HAL_AllianceStationID_kBlue1:
+      return 1;
+    case HAL_AllianceStationID_kRed2:
+    case HAL_AllianceStationID_kBlue2:
+      return 2;
+    case HAL_AllianceStationID_kRed3:
+    case HAL_AllianceStationID_kBlue3:
+      return 3;
+    default:
+      return 0;
+  }
+}
+
+void DriverStation::WaitForData() { WaitForData(0); }
+
+bool DriverStation::WaitForData(double timeout) {
+  auto timeoutTime =
+      std::chrono::steady_clock::now() + std::chrono::duration<double>(timeout);
+
+  std::unique_lock<wpi::mutex> lock(m_waitForDataMutex);
+  int currentCount = m_waitForDataCounter;
+  while (m_waitForDataCounter == currentCount) {
+    if (timeout > 0) {
+      auto timedOut = m_waitForDataCond.wait_until(lock, timeoutTime);
+      if (timedOut == std::cv_status::timeout) {
+        return false;
+      }
+    } else {
+      m_waitForDataCond.wait(lock);
+    }
+  }
+  return true;
+}
+
+double DriverStation::GetMatchTime() const {
+  int32_t status;
+  return HAL_GetMatchTime(&status);
+}
+
+double DriverStation::GetBatteryVoltage() const {
+  int32_t status = 0;
+  double voltage = HAL_GetVinVoltage(&status);
+  wpi_setErrorWithContext(status, "getVinVoltage");
+
+  return voltage;
+}
+
+void DriverStation::GetData() {
+  {
+    // Compute the pressed and released buttons
+    HAL_JoystickButtons currentButtons;
+    std::unique_lock<wpi::mutex> lock(m_buttonEdgeMutex);
+
+    for (int32_t i = 0; i < 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;
+
+      // If buttons were pressed and aren't now, set flags in m_buttonsReleased
+      m_joystickButtonsReleased[i] |=
+          m_previousButtonStates[i].buttons & ~currentButtons.buttons;
+
+      m_previousButtonStates[i] = currentButtons;
+    }
+  }
+
+  {
+    std::lock_guard<wpi::mutex> waitLock(m_waitForDataMutex);
+    // Nofify all threads
+    m_waitForDataCounter++;
+    m_waitForDataCond.notify_all();
+  }
+
+  SendMatchData();
+}
+
+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::ReportJoystickUnpluggedError(const wpi::Twine& message) {
+  double currentTime = Timer::GetFPGATimestamp();
+  if (currentTime > m_nextMessageTime) {
+    ReportError(message);
+    m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
+  }
+}
+
+void DriverStation::ReportJoystickUnpluggedWarning(const wpi::Twine& message) {
+  double currentTime = Timer::GetFPGATimestamp();
+  if (currentTime > m_nextMessageTime) {
+    ReportWarning(message);
+    m_nextMessageTime = currentTime + kJoystickUnpluggedMessageInterval;
+  }
+}
+
+void DriverStation::Run() {
+  m_isRunning = true;
+  int safetyCounter = 0;
+  while (m_isRunning) {
+    HAL_WaitForDSData();
+    GetData();
+
+    if (IsDisabled()) safetyCounter = 0;
+
+    if (++safetyCounter >= 4) {
+      MotorSafety::CheckMotors();
+      safetyCounter = 0;
+    }
+    if (m_userInDisabled) HAL_ObserveUserProgramDisabled();
+    if (m_userInAutonomous) HAL_ObserveUserProgramAutonomous();
+    if (m_userInTeleop) HAL_ObserveUserProgramTeleop();
+    if (m_userInTest) HAL_ObserveUserProgramTest();
+  }
+}
+
+void DriverStation::SendMatchData() {
+  int32_t status = 0;
+  HAL_AllianceStationID alliance = HAL_GetAllianceStation(&status);
+  bool isRedAlliance = false;
+  int stationNumber = 1;
+  switch (alliance) {
+    case HAL_AllianceStationID::HAL_AllianceStationID_kBlue1:
+      isRedAlliance = false;
+      stationNumber = 1;
+      break;
+    case HAL_AllianceStationID::HAL_AllianceStationID_kBlue2:
+      isRedAlliance = false;
+      stationNumber = 2;
+      break;
+    case HAL_AllianceStationID::HAL_AllianceStationID_kBlue3:
+      isRedAlliance = false;
+      stationNumber = 3;
+      break;
+    case HAL_AllianceStationID::HAL_AllianceStationID_kRed1:
+      isRedAlliance = true;
+      stationNumber = 1;
+      break;
+    case HAL_AllianceStationID::HAL_AllianceStationID_kRed2:
+      isRedAlliance = true;
+      stationNumber = 2;
+      break;
+    default:
+      isRedAlliance = true;
+      stationNumber = 3;
+      break;
+  }
+
+  HAL_MatchInfo tmpDataStore;
+  HAL_GetMatchInfo(&tmpDataStore);
+
+  m_matchDataSender->alliance.SetBoolean(isRedAlliance);
+  m_matchDataSender->station.SetDouble(stationNumber);
+  m_matchDataSender->eventName.SetString(tmpDataStore.eventName);
+  m_matchDataSender->gameSpecificMessage.SetString(
+      std::string(reinterpret_cast<char*>(tmpDataStore.gameSpecificMessage),
+                  tmpDataStore.gameSpecificMessageSize));
+  m_matchDataSender->matchNumber.SetDouble(tmpDataStore.matchNumber);
+  m_matchDataSender->replayNumber.SetDouble(tmpDataStore.replayNumber);
+  m_matchDataSender->matchType.SetDouble(
+      static_cast<int>(tmpDataStore.matchType));
+
+  HAL_ControlWord ctlWord;
+  HAL_GetControlWord(&ctlWord);
+  int32_t wordInt = 0;
+  std::memcpy(&wordInt, &ctlWord, sizeof(wordInt));
+  m_matchDataSender->controlWord.SetDouble(wordInt);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Encoder.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Encoder.cpp
new file mode 100644
index 0000000..77e7a2a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Encoder.cpp
@@ -0,0 +1,287 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Encoder.h"
+
+#include <utility>
+
+#include <hal/Encoder.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+
+#include "frc/DigitalInput.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection,
+                 EncodingType encodingType) {
+  m_aSource = std::make_shared<DigitalInput>(aChannel);
+  m_bSource = std::make_shared<DigitalInput>(bChannel);
+  InitEncoder(reverseDirection, encodingType);
+  AddChild(m_aSource);
+  AddChild(m_bSource);
+}
+
+Encoder::Encoder(DigitalSource* aSource, DigitalSource* bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(aSource, NullDeleter<DigitalSource>()),
+      m_bSource(bSource, NullDeleter<DigitalSource>()) {
+  if (m_aSource == nullptr || m_bSource == nullptr)
+    wpi_setWPIError(NullParameter);
+  else
+    InitEncoder(reverseDirection, encodingType);
+}
+
+Encoder::Encoder(DigitalSource& aSource, DigitalSource& bSource,
+                 bool reverseDirection, EncodingType encodingType)
+    : m_aSource(&aSource, NullDeleter<DigitalSource>()),
+      m_bSource(&bSource, NullDeleter<DigitalSource>()) {
+  InitEncoder(reverseDirection, encodingType);
+}
+
+Encoder::Encoder(std::shared_ptr<DigitalSource> aSource,
+                 std::shared_ptr<DigitalSource> bSource, bool reverseDirection,
+                 EncodingType encodingType)
+    : m_aSource(aSource), m_bSource(bSource) {
+  if (m_aSource == nullptr || m_bSource == nullptr)
+    wpi_setWPIError(NullParameter);
+  else
+    InitEncoder(reverseDirection, encodingType);
+}
+
+Encoder::~Encoder() {
+  int32_t status = 0;
+  HAL_FreeEncoder(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+Encoder::Encoder(Encoder&& rhs)
+    : ErrorBase(std::move(rhs)),
+      SendableBase(std::move(rhs)),
+      CounterBase(std::move(rhs)),
+      PIDSource(std::move(rhs)),
+      m_aSource(std::move(rhs.m_aSource)),
+      m_bSource(std::move(rhs.m_bSource)),
+      m_indexSource(std::move(rhs.m_indexSource)) {
+  std::swap(m_encoder, rhs.m_encoder);
+}
+
+Encoder& Encoder::operator=(Encoder&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+  CounterBase::operator=(std::move(rhs));
+  PIDSource::operator=(std::move(rhs));
+
+  m_aSource = std::move(rhs.m_aSource);
+  m_bSource = std::move(rhs.m_bSource);
+  m_indexSource = std::move(rhs.m_indexSource);
+  std::swap(m_encoder, rhs.m_encoder);
+
+  return *this;
+}
+
+int Encoder::Get() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetEncoder(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+void Encoder::Reset() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_ResetEncoder(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+double Encoder::GetPeriod() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderPeriod(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+void Encoder::SetMaxPeriod(double maxPeriod) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+bool Encoder::GetStopped() const {
+  if (StatusIsFatal()) return true;
+  int32_t status = 0;
+  bool value = HAL_GetEncoderStopped(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+bool Encoder::GetDirection() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetEncoderDirection(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+int Encoder::GetRaw() const {
+  if (StatusIsFatal()) return 0;
+  int32_t status = 0;
+  int value = HAL_GetEncoderRaw(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+int Encoder::GetEncodingScale() const {
+  int32_t status = 0;
+  int val = HAL_GetEncoderEncodingScale(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+double Encoder::GetDistance() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderDistance(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+double Encoder::GetRate() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double value = HAL_GetEncoderRate(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+void Encoder::SetMinRate(double minRate) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderMinRate(m_encoder, minRate, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Encoder::SetDistancePerPulse(double distancePerPulse) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderDistancePerPulse(m_encoder, distancePerPulse, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+double Encoder::GetDistancePerPulse() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double distancePerPulse = HAL_GetEncoderDistancePerPulse(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return distancePerPulse;
+}
+
+void Encoder::SetReverseDirection(bool reverseDirection) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetEncoderReverseDirection(m_encoder, reverseDirection, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Encoder::SetSamplesToAverage(int samplesToAverage) {
+  if (samplesToAverage < 1 || samplesToAverage > 127) {
+    wpi_setWPIErrorWithContext(
+        ParameterOutOfRange,
+        "Average counter values must be between 1 and 127");
+    return;
+  }
+  int32_t status = 0;
+  HAL_SetEncoderSamplesToAverage(m_encoder, samplesToAverage, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int Encoder::GetSamplesToAverage() const {
+  int32_t status = 0;
+  int result = HAL_GetEncoderSamplesToAverage(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return result;
+}
+
+double Encoder::PIDGet() {
+  if (StatusIsFatal()) return 0.0;
+  switch (GetPIDSourceType()) {
+    case PIDSourceType::kDisplacement:
+      return GetDistance();
+    case PIDSourceType::kRate:
+      return GetRate();
+    default:
+      return 0.0;
+  }
+}
+
+void Encoder::SetIndexSource(int channel, Encoder::IndexingType type) {
+  // Force digital input if just given an index
+  m_indexSource = std::make_shared<DigitalInput>(channel);
+  AddChild(m_indexSource);
+  SetIndexSource(*m_indexSource.get(), type);
+}
+
+void Encoder::SetIndexSource(const DigitalSource& source,
+                             Encoder::IndexingType type) {
+  int32_t status = 0;
+  HAL_SetEncoderIndexSource(
+      m_encoder, source.GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)source.GetAnalogTriggerTypeForRouting(),
+      (HAL_EncoderIndexingType)type, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int Encoder::GetFPGAIndex() const {
+  int32_t status = 0;
+  int val = HAL_GetEncoderFPGAIndex(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+void Encoder::InitSendable(SendableBuilder& builder) {
+  int32_t status = 0;
+  HAL_EncoderEncodingType type = HAL_GetEncoderEncodingType(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  if (type == HAL_EncoderEncodingType::HAL_Encoder_k4X)
+    builder.SetSmartDashboardType("Quadrature Encoder");
+  else
+    builder.SetSmartDashboardType("Encoder");
+
+  builder.AddDoubleProperty("Speed", [=]() { return GetRate(); }, nullptr);
+  builder.AddDoubleProperty("Distance", [=]() { return GetDistance(); },
+                            nullptr);
+  builder.AddDoubleProperty("Distance per Tick",
+                            [=]() { return GetDistancePerPulse(); }, nullptr);
+}
+
+void Encoder::InitEncoder(bool reverseDirection, EncodingType encodingType) {
+  int32_t status = 0;
+  m_encoder = HAL_InitializeEncoder(
+      m_aSource->GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)m_aSource->GetAnalogTriggerTypeForRouting(),
+      m_bSource->GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)m_bSource->GetAnalogTriggerTypeForRouting(),
+      reverseDirection, (HAL_EncoderEncodingType)encodingType, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_Report(HALUsageReporting::kResourceType_Encoder, GetFPGAIndex(),
+             encodingType);
+  SetName("Encoder", m_aSource->GetChannel());
+}
+
+double Encoder::DecodingScaleFactor() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double val = HAL_GetEncoderDecodingScaleFactor(m_encoder, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Error.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Error.cpp
new file mode 100644
index 0000000..f758032
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Error.cpp
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Error.h"
+
+#include <wpi/Path.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+
+using namespace frc;
+
+Error::Error(Code code, const wpi::Twine& contextMessage,
+             wpi::StringRef filename, wpi::StringRef function, int lineNumber,
+             const ErrorBase* originatingObject) {
+  Set(code, contextMessage, filename, function, lineNumber, originatingObject);
+}
+
+bool Error::operator<(const Error& rhs) const {
+  if (m_code < rhs.m_code) {
+    return true;
+  } else if (m_message < rhs.m_message) {
+    return true;
+  } else if (m_filename < rhs.m_filename) {
+    return true;
+  } else if (m_function < rhs.m_function) {
+    return true;
+  } else if (m_lineNumber < rhs.m_lineNumber) {
+    return true;
+  } else if (m_originatingObject < rhs.m_originatingObject) {
+    return true;
+  } else if (m_timestamp < rhs.m_timestamp) {
+    return true;
+  } else {
+    return false;
+  }
+}
+
+Error::Code Error::GetCode() const { return m_code; }
+
+std::string Error::GetMessage() const { return m_message; }
+
+std::string Error::GetFilename() const { return m_filename; }
+
+std::string Error::GetFunction() const { return m_function; }
+
+int Error::GetLineNumber() const { return m_lineNumber; }
+
+const ErrorBase* Error::GetOriginatingObject() const {
+  return m_originatingObject;
+}
+
+double Error::GetTimestamp() const { return m_timestamp; }
+
+void Error::Set(Code code, const wpi::Twine& contextMessage,
+                wpi::StringRef filename, wpi::StringRef function,
+                int lineNumber, const ErrorBase* originatingObject) {
+  bool report = true;
+
+  if (code == m_code && GetTime() - m_timestamp < 1) {
+    report = false;
+  }
+
+  m_code = code;
+  m_message = contextMessage.str();
+  m_filename = filename;
+  m_function = function;
+  m_lineNumber = lineNumber;
+  m_originatingObject = originatingObject;
+
+  if (report) {
+    m_timestamp = GetTime();
+    Report();
+  }
+}
+
+void Error::Report() {
+  DriverStation::ReportError(
+      true, m_code, m_message,
+      m_function + wpi::Twine(" [") + wpi::sys::path::filename(m_filename) +
+          wpi::Twine(':') + wpi::Twine(m_lineNumber) + wpi::Twine(']'),
+      GetStackTrace(4));
+}
+
+void Error::Clear() {
+  m_code = 0;
+  m_message = "";
+  m_filename = "";
+  m_function = "";
+  m_lineNumber = 0;
+  m_originatingObject = nullptr;
+  m_timestamp = 0.0;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ErrorBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ErrorBase.cpp
new file mode 100644
index 0000000..947e53b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/ErrorBase.cpp
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/ErrorBase.h"
+
+#include <cerrno>
+#include <cstdio>
+#include <cstring>
+#include <set>
+
+#include <hal/HAL.h>
+#include <wpi/Format.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#define WPI_ERRORS_DEFINE_STRINGS
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+static wpi::mutex globalErrorsMutex;
+static std::set<Error> globalErrors;
+
+ErrorBase::ErrorBase() { HAL_Initialize(500, 0); }
+
+Error& ErrorBase::GetError() { return m_error; }
+
+const Error& ErrorBase::GetError() const { return m_error; }
+
+void ErrorBase::ClearError() const { m_error.Clear(); }
+
+void ErrorBase::SetErrnoError(const wpi::Twine& contextMessage,
+                              wpi::StringRef filename, wpi::StringRef function,
+                              int lineNumber) const {
+  wpi::SmallString<128> buf;
+  wpi::raw_svector_ostream err(buf);
+  int errNo = errno;
+  if (errNo == 0) {
+    err << "OK: ";
+  } else {
+    err << std::strerror(errNo) << " (" << wpi::format_hex(errNo, 10, true)
+        << "): ";
+  }
+
+  // Set the current error information for this object.
+  m_error.Set(-1, err.str() + contextMessage, filename, function, lineNumber,
+              this);
+
+  // Update the global error if there is not one already set.
+  std::lock_guard<wpi::mutex> mutex(globalErrorsMutex);
+  globalErrors.insert(m_error);
+}
+
+void ErrorBase::SetImaqError(int success, const wpi::Twine& contextMessage,
+                             wpi::StringRef filename, wpi::StringRef function,
+                             int lineNumber) const {
+  // If there was an error
+  if (success <= 0) {
+    // Set the current error information for this object.
+    m_error.Set(success, wpi::Twine(success) + ": " + contextMessage, filename,
+                function, lineNumber, this);
+
+    // Update the global error if there is not one already set.
+    std::lock_guard<wpi::mutex> mutex(globalErrorsMutex);
+    globalErrors.insert(m_error);
+  }
+}
+
+void ErrorBase::SetError(Error::Code code, const wpi::Twine& contextMessage,
+                         wpi::StringRef filename, wpi::StringRef function,
+                         int lineNumber) const {
+  //  If there was an error
+  if (code != 0) {
+    //  Set the current error information for this object.
+    m_error.Set(code, contextMessage, filename, function, lineNumber, this);
+
+    // Update the global error if there is not one already set.
+    std::lock_guard<wpi::mutex> mutex(globalErrorsMutex);
+    globalErrors.insert(m_error);
+  }
+}
+
+void ErrorBase::SetErrorRange(Error::Code code, int32_t minRange,
+                              int32_t maxRange, int32_t requestedValue,
+                              const wpi::Twine& contextMessage,
+                              wpi::StringRef filename, wpi::StringRef function,
+                              int lineNumber) const {
+  //  If there was an error
+  if (code != 0) {
+    //  Set the current error information for this object.
+    m_error.Set(code,
+                contextMessage + ", Minimum Value: " + wpi::Twine(minRange) +
+                    ", MaximumValue: " + wpi::Twine(maxRange) +
+                    ", Requested Value: " + wpi::Twine(requestedValue),
+                filename, function, lineNumber, this);
+
+    // Update the global error if there is not one already set.
+    std::lock_guard<wpi::mutex> mutex(globalErrorsMutex);
+    globalErrors.insert(m_error);
+  }
+}
+
+void ErrorBase::SetWPIError(const wpi::Twine& errorMessage, Error::Code code,
+                            const wpi::Twine& contextMessage,
+                            wpi::StringRef filename, wpi::StringRef function,
+                            int lineNumber) const {
+  //  Set the current error information for this object.
+  m_error.Set(code, errorMessage + ": " + contextMessage, filename, function,
+              lineNumber, this);
+
+  // Update the global error if there is not one already set.
+  std::lock_guard<wpi::mutex> mutex(globalErrorsMutex);
+  globalErrors.insert(m_error);
+}
+
+void ErrorBase::CloneError(const ErrorBase& rhs) const {
+  m_error = rhs.GetError();
+}
+
+bool ErrorBase::StatusIsFatal() const { return m_error.GetCode() < 0; }
+
+void ErrorBase::SetGlobalError(Error::Code code,
+                               const wpi::Twine& contextMessage,
+                               wpi::StringRef filename, wpi::StringRef function,
+                               int lineNumber) {
+  // If there was an error
+  if (code != 0) {
+    std::lock_guard<wpi::mutex> mutex(globalErrorsMutex);
+
+    // Set the current error information for this object.
+    globalErrors.emplace(code, contextMessage, filename, function, lineNumber,
+                         nullptr);
+  }
+}
+
+void ErrorBase::SetGlobalWPIError(const wpi::Twine& errorMessage,
+                                  const wpi::Twine& contextMessage,
+                                  wpi::StringRef filename,
+                                  wpi::StringRef function, int lineNumber) {
+  std::lock_guard<wpi::mutex> mutex(globalErrorsMutex);
+  globalErrors.emplace(-1, errorMessage + ": " + contextMessage, filename,
+                       function, lineNumber, nullptr);
+}
+
+const Error& ErrorBase::GetGlobalError() {
+  std::lock_guard<wpi::mutex> mutex(globalErrorsMutex);
+  return *globalErrors.begin();
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Filesystem.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Filesystem.cpp
new file mode 100644
index 0000000..1546050
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Filesystem.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Filesystem.h"
+
+#include <wpi/FileSystem.h>
+#include <wpi/Path.h>
+
+#include "frc/RobotBase.h"
+
+void frc::filesystem::GetLaunchDirectory(wpi::SmallVectorImpl<char>& result) {
+  wpi::sys::fs::current_path(result);
+}
+
+void frc::filesystem::GetOperatingDirectory(
+    wpi::SmallVectorImpl<char>& result) {
+  if (RobotBase::IsReal()) {
+    wpi::sys::path::native("/home/lvuser", result);
+  } else {
+    frc::filesystem::GetLaunchDirectory(result);
+  }
+}
+
+void frc::filesystem::GetDeployDirectory(wpi::SmallVectorImpl<char>& result) {
+  frc::filesystem::GetOperatingDirectory(result);
+  wpi::sys::path::append(result, "deploy");
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GamepadBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GamepadBase.cpp
new file mode 100644
index 0000000..4eeb744
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GamepadBase.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/GamepadBase.h"
+
+using namespace frc;
+
+GamepadBase::GamepadBase(int port) : GenericHID(port) {}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GearTooth.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GearTooth.cpp
new file mode 100644
index 0000000..fba5a24
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GearTooth.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/GearTooth.h"
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+constexpr double GearTooth::kGearToothThreshold;
+
+GearTooth::GearTooth(int channel, bool directionSensitive) : Counter(channel) {
+  EnableDirectionSensing(directionSensitive);
+  SetName("GearTooth", channel);
+}
+
+GearTooth::GearTooth(DigitalSource* source, bool directionSensitive)
+    : Counter(source) {
+  EnableDirectionSensing(directionSensitive);
+  SetName("GearTooth", source->GetChannel());
+}
+
+GearTooth::GearTooth(std::shared_ptr<DigitalSource> source,
+                     bool directionSensitive)
+    : Counter(source) {
+  EnableDirectionSensing(directionSensitive);
+  SetName("GearTooth", source->GetChannel());
+}
+
+void GearTooth::EnableDirectionSensing(bool directionSensitive) {
+  if (directionSensitive) {
+    SetPulseLengthMode(kGearToothThreshold);
+  }
+}
+
+void GearTooth::InitSendable(SendableBuilder& builder) {
+  Counter::InitSendable(builder);
+  builder.SetSmartDashboardType("Gear Tooth");
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GenericHID.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GenericHID.cpp
new file mode 100644
index 0000000..d1a3112
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GenericHID.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/GenericHID.h"
+
+#include <hal/HAL.h>
+
+#include "frc/DriverStation.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+GenericHID::GenericHID(int port) : m_ds(DriverStation::GetInstance()) {
+  if (port >= DriverStation::kJoystickPorts) {
+    wpi_setWPIError(BadJoystickIndex);
+  }
+  m_port = port;
+}
+
+bool GenericHID::GetRawButton(int button) const {
+  return m_ds.GetStickButton(m_port, button);
+}
+
+bool GenericHID::GetRawButtonPressed(int button) {
+  return m_ds.GetStickButtonPressed(m_port, button);
+}
+
+bool GenericHID::GetRawButtonReleased(int button) {
+  return m_ds.GetStickButtonReleased(m_port, button);
+}
+
+double GenericHID::GetRawAxis(int axis) const {
+  return m_ds.GetStickAxis(m_port, axis);
+}
+
+int GenericHID::GetPOV(int pov) const { return m_ds.GetStickPOV(m_port, pov); }
+
+int GenericHID::GetAxisCount() const { return m_ds.GetStickAxisCount(m_port); }
+
+int GenericHID::GetPOVCount() const { return m_ds.GetStickPOVCount(m_port); }
+
+int GenericHID::GetButtonCount() const {
+  return m_ds.GetStickButtonCount(m_port);
+}
+
+GenericHID::HIDType GenericHID::GetType() const {
+  return static_cast<HIDType>(m_ds.GetJoystickType(m_port));
+}
+
+std::string GenericHID::GetName() const { return m_ds.GetJoystickName(m_port); }
+
+int GenericHID::GetAxisType(int axis) const {
+  return m_ds.GetJoystickAxisType(m_port, axis);
+}
+
+int GenericHID::GetPort() const { return m_port; }
+
+void GenericHID::SetOutput(int outputNumber, bool value) {
+  m_outputs =
+      (m_outputs & ~(1 << (outputNumber - 1))) | (value << (outputNumber - 1));
+
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
+
+void GenericHID::SetOutputs(int value) {
+  m_outputs = value;
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
+
+void GenericHID::SetRumble(RumbleType type, double value) {
+  if (value < 0)
+    value = 0;
+  else if (value > 1)
+    value = 1;
+  if (type == kLeftRumble) {
+    m_leftRumble = value * 65535;
+  } else {
+    m_rightRumble = value * 65535;
+  }
+  HAL_SetJoystickOutputs(m_port, m_outputs, m_leftRumble, m_rightRumble);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GyroBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GyroBase.cpp
new file mode 100644
index 0000000..ec67675
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/GyroBase.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/GyroBase.h"
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+double GyroBase::PIDGet() {
+  switch (GetPIDSourceType()) {
+    case PIDSourceType::kRate:
+      return GetRate();
+    case PIDSourceType::kDisplacement:
+      return GetAngle();
+    default:
+      return 0;
+  }
+}
+
+void GyroBase::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Gyro");
+  builder.AddDoubleProperty("Value", [=]() { return GetAngle(); }, nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/I2C.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/I2C.cpp
new file mode 100644
index 0000000..4b18f73
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/I2C.cpp
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/I2C.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+#include <hal/I2C.h>
+
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+I2C::I2C(Port port, int deviceAddress)
+    : m_port(static_cast<HAL_I2CPort>(port)), m_deviceAddress(deviceAddress) {
+  int32_t status = 0;
+  HAL_InitializeI2C(m_port, &status);
+  // wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_Report(HALUsageReporting::kResourceType_I2C, deviceAddress);
+}
+
+I2C::~I2C() { HAL_CloseI2C(m_port); }
+
+I2C::I2C(I2C&& rhs)
+    : ErrorBase(std::move(rhs)),
+      m_deviceAddress(std::move(rhs.m_deviceAddress)) {
+  std::swap(m_port, rhs.m_port);
+}
+
+I2C& I2C::operator=(I2C&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+
+  std::swap(m_port, rhs.m_port);
+  m_deviceAddress = std::move(rhs.m_deviceAddress);
+
+  return *this;
+}
+
+bool I2C::Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived,
+                      int receiveSize) {
+  int32_t status = 0;
+  status = HAL_TransactionI2C(m_port, m_deviceAddress, dataToSend, sendSize,
+                              dataReceived, receiveSize);
+  // wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return status < 0;
+}
+
+bool I2C::AddressOnly() { return Transaction(nullptr, 0, nullptr, 0); }
+
+bool I2C::Write(int registerAddress, uint8_t data) {
+  uint8_t buffer[2];
+  buffer[0] = registerAddress;
+  buffer[1] = data;
+  int32_t status = 0;
+  status = HAL_WriteI2C(m_port, m_deviceAddress, buffer, sizeof(buffer));
+  return status < 0;
+}
+
+bool I2C::WriteBulk(uint8_t* data, int count) {
+  int32_t status = 0;
+  status = HAL_WriteI2C(m_port, m_deviceAddress, data, count);
+  return status < 0;
+}
+
+bool I2C::Read(int registerAddress, int count, uint8_t* buffer) {
+  if (count < 1) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+    return true;
+  }
+  if (buffer == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "buffer");
+    return true;
+  }
+  uint8_t regAddr = registerAddress;
+  return Transaction(&regAddr, sizeof(regAddr), buffer, count);
+}
+
+bool I2C::ReadOnly(int count, uint8_t* buffer) {
+  if (count < 1) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "count");
+    return true;
+  }
+  if (buffer == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "buffer");
+    return true;
+  }
+  return HAL_ReadI2C(m_port, m_deviceAddress, buffer, count) < 0;
+}
+
+bool I2C::VerifySensor(int registerAddress, int count,
+                       const uint8_t* expected) {
+  // TODO: Make use of all 7 read bytes
+  uint8_t deviceData[4];
+  for (int i = 0, curRegisterAddress = registerAddress; i < count;
+       i += 4, curRegisterAddress += 4) {
+    int toRead = count - i < 4 ? count - i : 4;
+    // Read the chunk of data.  Return false if the sensor does not respond.
+    if (Read(curRegisterAddress, toRead, deviceData)) return false;
+
+    for (int j = 0; j < toRead; j++) {
+      if (deviceData[j] != expected[i + j]) return false;
+    }
+  }
+  return true;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/InterruptableSensorBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/InterruptableSensorBase.cpp
new file mode 100644
index 0000000..220043f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/InterruptableSensorBase.cpp
@@ -0,0 +1,135 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/InterruptableSensorBase.h"
+
+#include <hal/HAL.h>
+
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+void InterruptableSensorBase::RequestInterrupts(
+    HAL_InterruptHandlerFunction handler, void* param) {
+  if (StatusIsFatal()) return;
+
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  AllocateInterrupts(false);
+  if (StatusIsFatal()) return;  // if allocate failed, out of interrupts
+
+  int32_t status = 0;
+  HAL_RequestInterrupts(
+      m_interrupt, GetPortHandleForRouting(),
+      static_cast<HAL_AnalogTriggerType>(GetAnalogTriggerTypeForRouting()),
+      &status);
+  SetUpSourceEdge(true, false);
+  HAL_AttachInterruptHandler(m_interrupt, handler, param, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void InterruptableSensorBase::RequestInterrupts() {
+  if (StatusIsFatal()) return;
+
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  AllocateInterrupts(true);
+  if (StatusIsFatal()) return;  // if allocate failed, out of interrupts
+
+  int32_t status = 0;
+  HAL_RequestInterrupts(
+      m_interrupt, GetPortHandleForRouting(),
+      static_cast<HAL_AnalogTriggerType>(GetAnalogTriggerTypeForRouting()),
+      &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  SetUpSourceEdge(true, false);
+}
+
+void InterruptableSensorBase::CancelInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_CleanInterrupts(m_interrupt, &status);
+  // Ignore status, as an invalid handle just needs to be ignored.
+  m_interrupt = HAL_kInvalidHandle;
+}
+
+InterruptableSensorBase::WaitResult InterruptableSensorBase::WaitForInterrupt(
+    double timeout, bool ignorePrevious) {
+  if (StatusIsFatal()) return InterruptableSensorBase::kTimeout;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  int result;
+
+  result = HAL_WaitForInterrupt(m_interrupt, timeout, ignorePrevious, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  // Rising edge result is the interrupt bit set in the byte 0xFF
+  // Falling edge result is the interrupt bit set in the byte 0xFF00
+  // Set any bit set to be true for that edge, and AND the 2 results
+  // together to match the existing enum for all interrupts
+  int32_t rising = (result & 0xFF) ? 0x1 : 0x0;
+  int32_t falling = ((result & 0xFF00) ? 0x0100 : 0x0);
+  return static_cast<WaitResult>(falling | rising);
+}
+
+void InterruptableSensorBase::EnableInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_EnableInterrupts(m_interrupt, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void InterruptableSensorBase::DisableInterrupts() {
+  if (StatusIsFatal()) return;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  HAL_DisableInterrupts(m_interrupt, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+double InterruptableSensorBase::ReadRisingTimestamp() {
+  if (StatusIsFatal()) return 0.0;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  int64_t timestamp = HAL_ReadInterruptRisingTimestamp(m_interrupt, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return timestamp * 1e-6;
+}
+
+double InterruptableSensorBase::ReadFallingTimestamp() {
+  if (StatusIsFatal()) return 0.0;
+  wpi_assert(m_interrupt != HAL_kInvalidHandle);
+  int32_t status = 0;
+  int64_t timestamp = HAL_ReadInterruptFallingTimestamp(m_interrupt, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return timestamp * 1e-6;
+}
+
+void InterruptableSensorBase::SetUpSourceEdge(bool risingEdge,
+                                              bool fallingEdge) {
+  if (StatusIsFatal()) return;
+  if (m_interrupt == HAL_kInvalidHandle) {
+    wpi_setWPIErrorWithContext(
+        NullParameter,
+        "You must call RequestInterrupts before SetUpSourceEdge");
+    return;
+  }
+  if (m_interrupt != HAL_kInvalidHandle) {
+    int32_t status = 0;
+    HAL_SetInterruptUpSourceEdge(m_interrupt, risingEdge, fallingEdge, &status);
+    wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  }
+}
+
+void InterruptableSensorBase::AllocateInterrupts(bool watcher) {
+  wpi_assert(m_interrupt == HAL_kInvalidHandle);
+  // Expects the calling leaf class to allocate an interrupt index.
+  int32_t status = 0;
+  m_interrupt = HAL_InitializeInterrupts(watcher, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/IterativeRobot.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/IterativeRobot.cpp
new file mode 100644
index 0000000..0f3add3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/IterativeRobot.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/IterativeRobot.h"
+
+#include <hal/HAL.h>
+
+#include "frc/DriverStation.h"
+
+using namespace frc;
+
+static constexpr double kPacketPeriod = 0.02;
+
+IterativeRobot::IterativeRobot() : IterativeRobotBase(kPacketPeriod) {
+  HAL_Report(HALUsageReporting::kResourceType_Framework,
+             HALUsageReporting::kFramework_Iterative);
+}
+
+void IterativeRobot::StartCompetition() {
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HAL_ObserveUserProgramStarting();
+
+  // Loop forever, calling the appropriate mode-dependent function
+  while (true) {
+    // Wait for driver station data so the loop doesn't hog the CPU
+    DriverStation::GetInstance().WaitForData();
+
+    LoopFunc();
+  }
+}
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
new file mode 100644
index 0000000..771d81f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/IterativeRobotBase.cpp
@@ -0,0 +1,167 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/IterativeRobotBase.h"
+
+#include <cstdio>
+
+#include <hal/HAL.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Timer.h"
+#include "frc/commands/Scheduler.h"
+#include "frc/livewindow/LiveWindow.h"
+#include "frc/smartdashboard/SmartDashboard.h"
+
+using namespace frc;
+
+IterativeRobotBase::IterativeRobotBase(double period)
+    : m_period(period),
+      m_watchdog(period, [this] { PrintLoopOverrunMessage(); }) {}
+
+void IterativeRobotBase::RobotInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void IterativeRobotBase::DisabledInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void IterativeRobotBase::AutonomousInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void IterativeRobotBase::TeleopInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void IterativeRobotBase::TestInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void IterativeRobotBase::RobotPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::DisabledPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::AutonomousPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::TeleopPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::TestPeriodic() {
+  static bool firstRun = true;
+  if (firstRun) {
+    wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+    firstRun = false;
+  }
+}
+
+void IterativeRobotBase::LoopFunc() {
+  m_watchdog.Reset();
+
+  // Call the appropriate function depending upon the current robot mode
+  if (IsDisabled()) {
+    // 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);
+      DisabledInit();
+      m_watchdog.AddEpoch("DisabledInit()");
+      m_lastMode = Mode::kDisabled;
+    }
+
+    HAL_ObserveUserProgramDisabled();
+    DisabledPeriodic();
+    m_watchdog.AddEpoch("DisabledPeriodic()");
+  } else if (IsAutonomous()) {
+    // 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);
+      AutonomousInit();
+      m_watchdog.AddEpoch("AutonomousInit()");
+      m_lastMode = Mode::kAutonomous;
+    }
+
+    HAL_ObserveUserProgramAutonomous();
+    AutonomousPeriodic();
+    m_watchdog.AddEpoch("AutonomousPeriodic()");
+  } else if (IsOperatorControl()) {
+    // 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);
+      TeleopInit();
+      m_watchdog.AddEpoch("TeleopInit()");
+      m_lastMode = Mode::kTeleop;
+      Scheduler::GetInstance()->SetEnabled(true);
+    }
+
+    HAL_ObserveUserProgramTeleop();
+    TeleopPeriodic();
+    m_watchdog.AddEpoch("TeleopPeriodic()");
+  } else {
+    // 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);
+      TestInit();
+      m_watchdog.AddEpoch("TestInit()");
+      m_lastMode = Mode::kTest;
+    }
+
+    HAL_ObserveUserProgramTest();
+    TestPeriodic();
+    m_watchdog.AddEpoch("TestPeriodic()");
+  }
+
+  RobotPeriodic();
+  m_watchdog.AddEpoch("RobotPeriodic()");
+  m_watchdog.Disable();
+  SmartDashboard::UpdateValues();
+
+  LiveWindow::GetInstance()->UpdateValues();
+
+  // Warn on loop time overruns
+  if (m_watchdog.IsExpired()) {
+    m_watchdog.PrintEpochs();
+  }
+}
+
+void IterativeRobotBase::PrintLoopOverrunMessage() {
+  wpi::SmallString<128> str;
+  wpi::raw_svector_ostream buf(str);
+
+  buf << "Loop time of " << m_period << "s overrun\n";
+
+  DriverStation::ReportWarning(str);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Jaguar.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Jaguar.cpp
new file mode 100644
index 0000000..7bde6ba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Jaguar.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Jaguar.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+Jaguar::Jaguar(int channel) : PWMSpeedController(channel) {
+  /* Input profile defined by Luminary Micro.
+   *
+   * Full reverse ranges from 0.671325ms to 0.6972211ms
+   * Proportional reverse ranges from 0.6972211ms to 1.4482078ms
+   * Neutral ranges from 1.4482078ms to 1.5517922ms
+   * Proportional forward ranges from 1.5517922ms to 2.3027789ms
+   * Full forward ranges from 2.3027789ms to 2.328675ms
+   */
+  SetBounds(2.31, 1.55, 1.507, 1.454, .697);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Jaguar, GetChannel());
+  SetName("Jaguar", GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Joystick.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Joystick.cpp
new file mode 100644
index 0000000..da77d94
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Joystick.cpp
@@ -0,0 +1,133 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Joystick.h"
+
+#include <cmath>
+
+#include <hal/HAL.h>
+
+#include "frc/DriverStation.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+constexpr double kPi = 3.14159265358979323846;
+
+Joystick::Joystick(int port) : GenericHID(port) {
+  m_axes[Axis::kX] = kDefaultXChannel;
+  m_axes[Axis::kY] = kDefaultYChannel;
+  m_axes[Axis::kZ] = kDefaultZChannel;
+  m_axes[Axis::kTwist] = kDefaultTwistChannel;
+  m_axes[Axis::kThrottle] = kDefaultThrottleChannel;
+
+  HAL_Report(HALUsageReporting::kResourceType_Joystick, port);
+}
+
+void Joystick::SetXChannel(int channel) { m_axes[Axis::kX] = channel; }
+
+void Joystick::SetYChannel(int channel) { m_axes[Axis::kY] = channel; }
+
+void Joystick::SetZChannel(int channel) { m_axes[Axis::kZ] = channel; }
+
+void Joystick::SetTwistChannel(int channel) { m_axes[Axis::kTwist] = channel; }
+
+void Joystick::SetThrottleChannel(int channel) {
+  m_axes[Axis::kThrottle] = channel;
+}
+
+void Joystick::SetAxisChannel(AxisType axis, int channel) {
+  m_axes[axis] = channel;
+}
+
+int Joystick::GetXChannel() const { return m_axes[Axis::kX]; }
+
+int Joystick::GetYChannel() const { return m_axes[Axis::kY]; }
+
+int Joystick::GetZChannel() const { return m_axes[Axis::kZ]; }
+
+int Joystick::GetTwistChannel() const { return m_axes[Axis::kTwist]; }
+
+int Joystick::GetThrottleChannel() const { return m_axes[Axis::kThrottle]; }
+
+double Joystick::GetX(JoystickHand hand) const {
+  return GetRawAxis(m_axes[Axis::kX]);
+}
+
+double Joystick::GetY(JoystickHand hand) const {
+  return GetRawAxis(m_axes[Axis::kY]);
+}
+
+double Joystick::GetZ() const { return GetRawAxis(m_axes[Axis::kZ]); }
+
+double Joystick::GetTwist() const { return GetRawAxis(m_axes[Axis::kTwist]); }
+
+double Joystick::GetThrottle() const {
+  return GetRawAxis(m_axes[Axis::kThrottle]);
+}
+
+double Joystick::GetAxis(AxisType axis) const {
+  switch (axis) {
+    case kXAxis:
+      return GetX();
+    case kYAxis:
+      return GetY();
+    case kZAxis:
+      return GetZ();
+    case kTwistAxis:
+      return GetTwist();
+    case kThrottleAxis:
+      return GetThrottle();
+    default:
+      wpi_setWPIError(BadJoystickAxis);
+      return 0.0;
+  }
+}
+
+bool Joystick::GetTrigger() const { return GetRawButton(Button::kTrigger); }
+
+bool Joystick::GetTriggerPressed() {
+  return GetRawButtonPressed(Button::kTrigger);
+}
+
+bool Joystick::GetTriggerReleased() {
+  return GetRawButtonReleased(Button::kTrigger);
+}
+
+bool Joystick::GetTop() const { return GetRawButton(Button::kTop); }
+
+bool Joystick::GetTopPressed() { return GetRawButtonPressed(Button::kTop); }
+
+bool Joystick::GetTopReleased() { return GetRawButtonReleased(Button::kTop); }
+
+Joystick* Joystick::GetStickForPort(int port) {
+  static std::array<std::unique_ptr<Joystick>, DriverStation::kJoystickPorts>
+      joysticks{};
+  auto stick = joysticks[port].get();
+  if (stick == nullptr) {
+    joysticks[port] = std::make_unique<Joystick>(port);
+    stick = joysticks[port].get();
+  }
+  return stick;
+}
+
+bool Joystick::GetButton(ButtonType button) const {
+  int temp = button;
+  return GetRawButton(static_cast<Button>(temp));
+}
+
+double Joystick::GetMagnitude() const {
+  return std::sqrt(std::pow(GetX(), 2) + std::pow(GetY(), 2));
+}
+
+double Joystick::GetDirectionRadians() const {
+  return std::atan2(GetX(), -GetY());
+}
+
+double Joystick::GetDirectionDegrees() const {
+  return (180 / kPi) * GetDirectionRadians();
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/JoystickBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/JoystickBase.cpp
new file mode 100644
index 0000000..8e6858c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/JoystickBase.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/JoystickBase.h"
+
+using namespace frc;
+
+JoystickBase::JoystickBase(int port) : GenericHID(port) {}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/MotorSafety.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/MotorSafety.cpp
new file mode 100644
index 0000000..aff85d8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/MotorSafety.cpp
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/MotorSafety.h"
+
+#include <algorithm>
+#include <utility>
+
+#include <wpi/SmallPtrSet.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/DriverStation.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+static wpi::SmallPtrSet<MotorSafety*, 32> instanceList;
+static wpi::mutex listMutex;
+
+MotorSafety::MotorSafety() {
+  std::lock_guard<wpi::mutex> lock(listMutex);
+  instanceList.insert(this);
+}
+
+MotorSafety::~MotorSafety() {
+  std::lock_guard<wpi::mutex> lock(listMutex);
+  instanceList.erase(this);
+}
+
+MotorSafety::MotorSafety(MotorSafety&& rhs)
+    : ErrorBase(std::move(rhs)),
+      m_expiration(std::move(rhs.m_expiration)),
+      m_enabled(std::move(rhs.m_enabled)),
+      m_stopTime(std::move(rhs.m_stopTime)) {}
+
+MotorSafety& MotorSafety::operator=(MotorSafety&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+
+  m_expiration = std::move(rhs.m_expiration);
+  m_enabled = std::move(rhs.m_enabled);
+  m_stopTime = std::move(rhs.m_stopTime);
+
+  return *this;
+}
+
+void MotorSafety::Feed() {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_stopTime = Timer::GetFPGATimestamp() + m_expiration;
+}
+
+void MotorSafety::SetExpiration(double expirationTime) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_expiration = expirationTime;
+}
+
+double MotorSafety::GetExpiration() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_expiration;
+}
+
+bool MotorSafety::IsAlive() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return !m_enabled || m_stopTime > Timer::GetFPGATimestamp();
+}
+
+void MotorSafety::SetSafetyEnabled(bool enabled) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_enabled = enabled;
+}
+
+bool MotorSafety::IsSafetyEnabled() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_enabled;
+}
+
+void MotorSafety::Check() {
+  bool enabled;
+  double stopTime;
+
+  {
+    std::lock_guard<wpi::mutex> lock(m_thisMutex);
+    enabled = m_enabled;
+    stopTime = m_stopTime;
+  }
+
+  DriverStation& ds = DriverStation::GetInstance();
+  if (!enabled || ds.IsDisabled() || ds.IsTest()) {
+    return;
+  }
+
+  if (stopTime < Timer::GetFPGATimestamp()) {
+    wpi::SmallString<128> buf;
+    wpi::raw_svector_ostream desc(buf);
+    GetDescription(desc);
+    desc << "... Output not updated often enough.";
+    wpi_setWPIErrorWithContext(Timeout, desc.str());
+    StopMotor();
+  }
+}
+
+void MotorSafety::CheckMotors() {
+  std::lock_guard<wpi::mutex> lock(listMutex);
+  for (auto elem : instanceList) {
+    elem->Check();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/NidecBrushless.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/NidecBrushless.cpp
new file mode 100644
index 0000000..0ccc7c7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/NidecBrushless.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/NidecBrushless.h"
+
+#include <hal/HAL.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+NidecBrushless::NidecBrushless(int pwmChannel, int dioChannel)
+    : m_dio(dioChannel), m_pwm(pwmChannel) {
+  AddChild(&m_dio);
+  AddChild(&m_pwm);
+  SetExpiration(0.0);
+  SetSafetyEnabled(false);
+
+  // the dio controls the output (in PWM mode)
+  m_dio.SetPWMRate(15625);
+  m_dio.EnablePWM(0.5);
+
+  HAL_Report(HALUsageReporting::kResourceType_NidecBrushless, pwmChannel);
+  SetName("Nidec Brushless", pwmChannel);
+}
+
+void NidecBrushless::Set(double speed) {
+  if (!m_disabled) {
+    m_speed = speed;
+    m_dio.UpdateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
+    m_pwm.SetRaw(0xffff);
+  }
+  Feed();
+}
+
+double NidecBrushless::Get() const { return m_speed; }
+
+void NidecBrushless::SetInverted(bool isInverted) { m_isInverted = isInverted; }
+
+bool NidecBrushless::GetInverted() const { return m_isInverted; }
+
+void NidecBrushless::Disable() {
+  m_disabled = true;
+  m_dio.UpdateDutyCycle(0.5);
+  m_pwm.SetDisabled();
+}
+
+void NidecBrushless::Enable() { m_disabled = false; }
+
+void NidecBrushless::PIDWrite(double output) { Set(output); }
+
+void NidecBrushless::StopMotor() {
+  m_dio.UpdateDutyCycle(0.5);
+  m_pwm.SetDisabled();
+}
+
+void NidecBrushless::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "Nidec " << GetChannel();
+}
+
+int NidecBrushless::GetChannel() const { return m_pwm.GetChannel(); }
+
+void NidecBrushless::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Nidec Brushless");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { StopMotor(); });
+  builder.AddDoubleProperty("Value", [=]() { return Get(); },
+                            [=](double value) { Set(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Notifier.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Notifier.cpp
new file mode 100644
index 0000000..69a9f4e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Notifier.cpp
@@ -0,0 +1,131 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Notifier.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+Notifier::Notifier(TimerEventHandler handler) {
+  if (handler == nullptr)
+    wpi_setWPIErrorWithContext(NullParameter, "handler must not be nullptr");
+  m_handler = handler;
+  int32_t status = 0;
+  m_notifier = HAL_InitializeNotifier(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  m_thread = std::thread([=] {
+    for (;;) {
+      int32_t status = 0;
+      HAL_NotifierHandle notifier = m_notifier.load();
+      if (notifier == 0) break;
+      uint64_t curTime = HAL_WaitForNotifierAlarm(notifier, &status);
+      if (curTime == 0 || status != 0) break;
+
+      TimerEventHandler handler;
+      {
+        std::lock_guard<wpi::mutex> lock(m_processMutex);
+        handler = m_handler;
+        if (m_periodic) {
+          m_expirationTime += m_period;
+          UpdateAlarm();
+        } else {
+          // need to update the alarm to cause it to wait again
+          UpdateAlarm(UINT64_MAX);
+        }
+      }
+
+      // call callback
+      if (handler) handler();
+    }
+  });
+}
+
+Notifier::~Notifier() {
+  int32_t status = 0;
+  // atomically set handle to 0, then clean
+  HAL_NotifierHandle handle = m_notifier.exchange(0);
+  HAL_StopNotifier(handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  // Join the thread to ensure the handler has exited.
+  if (m_thread.joinable()) m_thread.join();
+
+  HAL_CleanNotifier(handle, &status);
+}
+
+Notifier::Notifier(Notifier&& rhs)
+    : ErrorBase(std::move(rhs)),
+      m_thread(std::move(rhs.m_thread)),
+      m_notifier(rhs.m_notifier.load()),
+      m_handler(std::move(rhs.m_handler)),
+      m_expirationTime(std::move(rhs.m_expirationTime)),
+      m_period(std::move(rhs.m_period)),
+      m_periodic(std::move(rhs.m_periodic)) {
+  rhs.m_notifier = HAL_kInvalidHandle;
+}
+
+Notifier& Notifier::operator=(Notifier&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+
+  m_thread = std::move(rhs.m_thread);
+  m_notifier = rhs.m_notifier.load();
+  rhs.m_notifier = HAL_kInvalidHandle;
+  m_handler = std::move(rhs.m_handler);
+  m_expirationTime = std::move(rhs.m_expirationTime);
+  m_period = std::move(rhs.m_period);
+  m_periodic = std::move(rhs.m_periodic);
+
+  return *this;
+}
+
+void Notifier::SetHandler(TimerEventHandler handler) {
+  std::lock_guard<wpi::mutex> lock(m_processMutex);
+  m_handler = handler;
+}
+
+void Notifier::StartSingle(double delay) {
+  std::lock_guard<wpi::mutex> lock(m_processMutex);
+  m_periodic = false;
+  m_period = delay;
+  m_expirationTime = Timer::GetFPGATimestamp() + m_period;
+  UpdateAlarm();
+}
+
+void Notifier::StartPeriodic(double period) {
+  std::lock_guard<wpi::mutex> lock(m_processMutex);
+  m_periodic = true;
+  m_period = period;
+  m_expirationTime = Timer::GetFPGATimestamp() + m_period;
+  UpdateAlarm();
+}
+
+void Notifier::Stop() {
+  int32_t status = 0;
+  HAL_CancelNotifierAlarm(m_notifier, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Notifier::UpdateAlarm(uint64_t triggerTime) {
+  int32_t status = 0;
+  // Return if we are being destructed, or were not created successfully
+  auto notifier = m_notifier.load();
+  if (notifier == 0) return;
+  HAL_UpdateNotifierAlarm(notifier, triggerTime, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Notifier::UpdateAlarm() {
+  UpdateAlarm(static_cast<uint64_t>(m_expirationTime * 1e6));
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDBase.cpp
new file mode 100644
index 0000000..872a45a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDBase.cpp
@@ -0,0 +1,360 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/PIDBase.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/HAL.h>
+
+#include "frc/PIDOutput.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+template <class T>
+constexpr const T& clamp(const T& value, const T& low, const T& high) {
+  return std::max(low, std::min(value, high));
+}
+
+PIDBase::PIDBase(double Kp, double Ki, double Kd, PIDSource& source,
+                 PIDOutput& output)
+    : PIDBase(Kp, Ki, Kd, 0.0, source, output) {}
+
+PIDBase::PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource& source,
+                 PIDOutput& output)
+    : SendableBase(false) {
+  m_P = Kp;
+  m_I = Ki;
+  m_D = Kd;
+  m_F = Kf;
+
+  // Save original source
+  m_origSource = std::shared_ptr<PIDSource>(&source, NullDeleter<PIDSource>());
+
+  // Create LinearDigitalFilter with original source as its source argument
+  m_filter = LinearDigitalFilter::MovingAverage(m_origSource, 1);
+  m_pidInput = &m_filter;
+
+  m_pidOutput = &output;
+
+  m_setpointTimer.Start();
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_PIDController, instances);
+  SetName("PIDController", instances);
+}
+
+double PIDBase::Get() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_result;
+}
+
+void PIDBase::SetContinuous(bool continuous) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_continuous = continuous;
+}
+
+void PIDBase::SetInputRange(double minimumInput, double maximumInput) {
+  {
+    std::lock_guard<wpi::mutex> lock(m_thisMutex);
+    m_minimumInput = minimumInput;
+    m_maximumInput = maximumInput;
+    m_inputRange = maximumInput - minimumInput;
+  }
+
+  SetSetpoint(m_setpoint);
+}
+
+void PIDBase::SetOutputRange(double minimumOutput, double maximumOutput) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_minimumOutput = minimumOutput;
+  m_maximumOutput = maximumOutput;
+}
+
+void PIDBase::SetPID(double p, double i, double d) {
+  {
+    std::lock_guard<wpi::mutex> lock(m_thisMutex);
+    m_P = p;
+    m_I = i;
+    m_D = d;
+  }
+}
+
+void PIDBase::SetPID(double p, double i, double d, double f) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_P = p;
+  m_I = i;
+  m_D = d;
+  m_F = f;
+}
+
+void PIDBase::SetP(double p) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_P = p;
+}
+
+void PIDBase::SetI(double i) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_I = i;
+}
+
+void PIDBase::SetD(double d) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_D = d;
+}
+
+void PIDBase::SetF(double f) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_F = f;
+}
+
+double PIDBase::GetP() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_P;
+}
+
+double PIDBase::GetI() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_I;
+}
+
+double PIDBase::GetD() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_D;
+}
+
+double PIDBase::GetF() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_F;
+}
+
+void PIDBase::SetSetpoint(double setpoint) {
+  {
+    std::lock_guard<wpi::mutex> lock(m_thisMutex);
+
+    if (m_maximumInput > m_minimumInput) {
+      if (setpoint > m_maximumInput)
+        m_setpoint = m_maximumInput;
+      else if (setpoint < m_minimumInput)
+        m_setpoint = m_minimumInput;
+      else
+        m_setpoint = setpoint;
+    } else {
+      m_setpoint = setpoint;
+    }
+  }
+}
+
+double PIDBase::GetSetpoint() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_setpoint;
+}
+
+double PIDBase::GetDeltaSetpoint() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return (m_setpoint - m_prevSetpoint) / m_setpointTimer.Get();
+}
+
+double PIDBase::GetError() const {
+  double setpoint = GetSetpoint();
+  {
+    std::lock_guard<wpi::mutex> lock(m_thisMutex);
+    return GetContinuousError(setpoint - m_pidInput->PIDGet());
+  }
+}
+
+double PIDBase::GetAvgError() const { return GetError(); }
+
+void PIDBase::SetPIDSourceType(PIDSourceType pidSource) {
+  m_pidInput->SetPIDSourceType(pidSource);
+}
+
+PIDSourceType PIDBase::GetPIDSourceType() const {
+  return m_pidInput->GetPIDSourceType();
+}
+
+void PIDBase::SetTolerance(double percent) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_toleranceType = kPercentTolerance;
+  m_tolerance = percent;
+}
+
+void PIDBase::SetAbsoluteTolerance(double absTolerance) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_toleranceType = kAbsoluteTolerance;
+  m_tolerance = absTolerance;
+}
+
+void PIDBase::SetPercentTolerance(double percent) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_toleranceType = kPercentTolerance;
+  m_tolerance = percent;
+}
+
+void PIDBase::SetToleranceBuffer(int bufLength) {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+
+  // Create LinearDigitalFilter with original source as its source argument
+  m_filter = LinearDigitalFilter::MovingAverage(m_origSource, bufLength);
+  m_pidInput = &m_filter;
+}
+
+bool PIDBase::OnTarget() const {
+  double error = GetError();
+
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  switch (m_toleranceType) {
+    case kPercentTolerance:
+      return std::fabs(error) < m_tolerance / 100 * m_inputRange;
+      break;
+    case kAbsoluteTolerance:
+      return std::fabs(error) < m_tolerance;
+      break;
+    case kNoTolerance:
+      // TODO: this case needs an error
+      return false;
+  }
+  return false;
+}
+
+void PIDBase::Reset() {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  m_prevError = 0;
+  m_totalError = 0;
+  m_result = 0;
+}
+
+void PIDBase::PIDWrite(double output) { SetSetpoint(output); }
+
+void PIDBase::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("PIDController");
+  builder.SetSafeState([=]() { Reset(); });
+  builder.AddDoubleProperty("p", [=]() { return GetP(); },
+                            [=](double value) { SetP(value); });
+  builder.AddDoubleProperty("i", [=]() { return GetI(); },
+                            [=](double value) { SetI(value); });
+  builder.AddDoubleProperty("d", [=]() { return GetD(); },
+                            [=](double value) { SetD(value); });
+  builder.AddDoubleProperty("f", [=]() { return GetF(); },
+                            [=](double value) { SetF(value); });
+  builder.AddDoubleProperty("setpoint", [=]() { return GetSetpoint(); },
+                            [=](double value) { SetSetpoint(value); });
+}
+
+void PIDBase::Calculate() {
+  if (m_origSource == nullptr || m_pidOutput == nullptr) return;
+
+  bool enabled;
+  {
+    std::lock_guard<wpi::mutex> lock(m_thisMutex);
+    enabled = m_enabled;
+  }
+
+  if (enabled) {
+    double input;
+
+    // Storage for function inputs
+    PIDSourceType pidSourceType;
+    double P;
+    double I;
+    double D;
+    double feedForward = CalculateFeedForward();
+    double minimumOutput;
+    double maximumOutput;
+
+    // Storage for function input-outputs
+    double prevError;
+    double error;
+    double totalError;
+
+    {
+      std::lock_guard<wpi::mutex> lock(m_thisMutex);
+
+      input = m_pidInput->PIDGet();
+
+      pidSourceType = m_pidInput->GetPIDSourceType();
+      P = m_P;
+      I = m_I;
+      D = m_D;
+      minimumOutput = m_minimumOutput;
+      maximumOutput = m_maximumOutput;
+
+      prevError = m_prevError;
+      error = GetContinuousError(m_setpoint - input);
+      totalError = m_totalError;
+    }
+
+    // Storage for function outputs
+    double result;
+
+    if (pidSourceType == PIDSourceType::kRate) {
+      if (P != 0) {
+        totalError =
+            clamp(totalError + error, minimumOutput / P, maximumOutput / P);
+      }
+
+      result = D * error + P * totalError + feedForward;
+    } else {
+      if (I != 0) {
+        totalError =
+            clamp(totalError + error, minimumOutput / I, maximumOutput / I);
+      }
+
+      result =
+          P * error + I * totalError + D * (error - prevError) + feedForward;
+    }
+
+    result = clamp(result, minimumOutput, maximumOutput);
+
+    {
+      // Ensures m_enabled check and PIDWrite() call occur atomically
+      std::lock_guard<wpi::mutex> pidWriteLock(m_pidWriteMutex);
+      std::unique_lock<wpi::mutex> mainLock(m_thisMutex);
+      if (m_enabled) {
+        // Don't block other PIDBase operations on PIDWrite()
+        mainLock.unlock();
+
+        m_pidOutput->PIDWrite(result);
+      }
+    }
+
+    std::lock_guard<wpi::mutex> lock(m_thisMutex);
+    m_prevError = m_error;
+    m_error = error;
+    m_totalError = totalError;
+    m_result = result;
+  }
+}
+
+double PIDBase::CalculateFeedForward() {
+  if (m_pidInput->GetPIDSourceType() == PIDSourceType::kRate) {
+    return m_F * GetSetpoint();
+  } else {
+    double temp = m_F * GetDeltaSetpoint();
+    m_prevSetpoint = m_setpoint;
+    m_setpointTimer.Reset();
+    return temp;
+  }
+}
+
+double PIDBase::GetContinuousError(double error) const {
+  if (m_continuous && m_inputRange != 0) {
+    error = std::fmod(error, m_inputRange);
+    if (std::fabs(error) > m_inputRange / 2) {
+      if (error > 0) {
+        return error - m_inputRange;
+      } else {
+        return error + m_inputRange;
+      }
+    }
+  }
+
+  return error;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDController.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDController.cpp
new file mode 100644
index 0000000..b1c51c6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDController.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/PIDController.h"
+
+#include "frc/Notifier.h"
+#include "frc/PIDOutput.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource* source,
+                             PIDOutput* output, double period)
+    : PIDController(Kp, Ki, Kd, 0.0, *source, *output, period) {}
+
+PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
+                             PIDSource* source, PIDOutput* output,
+                             double period)
+    : PIDController(Kp, Ki, Kd, Kf, *source, *output, period) {}
+
+PIDController::PIDController(double Kp, double Ki, double Kd, PIDSource& source,
+                             PIDOutput& output, double period)
+    : PIDController(Kp, Ki, Kd, 0.0, source, output, period) {}
+
+PIDController::PIDController(double Kp, double Ki, double Kd, double Kf,
+                             PIDSource& source, PIDOutput& output,
+                             double period)
+    : PIDBase(Kp, Ki, Kd, Kf, source, output) {
+  m_controlLoop = std::make_unique<Notifier>(&PIDController::Calculate, this);
+  m_controlLoop->StartPeriodic(period);
+}
+
+PIDController::~PIDController() {
+  // Forcefully stopping the notifier so the callback can successfully run.
+  m_controlLoop->Stop();
+}
+
+void PIDController::Enable() {
+  {
+    std::lock_guard<wpi::mutex> lock(m_thisMutex);
+    m_enabled = true;
+  }
+}
+
+void PIDController::Disable() {
+  {
+    // Ensures m_enabled modification and PIDWrite() call occur atomically
+    std::lock_guard<wpi::mutex> pidWriteLock(m_pidWriteMutex);
+    {
+      std::lock_guard<wpi::mutex> mainLock(m_thisMutex);
+      m_enabled = false;
+    }
+
+    m_pidOutput->PIDWrite(0);
+  }
+}
+
+void PIDController::SetEnabled(bool enable) {
+  if (enable) {
+    Enable();
+  } else {
+    Disable();
+  }
+}
+
+bool PIDController::IsEnabled() const {
+  std::lock_guard<wpi::mutex> lock(m_thisMutex);
+  return m_enabled;
+}
+
+void PIDController::Reset() {
+  Disable();
+
+  PIDBase::Reset();
+}
+
+void PIDController::InitSendable(SendableBuilder& builder) {
+  PIDBase::InitSendable(builder);
+  builder.AddBooleanProperty("enabled", [=]() { return IsEnabled(); },
+                             [=](bool value) { SetEnabled(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDSource.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDSource.cpp
new file mode 100644
index 0000000..28291dd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PIDSource.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/PIDSource.h"
+
+using namespace frc;
+
+void PIDSource::SetPIDSourceType(PIDSourceType pidSource) {
+  m_pidSource = pidSource;
+}
+
+PIDSourceType PIDSource::GetPIDSourceType() const { return m_pidSource; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWM.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWM.cpp
new file mode 100644
index 0000000..603c94b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWM.cpp
@@ -0,0 +1,220 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/PWM.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+#include <hal/PWM.h>
+#include <hal/Ports.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+PWM::PWM(int channel) {
+  if (!SensorUtil::CheckPWMChannel(channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "PWM Channel " + wpi::Twine(channel));
+    return;
+  }
+
+  int32_t status = 0;
+  m_handle = HAL_InitializePWMPort(HAL_GetPort(channel), &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumPWMChannels(), channel,
+                                 HAL_GetErrorMessage(status));
+    m_channel = std::numeric_limits<int>::max();
+    m_handle = HAL_kInvalidHandle;
+    return;
+  }
+
+  m_channel = channel;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  status = 0;
+  HAL_SetPWMEliminateDeadband(m_handle, false, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_Report(HALUsageReporting::kResourceType_PWM, channel);
+  SetName("PWM", channel);
+
+  SetSafetyEnabled(false);
+}
+
+PWM::~PWM() {
+  int32_t status = 0;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_FreePWMPort(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+PWM::PWM(PWM&& rhs)
+    : MotorSafety(std::move(rhs)),
+      SendableBase(std::move(rhs)),
+      m_channel(std::move(rhs.m_channel)) {
+  std::swap(m_handle, rhs.m_handle);
+}
+
+PWM& PWM::operator=(PWM&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+
+  m_channel = std::move(rhs.m_channel);
+  std::swap(m_handle, rhs.m_handle);
+
+  return *this;
+}
+
+void PWM::StopMotor() { SetDisabled(); }
+
+void PWM::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "PWM " << GetChannel();
+}
+
+void PWM::SetRaw(uint16_t value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+  HAL_SetPWMRaw(m_handle, value, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+uint16_t PWM::GetRaw() const {
+  if (StatusIsFatal()) return 0;
+
+  int32_t status = 0;
+  uint16_t value = HAL_GetPWMRaw(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  return value;
+}
+
+void PWM::SetPosition(double pos) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMPosition(m_handle, pos, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+double PWM::GetPosition() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double position = HAL_GetPWMPosition(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return position;
+}
+
+void PWM::SetSpeed(double speed) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMSpeed(m_handle, speed, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  Feed();
+}
+
+double PWM::GetSpeed() const {
+  if (StatusIsFatal()) return 0.0;
+  int32_t status = 0;
+  double speed = HAL_GetPWMSpeed(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return speed;
+}
+
+void PWM::SetDisabled() {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  HAL_SetPWMDisabled(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void PWM::SetPeriodMultiplier(PeriodMultiplier mult) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  switch (mult) {
+    case kPeriodMultiplier_4X:
+      HAL_SetPWMPeriodScale(m_handle, 3,
+                            &status);  // Squelch 3 out of 4 outputs
+      break;
+    case kPeriodMultiplier_2X:
+      HAL_SetPWMPeriodScale(m_handle, 1,
+                            &status);  // Squelch 1 out of 2 outputs
+      break;
+    case kPeriodMultiplier_1X:
+      HAL_SetPWMPeriodScale(m_handle, 0, &status);  // Don't squelch any outputs
+      break;
+    default:
+      wpi_assert(false);
+  }
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void PWM::SetZeroLatch() {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  HAL_LatchPWMZero(m_handle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void PWM::EnableDeadbandElimination(bool eliminateDeadband) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMEliminateDeadband(m_handle, eliminateDeadband, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void PWM::SetBounds(double max, double deadbandMax, double center,
+                    double deadbandMin, double min) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min,
+                   &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void PWM::SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
+                       int min) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
+                      &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void PWM::GetRawBounds(int* max, int* deadbandMax, int* center,
+                       int* deadbandMin, int* min) {
+  int32_t status = 0;
+  HAL_GetPWMConfigRaw(m_handle, max, deadbandMax, center, deadbandMin, min,
+                      &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int PWM::GetChannel() const { return m_channel; }
+
+void PWM::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("PWM");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { SetDisabled(); });
+  builder.AddDoubleProperty("Value", [=]() { return GetRaw(); },
+                            [=](double value) { SetRaw(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMSpeedController.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMSpeedController.cpp
new file mode 100644
index 0000000..ea298de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMSpeedController.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/PWMSpeedController.h"
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+void PWMSpeedController::Set(double speed) {
+  SetSpeed(m_isInverted ? -speed : speed);
+}
+
+double PWMSpeedController::Get() const { return GetSpeed(); }
+
+void PWMSpeedController::SetInverted(bool isInverted) {
+  m_isInverted = isInverted;
+}
+
+bool PWMSpeedController::GetInverted() const { return m_isInverted; }
+
+void PWMSpeedController::Disable() { SetDisabled(); }
+
+void PWMSpeedController::StopMotor() { PWM::StopMotor(); }
+
+void PWMSpeedController::PIDWrite(double output) { Set(output); }
+
+PWMSpeedController::PWMSpeedController(int channel) : PWM(channel) {}
+
+void PWMSpeedController::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Speed Controller");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { SetDisabled(); });
+  builder.AddDoubleProperty("Value", [=]() { return GetSpeed(); },
+                            [=](double value) { SetSpeed(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp
new file mode 100644
index 0000000..ccb50b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMTalonSRX.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/PWMTalonSRX.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+PWMTalonSRX::PWMTalonSRX(int channel) : PWMSpeedController(channel) {
+  /* Note that the PWMTalonSRX uses the following bounds for PWM values. These
+   * values should work reasonably well for most controllers, but if users
+   * experience issues such as asymmetric behavior around the deadband or
+   * inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the TalonSRX User
+   * Manual available from Cross The Road Electronics.
+   *   2.004ms = full "forward"
+   *   1.52ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.48ms = the "low end" of the deadband range
+   *   0.997ms = full "reverse"
+   */
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_PWMTalonSRX, GetChannel());
+  SetName("PWMTalonSRX", GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp
new file mode 100644
index 0000000..b4f1fd2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PWMVictorSPX.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/PWMVictorSPX.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+PWMVictorSPX::PWMVictorSPX(int channel) : PWMSpeedController(channel) {
+  /* Note that the PWMVictorSPX uses the following bounds for PWM values. These
+   * values should work reasonably well for most controllers, but if users
+   * experience issues such as asymmetric behavior around the deadband or
+   * inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the VictorSPX User
+   * Manual available from Cross The Road Electronics.
+   *   2.004ms = full "forward"
+   *   1.52ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.48ms = the "low end" of the deadband range
+   *   0.997ms = full "reverse"
+   */
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_PWMVictorSPX, GetChannel());
+  SetName("PWMVictorSPX", GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp
new file mode 100644
index 0000000..8872028
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/PowerDistributionPanel.cpp
@@ -0,0 +1,148 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/PowerDistributionPanel.h"
+
+#include <hal/HAL.h>
+#include <hal/PDP.h>
+#include <hal/Ports.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+PowerDistributionPanel::PowerDistributionPanel() : PowerDistributionPanel(0) {}
+
+/**
+ * Initialize the PDP.
+ */
+PowerDistributionPanel::PowerDistributionPanel(int module) {
+  int32_t status = 0;
+  m_handle = HAL_InitializePDP(module, &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumPDPModules(), module,
+                                 HAL_GetErrorMessage(status));
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_PDP, module);
+  SetName("PowerDistributionPanel", module);
+}
+
+double PowerDistributionPanel::GetVoltage() const {
+  int32_t status = 0;
+
+  double voltage = HAL_GetPDPVoltage(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return voltage;
+}
+
+double PowerDistributionPanel::GetTemperature() const {
+  int32_t status = 0;
+
+  double temperature = HAL_GetPDPTemperature(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return temperature;
+}
+
+double PowerDistributionPanel::GetCurrent(int channel) const {
+  int32_t status = 0;
+
+  if (!SensorUtil::CheckPDPChannel(channel)) {
+    wpi::SmallString<32> str;
+    wpi::raw_svector_ostream buf(str);
+    buf << "PDP Channel " << channel;
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, buf.str());
+  }
+
+  double current = HAL_GetPDPChannelCurrent(m_handle, channel, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return current;
+}
+
+double PowerDistributionPanel::GetTotalCurrent() const {
+  int32_t status = 0;
+
+  double current = HAL_GetPDPTotalCurrent(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return current;
+}
+
+double PowerDistributionPanel::GetTotalPower() const {
+  int32_t status = 0;
+
+  double power = HAL_GetPDPTotalPower(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return power;
+}
+
+double PowerDistributionPanel::GetTotalEnergy() const {
+  int32_t status = 0;
+
+  double energy = HAL_GetPDPTotalEnergy(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+
+  return energy;
+}
+
+void PowerDistributionPanel::ResetTotalEnergy() {
+  int32_t status = 0;
+
+  HAL_ResetPDPTotalEnergy(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+}
+
+void PowerDistributionPanel::ClearStickyFaults() {
+  int32_t status = 0;
+
+  HAL_ClearPDPStickyFaults(m_handle, &status);
+
+  if (status) {
+    wpi_setWPIErrorWithContext(Timeout, "");
+  }
+}
+
+void PowerDistributionPanel::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("PowerDistributionPanel");
+  for (int i = 0; i < SensorUtil::kPDPChannels; ++i) {
+    builder.AddDoubleProperty("Chan" + wpi::Twine(i),
+                              [=]() { return GetCurrent(i); }, nullptr);
+  }
+  builder.AddDoubleProperty("Voltage", [=]() { return GetVoltage(); }, nullptr);
+  builder.AddDoubleProperty("TotalCurrent", [=]() { return GetTotalCurrent(); },
+                            nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Preferences.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Preferences.cpp
new file mode 100644
index 0000000..7a896d1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Preferences.cpp
@@ -0,0 +1,114 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/Preferences.h"
+
+#include <algorithm>
+
+#include <hal/HAL.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/StringRef.h>
+
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+// The Preferences table name
+static wpi::StringRef kTableName{"Preferences"};
+
+Preferences* Preferences::GetInstance() {
+  static Preferences instance;
+  return &instance;
+}
+
+std::vector<std::string> Preferences::GetKeys() { return m_table->GetKeys(); }
+
+std::string Preferences::GetString(wpi::StringRef key,
+                                   wpi::StringRef defaultValue) {
+  return m_table->GetString(key, defaultValue);
+}
+
+int Preferences::GetInt(wpi::StringRef key, int defaultValue) {
+  return static_cast<int>(m_table->GetNumber(key, defaultValue));
+}
+
+double Preferences::GetDouble(wpi::StringRef key, double defaultValue) {
+  return m_table->GetNumber(key, defaultValue);
+}
+
+float Preferences::GetFloat(wpi::StringRef key, float defaultValue) {
+  return m_table->GetNumber(key, defaultValue);
+}
+
+bool Preferences::GetBoolean(wpi::StringRef key, bool defaultValue) {
+  return m_table->GetBoolean(key, defaultValue);
+}
+
+int64_t Preferences::GetLong(wpi::StringRef key, int64_t defaultValue) {
+  return static_cast<int64_t>(m_table->GetNumber(key, defaultValue));
+}
+
+void Preferences::PutString(wpi::StringRef key, wpi::StringRef value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetString(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutInt(wpi::StringRef key, int value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetDouble(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutDouble(wpi::StringRef key, double value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetDouble(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutFloat(wpi::StringRef key, float value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetDouble(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutBoolean(wpi::StringRef key, bool value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetBoolean(value);
+  entry.SetPersistent();
+}
+
+void Preferences::PutLong(wpi::StringRef key, int64_t value) {
+  auto entry = m_table->GetEntry(key);
+  entry.SetDouble(value);
+  entry.SetPersistent();
+}
+
+bool Preferences::ContainsKey(wpi::StringRef key) {
+  return m_table->ContainsKey(key);
+}
+
+void Preferences::Remove(wpi::StringRef key) { m_table->Delete(key); }
+
+void Preferences::RemoveAll() {
+  for (auto preference : GetKeys()) {
+    if (preference != ".type") {
+      Remove(preference);
+    }
+  }
+}
+
+Preferences::Preferences()
+    : m_table(nt::NetworkTableInstance::GetDefault().GetTable(kTableName)) {
+  m_table->GetEntry(".type").SetString("RobotPreferences");
+  m_listener = m_table->AddEntryListener(
+      [=](nt::NetworkTable* table, wpi::StringRef name,
+          nt::NetworkTableEntry entry, std::shared_ptr<nt::Value> value,
+          int flags) { entry.SetPersistent(); },
+      NT_NOTIFY_NEW | NT_NOTIFY_IMMEDIATE);
+  HAL_Report(HALUsageReporting::kResourceType_Preferences, 0);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Relay.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Relay.cpp
new file mode 100644
index 0000000..9128d20
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Relay.cpp
@@ -0,0 +1,233 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Relay.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+#include <hal/Ports.h>
+#include <hal/Relay.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+Relay::Relay(int channel, Relay::Direction direction)
+    : m_channel(channel), m_direction(direction) {
+  if (!SensorUtil::CheckRelayChannel(m_channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Relay Channel " + wpi::Twine(m_channel));
+    return;
+  }
+
+  HAL_PortHandle portHandle = HAL_GetPort(channel);
+
+  if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+    int32_t status = 0;
+    m_forwardHandle = HAL_InitializeRelayPort(portHandle, true, &status);
+    if (status != 0) {
+      wpi_setErrorWithContextRange(status, 0, HAL_GetNumRelayChannels(),
+                                   channel, HAL_GetErrorMessage(status));
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+    HAL_Report(HALUsageReporting::kResourceType_Relay, m_channel);
+  }
+  if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+    int32_t status = 0;
+    m_reverseHandle = HAL_InitializeRelayPort(portHandle, false, &status);
+    if (status != 0) {
+      wpi_setErrorWithContextRange(status, 0, HAL_GetNumRelayChannels(),
+                                   channel, HAL_GetErrorMessage(status));
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+
+    HAL_Report(HALUsageReporting::kResourceType_Relay, m_channel + 128);
+  }
+
+  int32_t status = 0;
+  if (m_forwardHandle != HAL_kInvalidHandle) {
+    HAL_SetRelay(m_forwardHandle, false, &status);
+    if (status != 0) {
+      wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+  if (m_reverseHandle != HAL_kInvalidHandle) {
+    HAL_SetRelay(m_reverseHandle, false, &status);
+    if (status != 0) {
+      wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+      m_forwardHandle = HAL_kInvalidHandle;
+      m_reverseHandle = HAL_kInvalidHandle;
+      return;
+    }
+  }
+
+  SetName("Relay", m_channel);
+}
+
+Relay::~Relay() {
+  int32_t status = 0;
+  HAL_SetRelay(m_forwardHandle, false, &status);
+  HAL_SetRelay(m_reverseHandle, false, &status);
+  // ignore errors, as we want to make sure a free happens.
+  if (m_forwardHandle != HAL_kInvalidHandle) HAL_FreeRelayPort(m_forwardHandle);
+  if (m_reverseHandle != HAL_kInvalidHandle) HAL_FreeRelayPort(m_reverseHandle);
+}
+
+Relay::Relay(Relay&& rhs)
+    : MotorSafety(std::move(rhs)),
+      SendableBase(std::move(rhs)),
+      m_channel(std::move(rhs.m_channel)),
+      m_direction(std::move(rhs.m_direction)) {
+  std::swap(m_forwardHandle, rhs.m_forwardHandle);
+  std::swap(m_reverseHandle, rhs.m_reverseHandle);
+}
+
+Relay& Relay::operator=(Relay&& rhs) {
+  MotorSafety::operator=(std::move(rhs));
+  SendableBase::operator=(std::move(rhs));
+
+  m_channel = std::move(rhs.m_channel);
+  m_direction = std::move(rhs.m_direction);
+  std::swap(m_forwardHandle, rhs.m_forwardHandle);
+  std::swap(m_reverseHandle, rhs.m_reverseHandle);
+
+  return *this;
+}
+
+void Relay::Set(Relay::Value value) {
+  if (StatusIsFatal()) return;
+
+  int32_t status = 0;
+
+  switch (value) {
+    case kOff:
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, false, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, false, &status);
+      }
+      break;
+    case kOn:
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, true, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, true, &status);
+      }
+      break;
+    case kForward:
+      if (m_direction == kReverseOnly) {
+        wpi_setWPIError(IncompatibleMode);
+        break;
+      }
+      if (m_direction == kBothDirections || m_direction == kForwardOnly) {
+        HAL_SetRelay(m_forwardHandle, true, &status);
+      }
+      if (m_direction == kBothDirections) {
+        HAL_SetRelay(m_reverseHandle, false, &status);
+      }
+      break;
+    case kReverse:
+      if (m_direction == kForwardOnly) {
+        wpi_setWPIError(IncompatibleMode);
+        break;
+      }
+      if (m_direction == kBothDirections) {
+        HAL_SetRelay(m_forwardHandle, false, &status);
+      }
+      if (m_direction == kBothDirections || m_direction == kReverseOnly) {
+        HAL_SetRelay(m_reverseHandle, true, &status);
+      }
+      break;
+  }
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+Relay::Value Relay::Get() const {
+  int32_t status;
+
+  if (m_direction == kForwardOnly) {
+    if (HAL_GetRelay(m_forwardHandle, &status)) {
+      return kOn;
+    } else {
+      return kOff;
+    }
+  } else if (m_direction == kReverseOnly) {
+    if (HAL_GetRelay(m_reverseHandle, &status)) {
+      return kOn;
+    } else {
+      return kOff;
+    }
+  } else {
+    if (HAL_GetRelay(m_forwardHandle, &status)) {
+      if (HAL_GetRelay(m_reverseHandle, &status)) {
+        return kOn;
+      } else {
+        return kForward;
+      }
+    } else {
+      if (HAL_GetRelay(m_reverseHandle, &status)) {
+        return kReverse;
+      } else {
+        return kOff;
+      }
+    }
+  }
+
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int Relay::GetChannel() const { return m_channel; }
+
+void Relay::StopMotor() { Set(kOff); }
+
+void Relay::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "Relay " << GetChannel();
+}
+
+void Relay::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Relay");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { Set(kOff); });
+  builder.AddSmallStringProperty(
+      "Value",
+      [=](wpi::SmallVectorImpl<char>& buf) -> wpi::StringRef {
+        switch (Get()) {
+          case kOn:
+            return "On";
+          case kForward:
+            return "Forward";
+          case kReverse:
+            return "Reverse";
+          default:
+            return "Off";
+        }
+      },
+      [=](wpi::StringRef value) {
+        if (value == "Off")
+          Set(kOff);
+        else if (value == "Forward")
+          Set(kForward);
+        else if (value == "Reverse")
+          Set(kReverse);
+        else if (value == "On")
+          Set(kOn);
+      });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Resource.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Resource.cpp
new file mode 100644
index 0000000..e2c53d4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Resource.cpp
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Resource.h"
+
+#include "frc/ErrorBase.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+wpi::mutex Resource::m_createMutex;
+
+void Resource::CreateResourceObject(std::unique_ptr<Resource>& r,
+                                    uint32_t elements) {
+  std::lock_guard<wpi::mutex> lock(m_createMutex);
+  if (!r) {
+    r = std::make_unique<Resource>(elements);
+  }
+}
+
+Resource::Resource(uint32_t elements) {
+  m_isAllocated = std::vector<bool>(elements, false);
+}
+
+uint32_t Resource::Allocate(const std::string& resourceDesc) {
+  std::lock_guard<wpi::mutex> lock(m_allocateMutex);
+  for (uint32_t i = 0; i < m_isAllocated.size(); i++) {
+    if (!m_isAllocated[i]) {
+      m_isAllocated[i] = true;
+      return i;
+    }
+  }
+  wpi_setWPIErrorWithContext(NoAvailableResources, resourceDesc);
+  return std::numeric_limits<uint32_t>::max();
+}
+
+uint32_t Resource::Allocate(uint32_t index, const std::string& resourceDesc) {
+  std::lock_guard<wpi::mutex> lock(m_allocateMutex);
+  if (index >= m_isAllocated.size()) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange, resourceDesc);
+    return std::numeric_limits<uint32_t>::max();
+  }
+  if (m_isAllocated[index]) {
+    wpi_setWPIErrorWithContext(ResourceAlreadyAllocated, resourceDesc);
+    return std::numeric_limits<uint32_t>::max();
+  }
+  m_isAllocated[index] = true;
+  return index;
+}
+
+void Resource::Free(uint32_t index) {
+  std::unique_lock<wpi::mutex> lock(m_allocateMutex);
+  if (index == std::numeric_limits<uint32_t>::max()) return;
+  if (index >= m_isAllocated.size()) {
+    wpi_setWPIError(NotAllocated);
+    return;
+  }
+  if (!m_isAllocated[index]) {
+    wpi_setWPIError(NotAllocated);
+    return;
+  }
+  m_isAllocated[index] = false;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotBase.cpp
new file mode 100644
index 0000000..bc316f4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotBase.cpp
@@ -0,0 +1,125 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/RobotBase.h"
+
+#include <cstdio>
+
+#include <cameraserver/CameraServerShared.h>
+#include <cscore.h>
+#include <hal/HAL.h>
+#include <networktables/NetworkTableInstance.h>
+
+#include "WPILibVersion.h"
+#include "frc/DriverStation.h"
+#include "frc/RobotState.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+#include "frc/livewindow/LiveWindow.h"
+#include "frc/smartdashboard/SmartDashboard.h"
+
+using namespace frc;
+
+int frc::RunHALInitialization() {
+  if (!HAL_Initialize(500, 0)) {
+    wpi::errs() << "FATAL ERROR: HAL could not be initialized\n";
+    return -1;
+  }
+  HAL_Report(HALUsageReporting::kResourceType_Language,
+             HALUsageReporting::kLanguage_CPlusPlus);
+  wpi::outs() << "\n********** Robot program starting **********\n";
+  return 0;
+}
+
+std::thread::id RobotBase::m_threadId;
+
+namespace {
+class WPILibCameraServerShared : public frc::CameraServerShared {
+ public:
+  void ReportUsbCamera(int id) override {
+    HAL_Report(HALUsageReporting::kResourceType_UsbCamera, id);
+  }
+  void ReportAxisCamera(int id) override {
+    HAL_Report(HALUsageReporting::kResourceType_AxisCamera, id);
+  }
+  void ReportVideoServer(int id) override {
+    HAL_Report(HALUsageReporting::kResourceType_PCVideoServer, id);
+  }
+  void SetCameraServerError(const wpi::Twine& error) override {
+    wpi_setGlobalWPIErrorWithContext(CameraServerError, error);
+  }
+  void SetVisionRunnerError(const wpi::Twine& error) override {
+    wpi_setGlobalErrorWithContext(-1, error);
+  }
+  void ReportDriverStationError(const wpi::Twine& error) override {
+    DriverStation::ReportError(error);
+  }
+  std::pair<std::thread::id, bool> GetRobotMainThreadId() const override {
+    return std::make_pair(RobotBase::GetThreadId(), true);
+  }
+};
+}  // namespace
+
+static void SetupCameraServerShared() {
+  SetCameraServerShared(std::make_unique<WPILibCameraServerShared>());
+}
+
+bool RobotBase::IsEnabled() const { return m_ds.IsEnabled(); }
+
+bool RobotBase::IsDisabled() const { return m_ds.IsDisabled(); }
+
+bool RobotBase::IsAutonomous() const { return m_ds.IsAutonomous(); }
+
+bool RobotBase::IsOperatorControl() const { return m_ds.IsOperatorControl(); }
+
+bool RobotBase::IsTest() const { return m_ds.IsTest(); }
+
+bool RobotBase::IsNewDataAvailable() const { return m_ds.IsNewControlData(); }
+
+std::thread::id RobotBase::GetThreadId() { return m_threadId; }
+
+RobotBase::RobotBase() : m_ds(DriverStation::GetInstance()) {
+  if (!HAL_Initialize(500, 0)) {
+    wpi::errs() << "FATAL ERROR: HAL could not be initialized\n";
+    wpi::errs().flush();
+    std::terminate();
+  }
+  m_threadId = std::this_thread::get_id();
+
+  SetupCameraServerShared();
+
+  auto inst = nt::NetworkTableInstance::GetDefault();
+  inst.SetNetworkIdentity("Robot");
+  inst.StartServer("/home/lvuser/networktables.ini");
+
+  SmartDashboard::init();
+
+  if (IsReal()) {
+    std::FILE* file = nullptr;
+    file = std::fopen("/tmp/frc_versions/FRC_Lib_Version.ini", "w");
+
+    if (file != nullptr) {
+      std::fputs("C++ ", file);
+      std::fputs(GetWPILibVersion(), file);
+      std::fclose(file);
+    }
+  }
+
+  // First and one-time initialization
+  inst.GetTable("LiveWindow")
+      ->GetSubTable(".status")
+      ->GetEntry("LW Enabled")
+      .SetBoolean(false);
+
+  LiveWindow::GetInstance()->SetEnabled(false);
+}
+
+RobotBase::RobotBase(RobotBase&&) : m_ds(DriverStation::GetInstance()) {}
+
+RobotBase::~RobotBase() { cs::Shutdown(); }
+
+RobotBase& RobotBase::operator=(RobotBase&&) { return *this; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotController.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotController.cpp
new file mode 100644
index 0000000..347440d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotController.cpp
@@ -0,0 +1,174 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/RobotController.h"
+
+#include <hal/HAL.h>
+
+#include "frc/ErrorBase.h"
+
+using namespace frc;
+
+int RobotController::GetFPGAVersion() {
+  int32_t status = 0;
+  int version = HAL_GetFPGAVersion(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return version;
+}
+
+int64_t RobotController::GetFPGARevision() {
+  int32_t status = 0;
+  int64_t revision = HAL_GetFPGARevision(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return revision;
+}
+
+uint64_t RobotController::GetFPGATime() {
+  int32_t status = 0;
+  uint64_t time = HAL_GetFPGATime(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return time;
+}
+
+bool RobotController::GetUserButton() {
+  int32_t status = 0;
+
+  bool value = HAL_GetFPGAButton(&status);
+  wpi_setGlobalError(status);
+
+  return value;
+}
+
+bool RobotController::IsSysActive() {
+  int32_t status = 0;
+  bool retVal = HAL_GetSystemActive(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+bool RobotController::IsBrownedOut() {
+  int32_t status = 0;
+  bool retVal = HAL_GetBrownedOut(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double RobotController::GetInputVoltage() {
+  int32_t status = 0;
+  double retVal = HAL_GetVinVoltage(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double RobotController::GetInputCurrent() {
+  int32_t status = 0;
+  double retVal = HAL_GetVinCurrent(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double RobotController::GetVoltage3V3() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double RobotController::GetCurrent3V3() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+bool RobotController::GetEnabled3V3() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+int RobotController::GetFaultCount3V3() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults3V3(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double RobotController::GetVoltage5V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double RobotController::GetCurrent5V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+bool RobotController::GetEnabled5V() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+int RobotController::GetFaultCount5V() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults5V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double RobotController::GetVoltage6V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserVoltage6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+double RobotController::GetCurrent6V() {
+  int32_t status = 0;
+  double retVal = HAL_GetUserCurrent6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+bool RobotController::GetEnabled6V() {
+  int32_t status = 0;
+  bool retVal = HAL_GetUserActive6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+int RobotController::GetFaultCount6V() {
+  int32_t status = 0;
+  int retVal = HAL_GetUserCurrentFaults6V(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+CANStatus RobotController::GetCANStatus() {
+  int32_t status = 0;
+  float percentBusUtilization = 0;
+  uint32_t busOffCount = 0;
+  uint32_t txFullCount = 0;
+  uint32_t receiveErrorCount = 0;
+  uint32_t transmitErrorCount = 0;
+  HAL_CAN_GetCANStatus(&percentBusUtilization, &busOffCount, &txFullCount,
+                       &receiveErrorCount, &transmitErrorCount, &status);
+  if (status != 0) {
+    wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+    return {};
+  }
+  return {percentBusUtilization, static_cast<int>(busOffCount),
+          static_cast<int>(txFullCount), static_cast<int>(receiveErrorCount),
+          static_cast<int>(transmitErrorCount)};
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotDrive.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotDrive.cpp
new file mode 100644
index 0000000..a20eb65
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotDrive.cpp
@@ -0,0 +1,427 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/RobotDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/HAL.h>
+
+#include "frc/GenericHID.h"
+#include "frc/Joystick.h"
+#include "frc/Talon.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+static std::shared_ptr<SpeedController> make_shared_nodelete(
+    SpeedController* ptr) {
+  return std::shared_ptr<SpeedController>(ptr, NullDeleter<SpeedController>());
+}
+
+RobotDrive::RobotDrive(int leftMotorChannel, int rightMotorChannel) {
+  InitRobotDrive();
+  m_rearLeftMotor = std::make_shared<Talon>(leftMotorChannel);
+  m_rearRightMotor = std::make_shared<Talon>(rightMotorChannel);
+  SetLeftRightMotorOutputs(0.0, 0.0);
+}
+
+RobotDrive::RobotDrive(int frontLeftMotor, int rearLeftMotor,
+                       int frontRightMotor, int rearRightMotor) {
+  InitRobotDrive();
+  m_rearLeftMotor = std::make_shared<Talon>(rearLeftMotor);
+  m_rearRightMotor = std::make_shared<Talon>(rearRightMotor);
+  m_frontLeftMotor = std::make_shared<Talon>(frontLeftMotor);
+  m_frontRightMotor = std::make_shared<Talon>(frontRightMotor);
+  SetLeftRightMotorOutputs(0.0, 0.0);
+}
+
+RobotDrive::RobotDrive(SpeedController* leftMotor,
+                       SpeedController* rightMotor) {
+  InitRobotDrive();
+  if (leftMotor == nullptr || rightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_rearLeftMotor = m_rearRightMotor = nullptr;
+    return;
+  }
+  m_rearLeftMotor = make_shared_nodelete(leftMotor);
+  m_rearRightMotor = make_shared_nodelete(rightMotor);
+}
+
+RobotDrive::RobotDrive(SpeedController& leftMotor,
+                       SpeedController& rightMotor) {
+  InitRobotDrive();
+  m_rearLeftMotor = make_shared_nodelete(&leftMotor);
+  m_rearRightMotor = make_shared_nodelete(&rightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+                       std::shared_ptr<SpeedController> rightMotor) {
+  InitRobotDrive();
+  if (leftMotor == nullptr || rightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_rearLeftMotor = m_rearRightMotor = nullptr;
+    return;
+  }
+  m_rearLeftMotor = leftMotor;
+  m_rearRightMotor = rightMotor;
+}
+
+RobotDrive::RobotDrive(SpeedController* frontLeftMotor,
+                       SpeedController* rearLeftMotor,
+                       SpeedController* frontRightMotor,
+                       SpeedController* rearRightMotor) {
+  InitRobotDrive();
+  if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+      frontRightMotor == nullptr || rearRightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  m_frontLeftMotor = make_shared_nodelete(frontLeftMotor);
+  m_rearLeftMotor = make_shared_nodelete(rearLeftMotor);
+  m_frontRightMotor = make_shared_nodelete(frontRightMotor);
+  m_rearRightMotor = make_shared_nodelete(rearRightMotor);
+}
+
+RobotDrive::RobotDrive(SpeedController& frontLeftMotor,
+                       SpeedController& rearLeftMotor,
+                       SpeedController& frontRightMotor,
+                       SpeedController& rearRightMotor) {
+  InitRobotDrive();
+  m_frontLeftMotor = make_shared_nodelete(&frontLeftMotor);
+  m_rearLeftMotor = make_shared_nodelete(&rearLeftMotor);
+  m_frontRightMotor = make_shared_nodelete(&frontRightMotor);
+  m_rearRightMotor = make_shared_nodelete(&rearRightMotor);
+}
+
+RobotDrive::RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+                       std::shared_ptr<SpeedController> rearLeftMotor,
+                       std::shared_ptr<SpeedController> frontRightMotor,
+                       std::shared_ptr<SpeedController> rearRightMotor) {
+  InitRobotDrive();
+  if (frontLeftMotor == nullptr || rearLeftMotor == nullptr ||
+      frontRightMotor == nullptr || rearRightMotor == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  m_frontLeftMotor = frontLeftMotor;
+  m_rearLeftMotor = rearLeftMotor;
+  m_frontRightMotor = frontRightMotor;
+  m_rearRightMotor = rearRightMotor;
+}
+
+void RobotDrive::Drive(double outputMagnitude, double curve) {
+  double leftOutput, rightOutput;
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_ArcadeRatioCurve);
+    reported = true;
+  }
+
+  if (curve < 0) {
+    double value = std::log(-curve);
+    double ratio = (value - m_sensitivity) / (value + m_sensitivity);
+    if (ratio == 0) ratio = .0000000001;
+    leftOutput = outputMagnitude / ratio;
+    rightOutput = outputMagnitude;
+  } else if (curve > 0) {
+    double value = std::log(curve);
+    double ratio = (value - m_sensitivity) / (value + m_sensitivity);
+    if (ratio == 0) ratio = .0000000001;
+    leftOutput = outputMagnitude;
+    rightOutput = outputMagnitude / ratio;
+  } else {
+    leftOutput = outputMagnitude;
+    rightOutput = outputMagnitude;
+  }
+  SetLeftRightMotorOutputs(leftOutput, rightOutput);
+}
+
+void RobotDrive::TankDrive(GenericHID* leftStick, GenericHID* rightStick,
+                           bool squaredInputs) {
+  if (leftStick == nullptr || rightStick == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  TankDrive(leftStick->GetY(), rightStick->GetY(), squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID& leftStick, GenericHID& rightStick,
+                           bool squaredInputs) {
+  TankDrive(leftStick.GetY(), rightStick.GetY(), squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID* leftStick, int leftAxis,
+                           GenericHID* rightStick, int rightAxis,
+                           bool squaredInputs) {
+  if (leftStick == nullptr || rightStick == nullptr) {
+    wpi_setWPIError(NullParameter);
+    return;
+  }
+  TankDrive(leftStick->GetRawAxis(leftAxis), rightStick->GetRawAxis(rightAxis),
+            squaredInputs);
+}
+
+void RobotDrive::TankDrive(GenericHID& leftStick, int leftAxis,
+                           GenericHID& rightStick, int rightAxis,
+                           bool squaredInputs) {
+  TankDrive(leftStick.GetRawAxis(leftAxis), rightStick.GetRawAxis(rightAxis),
+            squaredInputs);
+}
+
+void RobotDrive::TankDrive(double leftValue, double rightValue,
+                           bool squaredInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_Tank);
+    reported = true;
+  }
+
+  leftValue = Limit(leftValue);
+  rightValue = Limit(rightValue);
+
+  // square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power
+  if (squaredInputs) {
+    leftValue = std::copysign(leftValue * leftValue, leftValue);
+    rightValue = std::copysign(rightValue * rightValue, rightValue);
+  }
+
+  SetLeftRightMotorOutputs(leftValue, rightValue);
+}
+
+void RobotDrive::ArcadeDrive(GenericHID* stick, bool squaredInputs) {
+  // simply call the full-featured ArcadeDrive with the appropriate values
+  ArcadeDrive(stick->GetY(), stick->GetX(), squaredInputs);
+}
+
+void RobotDrive::ArcadeDrive(GenericHID& stick, bool squaredInputs) {
+  // simply call the full-featured ArcadeDrive with the appropriate values
+  ArcadeDrive(stick.GetY(), stick.GetX(), squaredInputs);
+}
+
+void RobotDrive::ArcadeDrive(GenericHID* moveStick, int moveAxis,
+                             GenericHID* rotateStick, int rotateAxis,
+                             bool squaredInputs) {
+  double moveValue = moveStick->GetRawAxis(moveAxis);
+  double rotateValue = rotateStick->GetRawAxis(rotateAxis);
+
+  ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+void RobotDrive::ArcadeDrive(GenericHID& moveStick, int moveAxis,
+                             GenericHID& rotateStick, int rotateAxis,
+                             bool squaredInputs) {
+  double moveValue = moveStick.GetRawAxis(moveAxis);
+  double rotateValue = rotateStick.GetRawAxis(rotateAxis);
+
+  ArcadeDrive(moveValue, rotateValue, squaredInputs);
+}
+
+void RobotDrive::ArcadeDrive(double moveValue, double rotateValue,
+                             bool squaredInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_ArcadeStandard);
+    reported = true;
+  }
+
+  // local variables to hold the computed PWM values for the motors
+  double leftMotorOutput;
+  double rightMotorOutput;
+
+  moveValue = Limit(moveValue);
+  rotateValue = Limit(rotateValue);
+
+  // square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power
+  if (squaredInputs) {
+    moveValue = std::copysign(moveValue * moveValue, moveValue);
+    rotateValue = std::copysign(rotateValue * rotateValue, rotateValue);
+  }
+
+  if (moveValue > 0.0) {
+    if (rotateValue > 0.0) {
+      leftMotorOutput = moveValue - rotateValue;
+      rightMotorOutput = std::max(moveValue, rotateValue);
+    } else {
+      leftMotorOutput = std::max(moveValue, -rotateValue);
+      rightMotorOutput = moveValue + rotateValue;
+    }
+  } else {
+    if (rotateValue > 0.0) {
+      leftMotorOutput = -std::max(-moveValue, rotateValue);
+      rightMotorOutput = moveValue + rotateValue;
+    } else {
+      leftMotorOutput = moveValue - rotateValue;
+      rightMotorOutput = -std::max(-moveValue, -rotateValue);
+    }
+  }
+  SetLeftRightMotorOutputs(leftMotorOutput, rightMotorOutput);
+}
+
+void RobotDrive::MecanumDrive_Cartesian(double x, double y, double rotation,
+                                        double gyroAngle) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_MecanumCartesian);
+    reported = true;
+  }
+
+  double xIn = x;
+  double yIn = y;
+  // Negate y for the joystick.
+  yIn = -yIn;
+  // Compenstate for gyro angle.
+  RotateVector(xIn, yIn, gyroAngle);
+
+  double wheelSpeeds[kMaxNumberOfMotors];
+  wheelSpeeds[kFrontLeftMotor] = xIn + yIn + rotation;
+  wheelSpeeds[kFrontRightMotor] = -xIn + yIn - rotation;
+  wheelSpeeds[kRearLeftMotor] = -xIn + yIn + rotation;
+  wheelSpeeds[kRearRightMotor] = xIn + yIn - rotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_maxOutput);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_maxOutput);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput);
+
+  Feed();
+}
+
+void RobotDrive::MecanumDrive_Polar(double magnitude, double direction,
+                                    double rotation) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, GetNumMotors(),
+               HALUsageReporting::kRobotDrive_MecanumPolar);
+    reported = true;
+  }
+
+  // Normalized for full power along the Cartesian axes.
+  magnitude = Limit(magnitude) * std::sqrt(2.0);
+  // The rollers are at 45 degree angles.
+  double dirInRad = (direction + 45.0) * 3.14159 / 180.0;
+  double cosD = std::cos(dirInRad);
+  double sinD = std::sin(dirInRad);
+
+  double wheelSpeeds[kMaxNumberOfMotors];
+  wheelSpeeds[kFrontLeftMotor] = sinD * magnitude + rotation;
+  wheelSpeeds[kFrontRightMotor] = cosD * magnitude - rotation;
+  wheelSpeeds[kRearLeftMotor] = cosD * magnitude + rotation;
+  wheelSpeeds[kRearRightMotor] = sinD * magnitude - rotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor->Set(wheelSpeeds[kFrontLeftMotor] * m_maxOutput);
+  m_frontRightMotor->Set(wheelSpeeds[kFrontRightMotor] * m_maxOutput);
+  m_rearLeftMotor->Set(wheelSpeeds[kRearLeftMotor] * m_maxOutput);
+  m_rearRightMotor->Set(wheelSpeeds[kRearRightMotor] * m_maxOutput);
+
+  Feed();
+}
+
+void RobotDrive::HolonomicDrive(double magnitude, double direction,
+                                double rotation) {
+  MecanumDrive_Polar(magnitude, direction, rotation);
+}
+
+void RobotDrive::SetLeftRightMotorOutputs(double leftOutput,
+                                          double rightOutput) {
+  wpi_assert(m_rearLeftMotor != nullptr && m_rearRightMotor != nullptr);
+
+  if (m_frontLeftMotor != nullptr)
+    m_frontLeftMotor->Set(Limit(leftOutput) * m_maxOutput);
+  m_rearLeftMotor->Set(Limit(leftOutput) * m_maxOutput);
+
+  if (m_frontRightMotor != nullptr)
+    m_frontRightMotor->Set(-Limit(rightOutput) * m_maxOutput);
+  m_rearRightMotor->Set(-Limit(rightOutput) * m_maxOutput);
+
+  Feed();
+}
+
+void RobotDrive::SetInvertedMotor(MotorType motor, bool isInverted) {
+  if (motor < 0 || motor > 3) {
+    wpi_setWPIError(InvalidMotorIndex);
+    return;
+  }
+  switch (motor) {
+    case kFrontLeftMotor:
+      m_frontLeftMotor->SetInverted(isInverted);
+      break;
+    case kFrontRightMotor:
+      m_frontRightMotor->SetInverted(isInverted);
+      break;
+    case kRearLeftMotor:
+      m_rearLeftMotor->SetInverted(isInverted);
+      break;
+    case kRearRightMotor:
+      m_rearRightMotor->SetInverted(isInverted);
+      break;
+  }
+}
+
+void RobotDrive::SetSensitivity(double sensitivity) {
+  m_sensitivity = sensitivity;
+}
+
+void RobotDrive::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
+
+void RobotDrive::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "RobotDrive";
+}
+
+void RobotDrive::StopMotor() {
+  if (m_frontLeftMotor != nullptr) m_frontLeftMotor->StopMotor();
+  if (m_frontRightMotor != nullptr) m_frontRightMotor->StopMotor();
+  if (m_rearLeftMotor != nullptr) m_rearLeftMotor->StopMotor();
+  if (m_rearRightMotor != nullptr) m_rearRightMotor->StopMotor();
+  Feed();
+}
+
+void RobotDrive::InitRobotDrive() { SetSafetyEnabled(true); }
+
+double RobotDrive::Limit(double number) {
+  if (number > 1.0) {
+    return 1.0;
+  }
+  if (number < -1.0) {
+    return -1.0;
+  }
+  return number;
+}
+
+void RobotDrive::Normalize(double* wheelSpeeds) {
+  double maxMagnitude = std::fabs(wheelSpeeds[0]);
+  for (int i = 1; i < kMaxNumberOfMotors; i++) {
+    double temp = std::fabs(wheelSpeeds[i]);
+    if (maxMagnitude < temp) maxMagnitude = temp;
+  }
+  if (maxMagnitude > 1.0) {
+    for (int i = 0; i < kMaxNumberOfMotors; i++) {
+      wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+    }
+  }
+}
+
+void RobotDrive::RotateVector(double& x, double& y, double angle) {
+  double cosA = std::cos(angle * (3.14159 / 180.0));
+  double sinA = std::sin(angle * (3.14159 / 180.0));
+  double xOut = x * cosA - y * sinA;
+  double yOut = x * sinA + y * cosA;
+  x = xOut;
+  y = yOut;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotState.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotState.cpp
new file mode 100644
index 0000000..f5da5c1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/RobotState.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/RobotState.h"
+
+#include "frc/DriverStation.h"
+
+using namespace frc;
+
+bool RobotState::IsDisabled() {
+  return DriverStation::GetInstance().IsDisabled();
+}
+
+bool RobotState::IsEnabled() {
+  return DriverStation::GetInstance().IsEnabled();
+}
+
+bool RobotState::IsOperatorControl() {
+  return DriverStation::GetInstance().IsOperatorControl();
+}
+
+bool RobotState::IsAutonomous() {
+  return DriverStation::GetInstance().IsAutonomous();
+}
+
+bool RobotState::IsTest() { return DriverStation::GetInstance().IsTest(); }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SD540.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SD540.cpp
new file mode 100644
index 0000000..977ae7b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SD540.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/SD540.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+SD540::SD540(int channel) : PWMSpeedController(channel) {
+  /* Note that the SD540 uses the following bounds for PWM values. These values
+   * should work reasonably well for most controllers, but if users experience
+   * issues such as asymmetric behavior around the deadband or inability to
+   * saturate the controller in either direction, calibration is recommended.
+   * The calibration procedure can be found in the SD540 User Manual available
+   * from Mindsensors.
+   *
+   *   2.05ms = full "forward"
+   *   1.55ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.44ms = the "low end" of the deadband range
+   *   0.94ms = full "reverse"
+   */
+  SetBounds(2.05, 1.55, 1.50, 1.44, .94);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_MindsensorsSD540, GetChannel());
+  SetName("SD540", GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SPI.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SPI.cpp
new file mode 100644
index 0000000..6b41adb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SPI.cpp
@@ -0,0 +1,442 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/SPI.h"
+
+#include <cstring>
+#include <utility>
+
+#include <hal/HAL.h>
+#include <hal/SPI.h>
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+#include "frc/DigitalSource.h"
+#include "frc/Notifier.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+static constexpr int kAccumulateDepth = 2048;
+
+class SPI::Accumulator {
+ public:
+  Accumulator(HAL_SPIPort port, int xferSize, int validMask, int validValue,
+              int dataShift, int dataSize, bool isSigned, bool bigEndian)
+      : m_notifier([=]() {
+          std::lock_guard<wpi::mutex> lock(m_mutex);
+          Update();
+        }),
+        m_buf(new uint32_t[(xferSize + 1) * kAccumulateDepth]),
+        m_validMask(validMask),
+        m_validValue(validValue),
+        m_dataMax(1 << dataSize),
+        m_dataMsbMask(1 << (dataSize - 1)),
+        m_dataShift(dataShift),
+        m_xferSize(xferSize + 1),  // +1 for timestamp
+        m_isSigned(isSigned),
+        m_bigEndian(bigEndian),
+        m_port(port) {}
+  ~Accumulator() { delete[] m_buf; }
+
+  void Update();
+
+  Notifier m_notifier;
+  uint32_t* m_buf;
+  wpi::mutex m_mutex;
+
+  int64_t m_value = 0;
+  uint32_t m_count = 0;
+  int32_t m_lastValue = 0;
+  uint32_t m_lastTimestamp = 0;
+  double m_integratedValue = 0;
+
+  int32_t m_center = 0;
+  int32_t m_deadband = 0;
+  double m_integratedCenter = 0;
+
+  int32_t m_validMask;
+  int32_t m_validValue;
+  int32_t m_dataMax;      // one more than max data value
+  int32_t m_dataMsbMask;  // data field MSB mask (for signed)
+  uint8_t m_dataShift;    // data field shift right amount, in bits
+  int32_t m_xferSize;     // SPI transfer size, in bytes
+  bool m_isSigned;        // is data field signed?
+  bool m_bigEndian;       // is response big endian?
+  HAL_SPIPort m_port;
+};
+
+void SPI::Accumulator::Update() {
+  bool done;
+  do {
+    done = true;
+    int32_t status = 0;
+
+    // get amount of data available
+    int32_t numToRead =
+        HAL_ReadSPIAutoReceivedData(m_port, m_buf, 0, 0, &status);
+    if (status != 0) return;  // error reading
+
+    // only get whole responses; +1 is for timestamp
+    numToRead -= numToRead % m_xferSize;
+    if (numToRead > m_xferSize * kAccumulateDepth) {
+      numToRead = m_xferSize * kAccumulateDepth;
+      done = false;
+    }
+    if (numToRead == 0) return;  // no samples
+
+    // read buffered data
+    HAL_ReadSPIAutoReceivedData(m_port, m_buf, numToRead, 0, &status);
+    if (status != 0) return;  // error reading
+
+    // loop over all responses
+    for (int32_t off = 0; off < numToRead; off += m_xferSize) {
+      // get timestamp from first word
+      uint32_t timestamp = m_buf[off];
+
+      // convert from bytes
+      uint32_t resp = 0;
+      if (m_bigEndian) {
+        for (int32_t i = 1; i < m_xferSize; ++i) {
+          resp <<= 8;
+          resp |= m_buf[off + i] & 0xff;
+        }
+      } else {
+        for (int32_t i = m_xferSize - 1; i >= 1; --i) {
+          resp <<= 8;
+          resp |= m_buf[off + i] & 0xff;
+        }
+      }
+
+      // process response
+      if ((resp & m_validMask) == static_cast<uint32_t>(m_validValue)) {
+        // valid sensor data; extract data field
+        int32_t data = static_cast<int32_t>(resp >> m_dataShift);
+        data &= m_dataMax - 1;
+        // 2s complement conversion if signed MSB is set
+        if (m_isSigned && (data & m_dataMsbMask) != 0) data -= m_dataMax;
+        // center offset
+        int32_t dataNoCenter = data;
+        data -= m_center;
+        // only accumulate if outside deadband
+        if (data < -m_deadband || data > m_deadband) {
+          m_value += data;
+          if (m_count != 0) {
+            // timestamps use the 1us FPGA clock; also handle rollover
+            if (timestamp >= m_lastTimestamp)
+              m_integratedValue +=
+                  dataNoCenter *
+                      static_cast<int32_t>(timestamp - m_lastTimestamp) * 1e-6 -
+                  m_integratedCenter;
+            else
+              m_integratedValue +=
+                  dataNoCenter *
+                      static_cast<int32_t>((1ULL << 32) - m_lastTimestamp +
+                                           timestamp) *
+                      1e-6 -
+                  m_integratedCenter;
+          }
+        }
+        ++m_count;
+        m_lastValue = data;
+      } else {
+        // no data from the sensor; just clear the last value
+        m_lastValue = 0;
+      }
+      m_lastTimestamp = timestamp;
+    }
+  } while (!done);
+}
+
+SPI::SPI(Port port) : m_port(static_cast<HAL_SPIPort>(port)) {
+  int32_t status = 0;
+  HAL_InitializeSPI(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_SPI, instances);
+}
+
+SPI::~SPI() { HAL_CloseSPI(m_port); }
+
+SPI::SPI(SPI&& rhs)
+    : ErrorBase(std::move(rhs)),
+      m_msbFirst(std::move(rhs.m_msbFirst)),
+      m_sampleOnTrailing(std::move(rhs.m_sampleOnTrailing)),
+      m_clockIdleHigh(std::move(rhs.m_clockIdleHigh)),
+      m_accum(std::move(rhs.m_accum)) {
+  std::swap(m_port, rhs.m_port);
+}
+
+SPI& SPI::operator=(SPI&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+
+  std::swap(m_port, rhs.m_port);
+  m_msbFirst = std::move(rhs.m_msbFirst);
+  m_sampleOnTrailing = std::move(rhs.m_sampleOnTrailing);
+  m_clockIdleHigh = std::move(rhs.m_clockIdleHigh);
+  m_accum = std::move(rhs.m_accum);
+
+  return *this;
+}
+
+void SPI::SetClockRate(double hz) { HAL_SetSPISpeed(m_port, hz); }
+
+void SPI::SetMSBFirst() {
+  m_msbFirst = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetLSBFirst() {
+  m_msbFirst = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetSampleDataOnLeadingEdge() {
+  m_sampleOnTrailing = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetSampleDataOnTrailingEdge() {
+  m_sampleOnTrailing = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetSampleDataOnFalling() {
+  m_sampleOnTrailing = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetSampleDataOnRising() {
+  m_sampleOnTrailing = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetClockActiveLow() {
+  m_clockIdleHigh = true;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetClockActiveHigh() {
+  m_clockIdleHigh = false;
+  HAL_SetSPIOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+}
+
+void SPI::SetChipSelectActiveHigh() {
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveHigh(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SPI::SetChipSelectActiveLow() {
+  int32_t status = 0;
+  HAL_SetSPIChipSelectActiveLow(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int SPI::Write(uint8_t* data, int size) {
+  int retVal = 0;
+  retVal = HAL_WriteSPI(m_port, data, size);
+  return retVal;
+}
+
+int SPI::Read(bool initiate, uint8_t* dataReceived, int size) {
+  int retVal = 0;
+  if (initiate) {
+    wpi::SmallVector<uint8_t, 32> dataToSend;
+    dataToSend.resize(size);
+    retVal = HAL_TransactionSPI(m_port, dataToSend.data(), dataReceived, size);
+  } else {
+    retVal = HAL_ReadSPI(m_port, dataReceived, size);
+  }
+  return retVal;
+}
+
+int SPI::Transaction(uint8_t* dataToSend, uint8_t* dataReceived, int size) {
+  int retVal = 0;
+  retVal = HAL_TransactionSPI(m_port, dataToSend, dataReceived, size);
+  return retVal;
+}
+
+void SPI::InitAuto(int bufferSize) {
+  int32_t status = 0;
+  HAL_InitSPIAuto(m_port, bufferSize, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SPI::FreeAuto() {
+  int32_t status = 0;
+  HAL_FreeSPIAuto(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SPI::SetAutoTransmitData(wpi::ArrayRef<uint8_t> dataToSend, int zeroSize) {
+  int32_t status = 0;
+  HAL_SetSPIAutoTransmitData(m_port, dataToSend.data(), dataToSend.size(),
+                             zeroSize, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SPI::StartAutoRate(double period) {
+  int32_t status = 0;
+  HAL_StartSPIAutoRate(m_port, period, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SPI::StartAutoTrigger(DigitalSource& source, bool rising, bool falling) {
+  int32_t status = 0;
+  HAL_StartSPIAutoTrigger(
+      m_port, source.GetPortHandleForRouting(),
+      (HAL_AnalogTriggerType)source.GetAnalogTriggerTypeForRouting(), rising,
+      falling, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SPI::StopAuto() {
+  int32_t status = 0;
+  HAL_StopSPIAuto(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SPI::ForceAutoRead() {
+  int32_t status = 0;
+  HAL_ForceSPIAutoRead(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int SPI::ReadAutoReceivedData(uint32_t* buffer, int numToRead, double timeout) {
+  int32_t status = 0;
+  int32_t val =
+      HAL_ReadSPIAutoReceivedData(m_port, buffer, numToRead, timeout, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+int SPI::GetAutoDroppedCount() {
+  int32_t status = 0;
+  int32_t val = HAL_GetSPIAutoDroppedCount(m_port, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return val;
+}
+
+void SPI::InitAccumulator(double period, int cmd, int xferSize, int validMask,
+                          int validValue, int dataShift, int dataSize,
+                          bool isSigned, bool bigEndian) {
+  InitAuto(xferSize * kAccumulateDepth);
+  uint8_t cmdBytes[4] = {0, 0, 0, 0};
+  if (bigEndian) {
+    for (int32_t i = xferSize - 1; i >= 0; --i) {
+      cmdBytes[i] = cmd & 0xff;
+      cmd >>= 8;
+    }
+  } else {
+    cmdBytes[0] = cmd & 0xff;
+    cmd >>= 8;
+    cmdBytes[1] = cmd & 0xff;
+    cmd >>= 8;
+    cmdBytes[2] = cmd & 0xff;
+    cmd >>= 8;
+    cmdBytes[3] = cmd & 0xff;
+  }
+  SetAutoTransmitData(cmdBytes, xferSize - 4);
+  StartAutoRate(period);
+
+  m_accum.reset(new Accumulator(m_port, xferSize, validMask, validValue,
+                                dataShift, dataSize, isSigned, bigEndian));
+  m_accum->m_notifier.StartPeriodic(period * kAccumulateDepth / 2);
+}
+
+void SPI::FreeAccumulator() {
+  m_accum.reset(nullptr);
+  FreeAuto();
+}
+
+void SPI::ResetAccumulator() {
+  if (!m_accum) return;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->m_value = 0;
+  m_accum->m_count = 0;
+  m_accum->m_lastValue = 0;
+  m_accum->m_lastTimestamp = 0;
+  m_accum->m_integratedValue = 0;
+}
+
+void SPI::SetAccumulatorCenter(int center) {
+  if (!m_accum) return;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->m_center = center;
+}
+
+void SPI::SetAccumulatorDeadband(int deadband) {
+  if (!m_accum) return;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->m_deadband = deadband;
+}
+
+int SPI::GetAccumulatorLastValue() const {
+  if (!m_accum) return 0;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->Update();
+  return m_accum->m_lastValue;
+}
+
+int64_t SPI::GetAccumulatorValue() const {
+  if (!m_accum) return 0;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->Update();
+  return m_accum->m_value;
+}
+
+int64_t SPI::GetAccumulatorCount() const {
+  if (!m_accum) return 0;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->Update();
+  return m_accum->m_count;
+}
+
+double SPI::GetAccumulatorAverage() const {
+  if (!m_accum) return 0;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->Update();
+  if (m_accum->m_count == 0) return 0.0;
+  return static_cast<double>(m_accum->m_value) / m_accum->m_count;
+}
+
+void SPI::GetAccumulatorOutput(int64_t& value, int64_t& count) const {
+  if (!m_accum) {
+    value = 0;
+    count = 0;
+    return;
+  }
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->Update();
+  value = m_accum->m_value;
+  count = m_accum->m_count;
+}
+
+void SPI::SetAccumulatorIntegratedCenter(double center) {
+  if (!m_accum) return;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->m_integratedCenter = center;
+}
+
+double SPI::GetAccumulatorIntegratedValue() const {
+  if (!m_accum) return 0;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->Update();
+  return m_accum->m_integratedValue;
+}
+
+double SPI::GetAccumulatorIntegratedAverage() const {
+  if (!m_accum) return 0;
+  std::lock_guard<wpi::mutex> lock(m_accum->m_mutex);
+  m_accum->Update();
+  if (m_accum->m_count <= 1) return 0.0;
+  // count-1 due to not integrating the first value received
+  return m_accum->m_integratedValue / (m_accum->m_count - 1);
+}
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
new file mode 100644
index 0000000..338f7be
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SampleRobot.cpp
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/SampleRobot.h"
+
+#include <hal/DriverStation.h>
+#include <hal/FRCUsageReporting.h>
+#include <hal/HALBase.h>
+#include <networktables/NetworkTable.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Timer.h"
+#include "frc/livewindow/LiveWindow.h"
+
+using namespace frc;
+
+void SampleRobot::StartCompetition() {
+  LiveWindow* lw = LiveWindow::GetInstance();
+
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HAL_ObserveUserProgramStarting();
+
+  RobotMain();
+
+  if (!m_robotMainOverridden) {
+    while (true) {
+      if (IsDisabled()) {
+        m_ds.InDisabled(true);
+        Disabled();
+        m_ds.InDisabled(false);
+        while (IsDisabled()) m_ds.WaitForData();
+      } else if (IsAutonomous()) {
+        m_ds.InAutonomous(true);
+        Autonomous();
+        m_ds.InAutonomous(false);
+        while (IsAutonomous() && IsEnabled()) m_ds.WaitForData();
+      } else if (IsTest()) {
+        lw->SetEnabled(true);
+        m_ds.InTest(true);
+        Test();
+        m_ds.InTest(false);
+        while (IsTest() && IsEnabled()) m_ds.WaitForData();
+        lw->SetEnabled(false);
+      } else {
+        m_ds.InOperatorControl(true);
+        OperatorControl();
+        m_ds.InOperatorControl(false);
+        while (IsOperatorControl() && IsEnabled()) m_ds.WaitForData();
+      }
+    }
+  }
+}
+
+void SampleRobot::RobotInit() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void SampleRobot::Disabled() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void SampleRobot::Autonomous() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void SampleRobot::OperatorControl() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void SampleRobot::Test() {
+  wpi::outs() << "Default " << __FUNCTION__ << "() method... Overload me!\n";
+}
+
+void SampleRobot::RobotMain() { m_robotMainOverridden = false; }
+
+SampleRobot::SampleRobot() {
+  HAL_Report(HALUsageReporting::kResourceType_Framework,
+             HALUsageReporting::kFramework_Simple);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SensorUtil.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SensorUtil.cpp
new file mode 100644
index 0000000..2012da4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SensorUtil.cpp
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/SensorUtil.h"
+
+#include <hal/AnalogInput.h>
+#include <hal/AnalogOutput.h>
+#include <hal/DIO.h>
+#include <hal/HAL.h>
+#include <hal/PDP.h>
+#include <hal/PWM.h>
+#include <hal/Ports.h>
+#include <hal/Relay.h>
+#include <hal/Solenoid.h>
+
+using namespace frc;
+
+const int SensorUtil::kDigitalChannels = HAL_GetNumDigitalChannels();
+const int SensorUtil::kAnalogInputs = HAL_GetNumAnalogInputs();
+const int SensorUtil::kSolenoidChannels = HAL_GetNumSolenoidChannels();
+const int SensorUtil::kSolenoidModules = HAL_GetNumPCMModules();
+const int SensorUtil::kPwmChannels = HAL_GetNumPWMChannels();
+const int SensorUtil::kRelayChannels = HAL_GetNumRelayHeaders();
+const int SensorUtil::kPDPChannels = HAL_GetNumPDPChannels();
+
+int SensorUtil::GetDefaultSolenoidModule() { return 0; }
+
+bool SensorUtil::CheckSolenoidModule(int moduleNumber) {
+  return HAL_CheckSolenoidModule(moduleNumber);
+}
+
+bool SensorUtil::CheckDigitalChannel(int channel) {
+  return HAL_CheckDIOChannel(channel);
+}
+
+bool SensorUtil::CheckRelayChannel(int channel) {
+  return HAL_CheckRelayChannel(channel);
+}
+
+bool SensorUtil::CheckPWMChannel(int channel) {
+  return HAL_CheckPWMChannel(channel);
+}
+
+bool SensorUtil::CheckAnalogInputChannel(int channel) {
+  return HAL_CheckAnalogInputChannel(channel);
+}
+
+bool SensorUtil::CheckAnalogOutputChannel(int channel) {
+  return HAL_CheckAnalogOutputChannel(channel);
+}
+
+bool SensorUtil::CheckSolenoidChannel(int channel) {
+  return HAL_CheckSolenoidChannel(channel);
+}
+
+bool SensorUtil::CheckPDPChannel(int channel) {
+  return HAL_CheckPDPChannel(channel);
+}
+
+bool SensorUtil::CheckPDPModule(int module) {
+  return HAL_CheckPDPModule(module);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SerialPort.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SerialPort.cpp
new file mode 100644
index 0000000..a399f4d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SerialPort.cpp
@@ -0,0 +1,203 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/SerialPort.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+#include <hal/SerialPort.h>
+
+// static ViStatus _VI_FUNCH ioCompleteHandler (ViSession vi, ViEventType
+// eventType, ViEvent event, ViAddr userHandle);
+
+using namespace frc;
+
+SerialPort::SerialPort(int baudRate, Port port, int dataBits,
+                       SerialPort::Parity parity,
+                       SerialPort::StopBits stopBits) {
+  int32_t status = 0;
+
+  m_port = port;
+
+  HAL_InitializeSerialPort(static_cast<HAL_SerialPort>(port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  // Don't continue if initialization failed
+  if (status < 0) return;
+  HAL_SetSerialBaudRate(static_cast<HAL_SerialPort>(port), baudRate, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialDataBits(static_cast<HAL_SerialPort>(port), dataBits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialParity(static_cast<HAL_SerialPort>(port), parity, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialStopBits(static_cast<HAL_SerialPort>(port), stopBits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  // Set the default timeout to 5 seconds.
+  SetTimeout(5.0);
+
+  // Don't wait until the buffer is full to transmit.
+  SetWriteBufferMode(kFlushOnAccess);
+
+  EnableTermination();
+
+  // viInstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler,
+  // this);
+  // viEnableEvent(m_portHandle, VI_EVENT_IO_COMPLETION, VI_HNDLR, VI_NULL);
+
+  HAL_Report(HALUsageReporting::kResourceType_SerialPort, 0);
+}
+
+SerialPort::SerialPort(int baudRate, const wpi::Twine& portName, Port port,
+                       int dataBits, SerialPort::Parity parity,
+                       SerialPort::StopBits stopBits) {
+  int32_t status = 0;
+
+  m_port = port;
+
+  wpi::SmallVector<char, 64> buf;
+  const char* portNameC = portName.toNullTerminatedStringRef(buf).data();
+
+  HAL_InitializeSerialPortDirect(static_cast<HAL_SerialPort>(port), portNameC,
+                                 &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  // Don't continue if initialization failed
+  if (status < 0) return;
+  HAL_SetSerialBaudRate(static_cast<HAL_SerialPort>(port), baudRate, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialDataBits(static_cast<HAL_SerialPort>(port), dataBits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialParity(static_cast<HAL_SerialPort>(port), parity, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  HAL_SetSerialStopBits(static_cast<HAL_SerialPort>(port), stopBits, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  // Set the default timeout to 5 seconds.
+  SetTimeout(5.0);
+
+  // Don't wait until the buffer is full to transmit.
+  SetWriteBufferMode(kFlushOnAccess);
+
+  EnableTermination();
+
+  // viInstallHandler(m_portHandle, VI_EVENT_IO_COMPLETION, ioCompleteHandler,
+  // this);
+  // viEnableEvent(m_portHandle, VI_EVENT_IO_COMPLETION, VI_HNDLR, VI_NULL);
+
+  HAL_Report(HALUsageReporting::kResourceType_SerialPort, 0);
+}
+
+SerialPort::~SerialPort() {
+  int32_t status = 0;
+  HAL_CloseSerial(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+SerialPort::SerialPort(SerialPort&& rhs)
+    : ErrorBase(std::move(rhs)),
+      m_resourceManagerHandle(std::move(rhs.m_resourceManagerHandle)),
+      m_portHandle(std::move(rhs.m_portHandle)),
+      m_consoleModeEnabled(std::move(rhs.m_consoleModeEnabled)) {
+  std::swap(m_port, rhs.m_port);
+}
+
+SerialPort& SerialPort::operator=(SerialPort&& rhs) {
+  ErrorBase::operator=(std::move(rhs));
+
+  m_resourceManagerHandle = std::move(rhs.m_resourceManagerHandle);
+  m_portHandle = std::move(rhs.m_portHandle);
+  m_consoleModeEnabled = std::move(rhs.m_consoleModeEnabled);
+  std::swap(m_port, rhs.m_port);
+
+  return *this;
+}
+
+void SerialPort::SetFlowControl(SerialPort::FlowControl flowControl) {
+  int32_t status = 0;
+  HAL_SetSerialFlowControl(static_cast<HAL_SerialPort>(m_port), flowControl,
+                           &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SerialPort::EnableTermination(char terminator) {
+  int32_t status = 0;
+  HAL_EnableSerialTermination(static_cast<HAL_SerialPort>(m_port), terminator,
+                              &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SerialPort::DisableTermination() {
+  int32_t status = 0;
+  HAL_DisableSerialTermination(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+int SerialPort::GetBytesReceived() {
+  int32_t status = 0;
+  int retVal =
+      HAL_GetSerialBytesReceived(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+int SerialPort::Read(char* buffer, int count) {
+  int32_t status = 0;
+  int retVal = HAL_ReadSerial(static_cast<HAL_SerialPort>(m_port), buffer,
+                              count, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+int SerialPort::Write(const char* buffer, int count) {
+  return Write(wpi::StringRef(buffer, static_cast<size_t>(count)));
+}
+
+int SerialPort::Write(wpi::StringRef buffer) {
+  int32_t status = 0;
+  int retVal = HAL_WriteSerial(static_cast<HAL_SerialPort>(m_port),
+                               buffer.data(), buffer.size(), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return retVal;
+}
+
+void SerialPort::SetTimeout(double timeout) {
+  int32_t status = 0;
+  HAL_SetSerialTimeout(static_cast<HAL_SerialPort>(m_port), timeout, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SerialPort::SetReadBufferSize(int size) {
+  int32_t status = 0;
+  HAL_SetSerialReadBufferSize(static_cast<HAL_SerialPort>(m_port), size,
+                              &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SerialPort::SetWriteBufferSize(int size) {
+  int32_t status = 0;
+  HAL_SetSerialWriteBufferSize(static_cast<HAL_SerialPort>(m_port), size,
+                               &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SerialPort::SetWriteBufferMode(SerialPort::WriteBufferMode mode) {
+  int32_t status = 0;
+  HAL_SetSerialWriteMode(static_cast<HAL_SerialPort>(m_port), mode, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SerialPort::Flush() {
+  int32_t status = 0;
+  HAL_FlushSerial(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void SerialPort::Reset() {
+  int32_t status = 0;
+  HAL_ClearSerial(static_cast<HAL_SerialPort>(m_port), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Servo.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Servo.cpp
new file mode 100644
index 0000000..b4c9eb5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Servo.cpp
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Servo.h"
+
+#include <hal/HAL.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+constexpr double Servo::kMaxServoAngle;
+constexpr double Servo::kMinServoAngle;
+
+constexpr double Servo::kDefaultMaxServoPWM;
+constexpr double Servo::kDefaultMinServoPWM;
+
+Servo::Servo(int channel) : PWM(channel) {
+  // Set minimum and maximum PWM values supported by the servo
+  SetBounds(kDefaultMaxServoPWM, 0.0, 0.0, 0.0, kDefaultMinServoPWM);
+
+  // Assign defaults for period multiplier for the servo PWM control signal
+  SetPeriodMultiplier(kPeriodMultiplier_4X);
+
+  HAL_Report(HALUsageReporting::kResourceType_Servo, channel);
+  SetName("Servo", channel);
+}
+
+void Servo::Set(double value) { SetPosition(value); }
+
+void Servo::SetOffline() { SetRaw(0); }
+
+double Servo::Get() const { return GetPosition(); }
+
+void Servo::SetAngle(double degrees) {
+  if (degrees < kMinServoAngle) {
+    degrees = kMinServoAngle;
+  } else if (degrees > kMaxServoAngle) {
+    degrees = kMaxServoAngle;
+  }
+
+  SetPosition((degrees - kMinServoAngle) / GetServoAngleRange());
+}
+
+double Servo::GetAngle() const {
+  return GetPosition() * GetServoAngleRange() + kMinServoAngle;
+}
+
+double Servo::GetMaxAngle() const { return kMaxServoAngle; }
+
+double Servo::GetMinAngle() const { return kMinServoAngle; }
+
+void Servo::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Servo");
+  builder.AddDoubleProperty("Value", [=]() { return Get(); },
+                            [=](double value) { Set(value); });
+}
+
+double Servo::GetServoAngleRange() const {
+  return kMaxServoAngle - kMinServoAngle;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Solenoid.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Solenoid.cpp
new file mode 100644
index 0000000..3445f5d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Solenoid.cpp
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Solenoid.h"
+
+#include <utility>
+
+#include <hal/HAL.h>
+#include <hal/Ports.h>
+#include <hal/Solenoid.h>
+
+#include "frc/SensorUtil.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+Solenoid::Solenoid(int channel)
+    : Solenoid(SensorUtil::GetDefaultSolenoidModule(), channel) {}
+
+Solenoid::Solenoid(int moduleNumber, int channel)
+    : SolenoidBase(moduleNumber), m_channel(channel) {
+  if (!SensorUtil::CheckSolenoidModule(m_moduleNumber)) {
+    wpi_setWPIErrorWithContext(ModuleIndexOutOfRange,
+                               "Solenoid Module " + wpi::Twine(m_moduleNumber));
+    return;
+  }
+  if (!SensorUtil::CheckSolenoidChannel(m_channel)) {
+    wpi_setWPIErrorWithContext(ChannelIndexOutOfRange,
+                               "Solenoid Channel " + wpi::Twine(m_channel));
+    return;
+  }
+
+  int32_t status = 0;
+  m_solenoidHandle = HAL_InitializeSolenoidPort(
+      HAL_GetPortWithModule(moduleNumber, channel), &status);
+  if (status != 0) {
+    wpi_setErrorWithContextRange(status, 0, HAL_GetNumSolenoidChannels(),
+                                 channel, HAL_GetErrorMessage(status));
+    m_solenoidHandle = HAL_kInvalidHandle;
+    return;
+  }
+
+  HAL_Report(HALUsageReporting::kResourceType_Solenoid, m_channel,
+             m_moduleNumber);
+  SetName("Solenoid", m_moduleNumber, m_channel);
+}
+
+Solenoid::~Solenoid() { HAL_FreeSolenoidPort(m_solenoidHandle); }
+
+Solenoid::Solenoid(Solenoid&& rhs)
+    : SolenoidBase(std::move(rhs)), m_channel(std::move(rhs.m_channel)) {
+  std::swap(m_solenoidHandle, rhs.m_solenoidHandle);
+}
+
+Solenoid& Solenoid::operator=(Solenoid&& rhs) {
+  SolenoidBase::operator=(std::move(rhs));
+
+  std::swap(m_solenoidHandle, rhs.m_solenoidHandle);
+  m_channel = std::move(rhs.m_channel);
+
+  return *this;
+}
+
+void Solenoid::Set(bool on) {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetSolenoid(m_solenoidHandle, on, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+bool Solenoid::Get() const {
+  if (StatusIsFatal()) return false;
+  int32_t status = 0;
+  bool value = HAL_GetSolenoid(m_solenoidHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+bool Solenoid::IsBlackListed() const {
+  int value = GetPCMSolenoidBlackList(m_moduleNumber) & (1 << m_channel);
+  return (value != 0);
+}
+
+void Solenoid::SetPulseDuration(double durationSeconds) {
+  int32_t durationMS = durationSeconds * 1000;
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_SetOneShotDuration(m_solenoidHandle, durationMS, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Solenoid::StartPulse() {
+  if (StatusIsFatal()) return;
+  int32_t status = 0;
+  HAL_FireOneShot(m_solenoidHandle, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
+
+void Solenoid::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Solenoid");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { Set(false); });
+  builder.AddBooleanProperty("Value", [=]() { return Get(); },
+                             [=](bool value) { Set(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SolenoidBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SolenoidBase.cpp
new file mode 100644
index 0000000..c0b79a5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SolenoidBase.cpp
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/SolenoidBase.h"
+
+#include <hal/HAL.h>
+#include <hal/Solenoid.h>
+
+using namespace frc;
+
+int SolenoidBase::GetAll(int module) {
+  int value = 0;
+  int32_t status = 0;
+  value = HAL_GetAllSolenoids(module, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return value;
+}
+
+int SolenoidBase::GetAll() const {
+  return SolenoidBase::GetAll(m_moduleNumber);
+}
+
+int SolenoidBase::GetPCMSolenoidBlackList(int module) {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidBlackList(module, &status);
+}
+
+int SolenoidBase::GetPCMSolenoidBlackList() const {
+  return SolenoidBase::GetPCMSolenoidBlackList(m_moduleNumber);
+}
+
+bool SolenoidBase::GetPCMSolenoidVoltageStickyFault(int module) {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidVoltageStickyFault(module, &status);
+}
+
+bool SolenoidBase::GetPCMSolenoidVoltageStickyFault() const {
+  return SolenoidBase::GetPCMSolenoidVoltageStickyFault(m_moduleNumber);
+}
+
+bool SolenoidBase::GetPCMSolenoidVoltageFault(int module) {
+  int32_t status = 0;
+  return HAL_GetPCMSolenoidVoltageFault(module, &status);
+}
+
+bool SolenoidBase::GetPCMSolenoidVoltageFault() const {
+  return SolenoidBase::GetPCMSolenoidVoltageFault(m_moduleNumber);
+}
+
+void SolenoidBase::ClearAllPCMStickyFaults(int module) {
+  int32_t status = 0;
+  return HAL_ClearAllPCMStickyFaults(module, &status);
+}
+
+void SolenoidBase::ClearAllPCMStickyFaults() {
+  SolenoidBase::ClearAllPCMStickyFaults(m_moduleNumber);
+}
+
+SolenoidBase::SolenoidBase(int moduleNumber) : m_moduleNumber(moduleNumber) {}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Spark.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Spark.cpp
new file mode 100644
index 0000000..fcfcb96
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Spark.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Spark.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+Spark::Spark(int channel) : PWMSpeedController(channel) {
+  /* Note that the Spark uses the following bounds for PWM values. These values
+   * should work reasonably well for most controllers, but if users experience
+   * issues such as asymmetric behavior around the deadband or inability to
+   * saturate the controller in either direction, calibration is recommended.
+   * The calibration procedure can be found in the Spark User Manual available
+   * from REV Robotics.
+   *
+   *   2.003ms = full "forward"
+   *   1.55ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.46ms = the "low end" of the deadband range
+   *   0.999ms = full "reverse"
+   */
+  SetBounds(2.003, 1.55, 1.50, 1.46, .999);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_RevSPARK, GetChannel());
+  SetName("Spark", GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp
new file mode 100644
index 0000000..a807afc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/SpeedControllerGroup.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/SpeedControllerGroup.h"
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+void SpeedControllerGroup::Set(double speed) {
+  for (auto speedController : m_speedControllers) {
+    speedController.get().Set(m_isInverted ? -speed : speed);
+  }
+}
+
+double SpeedControllerGroup::Get() const {
+  if (!m_speedControllers.empty()) {
+    return m_speedControllers.front().get().Get() * (m_isInverted ? -1 : 1);
+  }
+  return 0.0;
+}
+
+void SpeedControllerGroup::SetInverted(bool isInverted) {
+  m_isInverted = isInverted;
+}
+
+bool SpeedControllerGroup::GetInverted() const { return m_isInverted; }
+
+void SpeedControllerGroup::Disable() {
+  for (auto speedController : m_speedControllers) {
+    speedController.get().Disable();
+  }
+}
+
+void SpeedControllerGroup::StopMotor() {
+  for (auto speedController : m_speedControllers) {
+    speedController.get().StopMotor();
+  }
+}
+
+void SpeedControllerGroup::PIDWrite(double output) { Set(output); }
+
+void SpeedControllerGroup::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Speed Controller");
+  builder.SetActuator(true);
+  builder.SetSafeState([=]() { StopMotor(); });
+  builder.AddDoubleProperty("Value", [=]() { return Get(); },
+                            [=](double value) { Set(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Talon.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Talon.cpp
new file mode 100644
index 0000000..34f659a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Talon.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Talon.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+Talon::Talon(int channel) : PWMSpeedController(channel) {
+  /* Note that the Talon uses the following bounds for PWM values. These values
+   * should work reasonably well for most controllers, but if users experience
+   * issues such as asymmetric behavior around the deadband or inability to
+   * saturate the controller in either direction, calibration is recommended.
+   * The calibration procedure can be found in the Talon User Manual available
+   * from CTRE.
+   *
+   *   2.037ms = full "forward"
+   *   1.539ms = the "high end" of the deadband range
+   *   1.513ms = center of the deadband range (off)
+   *   1.487ms = the "low end" of the deadband range
+   *   0.989ms = full "reverse"
+   */
+  SetBounds(2.037, 1.539, 1.513, 1.487, .989);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Talon, GetChannel());
+  SetName("Talon", GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Threads.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Threads.cpp
new file mode 100644
index 0000000..7713f66
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Threads.cpp
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/Threads.h"
+
+#include <hal/HAL.h>
+#include <hal/Threads.h>
+
+#include "frc/ErrorBase.h"
+
+using namespace frc;
+
+int GetThreadPriority(std::thread& thread, bool* isRealTime) {
+  int32_t status = 0;
+  HAL_Bool rt = false;
+  auto native = thread.native_handle();
+  auto ret = HAL_GetThreadPriority(&native, &rt, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  *isRealTime = rt;
+  return ret;
+}
+
+int GetCurrentThreadPriority(bool* isRealTime) {
+  int32_t status = 0;
+  HAL_Bool rt = false;
+  auto ret = HAL_GetCurrentThreadPriority(&rt, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  *isRealTime = rt;
+  return ret;
+}
+
+bool SetThreadPriority(std::thread& thread, bool realTime, int priority) {
+  int32_t status = 0;
+  auto native = thread.native_handle();
+  auto ret = HAL_SetThreadPriority(&native, realTime, priority, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return ret;
+}
+
+bool SetCurrentThreadPriority(bool realTime, int priority) {
+  int32_t status = 0;
+  auto ret = HAL_SetCurrentThreadPriority(realTime, priority, &status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/TimedRobot.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/TimedRobot.cpp
new file mode 100644
index 0000000..24ab668
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/TimedRobot.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/TimedRobot.h"
+
+#include <stdint.h>
+
+#include <utility>
+
+#include <hal/HAL.h>
+
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+void TimedRobot::StartCompetition() {
+  RobotInit();
+
+  // Tell the DS that the robot is ready to be enabled
+  HAL_ObserveUserProgramStarting();
+
+  m_expirationTime = Timer::GetFPGATimestamp() + m_period;
+  UpdateAlarm();
+
+  // Loop forever, calling the appropriate mode-dependent function
+  while (true) {
+    int32_t status = 0;
+    uint64_t curTime = HAL_WaitForNotifierAlarm(m_notifier, &status);
+    if (curTime == 0 || status != 0) break;
+
+    m_expirationTime += m_period;
+
+    UpdateAlarm();
+
+    // Call callback
+    LoopFunc();
+  }
+}
+
+double TimedRobot::GetPeriod() const { return m_period; }
+
+TimedRobot::TimedRobot(double period) : IterativeRobotBase(period) {
+  int32_t status = 0;
+  m_notifier = HAL_InitializeNotifier(&status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_Report(HALUsageReporting::kResourceType_Framework,
+             HALUsageReporting::kFramework_Timed);
+}
+
+TimedRobot::~TimedRobot() {
+  int32_t status = 0;
+
+  HAL_StopNotifier(m_notifier, &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+
+  HAL_CleanNotifier(m_notifier, &status);
+}
+
+TimedRobot::TimedRobot(TimedRobot&& rhs)
+    : IterativeRobotBase(std::move(rhs)),
+      m_expirationTime(std::move(rhs.m_expirationTime)) {
+  std::swap(m_notifier, rhs.m_notifier);
+}
+
+TimedRobot& TimedRobot::operator=(TimedRobot&& rhs) {
+  IterativeRobotBase::operator=(std::move(rhs));
+  ErrorBase::operator=(std::move(rhs));
+
+  std::swap(m_notifier, rhs.m_notifier);
+  m_expirationTime = std::move(rhs.m_expirationTime);
+
+  return *this;
+}
+
+void TimedRobot::UpdateAlarm() {
+  int32_t status = 0;
+  HAL_UpdateNotifierAlarm(
+      m_notifier, static_cast<uint64_t>(m_expirationTime * 1e6), &status);
+  wpi_setErrorWithContext(status, HAL_GetErrorMessage(status));
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Timer.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Timer.cpp
new file mode 100644
index 0000000..ae4a66e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Timer.cpp
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Timer.h"
+
+#include <chrono>
+#include <thread>
+
+#include <hal/HAL.h>
+
+#include "frc/DriverStation.h"
+#include "frc/RobotController.h"
+
+namespace frc {
+
+void Wait(double seconds) {
+  std::this_thread::sleep_for(std::chrono::duration<double>(seconds));
+}
+
+double GetClock() { return Timer::GetFPGATimestamp(); }
+
+double GetTime() {
+  using std::chrono::duration;
+  using std::chrono::duration_cast;
+  using std::chrono::system_clock;
+
+  return duration_cast<duration<double>>(system_clock::now().time_since_epoch())
+      .count();
+}
+
+}  // namespace frc
+
+using namespace frc;
+
+// for compatibility with msvc12--see C2864
+const double Timer::kRolloverTime = (1ll << 32) / 1e6;
+
+Timer::Timer() { Reset(); }
+
+double Timer::Get() const {
+  double result;
+  double currentTime = GetFPGATimestamp();
+
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (m_running) {
+    // If the current time is before the start time, then the FPGA clock rolled
+    // over. Compensate by adding the ~71 minutes that it takes to roll over to
+    // the current time.
+    if (currentTime < m_startTime) {
+      currentTime += kRolloverTime;
+    }
+
+    result = (currentTime - m_startTime) + m_accumulatedTime;
+  } else {
+    result = m_accumulatedTime;
+  }
+
+  return result;
+}
+
+void Timer::Reset() {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_accumulatedTime = 0;
+  m_startTime = GetFPGATimestamp();
+}
+
+void Timer::Start() {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (!m_running) {
+    m_startTime = GetFPGATimestamp();
+    m_running = true;
+  }
+}
+
+void Timer::Stop() {
+  double temp = Get();
+
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (m_running) {
+    m_accumulatedTime = temp;
+    m_running = false;
+  }
+}
+
+bool Timer::HasPeriodPassed(double period) {
+  if (Get() > period) {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    // Advance the start time by the period.
+    m_startTime += period;
+    // Don't set it to the current time... we want to avoid drift.
+    return true;
+  }
+  return false;
+}
+
+double Timer::GetFPGATimestamp() {
+  // FPGA returns the timestamp in microseconds
+  return RobotController::GetFPGATime() * 1.0e-6;
+}
+
+double Timer::GetMatchTime() {
+  return DriverStation::GetInstance().GetMatchTime();
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Ultrasonic.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Ultrasonic.cpp
new file mode 100644
index 0000000..ee4f5cc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Ultrasonic.cpp
@@ -0,0 +1,207 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Ultrasonic.h"
+
+#include <hal/HAL.h>
+
+#include "frc/Counter.h"
+#include "frc/DigitalInput.h"
+#include "frc/DigitalOutput.h"
+#include "frc/Timer.h"
+#include "frc/Utility.h"
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+// Automatic round robin mode
+std::atomic<bool> Ultrasonic::m_automaticEnabled{false};
+
+std::vector<Ultrasonic*> Ultrasonic::m_sensors;
+std::thread Ultrasonic::m_thread;
+
+Ultrasonic::Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units)
+    : m_pingChannel(std::make_shared<DigitalOutput>(pingChannel)),
+      m_echoChannel(std::make_shared<DigitalInput>(echoChannel)),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+  AddChild(m_pingChannel);
+  AddChild(m_echoChannel);
+}
+
+Ultrasonic::Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(pingChannel, NullDeleter<DigitalOutput>()),
+      m_echoChannel(echoChannel, NullDeleter<DigitalInput>()),
+      m_counter(m_echoChannel) {
+  if (pingChannel == nullptr || echoChannel == nullptr) {
+    wpi_setWPIError(NullParameter);
+    m_units = units;
+    return;
+  }
+  m_units = units;
+  Initialize();
+}
+
+Ultrasonic::Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(&pingChannel, NullDeleter<DigitalOutput>()),
+      m_echoChannel(&echoChannel, NullDeleter<DigitalInput>()),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+Ultrasonic::Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
+                       std::shared_ptr<DigitalInput> echoChannel,
+                       DistanceUnit units)
+    : m_pingChannel(pingChannel),
+      m_echoChannel(echoChannel),
+      m_counter(m_echoChannel) {
+  m_units = units;
+  Initialize();
+}
+
+Ultrasonic::~Ultrasonic() {
+  // Delete the instance of the ultrasonic sensor by freeing the allocated
+  // digital channels. If the system was in automatic mode (round robin), then
+  // it is stopped, then started again after this sensor is removed (provided
+  // this wasn't the last sensor).
+
+  bool wasAutomaticMode = m_automaticEnabled;
+  SetAutomaticMode(false);
+
+  // No synchronization needed because the background task is stopped.
+  m_sensors.erase(std::remove(m_sensors.begin(), m_sensors.end(), this),
+                  m_sensors.end());
+
+  if (!m_sensors.empty() && wasAutomaticMode) {
+    SetAutomaticMode(true);
+  }
+}
+
+void Ultrasonic::Ping() {
+  wpi_assert(!m_automaticEnabled);
+
+  // Reset the counter to zero (invalid data now)
+  m_counter.Reset();
+
+  // Do the ping to start getting a single range
+  m_pingChannel->Pulse(kPingTime);
+}
+
+bool Ultrasonic::IsRangeValid() const { return m_counter.Get() > 1; }
+
+void Ultrasonic::SetAutomaticMode(bool enabling) {
+  if (enabling == m_automaticEnabled) return;  // ignore the case of no change
+
+  m_automaticEnabled = enabling;
+
+  if (enabling) {
+    /* Clear all the counters so no data is valid. No synchronization is needed
+     * because the background task is stopped.
+     */
+    for (auto& sensor : m_sensors) {
+      sensor->m_counter.Reset();
+    }
+
+    m_thread = std::thread(&Ultrasonic::UltrasonicChecker);
+
+    // TODO: Currently, lvuser does not have permissions to set task priorities.
+    // Until that is the case, uncommenting this will break user code that calls
+    // Ultrasonic::SetAutomicMode().
+    // m_task.SetPriority(kPriority);
+  } else {
+    // Wait for background task to stop running
+    if (m_thread.joinable()) {
+      m_thread.join();
+    }
+
+    // Clear all the counters (data now invalid) since automatic mode is
+    // disabled. No synchronization is needed because the background task is
+    // stopped.
+    for (auto& sensor : m_sensors) {
+      sensor->m_counter.Reset();
+    }
+  }
+}
+
+double Ultrasonic::GetRangeInches() const {
+  if (IsRangeValid())
+    return m_counter.GetPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
+  else
+    return 0;
+}
+
+double Ultrasonic::GetRangeMM() const { return GetRangeInches() * 25.4; }
+
+bool Ultrasonic::IsEnabled() const { return m_enabled; }
+
+void Ultrasonic::SetEnabled(bool enable) { m_enabled = enable; }
+
+void Ultrasonic::SetDistanceUnits(DistanceUnit units) { m_units = units; }
+
+Ultrasonic::DistanceUnit Ultrasonic::GetDistanceUnits() const {
+  return m_units;
+}
+
+double Ultrasonic::PIDGet() {
+  switch (m_units) {
+    case Ultrasonic::kInches:
+      return GetRangeInches();
+    case Ultrasonic::kMilliMeters:
+      return GetRangeMM();
+    default:
+      return 0.0;
+  }
+}
+
+void Ultrasonic::SetPIDSourceType(PIDSourceType pidSource) {
+  if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) {
+    m_pidSource = pidSource;
+  }
+}
+
+void Ultrasonic::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Ultrasonic");
+  builder.AddDoubleProperty("Value", [=]() { return GetRangeInches(); },
+                            nullptr);
+}
+
+void Ultrasonic::Initialize() {
+  bool originalMode = m_automaticEnabled;
+  SetAutomaticMode(false);  // Kill task when adding a new sensor
+  // Link this instance on the list
+  m_sensors.emplace_back(this);
+
+  m_counter.SetMaxPeriod(1.0);
+  m_counter.SetSemiPeriodMode(true);
+  m_counter.Reset();
+  m_enabled = true;  // Make it available for round robin scheduling
+  SetAutomaticMode(originalMode);
+
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_Ultrasonic, instances);
+  SetName("Ultrasonic", m_echoChannel->GetChannel());
+}
+
+void Ultrasonic::UltrasonicChecker() {
+  while (m_automaticEnabled) {
+    for (auto& sensor : m_sensors) {
+      if (!m_automaticEnabled) break;
+
+      if (sensor->IsEnabled()) {
+        sensor->m_pingChannel->Pulse(kPingTime);  // do the ping
+      }
+
+      Wait(0.1);  // wait for ping to return
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Utility.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Utility.cpp
new file mode 100644
index 0000000..503b6d0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Utility.cpp
@@ -0,0 +1,203 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Utility.h"
+
+#ifndef _WIN32
+#include <cxxabi.h>
+#include <execinfo.h>
+#endif
+
+#include <cstdio>
+#include <cstdlib>
+#include <cstring>
+
+#include <hal/DriverStation.h>
+#include <hal/HAL.h>
+#include <wpi/Path.h>
+#include <wpi/SmallString.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/ErrorBase.h"
+
+using namespace frc;
+
+bool wpi_assert_impl(bool conditionValue, const wpi::Twine& conditionText,
+                     const wpi::Twine& message, wpi::StringRef fileName,
+                     int lineNumber, wpi::StringRef funcName) {
+  if (!conditionValue) {
+    wpi::SmallString<128> locBuf;
+    wpi::raw_svector_ostream locStream(locBuf);
+    locStream << funcName << " [" << wpi::sys::path::filename(fileName) << ":"
+              << lineNumber << "]";
+
+    wpi::SmallString<128> errorBuf;
+    wpi::raw_svector_ostream errorStream(errorBuf);
+
+    errorStream << "Assertion \"" << conditionText << "\" ";
+
+    if (message.isTriviallyEmpty() ||
+        (message.isSingleStringRef() && message.getSingleStringRef().empty())) {
+      errorStream << "failed.\n";
+    } else {
+      errorStream << "failed: " << message << "\n";
+    }
+
+    std::string stack = GetStackTrace(2);
+
+    // Print the error and send it to the DriverStation
+    HAL_SendError(1, 1, 0, errorBuf.c_str(), locBuf.c_str(), stack.c_str(), 1);
+  }
+
+  return conditionValue;
+}
+
+/**
+ * Common error routines for wpi_assertEqual_impl and wpi_assertNotEqual_impl.
+ *
+ * This should not be called directly; it should only be used by
+ * wpi_assertEqual_impl and wpi_assertNotEqual_impl.
+ */
+void wpi_assertEqual_common_impl(const wpi::Twine& valueA,
+                                 const wpi::Twine& valueB,
+                                 const wpi::Twine& equalityType,
+                                 const wpi::Twine& message,
+                                 wpi::StringRef fileName, int lineNumber,
+                                 wpi::StringRef funcName) {
+  wpi::SmallString<128> locBuf;
+  wpi::raw_svector_ostream locStream(locBuf);
+  locStream << funcName << " [" << wpi::sys::path::filename(fileName) << ":"
+            << lineNumber << "]";
+
+  wpi::SmallString<128> errorBuf;
+  wpi::raw_svector_ostream errorStream(errorBuf);
+
+  errorStream << "Assertion \"" << valueA << " " << equalityType << " "
+              << valueB << "\" ";
+
+  if (message.isTriviallyEmpty() ||
+      (message.isSingleStringRef() && message.getSingleStringRef().empty())) {
+    errorStream << "failed.\n";
+  } else {
+    errorStream << "failed: " << message << "\n";
+  }
+
+  std::string trace = GetStackTrace(3);
+
+  // Print the error and send it to the DriverStation
+  HAL_SendError(1, 1, 0, errorBuf.c_str(), locBuf.c_str(), trace.c_str(), 1);
+}
+
+bool wpi_assertEqual_impl(int valueA, int valueB,
+                          const wpi::Twine& valueAString,
+                          const wpi::Twine& valueBString,
+                          const wpi::Twine& message, wpi::StringRef fileName,
+                          int lineNumber, wpi::StringRef funcName) {
+  if (!(valueA == valueB)) {
+    wpi_assertEqual_common_impl(valueAString, valueBString, "==", message,
+                                fileName, lineNumber, funcName);
+  }
+  return valueA == valueB;
+}
+
+bool wpi_assertNotEqual_impl(int valueA, int valueB,
+                             const wpi::Twine& valueAString,
+                             const wpi::Twine& valueBString,
+                             const wpi::Twine& message, wpi::StringRef fileName,
+                             int lineNumber, wpi::StringRef funcName) {
+  if (!(valueA != valueB)) {
+    wpi_assertEqual_common_impl(valueAString, valueBString, "!=", message,
+                                fileName, lineNumber, funcName);
+  }
+  return valueA != valueB;
+}
+
+namespace frc {
+
+int GetFPGAVersion() {
+  int32_t status = 0;
+  int version = HAL_GetFPGAVersion(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return version;
+}
+
+int64_t GetFPGARevision() {
+  int32_t status = 0;
+  int64_t revision = HAL_GetFPGARevision(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return revision;
+}
+
+uint64_t GetFPGATime() {
+  int32_t status = 0;
+  uint64_t time = HAL_GetFPGATime(&status);
+  wpi_setGlobalErrorWithContext(status, HAL_GetErrorMessage(status));
+  return time;
+}
+
+bool GetUserButton() {
+  int32_t status = 0;
+
+  bool value = HAL_GetFPGAButton(&status);
+  wpi_setGlobalError(status);
+
+  return value;
+}
+
+#ifndef _WIN32
+
+/**
+ * Demangle a C++ symbol, used for printing stack traces.
+ */
+static std::string demangle(char const* mangledSymbol) {
+  char buffer[256];
+  size_t length;
+  int32_t status;
+
+  if (std::sscanf(mangledSymbol, "%*[^(]%*[(]%255[^)+]", buffer)) {
+    char* symbol = abi::__cxa_demangle(buffer, nullptr, &length, &status);
+    if (status == 0) {
+      return symbol;
+    } else {
+      // If the symbol couldn't be demangled, it's probably a C function,
+      // so just return it as-is.
+      return buffer;
+    }
+  }
+
+  // If everything else failed, just return the mangled symbol
+  return mangledSymbol;
+}
+
+std::string GetStackTrace(int offset) {
+  void* stackTrace[128];
+  int stackSize = backtrace(stackTrace, 128);
+  char** mangledSymbols = backtrace_symbols(stackTrace, stackSize);
+  wpi::SmallString<1024> buf;
+  wpi::raw_svector_ostream trace(buf);
+
+  for (int i = offset; i < stackSize; i++) {
+    // Only print recursive functions once in a row.
+    if (i == 0 || stackTrace[i] != stackTrace[i - 1]) {
+      trace << "\tat " << demangle(mangledSymbols[i]) << "\n";
+    }
+  }
+
+  std::free(mangledSymbols);
+
+  return trace.str();
+}
+
+#else
+static std::string demangle(char const* mangledSymbol) {
+  return "no demangling on windows";
+}
+
+std::string GetStackTrace(int offset) { return "no stack trace on windows"; }
+#endif
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Victor.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Victor.cpp
new file mode 100644
index 0000000..2c29ece
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Victor.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/Victor.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+Victor::Victor(int channel) : PWMSpeedController(channel) {
+  /* Note that the Victor uses the following bounds for PWM values.  These
+   * values were determined empirically and optimized for the Victor 888. These
+   * values should work reasonably well for Victor 884 controllers as well but
+   * if users experience issues such as asymmetric behaviour around the deadband
+   * or inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the Victor 884 User
+   * Manual available from IFI.
+   *
+   *   2.027ms = full "forward"
+   *   1.525ms = the "high end" of the deadband range
+   *   1.507ms = center of the deadband range (off)
+   *   1.49ms = the "low end" of the deadband range
+   *   1.026ms = full "reverse"
+   */
+  SetBounds(2.027, 1.525, 1.507, 1.49, 1.026);
+  SetPeriodMultiplier(kPeriodMultiplier_2X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_Victor, GetChannel());
+  SetName("Victor", GetChannel());
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/VictorSP.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/VictorSP.cpp
new file mode 100644
index 0000000..5e2b6b9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/VictorSP.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/VictorSP.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+VictorSP::VictorSP(int channel) : PWMSpeedController(channel) {
+  /* Note that the VictorSP uses the following bounds for PWM values. These
+   * values should work reasonably well for most controllers, but if users
+   * experience issues such as asymmetric behavior around the deadband or
+   * inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the VictorSP User
+   * Manual available from Vex.
+   *
+   *   2.004ms = full "forward"
+   *   1.52ms = the "high end" of the deadband range
+   *   1.50ms = center of the deadband range (off)
+   *   1.48ms = the "low end" of the deadband range
+   *   0.997ms = full "reverse"
+   */
+  SetBounds(2.004, 1.52, 1.50, 1.48, .997);
+  SetPeriodMultiplier(kPeriodMultiplier_1X);
+  SetSpeed(0.0);
+  SetZeroLatch();
+
+  HAL_Report(HALUsageReporting::kResourceType_VictorSP, GetChannel());
+  SetName("VictorSP", GetChannel());
+}
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
new file mode 100644
index 0000000..b67f94d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/Watchdog.cpp
@@ -0,0 +1,184 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Watchdog.h"
+
+#include <wpi/Format.h>
+#include <wpi/PriorityQueue.h>
+#include <wpi/raw_ostream.h>
+
+using namespace frc;
+
+constexpr std::chrono::milliseconds Watchdog::kMinPrintPeriod;
+
+class Watchdog::Thread : public wpi::SafeThread {
+ public:
+  template <typename T>
+  struct DerefGreater : public std::binary_function<T, T, bool> {
+    constexpr bool operator()(const T& lhs, const T& rhs) const {
+      return *lhs > *rhs;
+    }
+  };
+
+  wpi::PriorityQueue<Watchdog*, std::vector<Watchdog*>, DerefGreater<Watchdog*>>
+      m_watchdogs;
+
+ private:
+  void Main() override;
+};
+
+void Watchdog::Thread::Main() {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+
+  while (m_active) {
+    if (m_watchdogs.size() > 0) {
+      if (m_cond.wait_until(lock, m_watchdogs.top()->m_expirationTime) ==
+          std::cv_status::timeout) {
+        if (m_watchdogs.size() == 0 ||
+            m_watchdogs.top()->m_expirationTime > hal::fpga_clock::now()) {
+          continue;
+        }
+
+        // If the condition variable timed out, that means a Watchdog timeout
+        // has occurred, so call its timeout function.
+        auto watchdog = m_watchdogs.top();
+        m_watchdogs.pop();
+
+        auto now = hal::fpga_clock::now();
+        if (now - watchdog->m_lastTimeoutPrintTime > kMinPrintPeriod) {
+          watchdog->m_lastTimeoutPrintTime = now;
+          if (!watchdog->m_suppressTimeoutMessage) {
+            wpi::outs() << "Watchdog not fed within "
+                        << wpi::format("%.6f",
+                                       watchdog->m_timeout.count() / 1.0e6)
+                        << "s\n";
+          }
+        }
+
+        // Set expiration flag before calling the callback so any manipulation
+        // of the flag in the callback (e.g., calling Disable()) isn't
+        // clobbered.
+        watchdog->m_isExpired = true;
+
+        lock.unlock();
+        watchdog->m_callback();
+        lock.lock();
+      }
+      // Otherwise, a Watchdog removed itself from the queue (it notifies the
+      // scheduler of this) or a spurious wakeup occurred, so just rewait with
+      // the soonest watchdog timeout.
+    } else {
+      m_cond.wait(lock, [&] { return m_watchdogs.size() > 0 || !m_active; });
+    }
+  }
+}
+
+Watchdog::Watchdog(double timeout, std::function<void()> callback)
+    : m_timeout(static_cast<int64_t>(timeout * 1.0e6)),
+      m_callback(callback),
+      m_owner(&GetThreadOwner()) {}
+
+Watchdog::~Watchdog() { Disable(); }
+
+double Watchdog::GetTime() const {
+  return (hal::fpga_clock::now() - m_startTime).count() / 1.0e6;
+}
+
+void Watchdog::SetTimeout(double timeout) {
+  m_startTime = hal::fpga_clock::now();
+  m_epochs.clear();
+
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+  if (!thr) return;
+
+  m_timeout = std::chrono::microseconds(static_cast<int64_t>(timeout * 1.0e6));
+  m_isExpired = false;
+
+  thr->m_watchdogs.remove(this);
+  m_expirationTime = m_startTime + m_timeout;
+  thr->m_watchdogs.emplace(this);
+  thr->m_cond.notify_all();
+}
+
+double Watchdog::GetTimeout() const {
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+
+  return m_timeout.count() / 1.0e6;
+}
+
+bool Watchdog::IsExpired() const {
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+
+  return m_isExpired;
+}
+
+void Watchdog::AddEpoch(wpi::StringRef epochName) {
+  auto currentTime = hal::fpga_clock::now();
+  m_epochs[epochName] = currentTime - m_startTime;
+  m_startTime = currentTime;
+}
+
+void Watchdog::PrintEpochs() {
+  auto now = hal::fpga_clock::now();
+  if (now - m_lastEpochsPrintTime > kMinPrintPeriod) {
+    m_lastEpochsPrintTime = now;
+    for (const auto& epoch : m_epochs) {
+      wpi::outs() << '\t' << epoch.getKey() << ": "
+                  << wpi::format("%.6f", epoch.getValue().count() / 1.0e6)
+                  << "s\n";
+    }
+  }
+}
+
+void Watchdog::Reset() { Enable(); }
+
+void Watchdog::Enable() {
+  m_startTime = hal::fpga_clock::now();
+  m_epochs.clear();
+
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+  if (!thr) return;
+
+  m_isExpired = false;
+
+  thr->m_watchdogs.remove(this);
+  m_expirationTime = m_startTime + m_timeout;
+  thr->m_watchdogs.emplace(this);
+  thr->m_cond.notify_all();
+}
+
+void Watchdog::Disable() {
+  // Locks mutex
+  auto thr = m_owner->GetThread();
+  if (!thr) return;
+
+  m_isExpired = false;
+
+  thr->m_watchdogs.remove(this);
+  thr->m_cond.notify_all();
+}
+
+void Watchdog::SuppressTimeoutMessage(bool suppress) {
+  m_suppressTimeoutMessage = suppress;
+}
+
+bool Watchdog::operator>(const Watchdog& rhs) {
+  return m_expirationTime > rhs.m_expirationTime;
+}
+
+wpi::SafeThreadOwner<Watchdog::Thread>& Watchdog::GetThreadOwner() {
+  static wpi::SafeThreadOwner<Thread> inst = [] {
+    wpi::SafeThreadOwner<Watchdog::Thread> inst;
+    inst.Start();
+    return inst;
+  }();
+  return inst;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/XboxController.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/XboxController.cpp
new file mode 100644
index 0000000..fa54980
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/XboxController.cpp
@@ -0,0 +1,160 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/XboxController.h"
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+XboxController::XboxController(int port) : GenericHID(port) {
+  HAL_Report(HALUsageReporting::kResourceType_XboxController, port);
+}
+
+double XboxController::GetX(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(0);
+  } else {
+    return GetRawAxis(4);
+  }
+}
+
+double XboxController::GetY(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(1);
+  } else {
+    return GetRawAxis(5);
+  }
+}
+
+double XboxController::GetTriggerAxis(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawAxis(2);
+  } else {
+    return GetRawAxis(3);
+  }
+}
+
+bool XboxController::GetBumper(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawButton(static_cast<int>(Button::kBumperLeft));
+  } else {
+    return GetRawButton(static_cast<int>(Button::kBumperRight));
+  }
+}
+
+bool XboxController::GetBumperPressed(JoystickHand hand) {
+  if (hand == kLeftHand) {
+    return GetRawButtonPressed(static_cast<int>(Button::kBumperLeft));
+  } else {
+    return GetRawButtonPressed(static_cast<int>(Button::kBumperRight));
+  }
+}
+
+bool XboxController::GetBumperReleased(JoystickHand hand) {
+  if (hand == kLeftHand) {
+    return GetRawButtonReleased(static_cast<int>(Button::kBumperLeft));
+  } else {
+    return GetRawButtonReleased(static_cast<int>(Button::kBumperRight));
+  }
+}
+
+bool XboxController::GetStickButton(JoystickHand hand) const {
+  if (hand == kLeftHand) {
+    return GetRawButton(static_cast<int>(Button::kStickLeft));
+  } else {
+    return GetRawButton(static_cast<int>(Button::kStickRight));
+  }
+}
+
+bool XboxController::GetStickButtonPressed(JoystickHand hand) {
+  if (hand == kLeftHand) {
+    return GetRawButtonPressed(static_cast<int>(Button::kStickLeft));
+  } else {
+    return GetRawButtonPressed(static_cast<int>(Button::kStickRight));
+  }
+}
+
+bool XboxController::GetStickButtonReleased(JoystickHand hand) {
+  if (hand == kLeftHand) {
+    return GetRawButtonReleased(static_cast<int>(Button::kStickLeft));
+  } else {
+    return GetRawButtonReleased(static_cast<int>(Button::kStickRight));
+  }
+}
+
+bool XboxController::GetAButton() const {
+  return GetRawButton(static_cast<int>(Button::kA));
+}
+
+bool XboxController::GetAButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kA));
+}
+
+bool XboxController::GetAButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kA));
+}
+
+bool XboxController::GetBButton() const {
+  return GetRawButton(static_cast<int>(Button::kB));
+}
+
+bool XboxController::GetBButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kB));
+}
+
+bool XboxController::GetBButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kB));
+}
+
+bool XboxController::GetXButton() const {
+  return GetRawButton(static_cast<int>(Button::kX));
+}
+
+bool XboxController::GetXButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kX));
+}
+
+bool XboxController::GetXButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kX));
+}
+
+bool XboxController::GetYButton() const {
+  return GetRawButton(static_cast<int>(Button::kY));
+}
+
+bool XboxController::GetYButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kY));
+}
+
+bool XboxController::GetYButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kY));
+}
+
+bool XboxController::GetBackButton() const {
+  return GetRawButton(static_cast<int>(Button::kBack));
+}
+
+bool XboxController::GetBackButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kBack));
+}
+
+bool XboxController::GetBackButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kBack));
+}
+
+bool XboxController::GetStartButton() const {
+  return GetRawButton(static_cast<int>(Button::kStart));
+}
+
+bool XboxController::GetStartButtonPressed() {
+  return GetRawButtonPressed(static_cast<int>(Button::kStart));
+}
+
+bool XboxController::GetStartButtonReleased() {
+  return GetRawButtonReleased(static_cast<int>(Button::kStart));
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/Button.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/Button.cpp
new file mode 100644
index 0000000..45ede65
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/Button.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/Button.h"
+
+using namespace frc;
+
+void Button::WhenPressed(Command* command) { WhenActive(command); }
+
+void Button::WhileHeld(Command* command) { WhileActive(command); }
+
+void Button::WhenReleased(Command* command) { WhenInactive(command); }
+
+void Button::CancelWhenPressed(Command* command) { CancelWhenActive(command); }
+
+void Button::ToggleWhenPressed(Command* command) { ToggleWhenActive(command); }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ButtonScheduler.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ButtonScheduler.cpp
new file mode 100644
index 0000000..1e10255
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ButtonScheduler.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/ButtonScheduler.h"
+
+#include "frc/commands/Scheduler.h"
+
+using namespace frc;
+
+ButtonScheduler::ButtonScheduler(bool last, Trigger* button, Command* orders)
+    : m_pressedLast(last), m_button(button), m_command(orders) {}
+
+void ButtonScheduler::Start() { Scheduler::GetInstance()->AddButton(this); }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/CancelButtonScheduler.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/CancelButtonScheduler.cpp
new file mode 100644
index 0000000..39d1d25
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/CancelButtonScheduler.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/CancelButtonScheduler.h"
+
+#include "frc/buttons/Button.h"
+#include "frc/commands/Command.h"
+
+using namespace frc;
+
+CancelButtonScheduler::CancelButtonScheduler(bool last, Trigger* button,
+                                             Command* orders)
+    : ButtonScheduler(last, button, orders) {}
+
+void CancelButtonScheduler::Execute() {
+  bool pressed = m_button->Grab();
+
+  if (!m_pressedLast && pressed) {
+    m_command->Cancel();
+  }
+
+  m_pressedLast = pressed;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/HeldButtonScheduler.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/HeldButtonScheduler.cpp
new file mode 100644
index 0000000..feaa3c6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/HeldButtonScheduler.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/HeldButtonScheduler.h"
+
+#include "frc/buttons/Button.h"
+#include "frc/commands/Command.h"
+
+using namespace frc;
+
+HeldButtonScheduler::HeldButtonScheduler(bool last, Trigger* button,
+                                         Command* orders)
+    : ButtonScheduler(last, button, orders) {}
+
+void HeldButtonScheduler::Execute() {
+  bool pressed = m_button->Grab();
+
+  if (pressed) {
+    m_command->Start();
+  } else if (m_pressedLast && !pressed) {
+    m_command->Cancel();
+  }
+
+  m_pressedLast = pressed;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/InternalButton.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/InternalButton.cpp
new file mode 100644
index 0000000..cac67c4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/InternalButton.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/InternalButton.h"
+
+using namespace frc;
+
+InternalButton::InternalButton(bool inverted)
+    : m_pressed(inverted), m_inverted(inverted) {}
+
+void InternalButton::SetInverted(bool inverted) { m_inverted = inverted; }
+
+void InternalButton::SetPressed(bool pressed) { m_pressed = pressed; }
+
+bool InternalButton::Get() { return m_pressed ^ m_inverted; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/JoystickButton.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/JoystickButton.cpp
new file mode 100644
index 0000000..2c93be2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/JoystickButton.cpp
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/JoystickButton.h"
+
+using namespace frc;
+
+JoystickButton::JoystickButton(GenericHID* joystick, int buttonNumber)
+    : m_joystick(joystick), m_buttonNumber(buttonNumber) {}
+
+bool JoystickButton::Get() { return m_joystick->GetRawButton(m_buttonNumber); }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/NetworkButton.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/NetworkButton.cpp
new file mode 100644
index 0000000..5e8b1e0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/NetworkButton.cpp
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/NetworkButton.h"
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+
+using namespace frc;
+
+NetworkButton::NetworkButton(const wpi::Twine& tableName,
+                             const wpi::Twine& field)
+    : NetworkButton(nt::NetworkTableInstance::GetDefault().GetTable(tableName),
+                    field) {}
+
+NetworkButton::NetworkButton(std::shared_ptr<nt::NetworkTable> table,
+                             const wpi::Twine& field)
+    : m_entry(table->GetEntry(field)) {}
+
+bool NetworkButton::Get() {
+  return m_entry.GetInstance().IsConnected() && m_entry.GetBoolean(false);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/POVButton.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/POVButton.cpp
new file mode 100644
index 0000000..6729923
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/POVButton.cpp
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* 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/buttons/POVButton.h"
+
+using namespace frc;
+
+POVButton::POVButton(GenericHID& joystick, int angle, int povNumber)
+    : m_joystick(&joystick), m_angle(angle), m_povNumber(povNumber) {}
+
+bool POVButton::Get() { return m_joystick->GetPOV(m_povNumber) == m_angle; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/PressedButtonScheduler.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/PressedButtonScheduler.cpp
new file mode 100644
index 0000000..a964117
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/PressedButtonScheduler.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/PressedButtonScheduler.h"
+
+#include "frc/buttons/Button.h"
+#include "frc/commands/Command.h"
+
+using namespace frc;
+
+PressedButtonScheduler::PressedButtonScheduler(bool last, Trigger* button,
+                                               Command* orders)
+    : ButtonScheduler(last, button, orders) {}
+
+void PressedButtonScheduler::Execute() {
+  bool pressed = m_button->Grab();
+
+  if (!m_pressedLast && pressed) {
+    m_command->Start();
+  }
+
+  m_pressedLast = pressed;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp
new file mode 100644
index 0000000..6d67004
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ReleasedButtonScheduler.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/ReleasedButtonScheduler.h"
+
+#include "frc/buttons/Button.h"
+#include "frc/commands/Command.h"
+
+using namespace frc;
+
+ReleasedButtonScheduler::ReleasedButtonScheduler(bool last, Trigger* button,
+                                                 Command* orders)
+    : ButtonScheduler(last, button, orders) {}
+
+void ReleasedButtonScheduler::Execute() {
+  bool pressed = m_button->Grab();
+
+  if (m_pressedLast && !pressed) {
+    m_command->Start();
+  }
+
+  m_pressedLast = pressed;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp
new file mode 100644
index 0000000..b722d45
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/ToggleButtonScheduler.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/ToggleButtonScheduler.h"
+
+#include "frc/buttons/Button.h"
+#include "frc/commands/Command.h"
+
+using namespace frc;
+
+ToggleButtonScheduler::ToggleButtonScheduler(bool last, Trigger* button,
+                                             Command* orders)
+    : ButtonScheduler(last, button, orders) {}
+
+void ToggleButtonScheduler::Execute() {
+  bool pressed = m_button->Grab();
+
+  if (!m_pressedLast && pressed) {
+    if (m_command->IsRunning()) {
+      m_command->Cancel();
+    } else {
+      m_command->Start();
+    }
+  }
+
+  m_pressedLast = pressed;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/Trigger.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/Trigger.cpp
new file mode 100644
index 0000000..2ccaaf2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/buttons/Trigger.cpp
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/buttons/Button.h"
+#include "frc/buttons/CancelButtonScheduler.h"
+#include "frc/buttons/HeldButtonScheduler.h"
+#include "frc/buttons/PressedButtonScheduler.h"
+#include "frc/buttons/ReleasedButtonScheduler.h"
+#include "frc/buttons/ToggleButtonScheduler.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+bool Trigger::Grab() { return Get() || m_sendablePressed; }
+
+void Trigger::WhenActive(Command* command) {
+  auto pbs = new PressedButtonScheduler(Grab(), this, command);
+  pbs->Start();
+}
+
+void Trigger::WhileActive(Command* command) {
+  auto hbs = new HeldButtonScheduler(Grab(), this, command);
+  hbs->Start();
+}
+
+void Trigger::WhenInactive(Command* command) {
+  auto rbs = new ReleasedButtonScheduler(Grab(), this, command);
+  rbs->Start();
+}
+
+void Trigger::CancelWhenActive(Command* command) {
+  auto cbs = new CancelButtonScheduler(Grab(), this, command);
+  cbs->Start();
+}
+
+void Trigger::ToggleWhenActive(Command* command) {
+  auto tbs = new ToggleButtonScheduler(Grab(), this, command);
+  tbs->Start();
+}
+
+void Trigger::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Button");
+  builder.SetSafeState([=]() { m_sendablePressed = false; });
+  builder.AddBooleanProperty("pressed", [=]() { return Grab(); },
+                             [=](bool value) { m_sendablePressed = value; });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Command.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Command.cpp
new file mode 100644
index 0000000..ad7824a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Command.cpp
@@ -0,0 +1,244 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/Command.h"
+
+#include <typeinfo>
+
+#include "frc/RobotState.h"
+#include "frc/Timer.h"
+#include "frc/WPIErrors.h"
+#include "frc/commands/CommandGroup.h"
+#include "frc/commands/Scheduler.h"
+#include "frc/livewindow/LiveWindow.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+int Command::m_commandCounter = 0;
+
+Command::Command() : Command("", -1.0) {}
+
+Command::Command(const wpi::Twine& name) : Command(name, -1.0) {}
+
+Command::Command(double timeout) : Command("", timeout) {}
+
+Command::Command(Subsystem& subsystem) : Command("", -1.0) {
+  Requires(&subsystem);
+}
+
+Command::Command(const wpi::Twine& name, double timeout) : SendableBase(false) {
+  // We use -1.0 to indicate no timeout.
+  if (timeout < 0.0 && timeout != -1.0)
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+
+  m_timeout = timeout;
+
+  // If name contains an empty string
+  if (name.isTriviallyEmpty() ||
+      (name.isSingleStringRef() && name.getSingleStringRef().empty())) {
+    SetName("Command_" + wpi::Twine(typeid(*this).name()));
+  } else {
+    SetName(name);
+  }
+}
+
+Command::Command(const wpi::Twine& name, Subsystem& subsystem)
+    : Command(name, -1.0) {
+  Requires(&subsystem);
+}
+
+Command::Command(double timeout, Subsystem& subsystem) : Command("", timeout) {
+  Requires(&subsystem);
+}
+
+Command::Command(const wpi::Twine& name, double timeout, Subsystem& subsystem)
+    : Command(name, timeout) {
+  Requires(&subsystem);
+}
+
+double Command::TimeSinceInitialized() const {
+  if (m_startTime < 0.0)
+    return 0.0;
+  else
+    return Timer::GetFPGATimestamp() - m_startTime;
+}
+
+void Command::Requires(Subsystem* subsystem) {
+  if (!AssertUnlocked("Can not add new requirement to command")) return;
+
+  if (subsystem != nullptr)
+    m_requirements.insert(subsystem);
+  else
+    wpi_setWPIErrorWithContext(NullParameter, "subsystem");
+}
+
+void Command::Start() {
+  LockChanges();
+  if (m_parent != nullptr)
+    wpi_setWPIErrorWithContext(
+        CommandIllegalUse,
+        "Can not start a command that is part of a command group");
+
+  m_completed = false;
+  Scheduler::GetInstance()->AddCommand(this);
+}
+
+bool Command::Run() {
+  if (!m_runWhenDisabled && m_parent == nullptr && RobotState::IsDisabled())
+    Cancel();
+
+  if (IsCanceled()) return false;
+
+  if (!m_initialized) {
+    m_initialized = true;
+    StartTiming();
+    _Initialize();
+    Initialize();
+  }
+  _Execute();
+  Execute();
+  return !IsFinished();
+}
+
+void Command::Cancel() {
+  if (m_parent != nullptr)
+    wpi_setWPIErrorWithContext(
+        CommandIllegalUse,
+        "Can not cancel a command that is part of a command group");
+
+  _Cancel();
+}
+
+bool Command::IsRunning() const { return m_running; }
+
+bool Command::IsInitialized() const { return m_initialized; }
+
+bool Command::IsCompleted() const { return m_completed; }
+
+bool Command::IsCanceled() const { return m_canceled; }
+
+bool Command::IsInterruptible() const { return m_interruptible; }
+
+void Command::SetInterruptible(bool interruptible) {
+  m_interruptible = interruptible;
+}
+
+bool Command::DoesRequire(Subsystem* system) const {
+  return m_requirements.count(system) > 0;
+}
+
+const Command::SubsystemSet& Command::GetRequirements() const {
+  return m_requirements;
+}
+
+CommandGroup* Command::GetGroup() const { return m_parent; }
+
+void Command::SetRunWhenDisabled(bool run) { m_runWhenDisabled = run; }
+
+bool Command::WillRunWhenDisabled() const { return m_runWhenDisabled; }
+
+int Command::GetID() const { return m_commandID; }
+
+void Command::SetTimeout(double timeout) {
+  if (timeout < 0.0)
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+  else
+    m_timeout = timeout;
+}
+
+bool Command::IsTimedOut() const {
+  return m_timeout != -1 && TimeSinceInitialized() >= m_timeout;
+}
+
+bool Command::AssertUnlocked(const std::string& message) {
+  if (m_locked) {
+    std::string buf =
+        message + " after being started or being added to a command group";
+    wpi_setWPIErrorWithContext(CommandIllegalUse, buf);
+    return false;
+  }
+  return true;
+}
+
+void Command::SetParent(CommandGroup* parent) {
+  if (parent == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "parent");
+  } else if (m_parent != nullptr) {
+    wpi_setWPIErrorWithContext(CommandIllegalUse,
+                               "Can not give command to a command group after "
+                               "already being put in a command group");
+  } else {
+    LockChanges();
+    m_parent = parent;
+  }
+}
+
+bool Command::IsParented() const { return m_parent != nullptr; }
+
+void Command::ClearRequirements() { m_requirements.clear(); }
+
+void Command::Initialize() {}
+
+void Command::Execute() {}
+
+void Command::End() {}
+
+void Command::Interrupted() { End(); }
+
+void Command::_Initialize() { m_completed = false; }
+
+void Command::_Interrupted() { m_completed = true; }
+
+void Command::_Execute() {}
+
+void Command::_End() { m_completed = true; }
+
+void Command::_Cancel() {
+  if (IsRunning()) m_canceled = true;
+}
+
+void Command::LockChanges() { m_locked = true; }
+
+void Command::Removed() {
+  if (m_initialized) {
+    if (IsCanceled()) {
+      Interrupted();
+      _Interrupted();
+    } else {
+      End();
+      _End();
+    }
+  }
+  m_initialized = false;
+  m_canceled = false;
+  m_running = false;
+  m_completed = true;
+}
+
+void Command::StartRunning() {
+  m_running = true;
+  m_startTime = -1;
+  m_completed = false;
+}
+
+void Command::StartTiming() { m_startTime = Timer::GetFPGATimestamp(); }
+
+void Command::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Command");
+  builder.AddStringProperty(".name", [=]() { return GetName(); }, nullptr);
+  builder.AddBooleanProperty("running", [=]() { return IsRunning(); },
+                             [=](bool value) {
+                               if (value) {
+                                 if (!IsRunning()) Start();
+                               } else {
+                                 if (IsRunning()) Cancel();
+                               }
+                             });
+  builder.AddBooleanProperty(".isParented", [=]() { return IsParented(); },
+                             nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/CommandGroup.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/CommandGroup.cpp
new file mode 100644
index 0000000..eac1746
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/CommandGroup.cpp
@@ -0,0 +1,243 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/CommandGroup.h"
+
+#include "frc/WPIErrors.h"
+
+using namespace frc;
+
+CommandGroup::CommandGroup(const wpi::Twine& name) : Command(name) {}
+
+void CommandGroup::AddSequential(Command* command) {
+  if (command == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "command");
+    return;
+  }
+  if (!AssertUnlocked("Cannot add new command to command group")) return;
+
+  m_commands.emplace_back(command, CommandGroupEntry::kSequence_InSequence);
+
+  command->SetParent(this);
+
+  // Iterate through command->GetRequirements() and call Requires() on each
+  // required subsystem
+  for (auto&& requirement : command->GetRequirements()) Requires(requirement);
+}
+
+void CommandGroup::AddSequential(Command* command, double timeout) {
+  if (command == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "command");
+    return;
+  }
+  if (!AssertUnlocked("Cannot add new command to command group")) return;
+  if (timeout < 0.0) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+    return;
+  }
+
+  m_commands.emplace_back(command, CommandGroupEntry::kSequence_InSequence,
+                          timeout);
+
+  command->SetParent(this);
+
+  // Iterate through command->GetRequirements() and call Requires() on each
+  // required subsystem
+  for (auto&& requirement : command->GetRequirements()) Requires(requirement);
+}
+
+void CommandGroup::AddParallel(Command* command) {
+  if (command == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "command");
+    return;
+  }
+  if (!AssertUnlocked("Cannot add new command to command group")) return;
+
+  m_commands.emplace_back(command, CommandGroupEntry::kSequence_BranchChild);
+
+  command->SetParent(this);
+
+  // Iterate through command->GetRequirements() and call Requires() on each
+  // required subsystem
+  for (auto&& requirement : command->GetRequirements()) Requires(requirement);
+}
+
+void CommandGroup::AddParallel(Command* command, double timeout) {
+  if (command == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "command");
+    return;
+  }
+  if (!AssertUnlocked("Cannot add new command to command group")) return;
+  if (timeout < 0.0) {
+    wpi_setWPIErrorWithContext(ParameterOutOfRange, "timeout < 0.0");
+    return;
+  }
+
+  m_commands.emplace_back(command, CommandGroupEntry::kSequence_BranchChild,
+                          timeout);
+
+  command->SetParent(this);
+
+  // Iterate through command->GetRequirements() and call Requires() on each
+  // required subsystem
+  for (auto&& requirement : command->GetRequirements()) Requires(requirement);
+}
+
+bool CommandGroup::IsInterruptible() const {
+  if (!Command::IsInterruptible()) return false;
+
+  if (m_currentCommandIndex != -1 &&
+      static_cast<size_t>(m_currentCommandIndex) < m_commands.size()) {
+    Command* cmd = m_commands[m_currentCommandIndex].m_command;
+    if (!cmd->IsInterruptible()) return false;
+  }
+
+  for (const auto& child : m_children) {
+    if (!child->m_command->IsInterruptible()) return false;
+  }
+
+  return true;
+}
+
+int CommandGroup::GetSize() const { return m_children.size(); }
+
+void CommandGroup::Initialize() {}
+
+void CommandGroup::Execute() {}
+
+bool CommandGroup::IsFinished() {
+  return static_cast<size_t>(m_currentCommandIndex) >= m_commands.size() &&
+         m_children.empty();
+}
+
+void CommandGroup::End() {}
+
+void CommandGroup::Interrupted() {}
+
+void CommandGroup::_Initialize() { m_currentCommandIndex = -1; }
+
+void CommandGroup::_Execute() {
+  CommandGroupEntry* entry;
+  Command* cmd = nullptr;
+  bool firstRun = false;
+
+  if (m_currentCommandIndex == -1) {
+    firstRun = true;
+    m_currentCommandIndex = 0;
+  }
+
+  // While there are still commands in this group to run
+  while (static_cast<size_t>(m_currentCommandIndex) < m_commands.size()) {
+    // If a command is prepared to run
+    if (cmd != nullptr) {
+      // If command timed out, cancel it so it's removed from the Scheduler
+      if (entry->IsTimedOut()) cmd->_Cancel();
+
+      // If command finished or was cancelled, remove it from Scheduler
+      if (cmd->Run()) {
+        break;
+      } else {
+        cmd->Removed();
+
+        // Advance to next command in group
+        m_currentCommandIndex++;
+        firstRun = true;
+        cmd = nullptr;
+        continue;
+      }
+    }
+
+    entry = &m_commands[m_currentCommandIndex];
+    cmd = nullptr;
+
+    switch (entry->m_state) {
+      case CommandGroupEntry::kSequence_InSequence:
+        cmd = entry->m_command;
+        if (firstRun) {
+          cmd->StartRunning();
+          CancelConflicts(cmd);
+          firstRun = false;
+        }
+        break;
+
+      case CommandGroupEntry::kSequence_BranchPeer:
+        // Start executing a parallel command and advance to next entry in group
+        m_currentCommandIndex++;
+        entry->m_command->Start();
+        break;
+
+      case CommandGroupEntry::kSequence_BranchChild:
+        m_currentCommandIndex++;
+
+        /* Causes scheduler to skip children of current command which require
+         * the same subsystems as it
+         */
+        CancelConflicts(entry->m_command);
+        entry->m_command->StartRunning();
+
+        // Add current command entry to list of children of this group
+        m_children.push_back(entry);
+        break;
+    }
+  }
+
+  // Run Children
+  for (auto& entry : m_children) {
+    auto child = entry->m_command;
+    if (entry->IsTimedOut()) {
+      child->_Cancel();
+    }
+
+    // If child finished or was cancelled, set it to nullptr. nullptr entries
+    // are removed later.
+    if (!child->Run()) {
+      child->Removed();
+      entry = nullptr;
+    }
+  }
+
+  m_children.erase(std::remove(m_children.begin(), m_children.end(), nullptr),
+                   m_children.end());
+}
+
+void CommandGroup::_End() {
+  // Theoretically, we don't have to check this, but we do if teams override the
+  // IsFinished method
+  if (m_currentCommandIndex != -1 &&
+      static_cast<size_t>(m_currentCommandIndex) < m_commands.size()) {
+    Command* cmd = m_commands[m_currentCommandIndex].m_command;
+    cmd->_Cancel();
+    cmd->Removed();
+  }
+
+  for (auto& child : m_children) {
+    Command* cmd = child->m_command;
+    cmd->_Cancel();
+    cmd->Removed();
+  }
+  m_children.clear();
+}
+
+void CommandGroup::_Interrupted() { _End(); }
+
+void CommandGroup::CancelConflicts(Command* command) {
+  for (auto childIter = m_children.begin(); childIter != m_children.end();) {
+    Command* child = (*childIter)->m_command;
+    bool erased = false;
+
+    for (auto&& requirement : command->GetRequirements()) {
+      if (child->DoesRequire(requirement)) {
+        child->_Cancel();
+        child->Removed();
+        childIter = m_children.erase(childIter);
+        erased = true;
+        break;
+      }
+    }
+    if (!erased) childIter++;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/CommandGroupEntry.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/CommandGroupEntry.cpp
new file mode 100644
index 0000000..7a75f00
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/CommandGroupEntry.cpp
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/CommandGroupEntry.h"
+
+#include "frc/commands/Command.h"
+
+using namespace frc;
+
+CommandGroupEntry::CommandGroupEntry(Command* command, Sequence state,
+                                     double timeout)
+    : m_timeout(timeout), m_command(command), m_state(state) {}
+
+bool CommandGroupEntry::IsTimedOut() const {
+  if (m_timeout < 0.0) return false;
+  double time = m_command->TimeSinceInitialized();
+  if (time == 0.0) return false;
+  return time >= m_timeout;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/ConditionalCommand.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/ConditionalCommand.cpp
new file mode 100644
index 0000000..c44f7ba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/ConditionalCommand.cpp
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/commands/ConditionalCommand.h"
+
+#include "frc/commands/Scheduler.h"
+
+using namespace frc;
+
+static void RequireAll(Command& command, Command* onTrue, Command* onFalse) {
+  if (onTrue != nullptr) {
+    for (auto requirement : onTrue->GetRequirements())
+      command.Requires(requirement);
+  }
+  if (onFalse != nullptr) {
+    for (auto requirement : onFalse->GetRequirements())
+      command.Requires(requirement);
+  }
+}
+
+ConditionalCommand::ConditionalCommand(Command* onTrue, Command* onFalse) {
+  m_onTrue = onTrue;
+  m_onFalse = onFalse;
+
+  RequireAll(*this, onTrue, onFalse);
+}
+
+ConditionalCommand::ConditionalCommand(const wpi::Twine& name, Command* onTrue,
+                                       Command* onFalse)
+    : Command(name) {
+  m_onTrue = onTrue;
+  m_onFalse = onFalse;
+
+  RequireAll(*this, onTrue, onFalse);
+}
+
+void ConditionalCommand::_Initialize() {
+  if (Condition()) {
+    m_chosenCommand = m_onTrue;
+  } else {
+    m_chosenCommand = m_onFalse;
+  }
+
+  if (m_chosenCommand != nullptr) {
+    // This is a hack to make cancelling the chosen command inside a
+    // CommandGroup work properly
+    m_chosenCommand->ClearRequirements();
+
+    m_chosenCommand->Start();
+  }
+  Command::_Initialize();
+}
+
+void ConditionalCommand::_Cancel() {
+  if (m_chosenCommand != nullptr && m_chosenCommand->IsRunning()) {
+    m_chosenCommand->Cancel();
+  }
+
+  Command::_Cancel();
+}
+
+bool ConditionalCommand::IsFinished() {
+  if (m_chosenCommand != nullptr) {
+    return m_chosenCommand->IsCompleted();
+  } else {
+    return true;
+  }
+}
+
+void ConditionalCommand::_Interrupted() {
+  if (m_chosenCommand != nullptr && m_chosenCommand->IsRunning()) {
+    m_chosenCommand->Cancel();
+  }
+
+  Command::_Interrupted();
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/InstantCommand.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/InstantCommand.cpp
new file mode 100644
index 0000000..88ebfde
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/InstantCommand.cpp
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/commands/InstantCommand.h"
+
+using namespace frc;
+
+InstantCommand::InstantCommand(const wpi::Twine& name) : Command(name) {}
+
+InstantCommand::InstantCommand(Subsystem& subsystem) : Command(subsystem) {}
+
+InstantCommand::InstantCommand(const wpi::Twine& name, Subsystem& subsystem)
+    : Command(name, subsystem) {}
+
+InstantCommand::InstantCommand(std::function<void()> func) : m_func(func) {}
+
+InstantCommand::InstantCommand(Subsystem& subsystem, std::function<void()> func)
+    : InstantCommand(subsystem) {
+  m_func = func;
+}
+
+InstantCommand::InstantCommand(const wpi::Twine& name,
+                               std::function<void()> func)
+    : InstantCommand(name) {
+  m_func = func;
+}
+
+InstantCommand::InstantCommand(const wpi::Twine& name, Subsystem& subsystem,
+                               std::function<void()> func)
+    : InstantCommand(name, subsystem) {
+  m_func = func;
+}
+
+void InstantCommand::_Initialize() {
+  Command::_Initialize();
+  if (m_func) {
+    m_func();
+  }
+}
+
+bool InstantCommand::IsFinished() { return true; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PIDCommand.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PIDCommand.cpp
new file mode 100644
index 0000000..875d8fe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PIDCommand.cpp
@@ -0,0 +1,108 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/PIDCommand.h"
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+PIDCommand::PIDCommand(const wpi::Twine& name, double p, double i, double d,
+                       double f, double period)
+    : Command(name) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
+}
+
+PIDCommand::PIDCommand(double p, double i, double d, double f, double period) {
+  m_controller =
+      std::make_shared<PIDController>(p, i, d, f, this, this, period);
+}
+
+PIDCommand::PIDCommand(const wpi::Twine& name, double p, double i, double d)
+    : Command(name) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
+}
+
+PIDCommand::PIDCommand(const wpi::Twine& name, double p, double i, double d,
+                       double period)
+    : Command(name) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
+}
+
+PIDCommand::PIDCommand(double p, double i, double d) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
+}
+
+PIDCommand::PIDCommand(double p, double i, double d, double period) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
+}
+
+PIDCommand::PIDCommand(const wpi::Twine& name, double p, double i, double d,
+                       double f, double period, Subsystem& subsystem)
+    : Command(name, subsystem) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
+}
+
+PIDCommand::PIDCommand(double p, double i, double d, double f, double period,
+                       Subsystem& subsystem)
+    : Command(subsystem) {
+  m_controller =
+      std::make_shared<PIDController>(p, i, d, f, this, this, period);
+}
+
+PIDCommand::PIDCommand(const wpi::Twine& name, double p, double i, double d,
+                       Subsystem& subsystem)
+    : Command(name, subsystem) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
+}
+
+PIDCommand::PIDCommand(const wpi::Twine& name, double p, double i, double d,
+                       double period, Subsystem& subsystem)
+    : Command(name, subsystem) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
+}
+
+PIDCommand::PIDCommand(double p, double i, double d, Subsystem& subsystem) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
+}
+
+PIDCommand::PIDCommand(double p, double i, double d, double period,
+                       Subsystem& subsystem) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this, period);
+}
+
+void PIDCommand::_Initialize() { m_controller->Enable(); }
+
+void PIDCommand::_End() { m_controller->Disable(); }
+
+void PIDCommand::_Interrupted() { _End(); }
+
+void PIDCommand::SetSetpointRelative(double deltaSetpoint) {
+  SetSetpoint(GetSetpoint() + deltaSetpoint);
+}
+
+void PIDCommand::PIDWrite(double output) { UsePIDOutput(output); }
+
+double PIDCommand::PIDGet() { return ReturnPIDInput(); }
+
+std::shared_ptr<PIDController> PIDCommand::GetPIDController() const {
+  return m_controller;
+}
+
+void PIDCommand::SetSetpoint(double setpoint) {
+  m_controller->SetSetpoint(setpoint);
+}
+
+double PIDCommand::GetSetpoint() const { return m_controller->GetSetpoint(); }
+
+double PIDCommand::GetPosition() { return ReturnPIDInput(); }
+
+void PIDCommand::InitSendable(SendableBuilder& builder) {
+  m_controller->InitSendable(builder);
+  Command::InitSendable(builder);
+  builder.SetSmartDashboardType("PIDCommand");
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PIDSubsystem.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PIDSubsystem.cpp
new file mode 100644
index 0000000..0893da3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PIDSubsystem.cpp
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/PIDSubsystem.h"
+
+#include "frc/PIDController.h"
+
+using namespace frc;
+
+PIDSubsystem::PIDSubsystem(const wpi::Twine& name, double p, double i, double d)
+    : Subsystem(name) {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
+  AddChild("PIDController", m_controller);
+}
+
+PIDSubsystem::PIDSubsystem(const wpi::Twine& name, double p, double i, double d,
+                           double f)
+    : Subsystem(name) {
+  m_controller = std::make_shared<PIDController>(p, i, d, f, this, this);
+  AddChild("PIDController", m_controller);
+}
+
+PIDSubsystem::PIDSubsystem(const wpi::Twine& name, double p, double i, double d,
+                           double f, double period)
+    : Subsystem(name) {
+  m_controller =
+      std::make_shared<PIDController>(p, i, d, f, this, this, period);
+  AddChild("PIDController", m_controller);
+}
+
+PIDSubsystem::PIDSubsystem(double p, double i, double d)
+    : Subsystem("PIDSubsystem") {
+  m_controller = std::make_shared<PIDController>(p, i, d, this, this);
+  AddChild("PIDController", m_controller);
+}
+
+PIDSubsystem::PIDSubsystem(double p, double i, double d, double f)
+    : Subsystem("PIDSubsystem") {
+  m_controller = std::make_shared<PIDController>(p, i, d, f, this, this);
+  AddChild("PIDController", m_controller);
+}
+
+PIDSubsystem::PIDSubsystem(double p, double i, double d, double f,
+                           double period)
+    : Subsystem("PIDSubsystem") {
+  m_controller =
+      std::make_shared<PIDController>(p, i, d, f, this, this, period);
+  AddChild("PIDController", m_controller);
+}
+
+void PIDSubsystem::Enable() { m_controller->Enable(); }
+
+void PIDSubsystem::Disable() { m_controller->Disable(); }
+
+void PIDSubsystem::PIDWrite(double output) { UsePIDOutput(output); }
+
+double PIDSubsystem::PIDGet() { return ReturnPIDInput(); }
+
+void PIDSubsystem::SetSetpoint(double setpoint) {
+  m_controller->SetSetpoint(setpoint);
+}
+
+void PIDSubsystem::SetSetpointRelative(double deltaSetpoint) {
+  SetSetpoint(GetSetpoint() + deltaSetpoint);
+}
+
+void PIDSubsystem::SetInputRange(double minimumInput, double maximumInput) {
+  m_controller->SetInputRange(minimumInput, maximumInput);
+}
+
+void PIDSubsystem::SetOutputRange(double minimumOutput, double maximumOutput) {
+  m_controller->SetOutputRange(minimumOutput, maximumOutput);
+}
+
+double PIDSubsystem::GetSetpoint() { return m_controller->GetSetpoint(); }
+
+double PIDSubsystem::GetPosition() { return ReturnPIDInput(); }
+
+double PIDSubsystem::GetRate() { return ReturnPIDInput(); }
+
+void PIDSubsystem::SetAbsoluteTolerance(double absValue) {
+  m_controller->SetAbsoluteTolerance(absValue);
+}
+
+void PIDSubsystem::SetPercentTolerance(double percent) {
+  m_controller->SetPercentTolerance(percent);
+}
+
+bool PIDSubsystem::OnTarget() const { return m_controller->OnTarget(); }
+
+std::shared_ptr<PIDController> PIDSubsystem::GetPIDController() {
+  return m_controller;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PrintCommand.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PrintCommand.cpp
new file mode 100644
index 0000000..b4bea24
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/PrintCommand.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/PrintCommand.h"
+
+#include <wpi/raw_ostream.h>
+
+using namespace frc;
+
+PrintCommand::PrintCommand(const wpi::Twine& message)
+    : InstantCommand("Print \"" + message + wpi::Twine('"')) {
+  m_message = message.str();
+}
+
+void PrintCommand::Initialize() { wpi::outs() << m_message << '\n'; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Scheduler.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Scheduler.cpp
new file mode 100644
index 0000000..8a7af76
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Scheduler.cpp
@@ -0,0 +1,243 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/Scheduler.h"
+
+#include <algorithm>
+#include <set>
+#include <string>
+#include <vector>
+
+#include <hal/HAL.h>
+#include <networktables/NetworkTableEntry.h>
+#include <wpi/mutex.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/buttons/ButtonScheduler.h"
+#include "frc/commands/Command.h"
+#include "frc/commands/Subsystem.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+struct Scheduler::Impl {
+  void Remove(Command* command);
+  void ProcessCommandAddition(Command* command);
+
+  using SubsystemSet = std::set<Subsystem*>;
+  SubsystemSet subsystems;
+  wpi::mutex buttonsMutex;
+  using ButtonVector = std::vector<std::unique_ptr<ButtonScheduler>>;
+  ButtonVector buttons;
+  using CommandVector = std::vector<Command*>;
+  wpi::mutex additionsMutex;
+  CommandVector additions;
+  using CommandSet = std::set<Command*>;
+  CommandSet commands;
+  bool adding = false;
+  bool enabled = true;
+  std::vector<std::string> commandsBuf;
+  std::vector<double> idsBuf;
+  bool runningCommandsChanged = false;
+};
+
+Scheduler* Scheduler::GetInstance() {
+  static Scheduler instance;
+  return &instance;
+}
+
+void Scheduler::AddCommand(Command* command) {
+  std::lock_guard<wpi::mutex> lock(m_impl->additionsMutex);
+  if (std::find(m_impl->additions.begin(), m_impl->additions.end(), command) !=
+      m_impl->additions.end())
+    return;
+  m_impl->additions.push_back(command);
+}
+
+void Scheduler::AddButton(ButtonScheduler* button) {
+  std::lock_guard<wpi::mutex> lock(m_impl->buttonsMutex);
+  m_impl->buttons.emplace_back(button);
+}
+
+void Scheduler::RegisterSubsystem(Subsystem* subsystem) {
+  if (subsystem == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "subsystem");
+    return;
+  }
+  m_impl->subsystems.insert(subsystem);
+}
+
+void Scheduler::Run() {
+  // Get button input (going backwards preserves button priority)
+  {
+    if (!m_impl->enabled) return;
+
+    std::lock_guard<wpi::mutex> lock(m_impl->buttonsMutex);
+    for (auto& button : m_impl->buttons) {
+      button->Execute();
+    }
+  }
+
+  // Call every subsystem's periodic method
+  for (auto& subsystem : m_impl->subsystems) {
+    subsystem->Periodic();
+  }
+
+  m_impl->runningCommandsChanged = false;
+
+  // Loop through the commands
+  for (auto cmdIter = m_impl->commands.begin();
+       cmdIter != m_impl->commands.end();) {
+    Command* command = *cmdIter;
+    // Increment before potentially removing to keep the iterator valid
+    ++cmdIter;
+    if (!command->Run()) {
+      Remove(command);
+      m_impl->runningCommandsChanged = true;
+    }
+  }
+
+  // Add the new things
+  {
+    std::lock_guard<wpi::mutex> lock(m_impl->additionsMutex);
+    for (auto& addition : m_impl->additions) {
+      // Check to make sure no adding during adding
+      if (m_impl->adding) {
+        wpi_setWPIErrorWithContext(IncompatibleState,
+                                   "Can not start command from cancel method");
+      } else {
+        m_impl->ProcessCommandAddition(addition);
+      }
+    }
+    m_impl->additions.clear();
+  }
+
+  // Add in the defaults
+  for (auto& subsystem : m_impl->subsystems) {
+    if (subsystem->GetCurrentCommand() == nullptr) {
+      if (m_impl->adding) {
+        wpi_setWPIErrorWithContext(IncompatibleState,
+                                   "Can not start command from cancel method");
+      } else {
+        m_impl->ProcessCommandAddition(subsystem->GetDefaultCommand());
+      }
+    }
+    subsystem->ConfirmCommand();
+  }
+}
+
+void Scheduler::Remove(Command* command) {
+  if (command == nullptr) {
+    wpi_setWPIErrorWithContext(NullParameter, "command");
+    return;
+  }
+
+  m_impl->Remove(command);
+}
+
+void Scheduler::RemoveAll() {
+  while (m_impl->commands.size() > 0) {
+    Remove(*m_impl->commands.begin());
+  }
+}
+
+void Scheduler::ResetAll() {
+  RemoveAll();
+  m_impl->subsystems.clear();
+  m_impl->buttons.clear();
+  m_impl->additions.clear();
+  m_impl->commands.clear();
+}
+
+void Scheduler::SetEnabled(bool enabled) { m_impl->enabled = enabled; }
+
+void Scheduler::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Scheduler");
+  auto namesEntry = builder.GetEntry("Names");
+  auto idsEntry = builder.GetEntry("Ids");
+  auto cancelEntry = builder.GetEntry("Cancel");
+  builder.SetUpdateTable([=]() {
+    // Get the list of possible commands to cancel
+    auto new_toCancel = cancelEntry.GetValue();
+    wpi::ArrayRef<double> toCancel;
+    if (new_toCancel) toCancel = new_toCancel->GetDoubleArray();
+
+    // Cancel commands whose cancel buttons were pressed on the SmartDashboard
+    if (!toCancel.empty()) {
+      for (auto& command : m_impl->commands) {
+        for (const auto& cancelled : toCancel) {
+          if (command->GetID() == cancelled) {
+            command->Cancel();
+          }
+        }
+      }
+      nt::NetworkTableEntry(cancelEntry).SetDoubleArray({});
+    }
+
+    // Set the running commands
+    if (m_impl->runningCommandsChanged) {
+      m_impl->commandsBuf.resize(0);
+      m_impl->idsBuf.resize(0);
+      for (const auto& command : m_impl->commands) {
+        m_impl->commandsBuf.emplace_back(command->GetName());
+        m_impl->idsBuf.emplace_back(command->GetID());
+      }
+      nt::NetworkTableEntry(namesEntry).SetStringArray(m_impl->commandsBuf);
+      nt::NetworkTableEntry(idsEntry).SetDoubleArray(m_impl->idsBuf);
+    }
+  });
+}
+
+Scheduler::Scheduler() : m_impl(new Impl) {
+  HAL_Report(HALUsageReporting::kResourceType_Command,
+             HALUsageReporting::kCommand_Scheduler);
+  SetName("Scheduler");
+}
+
+Scheduler::~Scheduler() {}
+
+void Scheduler::Impl::Remove(Command* command) {
+  if (!commands.erase(command)) return;
+
+  for (auto&& requirement : command->GetRequirements()) {
+    requirement->SetCurrentCommand(nullptr);
+  }
+
+  command->Removed();
+}
+
+void Scheduler::Impl::ProcessCommandAddition(Command* command) {
+  if (command == nullptr) return;
+
+  // Only add if not already in
+  auto found = commands.find(command);
+  if (found == commands.end()) {
+    // Check that the requirements can be had
+    const auto& requirements = command->GetRequirements();
+    for (const auto& requirement : requirements) {
+      if (requirement->GetCurrentCommand() != nullptr &&
+          !requirement->GetCurrentCommand()->IsInterruptible())
+        return;
+    }
+
+    // Give it the requirements
+    adding = true;
+    for (auto&& requirement : requirements) {
+      if (requirement->GetCurrentCommand() != nullptr) {
+        requirement->GetCurrentCommand()->Cancel();
+        Remove(requirement->GetCurrentCommand());
+      }
+      requirement->SetCurrentCommand(command);
+    }
+    adding = false;
+
+    commands.insert(command);
+
+    command->StartRunning();
+    runningCommandsChanged = true;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/StartCommand.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/StartCommand.cpp
new file mode 100644
index 0000000..8884124
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/StartCommand.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/StartCommand.h"
+
+using namespace frc;
+
+StartCommand::StartCommand(Command* commandToStart)
+    : InstantCommand("StartCommand") {
+  m_commandToFork = commandToStart;
+}
+
+void StartCommand::Initialize() { m_commandToFork->Start(); }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Subsystem.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Subsystem.cpp
new file mode 100644
index 0000000..308642f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/Subsystem.cpp
@@ -0,0 +1,114 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/Subsystem.h"
+
+#include "frc/WPIErrors.h"
+#include "frc/commands/Command.h"
+#include "frc/commands/Scheduler.h"
+#include "frc/livewindow/LiveWindow.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+Subsystem::Subsystem(const wpi::Twine& name) {
+  SetName(name, name);
+  Scheduler::GetInstance()->RegisterSubsystem(this);
+}
+
+void Subsystem::SetDefaultCommand(Command* command) {
+  if (command == nullptr) {
+    m_defaultCommand = nullptr;
+  } else {
+    const auto& reqs = command->GetRequirements();
+    if (std::find(reqs.begin(), reqs.end(), this) == reqs.end()) {
+      wpi_setWPIErrorWithContext(
+          CommandIllegalUse, "A default command must require the subsystem");
+      return;
+    }
+
+    m_defaultCommand = command;
+  }
+}
+
+Command* Subsystem::GetDefaultCommand() {
+  if (!m_initializedDefaultCommand) {
+    m_initializedDefaultCommand = true;
+    InitDefaultCommand();
+  }
+  return m_defaultCommand;
+}
+
+wpi::StringRef Subsystem::GetDefaultCommandName() {
+  Command* defaultCommand = GetDefaultCommand();
+  if (defaultCommand) {
+    return defaultCommand->GetName();
+  } else {
+    return wpi::StringRef();
+  }
+}
+
+void Subsystem::SetCurrentCommand(Command* command) {
+  m_currentCommand = command;
+  m_currentCommandChanged = true;
+}
+
+Command* Subsystem::GetCurrentCommand() const { return m_currentCommand; }
+
+wpi::StringRef Subsystem::GetCurrentCommandName() const {
+  Command* currentCommand = GetCurrentCommand();
+  if (currentCommand) {
+    return currentCommand->GetName();
+  } else {
+    return wpi::StringRef();
+  }
+}
+
+void Subsystem::Periodic() {}
+
+void Subsystem::InitDefaultCommand() {}
+
+void Subsystem::AddChild(const wpi::Twine& name,
+                         std::shared_ptr<Sendable> child) {
+  AddChild(name, *child);
+}
+
+void Subsystem::AddChild(const wpi::Twine& name, Sendable* child) {
+  AddChild(name, *child);
+}
+
+void Subsystem::AddChild(const wpi::Twine& name, Sendable& child) {
+  child.SetName(GetSubsystem(), name);
+  LiveWindow::GetInstance()->Add(&child);
+}
+
+void Subsystem::AddChild(std::shared_ptr<Sendable> child) { AddChild(*child); }
+
+void Subsystem::AddChild(Sendable* child) { AddChild(*child); }
+
+void Subsystem::AddChild(Sendable& child) {
+  child.SetSubsystem(GetSubsystem());
+  LiveWindow::GetInstance()->Add(&child);
+}
+
+void Subsystem::ConfirmCommand() {
+  if (m_currentCommandChanged) m_currentCommandChanged = false;
+}
+
+void Subsystem::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("Subsystem");
+
+  builder.AddBooleanProperty(
+      ".hasDefault", [=]() { return m_defaultCommand != nullptr; }, nullptr);
+  builder.AddStringProperty(".default",
+                            [=]() { return GetDefaultCommandName(); }, nullptr);
+
+  builder.AddBooleanProperty(
+      ".hasCommand", [=]() { return m_currentCommand != nullptr; }, nullptr);
+  builder.AddStringProperty(".command",
+                            [=]() { return GetCurrentCommandName(); }, nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/TimedCommand.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/TimedCommand.cpp
new file mode 100644
index 0000000..122751a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/TimedCommand.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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/commands/TimedCommand.h"
+
+using namespace frc;
+
+TimedCommand::TimedCommand(const wpi::Twine& name, double timeout)
+    : Command(name, timeout) {}
+
+TimedCommand::TimedCommand(double timeout) : Command(timeout) {}
+
+TimedCommand::TimedCommand(const wpi::Twine& name, double timeout,
+                           Subsystem& subsystem)
+    : Command(name, timeout, subsystem) {}
+
+TimedCommand::TimedCommand(double timeout, Subsystem& subsystem)
+    : Command(timeout, subsystem) {}
+
+bool TimedCommand::IsFinished() { return IsTimedOut(); }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitCommand.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitCommand.cpp
new file mode 100644
index 0000000..225d95b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitCommand.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/WaitCommand.h"
+
+using namespace frc;
+
+WaitCommand::WaitCommand(double timeout)
+    : TimedCommand("Wait(" + std::to_string(timeout) + ")", timeout) {}
+
+WaitCommand::WaitCommand(const wpi::Twine& name, double timeout)
+    : TimedCommand(name, timeout) {}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitForChildren.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitForChildren.cpp
new file mode 100644
index 0000000..5c99c1b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitForChildren.cpp
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/WaitForChildren.h"
+
+#include "frc/commands/CommandGroup.h"
+
+using namespace frc;
+
+WaitForChildren::WaitForChildren(double timeout)
+    : Command("WaitForChildren", timeout) {}
+
+WaitForChildren::WaitForChildren(const wpi::Twine& name, double timeout)
+    : Command(name, timeout) {}
+
+bool WaitForChildren::IsFinished() {
+  return GetGroup() == nullptr || GetGroup()->GetSize() == 0;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitUntilCommand.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitUntilCommand.cpp
new file mode 100644
index 0000000..6e24b6b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/commands/WaitUntilCommand.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/commands/WaitUntilCommand.h"
+
+#include "frc/Timer.h"
+
+using namespace frc;
+
+WaitUntilCommand::WaitUntilCommand(double time)
+    : Command("WaitUntilCommand", time) {
+  m_time = time;
+}
+
+WaitUntilCommand::WaitUntilCommand(const wpi::Twine& name, double time)
+    : Command(name, time) {
+  m_time = time;
+}
+
+bool WaitUntilCommand::IsFinished() { return Timer::GetMatchTime() >= m_time; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
new file mode 100644
index 0000000..5ad65b8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp
@@ -0,0 +1,225 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/drive/DifferentialDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/HAL.h>
+
+#include "frc/SpeedController.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+DifferentialDrive::DifferentialDrive(SpeedController& leftMotor,
+                                     SpeedController& rightMotor)
+    : m_leftMotor(leftMotor), m_rightMotor(rightMotor) {
+  AddChild(&m_leftMotor);
+  AddChild(&m_rightMotor);
+  static int instances = 0;
+  ++instances;
+  SetName("DifferentialDrive", instances);
+}
+
+void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation,
+                                    bool squareInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, 2,
+               HALUsageReporting::kRobotDrive2_DifferentialArcade);
+    reported = true;
+  }
+
+  xSpeed = Limit(xSpeed);
+  xSpeed = ApplyDeadband(xSpeed, m_deadband);
+
+  zRotation = Limit(zRotation);
+  zRotation = ApplyDeadband(zRotation, m_deadband);
+
+  // Square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power.
+  if (squareInputs) {
+    xSpeed = std::copysign(xSpeed * xSpeed, xSpeed);
+    zRotation = std::copysign(zRotation * zRotation, zRotation);
+  }
+
+  double leftMotorOutput;
+  double rightMotorOutput;
+
+  double maxInput =
+      std::copysign(std::max(std::abs(xSpeed), std::abs(zRotation)), xSpeed);
+
+  if (xSpeed >= 0.0) {
+    // First quadrant, else second quadrant
+    if (zRotation >= 0.0) {
+      leftMotorOutput = maxInput;
+      rightMotorOutput = xSpeed - zRotation;
+    } else {
+      leftMotorOutput = xSpeed + zRotation;
+      rightMotorOutput = maxInput;
+    }
+  } else {
+    // Third quadrant, else fourth quadrant
+    if (zRotation >= 0.0) {
+      leftMotorOutput = xSpeed + zRotation;
+      rightMotorOutput = maxInput;
+    } else {
+      leftMotorOutput = maxInput;
+      rightMotorOutput = xSpeed - zRotation;
+    }
+  }
+
+  m_leftMotor.Set(Limit(leftMotorOutput) * m_maxOutput);
+  m_rightMotor.Set(Limit(rightMotorOutput) * m_maxOutput *
+                   m_rightSideInvertMultiplier);
+
+  Feed();
+}
+
+void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation,
+                                       bool isQuickTurn) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, 2,
+               HALUsageReporting::kRobotDrive2_DifferentialCurvature);
+    reported = true;
+  }
+
+  xSpeed = Limit(xSpeed);
+  xSpeed = ApplyDeadband(xSpeed, m_deadband);
+
+  zRotation = Limit(zRotation);
+  zRotation = ApplyDeadband(zRotation, m_deadband);
+
+  double angularPower;
+  bool overPower;
+
+  if (isQuickTurn) {
+    if (std::abs(xSpeed) < m_quickStopThreshold) {
+      m_quickStopAccumulator = (1 - m_quickStopAlpha) * m_quickStopAccumulator +
+                               m_quickStopAlpha * Limit(zRotation) * 2;
+    }
+    overPower = true;
+    angularPower = zRotation;
+  } else {
+    overPower = false;
+    angularPower = std::abs(xSpeed) * zRotation - m_quickStopAccumulator;
+
+    if (m_quickStopAccumulator > 1) {
+      m_quickStopAccumulator -= 1;
+    } else if (m_quickStopAccumulator < -1) {
+      m_quickStopAccumulator += 1;
+    } else {
+      m_quickStopAccumulator = 0.0;
+    }
+  }
+
+  double leftMotorOutput = xSpeed + angularPower;
+  double rightMotorOutput = xSpeed - angularPower;
+
+  // If rotation is overpowered, reduce both outputs to within acceptable range
+  if (overPower) {
+    if (leftMotorOutput > 1.0) {
+      rightMotorOutput -= leftMotorOutput - 1.0;
+      leftMotorOutput = 1.0;
+    } else if (rightMotorOutput > 1.0) {
+      leftMotorOutput -= rightMotorOutput - 1.0;
+      rightMotorOutput = 1.0;
+    } else if (leftMotorOutput < -1.0) {
+      rightMotorOutput -= leftMotorOutput + 1.0;
+      leftMotorOutput = -1.0;
+    } else if (rightMotorOutput < -1.0) {
+      leftMotorOutput -= rightMotorOutput + 1.0;
+      rightMotorOutput = -1.0;
+    }
+  }
+
+  // Normalize the wheel speeds
+  double maxMagnitude =
+      std::max(std::abs(leftMotorOutput), std::abs(rightMotorOutput));
+  if (maxMagnitude > 1.0) {
+    leftMotorOutput /= maxMagnitude;
+    rightMotorOutput /= maxMagnitude;
+  }
+
+  m_leftMotor.Set(leftMotorOutput * m_maxOutput);
+  m_rightMotor.Set(rightMotorOutput * m_maxOutput *
+                   m_rightSideInvertMultiplier);
+
+  Feed();
+}
+
+void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed,
+                                  bool squareInputs) {
+  static bool reported = false;
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, 2,
+               HALUsageReporting::kRobotDrive2_DifferentialTank);
+    reported = true;
+  }
+
+  leftSpeed = Limit(leftSpeed);
+  leftSpeed = ApplyDeadband(leftSpeed, m_deadband);
+
+  rightSpeed = Limit(rightSpeed);
+  rightSpeed = ApplyDeadband(rightSpeed, m_deadband);
+
+  // Square the inputs (while preserving the sign) to increase fine control
+  // while permitting full power.
+  if (squareInputs) {
+    leftSpeed = std::copysign(leftSpeed * leftSpeed, leftSpeed);
+    rightSpeed = std::copysign(rightSpeed * rightSpeed, rightSpeed);
+  }
+
+  m_leftMotor.Set(leftSpeed * m_maxOutput);
+  m_rightMotor.Set(rightSpeed * m_maxOutput * m_rightSideInvertMultiplier);
+
+  Feed();
+}
+
+void DifferentialDrive::SetQuickStopThreshold(double threshold) {
+  m_quickStopThreshold = threshold;
+}
+
+void DifferentialDrive::SetQuickStopAlpha(double alpha) {
+  m_quickStopAlpha = alpha;
+}
+
+bool DifferentialDrive::IsRightSideInverted() const {
+  return m_rightSideInvertMultiplier == -1.0;
+}
+
+void DifferentialDrive::SetRightSideInverted(bool rightSideInverted) {
+  m_rightSideInvertMultiplier = rightSideInverted ? -1.0 : 1.0;
+}
+
+void DifferentialDrive::StopMotor() {
+  m_leftMotor.StopMotor();
+  m_rightMotor.StopMotor();
+  Feed();
+}
+
+void DifferentialDrive::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "DifferentialDrive";
+}
+
+void DifferentialDrive::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("DifferentialDrive");
+  builder.SetActuator(true);
+  builder.SetSafeState([=] { StopMotor(); });
+  builder.AddDoubleProperty("Left Motor Speed",
+                            [=]() { return m_leftMotor.Get(); },
+                            [=](double value) { m_leftMotor.Set(value); });
+  builder.AddDoubleProperty(
+      "Right Motor Speed",
+      [=]() { return m_rightMotor.Get() * m_rightSideInvertMultiplier; },
+      [=](double value) {
+        m_rightMotor.Set(value * m_rightSideInvertMultiplier);
+      });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp
new file mode 100644
index 0000000..b1af5de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/KilloughDrive.cpp
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/drive/KilloughDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/HAL.h>
+
+#include "frc/SpeedController.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+constexpr double kPi = 3.14159265358979323846;
+
+KilloughDrive::KilloughDrive(SpeedController& leftMotor,
+                             SpeedController& rightMotor,
+                             SpeedController& backMotor)
+    : KilloughDrive(leftMotor, rightMotor, backMotor, kDefaultLeftMotorAngle,
+                    kDefaultRightMotorAngle, kDefaultBackMotorAngle) {}
+
+KilloughDrive::KilloughDrive(SpeedController& leftMotor,
+                             SpeedController& rightMotor,
+                             SpeedController& backMotor, double leftMotorAngle,
+                             double rightMotorAngle, double backMotorAngle)
+    : m_leftMotor(leftMotor), m_rightMotor(rightMotor), m_backMotor(backMotor) {
+  m_leftVec = {std::cos(leftMotorAngle * (kPi / 180.0)),
+               std::sin(leftMotorAngle * (kPi / 180.0))};
+  m_rightVec = {std::cos(rightMotorAngle * (kPi / 180.0)),
+                std::sin(rightMotorAngle * (kPi / 180.0))};
+  m_backVec = {std::cos(backMotorAngle * (kPi / 180.0)),
+               std::sin(backMotorAngle * (kPi / 180.0))};
+  AddChild(&m_leftMotor);
+  AddChild(&m_rightMotor);
+  AddChild(&m_backMotor);
+  static int instances = 0;
+  ++instances;
+  SetName("KilloughDrive", instances);
+}
+
+void KilloughDrive::DriveCartesian(double ySpeed, double xSpeed,
+                                   double zRotation, double gyroAngle) {
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, 3,
+               HALUsageReporting::kRobotDrive2_KilloughCartesian);
+    reported = true;
+  }
+
+  ySpeed = Limit(ySpeed);
+  ySpeed = ApplyDeadband(ySpeed, m_deadband);
+
+  xSpeed = Limit(xSpeed);
+  xSpeed = ApplyDeadband(xSpeed, m_deadband);
+
+  // Compensate for gyro angle.
+  Vector2d input{ySpeed, xSpeed};
+  input.Rotate(-gyroAngle);
+
+  double wheelSpeeds[3];
+  wheelSpeeds[kLeft] = input.ScalarProject(m_leftVec) + zRotation;
+  wheelSpeeds[kRight] = input.ScalarProject(m_rightVec) + zRotation;
+  wheelSpeeds[kBack] = input.ScalarProject(m_backVec) + zRotation;
+
+  Normalize(wheelSpeeds);
+
+  m_leftMotor.Set(wheelSpeeds[kLeft] * m_maxOutput);
+  m_rightMotor.Set(wheelSpeeds[kRight] * m_maxOutput);
+  m_backMotor.Set(wheelSpeeds[kBack] * m_maxOutput);
+
+  Feed();
+}
+
+void KilloughDrive::DrivePolar(double magnitude, double angle,
+                               double zRotation) {
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, 3,
+               HALUsageReporting::kRobotDrive2_KilloughPolar);
+    reported = true;
+  }
+
+  DriveCartesian(magnitude * std::sin(angle * (kPi / 180.0)),
+                 magnitude * std::cos(angle * (kPi / 180.0)), zRotation, 0.0);
+}
+
+void KilloughDrive::StopMotor() {
+  m_leftMotor.StopMotor();
+  m_rightMotor.StopMotor();
+  m_backMotor.StopMotor();
+  Feed();
+}
+
+void KilloughDrive::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "KilloughDrive";
+}
+
+void KilloughDrive::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("KilloughDrive");
+  builder.SetActuator(true);
+  builder.SetSafeState([=] { StopMotor(); });
+  builder.AddDoubleProperty("Left Motor Speed",
+                            [=]() { return m_leftMotor.Get(); },
+                            [=](double value) { m_leftMotor.Set(value); });
+  builder.AddDoubleProperty("Right Motor Speed",
+                            [=]() { return m_rightMotor.Get(); },
+                            [=](double value) { m_rightMotor.Set(value); });
+  builder.AddDoubleProperty("Back Motor Speed",
+                            [=]() { return m_backMotor.Get(); },
+                            [=](double value) { m_backMotor.Set(value); });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
new file mode 100644
index 0000000..c74ba19
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp
@@ -0,0 +1,130 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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/drive/MecanumDrive.h"
+
+#include <algorithm>
+#include <cmath>
+
+#include <hal/HAL.h>
+
+#include "frc/SpeedController.h"
+#include "frc/drive/Vector2d.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+constexpr double kPi = 3.14159265358979323846;
+
+MecanumDrive::MecanumDrive(SpeedController& frontLeftMotor,
+                           SpeedController& rearLeftMotor,
+                           SpeedController& frontRightMotor,
+                           SpeedController& rearRightMotor)
+    : m_frontLeftMotor(frontLeftMotor),
+      m_rearLeftMotor(rearLeftMotor),
+      m_frontRightMotor(frontRightMotor),
+      m_rearRightMotor(rearRightMotor) {
+  AddChild(&m_frontLeftMotor);
+  AddChild(&m_rearLeftMotor);
+  AddChild(&m_frontRightMotor);
+  AddChild(&m_rearRightMotor);
+  static int instances = 0;
+  ++instances;
+  SetName("MecanumDrive", instances);
+}
+
+void MecanumDrive::DriveCartesian(double ySpeed, double xSpeed,
+                                  double zRotation, double gyroAngle) {
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, 4,
+               HALUsageReporting::kRobotDrive2_MecanumCartesian);
+    reported = true;
+  }
+
+  ySpeed = Limit(ySpeed);
+  ySpeed = ApplyDeadband(ySpeed, m_deadband);
+
+  xSpeed = Limit(xSpeed);
+  xSpeed = ApplyDeadband(xSpeed, m_deadband);
+
+  // Compensate for gyro angle.
+  Vector2d input{ySpeed, xSpeed};
+  input.Rotate(-gyroAngle);
+
+  double wheelSpeeds[4];
+  wheelSpeeds[kFrontLeft] = input.x + input.y + zRotation;
+  wheelSpeeds[kFrontRight] = -input.x + input.y - zRotation;
+  wheelSpeeds[kRearLeft] = -input.x + input.y + zRotation;
+  wheelSpeeds[kRearRight] = input.x + input.y - zRotation;
+
+  Normalize(wheelSpeeds);
+
+  m_frontLeftMotor.Set(wheelSpeeds[kFrontLeft] * m_maxOutput);
+  m_frontRightMotor.Set(wheelSpeeds[kFrontRight] * m_maxOutput *
+                        m_rightSideInvertMultiplier);
+  m_rearLeftMotor.Set(wheelSpeeds[kRearLeft] * m_maxOutput);
+  m_rearRightMotor.Set(wheelSpeeds[kRearRight] * m_maxOutput *
+                       m_rightSideInvertMultiplier);
+
+  Feed();
+}
+
+void MecanumDrive::DrivePolar(double magnitude, double angle,
+                              double zRotation) {
+  if (!reported) {
+    HAL_Report(HALUsageReporting::kResourceType_RobotDrive, 4,
+               HALUsageReporting::kRobotDrive2_MecanumPolar);
+    reported = true;
+  }
+
+  DriveCartesian(magnitude * std::sin(angle * (kPi / 180.0)),
+                 magnitude * std::cos(angle * (kPi / 180.0)), zRotation, 0.0);
+}
+
+bool MecanumDrive::IsRightSideInverted() const {
+  return m_rightSideInvertMultiplier == -1.0;
+}
+
+void MecanumDrive::SetRightSideInverted(bool rightSideInverted) {
+  m_rightSideInvertMultiplier = rightSideInverted ? -1.0 : 1.0;
+}
+
+void MecanumDrive::StopMotor() {
+  m_frontLeftMotor.StopMotor();
+  m_frontRightMotor.StopMotor();
+  m_rearLeftMotor.StopMotor();
+  m_rearRightMotor.StopMotor();
+  Feed();
+}
+
+void MecanumDrive::GetDescription(wpi::raw_ostream& desc) const {
+  desc << "MecanumDrive";
+}
+
+void MecanumDrive::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("MecanumDrive");
+  builder.SetActuator(true);
+  builder.SetSafeState([=] { StopMotor(); });
+  builder.AddDoubleProperty("Front Left Motor Speed",
+                            [=]() { return m_frontLeftMotor.Get(); },
+                            [=](double value) { m_frontLeftMotor.Set(value); });
+  builder.AddDoubleProperty(
+      "Front Right Motor Speed",
+      [=]() { return m_frontRightMotor.Get() * m_rightSideInvertMultiplier; },
+      [=](double value) {
+        m_frontRightMotor.Set(value * m_rightSideInvertMultiplier);
+      });
+  builder.AddDoubleProperty("Rear Left Motor Speed",
+                            [=]() { return m_rearLeftMotor.Get(); },
+                            [=](double value) { m_rearLeftMotor.Set(value); });
+  builder.AddDoubleProperty(
+      "Rear Right Motor Speed",
+      [=]() { return m_rearRightMotor.Get() * m_rightSideInvertMultiplier; },
+      [=](double value) {
+        m_rearRightMotor.Set(value * m_rightSideInvertMultiplier);
+      });
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp
new file mode 100644
index 0000000..c22cb2a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/drive/RobotDriveBase.h"
+
+#include <algorithm>
+#include <cmath>
+#include <cstddef>
+
+#include <hal/HAL.h>
+
+#include "frc/Base.h"
+#include "frc/SpeedController.h"
+
+using namespace frc;
+
+RobotDriveBase::RobotDriveBase() { SetSafetyEnabled(true); }
+
+void RobotDriveBase::SetDeadband(double deadband) { m_deadband = deadband; }
+
+void RobotDriveBase::SetMaxOutput(double maxOutput) { m_maxOutput = maxOutput; }
+
+void RobotDriveBase::FeedWatchdog() { Feed(); }
+
+double RobotDriveBase::Limit(double value) {
+  if (value > 1.0) {
+    return 1.0;
+  }
+  if (value < -1.0) {
+    return -1.0;
+  }
+  return value;
+}
+
+double RobotDriveBase::ApplyDeadband(double value, double deadband) {
+  if (std::abs(value) > deadband) {
+    if (value > 0.0) {
+      return (value - deadband) / (1.0 - deadband);
+    } else {
+      return (value + deadband) / (1.0 - deadband);
+    }
+  } else {
+    return 0.0;
+  }
+}
+
+void RobotDriveBase::Normalize(wpi::MutableArrayRef<double> wheelSpeeds) {
+  double maxMagnitude = std::abs(wheelSpeeds[0]);
+  for (size_t i = 1; i < wheelSpeeds.size(); i++) {
+    double temp = std::abs(wheelSpeeds[i]);
+    if (maxMagnitude < temp) {
+      maxMagnitude = temp;
+    }
+  }
+  if (maxMagnitude > 1.0) {
+    for (size_t i = 0; i < wheelSpeeds.size(); i++) {
+      wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/Vector2d.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/Vector2d.cpp
new file mode 100644
index 0000000..3d4b689
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/drive/Vector2d.cpp
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/drive/Vector2d.h"
+
+#include <cmath>
+
+using namespace frc;
+
+constexpr double kPi = 3.14159265358979323846;
+
+Vector2d::Vector2d(double x, double y) {
+  this->x = x;
+  this->y = y;
+}
+
+void Vector2d::Rotate(double angle) {
+  double cosA = std::cos(angle * (kPi / 180.0));
+  double sinA = std::sin(angle * (kPi / 180.0));
+  double out[2];
+  out[0] = x * cosA - y * sinA;
+  out[1] = x * sinA + y * cosA;
+  x = out[0];
+  y = out[1];
+}
+
+double Vector2d::Dot(const Vector2d& vec) const {
+  return x * vec.x + y * vec.y;
+}
+
+double Vector2d::Magnitude() const { return std::sqrt(x * x + y * y); }
+
+double Vector2d::ScalarProject(const Vector2d& vec) const {
+  return Dot(vec) / vec.Magnitude();
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/filters/Filter.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/filters/Filter.cpp
new file mode 100644
index 0000000..c25d7af
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/filters/Filter.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/filters/Filter.h"
+
+#include "frc/Base.h"
+
+using namespace frc;
+
+Filter::Filter(PIDSource& source)
+    : m_source(std::shared_ptr<PIDSource>(&source, NullDeleter<PIDSource>())) {}
+
+Filter::Filter(std::shared_ptr<PIDSource> source)
+    : m_source(std::move(source)) {}
+
+void Filter::SetPIDSourceType(PIDSourceType pidSource) {
+  m_source->SetPIDSourceType(pidSource);
+}
+
+PIDSourceType Filter::GetPIDSourceType() const {
+  return m_source->GetPIDSourceType();
+}
+
+double Filter::PIDGetSource() { return m_source->PIDGet(); }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp
new file mode 100644
index 0000000..db4cebe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/filters/LinearDigitalFilter.cpp
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/filters/LinearDigitalFilter.h"
+
+#include <cassert>
+#include <cmath>
+
+#include <hal/HAL.h>
+
+using namespace frc;
+
+LinearDigitalFilter::LinearDigitalFilter(PIDSource& source,
+                                         wpi::ArrayRef<double> ffGains,
+                                         wpi::ArrayRef<double> fbGains)
+    : Filter(source),
+      m_inputs(ffGains.size()),
+      m_outputs(fbGains.size()),
+      m_inputGains(ffGains),
+      m_outputGains(fbGains) {
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_LinearFilter, instances);
+}
+
+LinearDigitalFilter::LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                                         wpi::ArrayRef<double> ffGains,
+                                         wpi::ArrayRef<double> fbGains)
+    : Filter(source),
+      m_inputs(ffGains.size()),
+      m_outputs(fbGains.size()),
+      m_inputGains(ffGains),
+      m_outputGains(fbGains) {
+  static int instances = 0;
+  instances++;
+  HAL_Report(HALUsageReporting::kResourceType_LinearFilter, instances);
+}
+
+LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(PIDSource& source,
+                                                       double timeConstant,
+                                                       double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(source, {1.0 - gain}, {-gain});
+}
+
+LinearDigitalFilter LinearDigitalFilter::HighPass(PIDSource& source,
+                                                  double timeConstant,
+                                                  double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(source, {gain, -gain}, {-gain});
+}
+
+LinearDigitalFilter LinearDigitalFilter::MovingAverage(PIDSource& source,
+                                                       int taps) {
+  assert(taps > 0);
+
+  std::vector<double> gains(taps, 1.0 / taps);
+  return LinearDigitalFilter(source, gains, {});
+}
+
+LinearDigitalFilter LinearDigitalFilter::SinglePoleIIR(
+    std::shared_ptr<PIDSource> source, double timeConstant, double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(std::move(source), {1.0 - gain}, {-gain});
+}
+
+LinearDigitalFilter LinearDigitalFilter::HighPass(
+    std::shared_ptr<PIDSource> source, double timeConstant, double period) {
+  double gain = std::exp(-period / timeConstant);
+  return LinearDigitalFilter(std::move(source), {gain, -gain}, {-gain});
+}
+
+LinearDigitalFilter LinearDigitalFilter::MovingAverage(
+    std::shared_ptr<PIDSource> source, int taps) {
+  assert(taps > 0);
+
+  std::vector<double> gains(taps, 1.0 / taps);
+  return LinearDigitalFilter(std::move(source), gains, {});
+}
+
+double LinearDigitalFilter::Get() const {
+  double retVal = 0.0;
+
+  // Calculate the new value
+  for (size_t i = 0; i < m_inputGains.size(); i++) {
+    retVal += m_inputs[i] * m_inputGains[i];
+  }
+  for (size_t i = 0; i < m_outputGains.size(); i++) {
+    retVal -= m_outputs[i] * m_outputGains[i];
+  }
+
+  return retVal;
+}
+
+void LinearDigitalFilter::Reset() {
+  m_inputs.reset();
+  m_outputs.reset();
+}
+
+double LinearDigitalFilter::PIDGet() {
+  double retVal = 0.0;
+
+  // Rotate the inputs
+  m_inputs.push_front(PIDGetSource());
+
+  // Calculate the new value
+  for (size_t i = 0; i < m_inputGains.size(); i++) {
+    retVal += m_inputs[i] * m_inputGains[i];
+  }
+  for (size_t i = 0; i < m_outputGains.size(); i++) {
+    retVal -= m_outputs[i] * m_outputGains[i];
+  }
+
+  // Rotate the outputs
+  m_outputs.push_front(retVal);
+
+  return retVal;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp
new file mode 100644
index 0000000..44f4aab
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/interfaces/Potentiometer.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/interfaces/Potentiometer.h"
+
+#include "frc/Utility.h"
+
+using namespace frc;
+
+void Potentiometer::SetPIDSourceType(PIDSourceType pidSource) {
+  if (wpi_assert(pidSource == PIDSourceType::kDisplacement)) {
+    m_pidSource = pidSource;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp
new file mode 100644
index 0000000..135d044
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/livewindow/LiveWindow.cpp
@@ -0,0 +1,238 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2012-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/livewindow/LiveWindow.h"
+
+#include <algorithm>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/DenseMap.h>
+#include <wpi/SmallString.h>
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/commands/Scheduler.h"
+#include "frc/smartdashboard/SendableBuilderImpl.h"
+
+using namespace frc;
+
+using wpi::Twine;
+
+struct LiveWindow::Impl {
+  Impl();
+
+  struct Component {
+    std::shared_ptr<Sendable> sendable;
+    Sendable* parent = nullptr;
+    SendableBuilderImpl builder;
+    bool firstTime = true;
+    bool telemetryEnabled = true;
+  };
+
+  wpi::mutex mutex;
+
+  wpi::DenseMap<void*, Component> components;
+
+  std::shared_ptr<nt::NetworkTable> liveWindowTable;
+  std::shared_ptr<nt::NetworkTable> statusTable;
+  nt::NetworkTableEntry enabledEntry;
+
+  bool startLiveWindow = false;
+  bool liveWindowEnabled = false;
+  bool telemetryEnabled = true;
+};
+
+LiveWindow::Impl::Impl()
+    : liveWindowTable(
+          nt::NetworkTableInstance::GetDefault().GetTable("LiveWindow")) {
+  statusTable = liveWindowTable->GetSubTable(".status");
+  enabledEntry = statusTable->GetEntry("LW Enabled");
+}
+
+LiveWindow* LiveWindow::GetInstance() {
+  static LiveWindow instance;
+  return &instance;
+}
+
+void LiveWindow::Run() { UpdateValues(); }
+
+void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
+                           Sendable* component) {
+  Add(component);
+  component->SetName(subsystem, name);
+}
+
+void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
+                           Sendable& component) {
+  Add(&component);
+  component.SetName(subsystem, name);
+}
+
+void LiveWindow::AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
+                           std::shared_ptr<Sendable> component) {
+  Add(component);
+  component->SetName(subsystem, name);
+}
+
+void LiveWindow::AddActuator(const wpi::Twine& subsystem,
+                             const wpi::Twine& name, Sendable* component) {
+  Add(component);
+  component->SetName(subsystem, name);
+}
+
+void LiveWindow::AddActuator(const wpi::Twine& subsystem,
+                             const wpi::Twine& name, Sendable& component) {
+  Add(&component);
+  component.SetName(subsystem, name);
+}
+
+void LiveWindow::AddActuator(const wpi::Twine& subsystem,
+                             const wpi::Twine& name,
+                             std::shared_ptr<Sendable> component) {
+  Add(component);
+  component->SetName(subsystem, name);
+}
+
+void LiveWindow::AddSensor(const wpi::Twine& type, int channel,
+                           Sendable* component) {
+  Add(component);
+  component->SetName("Ungrouped",
+                     type + Twine('[') + Twine(channel) + Twine(']'));
+}
+
+void LiveWindow::AddActuator(const wpi::Twine& type, int channel,
+                             Sendable* component) {
+  Add(component);
+  component->SetName("Ungrouped",
+                     type + Twine('[') + Twine(channel) + Twine(']'));
+}
+
+void LiveWindow::AddActuator(const wpi::Twine& type, int module, int channel,
+                             Sendable* component) {
+  Add(component);
+  component->SetName("Ungrouped", type + Twine('[') + Twine(module) +
+                                      Twine(',') + Twine(channel) + Twine(']'));
+}
+
+void LiveWindow::Add(std::shared_ptr<Sendable> sendable) {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  auto& comp = m_impl->components[sendable.get()];
+  comp.sendable = sendable;
+}
+
+void LiveWindow::Add(Sendable* sendable) {
+  Add(std::shared_ptr<Sendable>(sendable, NullDeleter<Sendable>()));
+}
+
+void LiveWindow::AddChild(Sendable* parent, std::shared_ptr<Sendable> child) {
+  AddChild(parent, child.get());
+}
+
+void LiveWindow::AddChild(Sendable* parent, void* child) {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  auto& comp = m_impl->components[child];
+  comp.parent = parent;
+  comp.telemetryEnabled = false;
+}
+
+void LiveWindow::Remove(Sendable* sendable) {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  m_impl->components.erase(sendable);
+}
+
+void LiveWindow::EnableTelemetry(Sendable* sendable) {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  // Re-enable global setting in case DisableAllTelemetry() was called.
+  m_impl->telemetryEnabled = true;
+  auto i = m_impl->components.find(sendable);
+  if (i != m_impl->components.end()) i->getSecond().telemetryEnabled = true;
+}
+
+void LiveWindow::DisableTelemetry(Sendable* sendable) {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  auto i = m_impl->components.find(sendable);
+  if (i != m_impl->components.end()) i->getSecond().telemetryEnabled = false;
+}
+
+void LiveWindow::DisableAllTelemetry() {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  m_impl->telemetryEnabled = false;
+  for (auto& i : m_impl->components) i.getSecond().telemetryEnabled = false;
+}
+
+bool LiveWindow::IsEnabled() const {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  return m_impl->liveWindowEnabled;
+}
+
+void LiveWindow::SetEnabled(bool enabled) {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  if (m_impl->liveWindowEnabled == enabled) return;
+  Scheduler* scheduler = Scheduler::GetInstance();
+  m_impl->startLiveWindow = enabled;
+  m_impl->liveWindowEnabled = enabled;
+  // Force table generation now to make sure everything is defined
+  UpdateValuesUnsafe();
+  if (enabled) {
+    scheduler->SetEnabled(false);
+    scheduler->RemoveAll();
+  } else {
+    for (auto& i : m_impl->components) {
+      i.getSecond().builder.StopLiveWindowMode();
+    }
+    scheduler->SetEnabled(true);
+  }
+  m_impl->enabledEntry.SetBoolean(enabled);
+}
+
+void LiveWindow::UpdateValues() {
+  std::lock_guard<wpi::mutex> lock(m_impl->mutex);
+  UpdateValuesUnsafe();
+}
+
+void LiveWindow::UpdateValuesUnsafe() {
+  // Only do this if either LiveWindow mode or telemetry is enabled.
+  if (!m_impl->liveWindowEnabled && !m_impl->telemetryEnabled) return;
+
+  for (auto& i : m_impl->components) {
+    auto& comp = i.getSecond();
+    if (comp.sendable && !comp.parent &&
+        (m_impl->liveWindowEnabled || comp.telemetryEnabled)) {
+      if (comp.firstTime) {
+        // By holding off creating the NetworkTable entries, it allows the
+        // components to be redefined. This allows default sensor and actuator
+        // values to be created that are replaced with the custom names from
+        // users calling setName.
+        auto name = comp.sendable->GetName();
+        if (name.empty()) continue;
+        auto subsystem = comp.sendable->GetSubsystem();
+        auto ssTable = m_impl->liveWindowTable->GetSubTable(subsystem);
+        std::shared_ptr<NetworkTable> table;
+        // Treat name==subsystem as top level of subsystem
+        if (name == subsystem)
+          table = ssTable;
+        else
+          table = ssTable->GetSubTable(name);
+        table->GetEntry(".name").SetString(name);
+        comp.builder.SetTable(table);
+        comp.sendable->InitSendable(comp.builder);
+        ssTable->GetEntry(".type").SetString("LW Subsystem");
+
+        comp.firstTime = false;
+      }
+
+      if (m_impl->startLiveWindow) comp.builder.StartLiveWindowMode();
+      comp.builder.UpdateTable();
+    }
+  }
+
+  m_impl->startLiveWindow = false;
+}
+
+LiveWindow::LiveWindow() : m_impl(new Impl) {}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/livewindow/LiveWindowSendable.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/livewindow/LiveWindowSendable.cpp
new file mode 100644
index 0000000..7f03f52
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/livewindow/LiveWindowSendable.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/livewindow/LiveWindowSendable.h"
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+std::string LiveWindowSendable::GetName() const { return std::string(); }
+
+void LiveWindowSendable::SetName(const wpi::Twine&) {}
+
+std::string LiveWindowSendable::GetSubsystem() const { return std::string(); }
+
+void LiveWindowSendable::SetSubsystem(const wpi::Twine&) {}
+
+void LiveWindowSendable::InitSendable(SendableBuilder& builder) {
+  builder.SetUpdateTable([=]() { UpdateTable(); });
+}
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
new file mode 100644
index 0000000..5d09310
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/BuiltInLayouts.cpp
@@ -0,0 +1,13 @@
+/*----------------------------------------------------------------------------*/
+/* 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
new file mode 100644
index 0000000..df6a1f3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/BuiltInWidgets.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ComplexWidget.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ComplexWidget.cpp
new file mode 100644
index 0000000..19e17bb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ComplexWidget.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ComplexWidget.h"
+
+#include "frc/smartdashboard/Sendable.h"
+
+using namespace frc;
+
+ComplexWidget::ComplexWidget(ShuffleboardContainer& parent,
+                             const wpi::Twine& title, Sendable& sendable)
+    : ShuffleboardValue(title),
+      ShuffleboardWidget(parent, title),
+      m_sendable(sendable) {}
+
+void ComplexWidget::EnableIfActuator() {
+  if (m_builder.IsActuator()) {
+    m_builder.StartLiveWindowMode();
+  }
+}
+
+void ComplexWidget::DisableIfActuator() {
+  if (m_builder.IsActuator()) {
+    m_builder.StopLiveWindowMode();
+  }
+}
+
+void ComplexWidget::BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                              std::shared_ptr<nt::NetworkTable> metaTable) {
+  BuildMetadata(metaTable);
+  if (!m_builderInit) {
+    m_builder.SetTable(parentTable->GetSubTable(GetTitle()));
+    m_sendable.InitSendable(m_builder);
+    m_builder.StartListeners();
+    m_builderInit = true;
+  }
+  m_builder.UpdateTable();
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/LayoutType.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/LayoutType.cpp
new file mode 100644
index 0000000..a21cad9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/LayoutType.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* 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/LayoutType.h"
+
+using namespace frc;
+
+wpi::StringRef LayoutType::GetLayoutName() const { return m_layoutName; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp
new file mode 100644
index 0000000..294be79
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/RecordingController.cpp
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* 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/RecordingController.h"
+
+#include "frc/DriverStation.h"
+
+using namespace frc;
+using namespace frc::detail;
+
+RecordingController::RecordingController(nt::NetworkTableInstance ntInstance)
+    : m_recordingControlEntry(), m_recordingFileNameFormatEntry() {
+  m_recordingControlEntry =
+      ntInstance.GetEntry("/Shuffleboard/.recording/RecordData");
+  m_recordingFileNameFormatEntry =
+      ntInstance.GetEntry("/Shuffleboard/.recording/FileNameFormat");
+  m_eventsTable = ntInstance.GetTable("/Shuffleboard/.recording/events");
+}
+
+void RecordingController::StartRecording() {
+  m_recordingControlEntry.SetBoolean(true);
+}
+
+void RecordingController::StopRecording() {
+  m_recordingControlEntry.SetBoolean(false);
+}
+
+void RecordingController::SetRecordingFileNameFormat(wpi::StringRef format) {
+  m_recordingFileNameFormatEntry.SetString(format);
+}
+
+void RecordingController::ClearRecordingFileNameFormat() {
+  m_recordingFileNameFormatEntry.Delete();
+}
+
+void RecordingController::AddEventMarker(
+    wpi::StringRef name, wpi::StringRef description,
+    ShuffleboardEventImportance importance) {
+  if (name.empty()) {
+    DriverStation::ReportError("Shuffleboard event name was not specified");
+    return;
+  }
+  auto arr = wpi::ArrayRef<std::string>{
+      description, ShuffleboardEventImportanceName(importance)};
+  m_eventsTable->GetSubTable(name)->GetEntry("Info").SetStringArray(arr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp
new file mode 100644
index 0000000..87d7e9d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/SendableCameraWrapper.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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/SendableCameraWrapper.h"
+
+#include <cscore_oo.h>
+#include <wpi/DenseMap.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+using namespace frc;
+
+namespace {
+constexpr const char* kProtocol = "camera_server://";
+wpi::DenseMap<int, std::unique_ptr<SendableCameraWrapper>> wrappers;
+}  // namespace
+
+SendableCameraWrapper& SendableCameraWrapper::Wrap(
+    const cs::VideoSource& source) {
+  return Wrap(source.GetHandle());
+}
+
+SendableCameraWrapper& SendableCameraWrapper::Wrap(CS_Source source) {
+  auto& wrapper = wrappers[static_cast<int>(source)];
+  if (!wrapper)
+    wrapper = std::make_unique<SendableCameraWrapper>(source, private_init{});
+  return *wrapper;
+}
+
+SendableCameraWrapper::SendableCameraWrapper(CS_Source source,
+                                             const private_init&)
+    : SendableBase(false), m_uri(kProtocol) {
+  CS_Status status = 0;
+  auto name = cs::GetSourceName(source, &status);
+  SetName(name);
+  m_uri += name;
+}
+
+void SendableCameraWrapper::InitSendable(SendableBuilder& builder) {
+  builder.AddStringProperty(".ShuffleboardURI", [this] { return m_uri; },
+                            nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp
new file mode 100644
index 0000000..2d69847
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/Shuffleboard.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Shuffleboard.h"
+
+#include <networktables/NetworkTableInstance.h>
+
+#include "frc/shuffleboard/ShuffleboardTab.h"
+
+using namespace frc;
+
+void Shuffleboard::Update() { GetInstance().Update(); }
+
+ShuffleboardTab& Shuffleboard::GetTab(wpi::StringRef title) {
+  return GetInstance().GetTab(title);
+}
+
+void Shuffleboard::SelectTab(int index) { GetInstance().SelectTab(index); }
+
+void Shuffleboard::SelectTab(wpi::StringRef title) {
+  GetInstance().SelectTab(title);
+}
+
+void Shuffleboard::EnableActuatorWidgets() {
+  GetInstance().EnableActuatorWidgets();
+}
+
+void Shuffleboard::DisableActuatorWidgets() {
+  // Need to update to make sure the sendable builders are initialized
+  Update();
+  GetInstance().DisableActuatorWidgets();
+}
+
+void Shuffleboard::StartRecording() {
+  GetRecordingController().StartRecording();
+}
+
+void Shuffleboard::StopRecording() { GetRecordingController().StopRecording(); }
+
+void Shuffleboard::SetRecordingFileNameFormat(wpi::StringRef format) {
+  GetRecordingController().SetRecordingFileNameFormat(format);
+}
+
+void Shuffleboard::ClearRecordingFileNameFormat() {
+  GetRecordingController().ClearRecordingFileNameFormat();
+}
+
+void Shuffleboard::AddEventMarker(wpi::StringRef name,
+                                  wpi::StringRef description,
+                                  ShuffleboardEventImportance importance) {
+  GetRecordingController().AddEventMarker(name, description, importance);
+}
+
+void Shuffleboard::AddEventMarker(wpi::StringRef name,
+                                  ShuffleboardEventImportance importance) {
+  AddEventMarker(name, "", importance);
+}
+
+detail::ShuffleboardInstance& Shuffleboard::GetInstance() {
+  static detail::ShuffleboardInstance inst(
+      nt::NetworkTableInstance::GetDefault());
+  return inst;
+}
+
+detail::RecordingController& Shuffleboard::GetRecordingController() {
+  static detail::RecordingController inst(
+      nt::NetworkTableInstance::GetDefault());
+  return inst;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp
new file mode 100644
index 0000000..7617333
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardComponentBase.cpp
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardComponentBase.h"
+
+#include <wpi/SmallVector.h>
+
+using namespace frc;
+
+ShuffleboardComponentBase::ShuffleboardComponentBase(
+    ShuffleboardContainer& parent, const wpi::Twine& title,
+    const wpi::Twine& type)
+    : ShuffleboardValue(title), m_parent(parent) {
+  wpi::SmallVector<char, 16> storage;
+  m_type = type.toStringRef(storage);
+}
+
+void ShuffleboardComponentBase::SetType(const wpi::Twine& type) {
+  wpi::SmallVector<char, 16> storage;
+  m_type = type.toStringRef(storage);
+  m_metadataDirty = true;
+}
+
+void ShuffleboardComponentBase::BuildMetadata(
+    std::shared_ptr<nt::NetworkTable> metaTable) {
+  if (!m_metadataDirty) {
+    return;
+  }
+  // Component type
+  if (GetType() == "") {
+    metaTable->GetEntry("PreferredComponent").Delete();
+  } else {
+    metaTable->GetEntry("PreferredComponent").ForceSetString(GetType());
+  }
+
+  // Tile size
+  if (m_width <= 0 || m_height <= 0) {
+    metaTable->GetEntry("Size").Delete();
+  } else {
+    metaTable->GetEntry("Size").SetDoubleArray(
+        {static_cast<double>(m_width), static_cast<double>(m_height)});
+  }
+
+  // Tile position
+  if (m_column < 0 || m_row < 0) {
+    metaTable->GetEntry("Position").Delete();
+  } else {
+    metaTable->GetEntry("Position")
+        .SetDoubleArray(
+            {static_cast<double>(m_column), static_cast<double>(m_row)});
+  }
+
+  // Custom properties
+  if (GetProperties().size() > 0) {
+    auto propTable = metaTable->GetSubTable("Properties");
+    for (auto& entry : GetProperties()) {
+      propTable->GetEntry(entry.first()).SetValue(entry.second);
+    }
+  }
+  m_metadataDirty = false;
+}
+
+ShuffleboardContainer& ShuffleboardComponentBase::GetParent() {
+  return m_parent;
+}
+
+const std::string& ShuffleboardComponentBase::GetType() const { return m_type; }
+
+const wpi::StringMap<std::shared_ptr<nt::Value>>&
+ShuffleboardComponentBase::GetProperties() const {
+  return m_properties;
+}
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
new file mode 100644
index 0000000..4954cff
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp
@@ -0,0 +1,195 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardContainer.h"
+
+#include <wpi/SmallVector.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/shuffleboard/ComplexWidget.h"
+#include "frc/shuffleboard/SendableCameraWrapper.h"
+#include "frc/shuffleboard/ShuffleboardComponent.h"
+#include "frc/shuffleboard/ShuffleboardLayout.h"
+#include "frc/shuffleboard/SimpleWidget.h"
+
+using namespace frc;
+
+ShuffleboardContainer::ShuffleboardContainer(const wpi::Twine& title)
+    : ShuffleboardValue(title) {}
+
+const std::vector<std::unique_ptr<ShuffleboardComponentBase>>&
+ShuffleboardContainer::GetComponents() const {
+  return m_components;
+}
+
+ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title,
+                                                     const LayoutType& type) {
+  return GetLayout(title, type.GetLayoutName());
+}
+
+ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title,
+                                                     const wpi::Twine& type) {
+  wpi::SmallVector<char, 16> storage;
+  auto titleRef = title.toStringRef(storage);
+  if (m_layouts.count(titleRef) == 0) {
+    auto layout = std::make_unique<ShuffleboardLayout>(*this, type, titleRef);
+    auto ptr = layout.get();
+    m_components.emplace_back(std::move(layout));
+    m_layouts.insert(std::make_pair(titleRef, ptr));
+  }
+  return *m_layouts[titleRef];
+}
+
+ShuffleboardLayout& ShuffleboardContainer::GetLayout(const wpi::Twine& title) {
+  wpi::SmallVector<char, 16> storage;
+  auto titleRef = title.toStringRef(storage);
+  if (m_layouts.count(titleRef) == 0) {
+    wpi_setWPIErrorWithContext(
+        InvalidParameter, "No layout with the given title has been defined");
+  }
+  return *m_layouts[titleRef];
+}
+
+ComplexWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                          Sendable& sendable) {
+  CheckTitle(title);
+  auto widget = std::make_unique<ComplexWidget>(*this, title, sendable);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  return *ptr;
+}
+
+ComplexWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                          const cs::VideoSource& video) {
+  return Add(title, SendableCameraWrapper::Wrap(video));
+}
+
+ComplexWidget& ShuffleboardContainer::Add(Sendable& sendable) {
+  if (sendable.GetName().empty()) {
+    wpi::outs() << "Sendable must have a name\n";
+  }
+  return Add(sendable.GetName(), sendable);
+}
+
+ComplexWidget& ShuffleboardContainer::Add(const cs::VideoSource& video) {
+  return Add(SendableCameraWrapper::Wrap(video));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(
+    const wpi::Twine& title, std::shared_ptr<nt::Value> defaultValue) {
+  CheckTitle(title);
+
+  auto widget = std::make_unique<SimpleWidget>(*this, title);
+  auto ptr = widget.get();
+  m_components.emplace_back(std::move(widget));
+  ptr->GetEntry().SetDefaultValue(defaultValue);
+  return *ptr;
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         bool defaultValue) {
+  return Add(title, nt::Value::MakeBoolean(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         double defaultValue) {
+  return Add(title, nt::Value::MakeDouble(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         int defaultValue) {
+  return Add(title, nt::Value::MakeDouble(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         const wpi::Twine& defaultValue) {
+  return Add(title, nt::Value::MakeString(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         const char* defaultValue) {
+  return Add(title, nt::Value::MakeString(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         wpi::ArrayRef<bool> defaultValue) {
+  return Add(title, nt::Value::MakeBooleanArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(const wpi::Twine& title,
+                                         wpi::ArrayRef<double> defaultValue) {
+  return Add(title, nt::Value::MakeDoubleArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::Add(
+    const wpi::Twine& title, wpi::ArrayRef<std::string> defaultValue) {
+  return Add(title, nt::Value::MakeStringArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, std::shared_ptr<nt::Value> defaultValue) {
+  auto& widget = Add(title, defaultValue);
+  widget.GetEntry().SetPersistent();
+  return widget;
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(const wpi::Twine& title,
+                                                   bool defaultValue) {
+  return AddPersistent(title, nt::Value::MakeBoolean(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(const wpi::Twine& title,
+                                                   double defaultValue) {
+  return AddPersistent(title, nt::Value::MakeDouble(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(const wpi::Twine& title,
+                                                   int defaultValue) {
+  return AddPersistent(title, nt::Value::MakeDouble(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, const wpi::Twine& defaultValue) {
+  return AddPersistent(title, nt::Value::MakeString(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, wpi::ArrayRef<bool> defaultValue) {
+  return AddPersistent(title, nt::Value::MakeBooleanArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, wpi::ArrayRef<double> defaultValue) {
+  return AddPersistent(title, nt::Value::MakeDoubleArray(defaultValue));
+}
+
+SimpleWidget& ShuffleboardContainer::AddPersistent(
+    const wpi::Twine& title, wpi::ArrayRef<std::string> defaultValue) {
+  return AddPersistent(title, nt::Value::MakeStringArray(defaultValue));
+}
+
+void ShuffleboardContainer::EnableIfActuator() {
+  for (auto& component : GetComponents()) {
+    component->EnableIfActuator();
+  }
+}
+
+void ShuffleboardContainer::DisableIfActuator() {
+  for (auto& component : GetComponents()) {
+    component->DisableIfActuator();
+  }
+}
+
+void ShuffleboardContainer::CheckTitle(const wpi::Twine& title) {
+  wpi::SmallVector<char, 16> storage;
+  auto titleRef = title.toStringRef(storage);
+  if (m_usedTitles.count(titleRef) > 0) {
+    wpi::errs() << "Title is already in use: " << title << "\n";
+    return;
+  }
+  m_usedTitles.insert(titleRef);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
new file mode 100644
index 0000000..39e5778
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardInstance.cpp
@@ -0,0 +1,82 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardInstance.h"
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/StringMap.h>
+
+#include "frc/shuffleboard/Shuffleboard.h"
+
+using namespace frc::detail;
+
+struct ShuffleboardInstance::Impl {
+  wpi::StringMap<ShuffleboardTab> tabs;
+
+  bool tabsChanged = false;
+  std::shared_ptr<nt::NetworkTable> rootTable;
+  std::shared_ptr<nt::NetworkTable> rootMetaTable;
+};
+
+ShuffleboardInstance::ShuffleboardInstance(nt::NetworkTableInstance ntInstance)
+    : m_impl(new Impl) {
+  m_impl->rootTable = ntInstance.GetTable(Shuffleboard::kBaseTableName);
+  m_impl->rootMetaTable = m_impl->rootTable->GetSubTable(".metadata");
+}
+
+ShuffleboardInstance::~ShuffleboardInstance() {}
+
+frc::ShuffleboardTab& ShuffleboardInstance::GetTab(wpi::StringRef title) {
+  if (m_impl->tabs.find(title) == m_impl->tabs.end()) {
+    m_impl->tabs.try_emplace(title, ShuffleboardTab(*this, title));
+    m_impl->tabsChanged = true;
+  }
+  return m_impl->tabs.find(title)->second;
+}
+
+void ShuffleboardInstance::Update() {
+  if (m_impl->tabsChanged) {
+    std::vector<std::string> tabTitles;
+    for (auto& entry : m_impl->tabs) {
+      tabTitles.emplace_back(entry.second.GetTitle());
+    }
+    m_impl->rootMetaTable->GetEntry("Tabs").ForceSetStringArray(tabTitles);
+    m_impl->tabsChanged = false;
+  }
+  for (auto& entry : m_impl->tabs) {
+    auto& tab = entry.second;
+    tab.BuildInto(m_impl->rootTable,
+                  m_impl->rootMetaTable->GetSubTable(tab.GetTitle()));
+  }
+}
+
+void ShuffleboardInstance::EnableActuatorWidgets() {
+  for (auto& entry : m_impl->tabs) {
+    auto& tab = entry.second;
+    for (auto& component : tab.GetComponents()) {
+      component->EnableIfActuator();
+    }
+  }
+}
+
+void ShuffleboardInstance::DisableActuatorWidgets() {
+  for (auto& entry : m_impl->tabs) {
+    auto& tab = entry.second;
+    for (auto& component : tab.GetComponents()) {
+      component->DisableIfActuator();
+    }
+  }
+}
+
+void ShuffleboardInstance::SelectTab(int index) {
+  m_impl->rootMetaTable->GetEntry("Selected").ForceSetDouble(index);
+}
+
+void ShuffleboardInstance::SelectTab(wpi::StringRef title) {
+  m_impl->rootMetaTable->GetEntry("Selected").ForceSetString(title);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardLayout.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardLayout.cpp
new file mode 100644
index 0000000..8418b77
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardLayout.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardLayout.h"
+
+using namespace frc;
+
+ShuffleboardLayout::ShuffleboardLayout(ShuffleboardContainer& parent,
+                                       const wpi::Twine& name,
+                                       const wpi::Twine& type)
+    : ShuffleboardValue(type),
+      ShuffleboardComponent(parent, type, name),
+      ShuffleboardContainer(name) {
+  m_isLayout = true;
+}
+
+void ShuffleboardLayout::BuildInto(
+    std::shared_ptr<nt::NetworkTable> parentTable,
+    std::shared_ptr<nt::NetworkTable> metaTable) {
+  BuildMetadata(metaTable);
+  auto table = parentTable->GetSubTable(GetTitle());
+  table->GetEntry(".type").SetString("ShuffleboardLayout");
+  for (auto& component : GetComponents()) {
+    component->BuildInto(table, metaTable->GetSubTable(component->GetTitle()));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardTab.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardTab.cpp
new file mode 100644
index 0000000..7a8338e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardTab.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardTab.h"
+
+using namespace frc;
+
+ShuffleboardTab::ShuffleboardTab(ShuffleboardRoot& root, wpi::StringRef title)
+    : ShuffleboardValue(title), ShuffleboardContainer(title), m_root(root) {}
+
+ShuffleboardRoot& ShuffleboardTab::GetRoot() { return m_root; }
+
+void ShuffleboardTab::BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                                std::shared_ptr<nt::NetworkTable> metaTable) {
+  auto tabTable = parentTable->GetSubTable(GetTitle());
+  tabTable->GetEntry(".type").SetString("ShuffleboardTab");
+  for (auto& component : GetComponents()) {
+    component->BuildInto(tabTable,
+                         metaTable->GetSubTable(component->GetTitle()));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp
new file mode 100644
index 0000000..89af25d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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/SimpleWidget.h"
+
+#include "frc/shuffleboard/Shuffleboard.h"
+#include "frc/shuffleboard/ShuffleboardLayout.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+
+using namespace frc;
+
+SimpleWidget::SimpleWidget(ShuffleboardContainer& parent,
+                           const wpi::Twine& title)
+    : ShuffleboardValue(title), ShuffleboardWidget(parent, title), m_entry() {}
+
+nt::NetworkTableEntry SimpleWidget::GetEntry() {
+  if (!m_entry) {
+    ForceGenerate();
+  }
+  return m_entry;
+}
+
+void SimpleWidget::BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                             std::shared_ptr<nt::NetworkTable> metaTable) {
+  BuildMetadata(metaTable);
+  if (!m_entry) {
+    m_entry = parentTable->GetEntry(GetTitle());
+  }
+}
+
+void SimpleWidget::ForceGenerate() {
+  ShuffleboardContainer* parent = &GetParent();
+
+  while (parent->m_isLayout) {
+    parent = &(static_cast<ShuffleboardLayout*>(parent)->GetParent());
+  }
+
+  auto& tab = *static_cast<ShuffleboardTab*>(parent);
+  tab.GetRoot().Update();
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/WidgetType.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/WidgetType.cpp
new file mode 100644
index 0000000..cb73d30
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/shuffleboard/WidgetType.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* 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/WidgetType.h"
+
+using namespace frc;
+
+wpi::StringRef WidgetType::GetWidgetName() const { return m_widgetName; }
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/NamedSendable.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/NamedSendable.cpp
new file mode 100644
index 0000000..61028b3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/NamedSendable.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/smartdashboard/NamedSendable.h"
+
+using namespace frc;
+
+void NamedSendable::SetName(const wpi::Twine&) {}
+
+std::string NamedSendable::GetSubsystem() const { return std::string(); }
+
+void NamedSendable::SetSubsystem(const wpi::Twine&) {}
+
+void NamedSendable::InitSendable(SendableBuilder&) {}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp
new file mode 100644
index 0000000..28bd7fd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableBase.cpp
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/smartdashboard/SendableBase.h"
+
+#include <utility>
+
+#include "frc/livewindow/LiveWindow.h"
+
+using namespace frc;
+
+SendableBase::SendableBase(bool addLiveWindow) {
+  if (addLiveWindow) LiveWindow::GetInstance()->Add(this);
+}
+
+SendableBase::~SendableBase() { LiveWindow::GetInstance()->Remove(this); }
+
+SendableBase::SendableBase(SendableBase&& rhs) {
+  m_name = std::move(rhs.m_name);
+  m_subsystem = std::move(rhs.m_subsystem);
+}
+
+SendableBase& SendableBase::operator=(SendableBase&& rhs) {
+  Sendable::operator=(std::move(rhs));
+
+  m_name = std::move(rhs.m_name);
+  m_subsystem = std::move(rhs.m_subsystem);
+
+  return *this;
+}
+
+std::string SendableBase::GetName() const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return m_name;
+}
+
+void SendableBase::SetName(const wpi::Twine& name) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_name = name.str();
+}
+
+std::string SendableBase::GetSubsystem() const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return m_subsystem;
+}
+
+void SendableBase::SetSubsystem(const wpi::Twine& subsystem) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  m_subsystem = subsystem.str();
+}
+
+void SendableBase::AddChild(std::shared_ptr<Sendable> child) {
+  LiveWindow::GetInstance()->AddChild(this, child);
+}
+
+void SendableBase::AddChild(void* child) {
+  LiveWindow::GetInstance()->AddChild(this, child);
+}
+
+void SendableBase::SetName(const wpi::Twine& moduleType, int channel) {
+  SetName(moduleType + wpi::Twine('[') + wpi::Twine(channel) + wpi::Twine(']'));
+}
+
+void SendableBase::SetName(const wpi::Twine& moduleType, int moduleNumber,
+                           int channel) {
+  SetName(moduleType + wpi::Twine('[') + wpi::Twine(moduleNumber) +
+          wpi::Twine(',') + wpi::Twine(channel) + wpi::Twine(']'));
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp
new file mode 100644
index 0000000..bce03b5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp
@@ -0,0 +1,382 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/smartdashboard/SendableBuilderImpl.h"
+
+#include <ntcore_cpp.h>
+#include <wpi/SmallString.h>
+
+using namespace frc;
+
+void SendableBuilderImpl::SetTable(std::shared_ptr<nt::NetworkTable> table) {
+  m_table = table;
+  m_controllableEntry = table->GetEntry(".controllable");
+}
+
+std::shared_ptr<nt::NetworkTable> SendableBuilderImpl::GetTable() {
+  return m_table;
+}
+
+bool SendableBuilderImpl::IsActuator() const { return m_actuator; }
+
+void SendableBuilderImpl::UpdateTable() {
+  uint64_t time = nt::Now();
+  for (auto& property : m_properties) {
+    if (property.update) property.update(property.entry, time);
+  }
+  if (m_updateTable) m_updateTable();
+}
+
+void SendableBuilderImpl::StartListeners() {
+  for (auto& property : m_properties) property.StartListener();
+  if (m_controllableEntry) m_controllableEntry.SetBoolean(true);
+}
+
+void SendableBuilderImpl::StopListeners() {
+  for (auto& property : m_properties) property.StopListener();
+  if (m_controllableEntry) m_controllableEntry.SetBoolean(false);
+}
+
+void SendableBuilderImpl::StartLiveWindowMode() {
+  if (m_safeState) m_safeState();
+  StartListeners();
+}
+
+void SendableBuilderImpl::StopLiveWindowMode() {
+  StopListeners();
+  if (m_safeState) m_safeState();
+}
+
+void SendableBuilderImpl::SetSmartDashboardType(const wpi::Twine& type) {
+  m_table->GetEntry(".type").SetString(type);
+}
+
+void SendableBuilderImpl::SetActuator(bool value) {
+  m_table->GetEntry(".actuator").SetBoolean(value);
+  m_actuator = value;
+}
+
+void SendableBuilderImpl::SetSafeState(std::function<void()> func) {
+  m_safeState = func;
+}
+
+void SendableBuilderImpl::SetUpdateTable(std::function<void()> func) {
+  m_updateTable = func;
+}
+
+nt::NetworkTableEntry SendableBuilderImpl::GetEntry(const wpi::Twine& key) {
+  return m_table->GetEntry(key);
+}
+
+void SendableBuilderImpl::AddBooleanProperty(const wpi::Twine& key,
+                                             std::function<bool()> getter,
+                                             std::function<void(bool)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeBoolean(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsBoolean()) return;
+            setter(event.value->GetBoolean());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddDoubleProperty(
+    const wpi::Twine& key, std::function<double()> getter,
+    std::function<void(double)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeDouble(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsDouble()) return;
+            setter(event.value->GetDouble());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddStringProperty(
+    const wpi::Twine& key, std::function<std::string()> getter,
+    std::function<void(wpi::StringRef)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeString(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsString()) return;
+            setter(event.value->GetString());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddBooleanArrayProperty(
+    const wpi::Twine& key, std::function<std::vector<int>()> getter,
+    std::function<void(wpi::ArrayRef<int>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeBooleanArray(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsBooleanArray()) return;
+            setter(event.value->GetBooleanArray());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddDoubleArrayProperty(
+    const wpi::Twine& key, std::function<std::vector<double>()> getter,
+    std::function<void(wpi::ArrayRef<double>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeDoubleArray(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsDoubleArray()) return;
+            setter(event.value->GetDoubleArray());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddStringArrayProperty(
+    const wpi::Twine& key, std::function<std::vector<std::string>()> getter,
+    std::function<void(wpi::ArrayRef<std::string>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeStringArray(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsStringArray()) return;
+            setter(event.value->GetStringArray());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddRawProperty(
+    const wpi::Twine& key, std::function<std::string()> getter,
+    std::function<void(wpi::StringRef)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(nt::Value::MakeRaw(getter(), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsRaw()) return;
+            setter(event.value->GetRaw());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddValueProperty(
+    const wpi::Twine& key, std::function<std::shared_ptr<nt::Value>()> getter,
+    std::function<void(std::shared_ptr<nt::Value>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      entry.SetValue(getter());
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) { setter(event.value); },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallStringProperty(
+    const wpi::Twine& key,
+    std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+    std::function<void(wpi::StringRef)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallString<128> buf;
+      entry.SetValue(nt::Value::MakeString(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsString()) return;
+            setter(event.value->GetString());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallBooleanArrayProperty(
+    const wpi::Twine& key,
+    std::function<wpi::ArrayRef<int>(wpi::SmallVectorImpl<int>& buf)> getter,
+    std::function<void(wpi::ArrayRef<int>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallVector<int, 16> buf;
+      entry.SetValue(nt::Value::MakeBooleanArray(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsBooleanArray()) return;
+            setter(event.value->GetBooleanArray());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallDoubleArrayProperty(
+    const wpi::Twine& key,
+    std::function<wpi::ArrayRef<double>(wpi::SmallVectorImpl<double>& buf)>
+        getter,
+    std::function<void(wpi::ArrayRef<double>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallVector<double, 16> buf;
+      entry.SetValue(nt::Value::MakeDoubleArray(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsDoubleArray()) return;
+            setter(event.value->GetDoubleArray());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallStringArrayProperty(
+    const wpi::Twine& key,
+    std::function<
+        wpi::ArrayRef<std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+        getter,
+    std::function<void(wpi::ArrayRef<std::string>)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallVector<std::string, 16> buf;
+      entry.SetValue(nt::Value::MakeStringArray(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsStringArray()) return;
+            setter(event.value->GetStringArray());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
+
+void SendableBuilderImpl::AddSmallRawProperty(
+    const wpi::Twine& key,
+    std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+    std::function<void(wpi::StringRef)> setter) {
+  m_properties.emplace_back(*m_table, key);
+  if (getter) {
+    m_properties.back().update = [=](nt::NetworkTableEntry entry,
+                                     uint64_t time) {
+      wpi::SmallVector<char, 128> buf;
+      entry.SetValue(nt::Value::MakeRaw(getter(buf), time));
+    };
+  }
+  if (setter) {
+    m_properties.back().createListener =
+        [=](nt::NetworkTableEntry entry) -> NT_EntryListener {
+      return entry.AddListener(
+          [=](const nt::EntryNotification& event) {
+            if (!event.value->IsRaw()) return;
+            setter(event.value->GetRaw());
+          },
+          NT_NOTIFY_IMMEDIATE | NT_NOTIFY_NEW | NT_NOTIFY_UPDATE);
+    };
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp
new file mode 100644
index 0000000..2cdf92c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/smartdashboard/SendableChooserBase.h"
+
+using namespace frc;
+
+std::atomic_int SendableChooserBase::s_instances{0};
+
+SendableChooserBase::SendableChooserBase()
+    : SendableBase(false), m_instance{s_instances++} {}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
new file mode 100644
index 0000000..98e5568
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp
@@ -0,0 +1,263 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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/smartdashboard/SmartDashboard.h"
+
+#include <hal/HAL.h>
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/StringMap.h>
+#include <wpi/mutex.h>
+
+#include "frc/WPIErrors.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableBuilderImpl.h"
+
+using namespace frc;
+
+namespace {
+class SmartDashboardData {
+ public:
+  SmartDashboardData() = default;
+  explicit SmartDashboardData(Sendable* sendable_) : sendable(sendable_) {}
+
+  Sendable* sendable = nullptr;
+  SendableBuilderImpl builder;
+};
+
+class Singleton {
+ public:
+  static Singleton& GetInstance();
+
+  std::shared_ptr<nt::NetworkTable> table;
+  wpi::StringMap<SmartDashboardData> 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;
+  return instance;
+}
+
+void SmartDashboard::init() { Singleton::GetInstance(); }
+
+bool SmartDashboard::ContainsKey(wpi::StringRef key) {
+  return Singleton::GetInstance().table->ContainsKey(key);
+}
+
+std::vector<std::string> SmartDashboard::GetKeys(int types) {
+  return Singleton::GetInstance().table->GetKeys(types);
+}
+
+void SmartDashboard::SetPersistent(wpi::StringRef key) {
+  Singleton::GetInstance().table->GetEntry(key).SetPersistent();
+}
+
+void SmartDashboard::ClearPersistent(wpi::StringRef key) {
+  Singleton::GetInstance().table->GetEntry(key).ClearPersistent();
+}
+
+bool SmartDashboard::IsPersistent(wpi::StringRef key) {
+  return Singleton::GetInstance().table->GetEntry(key).IsPersistent();
+}
+
+void SmartDashboard::SetFlags(wpi::StringRef key, unsigned int flags) {
+  Singleton::GetInstance().table->GetEntry(key).SetFlags(flags);
+}
+
+void SmartDashboard::ClearFlags(wpi::StringRef key, unsigned int flags) {
+  Singleton::GetInstance().table->GetEntry(key).ClearFlags(flags);
+}
+
+unsigned int SmartDashboard::GetFlags(wpi::StringRef key) {
+  return Singleton::GetInstance().table->GetEntry(key).GetFlags();
+}
+
+void SmartDashboard::Delete(wpi::StringRef key) {
+  Singleton::GetInstance().table->Delete(key);
+}
+
+void SmartDashboard::PutData(wpi::StringRef key, Sendable* data) {
+  if (data == nullptr) {
+    wpi_setGlobalWPIErrorWithContext(NullParameter, "value");
+    return;
+  }
+  auto& inst = Singleton::GetInstance();
+  std::lock_guard<wpi::mutex> lock(inst.tablesToDataMutex);
+  auto& sddata = inst.tablesToData[key];
+  if (!sddata.sendable || sddata.sendable != data) {
+    sddata = SmartDashboardData(data);
+    auto dataTable = inst.table->GetSubTable(key);
+    sddata.builder.SetTable(dataTable);
+    data->InitSendable(sddata.builder);
+    sddata.builder.UpdateTable();
+    sddata.builder.StartListeners();
+    dataTable->GetEntry(".name").SetString(key);
+  }
+}
+
+void SmartDashboard::PutData(Sendable* value) {
+  if (value == nullptr) {
+    wpi_setGlobalWPIErrorWithContext(NullParameter, "value");
+    return;
+  }
+  PutData(value->GetName(), value);
+}
+
+Sendable* SmartDashboard::GetData(wpi::StringRef key) {
+  auto& inst = Singleton::GetInstance();
+  std::lock_guard<wpi::mutex> lock(inst.tablesToDataMutex);
+  auto data = inst.tablesToData.find(key);
+  if (data == inst.tablesToData.end()) {
+    wpi_setGlobalWPIErrorWithContext(SmartDashboardMissingKey, key);
+    return nullptr;
+  }
+  return data->getValue().sendable;
+}
+
+bool SmartDashboard::PutBoolean(wpi::StringRef keyName, bool value) {
+  return Singleton::GetInstance().table->GetEntry(keyName).SetBoolean(value);
+}
+
+bool SmartDashboard::SetDefaultBoolean(wpi::StringRef key, bool defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultBoolean(
+      defaultValue);
+}
+
+bool SmartDashboard::GetBoolean(wpi::StringRef keyName, bool defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(keyName).GetBoolean(
+      defaultValue);
+}
+
+bool SmartDashboard::PutNumber(wpi::StringRef keyName, double value) {
+  return Singleton::GetInstance().table->GetEntry(keyName).SetDouble(value);
+}
+
+bool SmartDashboard::SetDefaultNumber(wpi::StringRef key, double defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultDouble(
+      defaultValue);
+}
+
+double SmartDashboard::GetNumber(wpi::StringRef keyName, double defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(keyName).GetDouble(
+      defaultValue);
+}
+
+bool SmartDashboard::PutString(wpi::StringRef keyName, wpi::StringRef value) {
+  return Singleton::GetInstance().table->GetEntry(keyName).SetString(value);
+}
+
+bool SmartDashboard::SetDefaultString(wpi::StringRef key,
+                                      wpi::StringRef defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultString(
+      defaultValue);
+}
+
+std::string SmartDashboard::GetString(wpi::StringRef keyName,
+                                      wpi::StringRef defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(keyName).GetString(
+      defaultValue);
+}
+
+bool SmartDashboard::PutBooleanArray(wpi::StringRef key,
+                                     wpi::ArrayRef<int> value) {
+  return Singleton::GetInstance().table->GetEntry(key).SetBooleanArray(value);
+}
+
+bool SmartDashboard::SetDefaultBooleanArray(wpi::StringRef key,
+                                            wpi::ArrayRef<int> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultBooleanArray(
+      defaultValue);
+}
+
+std::vector<int> SmartDashboard::GetBooleanArray(
+    wpi::StringRef key, wpi::ArrayRef<int> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).GetBooleanArray(
+      defaultValue);
+}
+
+bool SmartDashboard::PutNumberArray(wpi::StringRef key,
+                                    wpi::ArrayRef<double> value) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDoubleArray(value);
+}
+
+bool SmartDashboard::SetDefaultNumberArray(wpi::StringRef key,
+                                           wpi::ArrayRef<double> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultDoubleArray(
+      defaultValue);
+}
+
+std::vector<double> SmartDashboard::GetNumberArray(
+    wpi::StringRef key, wpi::ArrayRef<double> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).GetDoubleArray(
+      defaultValue);
+}
+
+bool SmartDashboard::PutStringArray(wpi::StringRef key,
+                                    wpi::ArrayRef<std::string> value) {
+  return Singleton::GetInstance().table->GetEntry(key).SetStringArray(value);
+}
+
+bool SmartDashboard::SetDefaultStringArray(
+    wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultStringArray(
+      defaultValue);
+}
+
+std::vector<std::string> SmartDashboard::GetStringArray(
+    wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).GetStringArray(
+      defaultValue);
+}
+
+bool SmartDashboard::PutRaw(wpi::StringRef key, wpi::StringRef value) {
+  return Singleton::GetInstance().table->GetEntry(key).SetRaw(value);
+}
+
+bool SmartDashboard::SetDefaultRaw(wpi::StringRef key,
+                                   wpi::StringRef defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultRaw(
+      defaultValue);
+}
+
+std::string SmartDashboard::GetRaw(wpi::StringRef key,
+                                   wpi::StringRef defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).GetRaw(defaultValue);
+}
+
+bool SmartDashboard::PutValue(wpi::StringRef keyName,
+                              std::shared_ptr<nt::Value> value) {
+  return Singleton::GetInstance().table->GetEntry(keyName).SetValue(value);
+}
+
+bool SmartDashboard::SetDefaultValue(wpi::StringRef key,
+                                     std::shared_ptr<nt::Value> defaultValue) {
+  return Singleton::GetInstance().table->GetEntry(key).SetDefaultValue(
+      defaultValue);
+}
+
+std::shared_ptr<nt::Value> SmartDashboard::GetValue(wpi::StringRef keyName) {
+  return Singleton::GetInstance().table->GetEntry(keyName).GetValue();
+}
+
+void SmartDashboard::UpdateValues() {
+  auto& inst = Singleton::GetInstance();
+  std::lock_guard<wpi::mutex> lock(inst.tablesToDataMutex);
+  for (auto& i : inst.tablesToData) {
+    i.getValue().builder.UpdateTable();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL345_I2C.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL345_I2C.h
new file mode 100644
index 0000000..a155d6c0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL345_I2C.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: ADXL345_I2C.h is deprecated; include frc/ADXL345_I2C.h instead"
+#else
+#warning "ADXL345_I2C.h is deprecated; include frc/ADXL345_I2C.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/ADXL345_I2C.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL345_SPI.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL345_SPI.h
new file mode 100644
index 0000000..490594c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL345_SPI.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: ADXL345_SPI.h is deprecated; include frc/ADXL345_SPI.h instead"
+#else
+#warning "ADXL345_SPI.h is deprecated; include frc/ADXL345_SPI.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/ADXL345_SPI.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL362.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL362.h
new file mode 100644
index 0000000..238ee10
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXL362.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: ADXL362.h is deprecated; include frc/ADXL362.h instead"
+#else
+#warning "ADXL362.h is deprecated; include frc/ADXL362.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/ADXL362.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXRS450_Gyro.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXRS450_Gyro.h
new file mode 100644
index 0000000..46b337f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ADXRS450_Gyro.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: ADXRS450_Gyro.h is deprecated; include frc/ADXRS450_Gyro.h instead"
+#else
+#warning "ADXRS450_Gyro.h is deprecated; include frc/ADXRS450_Gyro.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/ADXRS450_Gyro.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogAccelerometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogAccelerometer.h
new file mode 100644
index 0000000..926005e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogAccelerometer.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: AnalogAccelerometer.h is deprecated; include frc/AnalogAccelerometer.h instead"
+#else
+#warning "AnalogAccelerometer.h is deprecated; include frc/AnalogAccelerometer.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/AnalogAccelerometer.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogGyro.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogGyro.h
new file mode 100644
index 0000000..287bf46
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogGyro.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: AnalogGyro.h is deprecated; include frc/AnalogGyro.h instead"
+#else
+#warning "AnalogGyro.h is deprecated; include frc/AnalogGyro.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/AnalogGyro.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogInput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogInput.h
new file mode 100644
index 0000000..64bacdf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogInput.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: AnalogInput.h is deprecated; include frc/AnalogInput.h instead"
+#else
+#warning "AnalogInput.h is deprecated; include frc/AnalogInput.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/AnalogInput.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogOutput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogOutput.h
new file mode 100644
index 0000000..b08d3ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogOutput.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: AnalogOutput.h is deprecated; include frc/AnalogOutput.h instead"
+#else
+#warning "AnalogOutput.h is deprecated; include frc/AnalogOutput.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/AnalogOutput.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogPotentiometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogPotentiometer.h
new file mode 100644
index 0000000..5b01b97
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogPotentiometer.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: AnalogPotentiometer.h is deprecated; include frc/AnalogPotentiometer.h instead"
+#else
+#warning "AnalogPotentiometer.h is deprecated; include frc/AnalogPotentiometer.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/AnalogPotentiometer.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTrigger.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTrigger.h
new file mode 100644
index 0000000..e88547d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTrigger.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: AnalogTrigger.h is deprecated; include frc/AnalogTrigger.h instead"
+#else
+#warning "AnalogTrigger.h is deprecated; include frc/AnalogTrigger.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/AnalogTrigger.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTriggerOutput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTriggerOutput.h
new file mode 100644
index 0000000..d8754a0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTriggerOutput.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: AnalogTriggerOutput.h is deprecated; include frc/AnalogTriggerOutput.h instead"
+#else
+#warning "AnalogTriggerOutput.h is deprecated; include frc/AnalogTriggerOutput.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/AnalogTriggerOutput.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTriggerType.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTriggerType.h
new file mode 100644
index 0000000..6f55772
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/AnalogTriggerType.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: AnalogTriggerType.h is deprecated; include frc/AnalogTriggerType.h instead"
+#else
+#warning "AnalogTriggerType.h is deprecated; include frc/AnalogTriggerType.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/AnalogTriggerType.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Base.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Base.h
new file mode 100644
index 0000000..c6fc91a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Base.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Base.h is deprecated; include frc/Base.h instead"
+#else
+#warning "Base.h is deprecated; include frc/Base.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Base.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/BuiltInAccelerometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/BuiltInAccelerometer.h
new file mode 100644
index 0000000..e394037
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/BuiltInAccelerometer.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: BuiltInAccelerometer.h is deprecated; include frc/BuiltInAccelerometer.h instead"
+#else
+#warning "BuiltInAccelerometer.h is deprecated; include frc/BuiltInAccelerometer.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/BuiltInAccelerometer.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/Button.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/Button.h
new file mode 100644
index 0000000..f71bee2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/Button.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Buttons/Button.h is deprecated; include frc/buttons/Button.h instead"
+#else
+#warning "Buttons/Button.h is deprecated; include frc/buttons/Button.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/Button.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ButtonScheduler.h
new file mode 100644
index 0000000..48392c7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ButtonScheduler.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/ButtonScheduler.h is deprecated; include frc/buttons/ButtonScheduler.h instead"
+#else
+#warning "buttons/ButtonScheduler.h is deprecated; include frc/buttons/ButtonScheduler.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/ButtonScheduler.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/CancelButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/CancelButtonScheduler.h
new file mode 100644
index 0000000..201d024
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/CancelButtonScheduler.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/CancelButtonScheduler.h is deprecated; include frc/buttons/CancelButtonScheduler.h instead"
+#else
+#warning "buttons/CancelButtonScheduler.h is deprecated; include frc/buttons/CancelButtonScheduler.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/CancelButtonScheduler.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/HeldButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/HeldButtonScheduler.h
new file mode 100644
index 0000000..4886832
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/HeldButtonScheduler.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/HeldButtonScheduler.h is deprecated; include frc/buttons/HeldButtonScheduler.h instead"
+#else
+#warning "buttons/HeldButtonScheduler.h is deprecated; include frc/buttons/HeldButtonScheduler.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/HeldButtonScheduler.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/InternalButton.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/InternalButton.h
new file mode 100644
index 0000000..4cde15a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/InternalButton.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/InternalButton.h is deprecated; include frc/buttons/InternalButton.h instead"
+#else
+#warning "buttons/InternalButton.h is deprecated; include frc/buttons/InternalButton.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/InternalButton.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/JoystickButton.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/JoystickButton.h
new file mode 100644
index 0000000..6ad611e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/JoystickButton.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/JoystickButton.h is deprecated; include frc/buttons/JoystickButton.h instead"
+#else
+#warning "buttons/JoystickButton.h is deprecated; include frc/buttons/JoystickButton.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/JoystickButton.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/NetworkButton.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/NetworkButton.h
new file mode 100644
index 0000000..8d23810
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/NetworkButton.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/NetworkButton.h is deprecated; include frc/buttons/NetworkButton.h instead"
+#else
+#warning "buttons/NetworkButton.h is deprecated; include frc/buttons/NetworkButton.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/NetworkButton.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/PressedButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/PressedButtonScheduler.h
new file mode 100644
index 0000000..323d9e2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/PressedButtonScheduler.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/PressedButtonScheduler.h is deprecated; include frc/buttons/PressedButtonScheduler.h instead"
+#else
+#warning "buttons/PressedButtonScheduler.h is deprecated; include frc/buttons/PressedButtonScheduler.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/PressedButtonScheduler.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ReleasedButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ReleasedButtonScheduler.h
new file mode 100644
index 0000000..88ef25c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ReleasedButtonScheduler.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/ReleasedButtonScheduler.h is deprecated; include frc/buttons/ReleasedButtonScheduler.h instead"
+#else
+#warning "buttons/ReleasedButtonScheduler.h is deprecated; include frc/buttons/ReleasedButtonScheduler.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/ReleasedButtonScheduler.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ToggleButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ToggleButtonScheduler.h
new file mode 100644
index 0000000..7848f91
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/ToggleButtonScheduler.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/ToggleButtonScheduler.h is deprecated; include frc/buttons/ToggleButtonScheduler.h instead"
+#else
+#warning "buttons/ToggleButtonScheduler.h is deprecated; include frc/buttons/ToggleButtonScheduler.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/ToggleButtonScheduler.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/Trigger.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/Trigger.h
new file mode 100644
index 0000000..7fb8889
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Buttons/Trigger.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: buttons/Trigger.h is deprecated; include frc/buttons/Trigger.h instead"
+#else
+#warning "buttons/Trigger.h is deprecated; include frc/buttons/Trigger.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/buttons/Trigger.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/CAN.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/CAN.h
new file mode 100644
index 0000000..28d49b8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/CAN.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: CAN.h is deprecated; include frc/CAN.h instead"
+#else
+#warning "CAN.h is deprecated; include frc/CAN.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/CAN.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Command.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Command.h
new file mode 100644
index 0000000..f170ced
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Command.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/Command.h is deprecated; include frc/commands/Command.h instead"
+#else
+#warning "Commands/Command.h is deprecated; include frc/commands/Command.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/Command.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/CommandGroup.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/CommandGroup.h
new file mode 100644
index 0000000..0e124f2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/CommandGroup.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/CommandGroup.h is deprecated; include frc/commands/CommandGroup.h instead"
+#else
+#warning "Commands/CommandGroup.h is deprecated; include frc/commands/CommandGroup.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/CommandGroup.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/CommandGroupEntry.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/CommandGroupEntry.h
new file mode 100644
index 0000000..1f5ee67
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/CommandGroupEntry.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/CommandGroupEntry.h is deprecated; include frc/commands/CommandGroupEntry.h instead"
+#else
+#warning "Commands/CommandGroupEntry.h is deprecated; include frc/commands/CommandGroupEntry.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/CommandGroupEntry.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/ConditionalCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/ConditionalCommand.h
new file mode 100644
index 0000000..a0d3df8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/ConditionalCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/ConditionalCommand.h is deprecated; include frc/commands/ConditionalCommand.h instead"
+#else
+#warning "Commands/ConditionalCommand.h is deprecated; include frc/commands/ConditionalCommand.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/ConditionalCommand.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/InstantCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/InstantCommand.h
new file mode 100644
index 0000000..c097c1a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/InstantCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/InstantCommand.h is deprecated; include frc/commands/InstantCommand.h instead"
+#else
+#warning "Commands/InstantCommand.h is deprecated; include frc/commands/InstantCommand.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/InstantCommand.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PIDCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PIDCommand.h
new file mode 100644
index 0000000..462e807
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PIDCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/PIDCommand.h is deprecated; include frc/commands/PIDCommand.h instead"
+#else
+#warning "Commands/PIDCommand.h is deprecated; include frc/commands/PIDCommand.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/PIDCommand.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PIDSubsystem.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PIDSubsystem.h
new file mode 100644
index 0000000..d4bc1ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PIDSubsystem.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/PIDSubsystem.h is deprecated; include frc/commands/PIDSubsystem.h instead"
+#else
+#warning "Commands/PIDSubsystem.h is deprecated; include frc/commands/PIDSubsystem.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/PIDSubsystem.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PrintCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PrintCommand.h
new file mode 100644
index 0000000..801a539
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/PrintCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/PrintCommand.h is deprecated; include frc/commands/PrintCommand.h instead"
+#else
+#warning "Commands/PrintCommand.h is deprecated; include frc/commands/PrintCommand.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/PrintCommand.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Scheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Scheduler.h
new file mode 100644
index 0000000..df7591c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Scheduler.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/Scheduler.h is deprecated; include frc/commands/Scheduler.h instead"
+#else
+#warning "Commands/Scheduler.h is deprecated; include frc/commands/Scheduler.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/Scheduler.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/StartCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/StartCommand.h
new file mode 100644
index 0000000..7ae1603
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/StartCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/StartCommand.h is deprecated; include frc/commands/StartCommand.h instead"
+#else
+#warning "Commands/StartCommand.h is deprecated; include frc/commands/StartCommand.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/StartCommand.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Subsystem.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Subsystem.h
new file mode 100644
index 0000000..ffd0697
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/Subsystem.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/Subsystem.h is deprecated; include frc/commands/Subsystem.h instead"
+#else
+#warning "Commands/Subsystem.h is deprecated; include frc/commands/Subsystem.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/Subsystem.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/TimedCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/TimedCommand.h
new file mode 100644
index 0000000..848f4b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/TimedCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/TimedCommand.h is deprecated; include frc/commands/TimedCommand.h instead"
+#else
+#warning "Commands/TimedCommand.h is deprecated; include frc/commands/TimedCommand.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/TimedCommand.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitCommand.h
new file mode 100644
index 0000000..1901fba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/WaitCommand.h is deprecated; include frc/commands/WaitCommand.h instead"
+#else
+#warning "Commands/WaitCommand.h is deprecated; include frc/commands/WaitCommand.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/WaitCommand.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitForChildren.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitForChildren.h
new file mode 100644
index 0000000..178c835
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitForChildren.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/WaitForChildren.h is deprecated; include frc/commands/WaitForChildren.h instead"
+#else
+#warning "Commands/WaitForChildren.h is deprecated; include frc/commands/WaitForChildren.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/WaitForChildren.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitUntilCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitUntilCommand.h
new file mode 100644
index 0000000..b338d5f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Commands/WaitUntilCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Commands/WaitUntilCommand.h is deprecated; include frc/commands/WaitUntilCommand.h instead"
+#else
+#warning "Commands/WaitUntilCommand.h is deprecated; include frc/commands/WaitUntilCommand.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/commands/WaitUntilCommand.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Compressor.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Compressor.h
new file mode 100644
index 0000000..bfb018e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Compressor.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Compressor.h is deprecated; include frc/Compressor.h instead"
+#else
+#warning "Compressor.h is deprecated; include frc/Compressor.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Compressor.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Controller.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Controller.h
new file mode 100644
index 0000000..b869373
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Controller.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Controller.h is deprecated; include frc/Controller.h instead"
+#else
+#warning "Controller.h is deprecated; include frc/Controller.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Controller.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/ControllerPower.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ControllerPower.h
new file mode 100644
index 0000000..1469d19
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ControllerPower.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: ControllerPower.h is deprecated; include frc/ControllerPower.h instead"
+#else
+#warning "ControllerPower.h is deprecated; include frc/ControllerPower.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/ControllerPower.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Counter.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Counter.h
new file mode 100644
index 0000000..e088897
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Counter.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Counter.h is deprecated; include frc/Counter.h instead"
+#else
+#warning "Counter.h is deprecated; include frc/Counter.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Counter.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/CounterBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/CounterBase.h
new file mode 100644
index 0000000..736577f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/CounterBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: CounterBase.h is deprecated; include frc/CounterBase.h instead"
+#else
+#warning "CounterBase.h is deprecated; include frc/CounterBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/CounterBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/DMC60.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DMC60.h
new file mode 100644
index 0000000..0fe0415
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DMC60.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: DMC60.h is deprecated; include frc/DMC60.h instead"
+#else
+#warning "DMC60.h is deprecated; include frc/DMC60.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/DMC60.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalGlitchFilter.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalGlitchFilter.h
new file mode 100644
index 0000000..d35c82a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalGlitchFilter.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: DigitalGlitchFilter.h is deprecated; include frc/DigitalGlitchFilter.h instead"
+#else
+#warning "DigitalGlitchFilter.h is deprecated; include frc/DigitalGlitchFilter.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/DigitalGlitchFilter.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalInput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalInput.h
new file mode 100644
index 0000000..2b2a9b1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalInput.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: DigitalInput.h is deprecated; include frc/DigitalInput.h instead"
+#else
+#warning "DigitalInput.h is deprecated; include frc/DigitalInput.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/DigitalInput.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalOutput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalOutput.h
new file mode 100644
index 0000000..56983c6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalOutput.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: DigitalOutput.h is deprecated; include frc/DigitalOutput.h instead"
+#else
+#warning "DigitalOutput.h is deprecated; include frc/DigitalOutput.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/DigitalOutput.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalSource.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalSource.h
new file mode 100644
index 0000000..9eae461
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DigitalSource.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: DigitalSource.h is deprecated; include frc/DigitalSource.h instead"
+#else
+#warning "DigitalSource.h is deprecated; include frc/DigitalSource.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/DigitalSource.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/DoubleSolenoid.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DoubleSolenoid.h
new file mode 100644
index 0000000..3c1bf96
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DoubleSolenoid.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: DoubleSolenoid.h is deprecated; include frc/DoubleSolenoid.h instead"
+#else
+#warning "DoubleSolenoid.h is deprecated; include frc/DoubleSolenoid.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/DoubleSolenoid.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/DifferentialDrive.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/DifferentialDrive.h
new file mode 100644
index 0000000..4071d60
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/DifferentialDrive.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Drive/DifferentialDrive.h is deprecated; include frc/drive/DifferentialDrive.h instead"
+#else
+#warning "Drive/DifferentialDrive.h is deprecated; include frc/drive/DifferentialDrive.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/drive/DifferentialDrive.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/KilloughDrive.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/KilloughDrive.h
new file mode 100644
index 0000000..fbe54a4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/KilloughDrive.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Drive/KilloughDrive.h is deprecated; include frc/drive/KilloughDrive.h instead"
+#else
+#warning "Drive/KilloughDrive.h is deprecated; include frc/drive/KilloughDrive.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/drive/KilloughDrive.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/MecanumDrive.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/MecanumDrive.h
new file mode 100644
index 0000000..b5a22aa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/MecanumDrive.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Drive/MecanumDrive.h is deprecated; include frc/drive/MecanumDrive.h instead"
+#else
+#warning "Drive/MecanumDrive.h is deprecated; include frc/drive/MecanumDrive.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/drive/MecanumDrive.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/RobotDriveBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/RobotDriveBase.h
new file mode 100644
index 0000000..f37ec0c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/RobotDriveBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Drive/RobotDriveBase.h is deprecated; include frc/drive/RobotDriveBase.h instead"
+#else
+#warning "Drive/RobotDriveBase.h is deprecated; include frc/drive/RobotDriveBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/drive/RobotDriveBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/Vector2d.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/Vector2d.h
new file mode 100644
index 0000000..01516ed
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Drive/Vector2d.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Drive/Vector2d.h is deprecated; include frc/drive/Vector2d.h instead"
+#else
+#warning "Drive/Vector2d.h is deprecated; include frc/drive/Vector2d.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/drive/Vector2d.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/DriverStation.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DriverStation.h
new file mode 100644
index 0000000..c00adbc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/DriverStation.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: DriverStation.h is deprecated; include frc/DriverStation.h instead"
+#else
+#warning "DriverStation.h is deprecated; include frc/DriverStation.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/DriverStation.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Encoder.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Encoder.h
new file mode 100644
index 0000000..214100d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Encoder.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Encoder.h is deprecated; include frc/Encoder.h instead"
+#else
+#warning "Encoder.h is deprecated; include frc/Encoder.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Encoder.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Error.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Error.h
new file mode 100644
index 0000000..f3fb5de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Error.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Error.h is deprecated; include frc/Error.h instead"
+#else
+#warning "Error.h is deprecated; include frc/Error.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Error.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/ErrorBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ErrorBase.h
new file mode 100644
index 0000000..eb300d9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/ErrorBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: ErrorBase.h is deprecated; include frc/ErrorBase.h instead"
+#else
+#warning "ErrorBase.h is deprecated; include frc/ErrorBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/ErrorBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Filters/Filter.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Filters/Filter.h
new file mode 100644
index 0000000..4fd382f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Filters/Filter.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Filters/Filter.h is deprecated; include frc/filters/Filter.h instead"
+#else
+#warning "Filters/Filter.h is deprecated; include frc/filters/Filter.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/filters/Filter.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Filters/LinearDigitalFilter.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Filters/LinearDigitalFilter.h
new file mode 100644
index 0000000..b0da22c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Filters/LinearDigitalFilter.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Filters/LinearDigitalFilter.h is deprecated; include frc/filters/LinearDigitalFilter.h instead"
+#else
+#warning "Filters/LinearDigitalFilter.h is deprecated; include frc/filters/LinearDigitalFilter.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/filters/LinearDigitalFilter.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/GamepadBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/GamepadBase.h
new file mode 100644
index 0000000..bc8d809
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/GamepadBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: GamepadBase.h is deprecated; include frc/GamepadBase.h instead"
+#else
+#warning "GamepadBase.h is deprecated; include frc/GamepadBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/GamepadBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/GearTooth.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/GearTooth.h
new file mode 100644
index 0000000..2c56f95
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/GearTooth.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: GearTooth.h is deprecated; include frc/GearTooth.h instead"
+#else
+#warning "GearTooth.h is deprecated; include frc/GearTooth.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/GearTooth.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/GenericHID.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/GenericHID.h
new file mode 100644
index 0000000..d305692
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/GenericHID.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: GenericHID.h is deprecated; include frc/GenericHID.h instead"
+#else
+#warning "GenericHID.h is deprecated; include frc/GenericHID.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/GenericHID.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/GyroBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/GyroBase.h
new file mode 100644
index 0000000..f2b9097
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/GyroBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: GyroBase.h is deprecated; include frc/GyroBase.h instead"
+#else
+#warning "GyroBase.h is deprecated; include frc/GyroBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/GyroBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/I2C.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/I2C.h
new file mode 100644
index 0000000..594fdaf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/I2C.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: I2C.h is deprecated; include frc/I2C.h instead"
+#else
+#warning "I2C.h is deprecated; include frc/I2C.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/I2C.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/InterruptableSensorBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/InterruptableSensorBase.h
new file mode 100644
index 0000000..43e4f74
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/InterruptableSensorBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: InterruptableSensorBase.h is deprecated; include frc/InterruptableSensorBase.h instead"
+#else
+#warning "InterruptableSensorBase.h is deprecated; include frc/InterruptableSensorBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/InterruptableSensorBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/IterativeRobot.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/IterativeRobot.h
new file mode 100644
index 0000000..7ad7973
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/IterativeRobot.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: IterativeRobot.h is deprecated; include frc/IterativeRobot.h instead"
+#else
+#warning "IterativeRobot.h is deprecated; include frc/IterativeRobot.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/IterativeRobot.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/IterativeRobotBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/IterativeRobotBase.h
new file mode 100644
index 0000000..e87c547
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/IterativeRobotBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: IterativeRobotBase.h is deprecated; include frc/IterativeRobotBase.h instead"
+#else
+#warning "IterativeRobotBase.h is deprecated; include frc/IterativeRobotBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/IterativeRobotBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Jaguar.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Jaguar.h
new file mode 100644
index 0000000..7eea49d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Jaguar.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Jaguar.h is deprecated; include frc/Jaguar.h instead"
+#else
+#warning "Jaguar.h is deprecated; include frc/Jaguar.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Jaguar.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Joystick.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Joystick.h
new file mode 100644
index 0000000..febc148
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Joystick.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Joystick.h is deprecated; include frc/Joystick.h instead"
+#else
+#warning "Joystick.h is deprecated; include frc/Joystick.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Joystick.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/JoystickBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/JoystickBase.h
new file mode 100644
index 0000000..4aa2a59
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/JoystickBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: JoystickBase.h is deprecated; include frc/JoystickBase.h instead"
+#else
+#warning "JoystickBase.h is deprecated; include frc/JoystickBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/JoystickBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/LiveWindow/LiveWindow.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/LiveWindow/LiveWindow.h
new file mode 100644
index 0000000..99e7628
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/LiveWindow/LiveWindow.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: LiveWindow/LiveWindow.h is deprecated; include frc/livewindow/LiveWindow.h instead"
+#else
+#warning "LiveWindow/LiveWindow.h is deprecated; include frc/livewindow/LiveWindow.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/livewindow/LiveWindow.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/LiveWindow/LiveWindowSendable.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/LiveWindow/LiveWindowSendable.h
new file mode 100644
index 0000000..cc8082b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/LiveWindow/LiveWindowSendable.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: LiveWindow/LiveWindowSendable.h is deprecated; include frc/livewindow/LiveWindowSendable.h instead"
+#else
+#warning "LiveWindow/LiveWindowSendable.h is deprecated; include frc/livewindow/LiveWindowSendable.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/livewindow/LiveWindowSendable.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/MotorSafety.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/MotorSafety.h
new file mode 100644
index 0000000..a33fd0b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/MotorSafety.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: MotorSafety.h is deprecated; include frc/MotorSafety.h instead"
+#else
+#warning "MotorSafety.h is deprecated; include frc/MotorSafety.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/MotorSafety.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/NidecBrushless.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/NidecBrushless.h
new file mode 100644
index 0000000..0937787
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/NidecBrushless.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: NidecBrushless.h is deprecated; include frc/NidecBrushless.h instead"
+#else
+#warning "NidecBrushless.h is deprecated; include frc/NidecBrushless.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/NidecBrushless.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Notifier.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Notifier.h
new file mode 100644
index 0000000..28e6a20
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Notifier.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Notifier.h is deprecated; include frc/Notifier.h instead"
+#else
+#warning "Notifier.h is deprecated; include frc/Notifier.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Notifier.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDBase.h
new file mode 100644
index 0000000..b9e2d50
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PIDBase.h is deprecated; include frc/PIDBase.h instead"
+#else
+#warning "PIDBase.h is deprecated; include frc/PIDBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PIDBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDController.h
new file mode 100644
index 0000000..38777ea
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDController.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PIDController.h is deprecated; include frc/PIDController.h instead"
+#else
+#warning "PIDController.h is deprecated; include frc/PIDController.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PIDController.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDInterface.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDInterface.h
new file mode 100644
index 0000000..8e0f10e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDInterface.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PIDInterface.h is deprecated; include frc/PIDInterface.h instead"
+#else
+#warning "PIDInterface.h is deprecated; include frc/PIDInterface.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PIDInterface.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDOutput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDOutput.h
new file mode 100644
index 0000000..857ce0f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDOutput.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PIDOutput.h is deprecated; include frc/PIDOutput.h instead"
+#else
+#warning "PIDOutput.h is deprecated; include frc/PIDOutput.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PIDOutput.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDSource.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDSource.h
new file mode 100644
index 0000000..29b8469
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PIDSource.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PIDSource.h is deprecated; include frc/PIDSource.h instead"
+#else
+#warning "PIDSource.h is deprecated; include frc/PIDSource.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PIDSource.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWM.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWM.h
new file mode 100644
index 0000000..989c4f7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWM.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PWM.h is deprecated; include frc/PWM.h instead"
+#else
+#warning "PWM.h is deprecated; include frc/PWM.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PWM.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMSpeedController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMSpeedController.h
new file mode 100644
index 0000000..f15f384
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMSpeedController.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PWMSpeedController.h is deprecated; include frc/PWMSpeedController.h instead"
+#else
+#warning "PWMSpeedController.h is deprecated; include frc/PWMSpeedController.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PWMSpeedController.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMTalonSRX.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMTalonSRX.h
new file mode 100644
index 0000000..43a132a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMTalonSRX.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PWMTalonSRX.h is deprecated; include frc/PWMTalonSRX.h instead"
+#else
+#warning "PWMTalonSRX.h is deprecated; include frc/PWMTalonSRX.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PWMTalonSRX.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMVictorSPX.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMVictorSPX.h
new file mode 100644
index 0000000..0fd6a1e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PWMVictorSPX.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PWMVictorSPX.h is deprecated; include frc/PWMVictorSPX.h instead"
+#else
+#warning "PWMVictorSPX.h is deprecated; include frc/PWMVictorSPX.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PWMVictorSPX.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/PowerDistributionPanel.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PowerDistributionPanel.h
new file mode 100644
index 0000000..fa4cae5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/PowerDistributionPanel.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: PowerDistributionPanel.h is deprecated; include frc/PowerDistributionPanel.h instead"
+#else
+#warning "PowerDistributionPanel.h is deprecated; include frc/PowerDistributionPanel.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/PowerDistributionPanel.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Preferences.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Preferences.h
new file mode 100644
index 0000000..3a857f3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Preferences.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Preferences.h is deprecated; include frc/Preferences.h instead"
+#else
+#warning "Preferences.h is deprecated; include frc/Preferences.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Preferences.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Relay.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Relay.h
new file mode 100644
index 0000000..22896fe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Relay.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Relay.h is deprecated; include frc/Relay.h instead"
+#else
+#warning "Relay.h is deprecated; include frc/Relay.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Relay.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Resource.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Resource.h
new file mode 100644
index 0000000..c314eb3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Resource.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Resource.h is deprecated; include frc/Resource.h instead"
+#else
+#warning "Resource.h is deprecated; include frc/Resource.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Resource.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotBase.h
new file mode 100644
index 0000000..f6faa81
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: RobotBase.h is deprecated; include frc/RobotBase.h instead"
+#else
+#warning "RobotBase.h is deprecated; include frc/RobotBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/RobotBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotController.h
new file mode 100644
index 0000000..0cf64b2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotController.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: RobotController.h is deprecated; include frc/RobotController.h instead"
+#else
+#warning "RobotController.h is deprecated; include frc/RobotController.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/RobotController.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotDrive.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotDrive.h
new file mode 100644
index 0000000..7b34cc4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotDrive.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: RobotDrive.h is deprecated; include frc/RobotDrive.h instead"
+#else
+#warning "RobotDrive.h is deprecated; include frc/RobotDrive.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/RobotDrive.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotState.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotState.h
new file mode 100644
index 0000000..329b8ed
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/RobotState.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: RobotState.h is deprecated; include frc/RobotState.h instead"
+#else
+#warning "RobotState.h is deprecated; include frc/RobotState.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/RobotState.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SD540.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SD540.h
new file mode 100644
index 0000000..8518703
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SD540.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SD540.h is deprecated; include frc/SD540.h instead"
+#else
+#warning "SD540.h is deprecated; include frc/SD540.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SD540.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SPI.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SPI.h
new file mode 100644
index 0000000..827a10c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SPI.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SPI.h is deprecated; include frc/SPI.h instead"
+#else
+#warning "SPI.h is deprecated; include frc/SPI.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SPI.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SampleRobot.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SampleRobot.h
new file mode 100644
index 0000000..16ca36a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SampleRobot.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SampleRobot.h is deprecated; include frc/SampleRobot.h instead"
+#else
+#warning "SampleRobot.h is deprecated; include frc/SampleRobot.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SampleRobot.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SensorUtil.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SensorUtil.h
new file mode 100644
index 0000000..8fd7b36
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SensorUtil.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SensorUtil.h is deprecated; include frc/SensorUtil.h instead"
+#else
+#warning "SensorUtil.h is deprecated; include frc/SensorUtil.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SensorUtil.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SerialPort.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SerialPort.h
new file mode 100644
index 0000000..4df02ca
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SerialPort.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SerialPort.h is deprecated; include frc/SerialPort.h instead"
+#else
+#warning "SerialPort.h is deprecated; include frc/SerialPort.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SerialPort.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Servo.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Servo.h
new file mode 100644
index 0000000..99cf2f2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Servo.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Servo.h is deprecated; include frc/Servo.h instead"
+#else
+#warning "Servo.h is deprecated; include frc/Servo.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Servo.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/NamedSendable.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/NamedSendable.h
new file mode 100644
index 0000000..7cbcbe7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/NamedSendable.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SmartDashboard/NamedSendable.h is deprecated; include frc/smartdashboard/NamedSendable.h instead"
+#else
+#warning "SmartDashboard/NamedSendable.h is deprecated; include frc/smartdashboard/NamedSendable.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/NamedSendable.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/Sendable.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/Sendable.h
new file mode 100644
index 0000000..187c1ea
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/Sendable.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: smartdashboard/Sendable.h is deprecated; include frc/smartdashboard/Sendable.h instead"
+#else
+#warning "smartdashboard/Sendable.h is deprecated; include frc/smartdashboard/Sendable.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/Sendable.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBase.h
new file mode 100644
index 0000000..d898040
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: smartdashboard/SendableBase.h is deprecated; include frc/smartdashboard/SendableBase.h instead"
+#else
+#warning "smartdashboard/SendableBase.h is deprecated; include frc/smartdashboard/SendableBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/SendableBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBuilder.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBuilder.h
new file mode 100644
index 0000000..7102c35
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBuilder.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: smartdashboard/SendableBuilder.h is deprecated; include frc/smartdashboard/SendableBuilder.h instead"
+#else
+#warning "smartdashboard/SendableBuilder.h is deprecated; include frc/smartdashboard/SendableBuilder.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/SendableBuilder.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBuilderImpl.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBuilderImpl.h
new file mode 100644
index 0000000..b956309
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableBuilderImpl.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: smartdashboard/SendableBuilderImpl.h is deprecated; include frc/smartdashboard/SendableBuilderImpl.h instead"
+#else
+#warning "smartdashboard/SendableBuilderImpl.h is deprecated; include frc/smartdashboard/SendableBuilderImpl.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/SendableBuilderImpl.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooser.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooser.h
new file mode 100644
index 0000000..5e4683f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooser.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: smartdashboard/SendableChooser.h is deprecated; include frc/smartdashboard/SendableChooser.h instead"
+#else
+#warning "smartdashboard/SendableChooser.h is deprecated; include frc/smartdashboard/SendableChooser.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/SendableChooser.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooser.inc b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooser.inc
new file mode 100644
index 0000000..79e8b16
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooser.inc
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: smartdashboard/SendableChooser.inc is deprecated; include frc/smartdashboard/SendableChooser.inc instead"
+#else
+#warning "smartdashboard/SendableChooser.inc is deprecated; include frc/smartdashboard/SendableChooser.inc instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/SendableChooser.inc"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooserBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooserBase.h
new file mode 100644
index 0000000..436675c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SendableChooserBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: smartdashboard/SendableChooserBase.h is deprecated; include frc/smartdashboard/SendableChooserBase.h instead"
+#else
+#warning "smartdashboard/SendableChooserBase.h is deprecated; include frc/smartdashboard/SendableChooserBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/SendableChooserBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SmartDashboard.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SmartDashboard.h
new file mode 100644
index 0000000..cc7c75f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SmartDashboard/SmartDashboard.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: smartdashboard/SmartDashboard.h is deprecated; include frc/smartdashboard/SmartDashboard.h instead"
+#else
+#warning "smartdashboard/SmartDashboard.h is deprecated; include frc/smartdashboard/SmartDashboard.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/smartdashboard/SmartDashboard.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Solenoid.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Solenoid.h
new file mode 100644
index 0000000..b565188
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Solenoid.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Solenoid.h is deprecated; include frc/Solenoid.h instead"
+#else
+#warning "Solenoid.h is deprecated; include frc/Solenoid.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Solenoid.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SolenoidBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SolenoidBase.h
new file mode 100644
index 0000000..9678200
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SolenoidBase.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SolenoidBase.h is deprecated; include frc/SolenoidBase.h instead"
+#else
+#warning "SolenoidBase.h is deprecated; include frc/SolenoidBase.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SolenoidBase.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Spark.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Spark.h
new file mode 100644
index 0000000..b01c2c9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Spark.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Spark.h is deprecated; include frc/Spark.h instead"
+#else
+#warning "Spark.h is deprecated; include frc/Spark.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Spark.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedController.h
new file mode 100644
index 0000000..27f0c9d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedController.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SpeedController.h is deprecated; include frc/SpeedController.h instead"
+#else
+#warning "SpeedController.h is deprecated; include frc/SpeedController.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SpeedController.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedControllerGroup.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedControllerGroup.h
new file mode 100644
index 0000000..ae387b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedControllerGroup.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SpeedControllerGroup.h is deprecated; include frc/SpeedControllerGroup.h instead"
+#else
+#warning "SpeedControllerGroup.h is deprecated; include frc/SpeedControllerGroup.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SpeedControllerGroup.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedControllerGroup.inc b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedControllerGroup.inc
new file mode 100644
index 0000000..f1f6271
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SpeedControllerGroup.inc
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SpeedControllerGroup.inc is deprecated; include frc/SpeedControllerGroup.inc instead"
+#else
+#warning "SpeedControllerGroup.inc is deprecated; include frc/SpeedControllerGroup.inc instead"
+#endif
+
+// clang-format on
+
+#include "frc/SpeedControllerGroup.inc"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/SynchronousPID.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SynchronousPID.h
new file mode 100644
index 0000000..f2a9c53
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/SynchronousPID.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: SynchronousPID.h is deprecated; include frc/SynchronousPID.h instead"
+#else
+#warning "SynchronousPID.h is deprecated; include frc/SynchronousPID.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/SynchronousPID.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Talon.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Talon.h
new file mode 100644
index 0000000..59c431c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Talon.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Talon.h is deprecated; include frc/Talon.h instead"
+#else
+#warning "Talon.h is deprecated; include frc/Talon.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Talon.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Threads.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Threads.h
new file mode 100644
index 0000000..3a9561f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Threads.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Threads.h is deprecated; include frc/Threads.h instead"
+#else
+#warning "Threads.h is deprecated; include frc/Threads.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Threads.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/TimedRobot.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/TimedRobot.h
new file mode 100644
index 0000000..3c5f393
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/TimedRobot.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: TimedRobot.h is deprecated; include frc/TimedRobot.h instead"
+#else
+#warning "TimedRobot.h is deprecated; include frc/TimedRobot.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/TimedRobot.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Timer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Timer.h
new file mode 100644
index 0000000..2df6097
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Timer.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Timer.h is deprecated; include frc/Timer.h instead"
+#else
+#warning "Timer.h is deprecated; include frc/Timer.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Timer.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Ultrasonic.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Ultrasonic.h
new file mode 100644
index 0000000..8c32ad8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Ultrasonic.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Ultrasonic.h is deprecated; include frc/Ultrasonic.h instead"
+#else
+#warning "Ultrasonic.h is deprecated; include frc/Ultrasonic.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Ultrasonic.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Utility.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Utility.h
new file mode 100644
index 0000000..2294238
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Utility.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Utility.h is deprecated; include frc/Utility.h instead"
+#else
+#warning "Utility.h is deprecated; include frc/Utility.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Utility.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Victor.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Victor.h
new file mode 100644
index 0000000..d17df6d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Victor.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Victor.h is deprecated; include frc/Victor.h instead"
+#else
+#warning "Victor.h is deprecated; include frc/Victor.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Victor.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/VictorSP.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/VictorSP.h
new file mode 100644
index 0000000..a0c8616
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/VictorSP.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: VictorSP.h is deprecated; include frc/VictorSP.h instead"
+#else
+#warning "VictorSP.h is deprecated; include frc/VictorSP.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/VictorSP.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPIErrors.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPIErrors.h
new file mode 100644
index 0000000..6893bce
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPIErrors.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: WPIErrors.h is deprecated; include frc/WPIErrors.h instead"
+#else
+#warning "WPIErrors.h is deprecated; include frc/WPIErrors.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/WPIErrors.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPILib.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPILib.h
new file mode 100644
index 0000000..ab3e608
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPILib.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: WPILib.h is deprecated; include frc/WPILib.h instead"
+#else
+#warning "WPILib.h is deprecated; include frc/WPILib.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/WPILib.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPILibVersion.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPILibVersion.h
new file mode 100644
index 0000000..8aab880
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/WPILibVersion.h
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/*
+ * The corresponding WPILibVersion.cpp file is autogenerated by the build
+ * system. If it does not exist, make sure that you run a build.
+ */
+extern const char* GetWPILibVersion();
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/Watchdog.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Watchdog.h
new file mode 100644
index 0000000..7ba2bf8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/Watchdog.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: Watchdog.h is deprecated; include frc/Watchdog.h instead"
+#else
+#warning "Watchdog.h is deprecated; include frc/Watchdog.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/Watchdog.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/XboxController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/XboxController.h
new file mode 100644
index 0000000..b0abca9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/XboxController.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: XboxController.h is deprecated; include frc/XboxController.h instead"
+#else
+#warning "XboxController.h is deprecated; include frc/XboxController.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/XboxController.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/circular_buffer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/circular_buffer.h
new file mode 100644
index 0000000..a150058
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/circular_buffer.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: circular_buffer.h is deprecated; include frc/circular_buffer.h instead"
+#else
+#warning "circular_buffer.h is deprecated; include frc/circular_buffer.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/circular_buffer.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/circular_buffer.inc b/third_party/allwpilib_2019/wpilibc/src/main/native/include/circular_buffer.inc
new file mode 100644
index 0000000..417286a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/circular_buffer.inc
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: circular_buffer.inc is deprecated; include frc/circular_buffer.inc instead"
+#else
+#warning "circular_buffer.inc is deprecated; include frc/circular_buffer.inc instead"
+#endif
+
+// clang-format on
+
+#include "frc/circular_buffer.inc"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL345_I2C.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
new file mode 100644
index 0000000..5d5fed4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL345_I2C.h
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+#include "frc/I2C.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * ADXL345 Accelerometer on I2C.
+ *
+ * This class allows access to a Analog Devices ADXL345 3-axis accelerometer on
+ * an I2C bus. This class assumes the default (not alternate) sensor address of
+ * 0x1D (7-bit address).
+ */
+class ADXL345_I2C : public ErrorBase,
+                    public SendableBase,
+                    public Accelerometer {
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+  /**
+   * Constructs the ADXL345 Accelerometer over I2C.
+   *
+   * @param port          The I2C port the accelerometer is attached to
+   * @param range         The range (+ or -) that the accelerometer will measure
+   * @param deviceAddress The I2C address of the accelerometer (0x1D or 0x53)
+   */
+  explicit ADXL345_I2C(I2C::Port port, Range range = kRange_2G,
+                       int deviceAddress = kAddress);
+  ~ADXL345_I2C() override = default;
+
+  ADXL345_I2C(ADXL345_I2C&&) = default;
+  ADXL345_I2C& operator=(ADXL345_I2C&&) = default;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL345 in Gs.
+   */
+  virtual double GetAcceleration(Axes axis);
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the
+   *         ADXL345 in Gs.
+   */
+  virtual AllAxes GetAccelerations();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  I2C m_i2c;
+
+  static constexpr int kAddress = 0x1D;
+  static constexpr int kPowerCtlRegister = 0x2D;
+  static constexpr int kDataFormatRegister = 0x31;
+  static constexpr int kDataRegister = 0x32;
+  static constexpr double kGsPerLSB = 0.00390625;
+
+  enum PowerCtlFields {
+    kPowerCtl_Link = 0x20,
+    kPowerCtl_AutoSleep = 0x10,
+    kPowerCtl_Measure = 0x08,
+    kPowerCtl_Sleep = 0x04
+  };
+
+  enum DataFormatFields {
+    kDataFormat_SelfTest = 0x80,
+    kDataFormat_SPI = 0x40,
+    kDataFormat_IntInvert = 0x20,
+    kDataFormat_FullRes = 0x08,
+    kDataFormat_Justify = 0x04
+  };
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL345_SPI.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL345_SPI.h
new file mode 100644
index 0000000..ac5d6d9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL345_SPI.h
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+#include "frc/SPI.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * ADXL345 Accelerometer on SPI.
+ *
+ * This class allows access to an Analog Devices ADXL345 3-axis accelerometer
+ * via SPI. This class assumes the sensor is wired in 4-wire SPI mode.
+ */
+class ADXL345_SPI : public ErrorBase,
+                    public SendableBase,
+                    public Accelerometer {
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+  /**
+   * Constructor.
+   *
+   * @param port  The SPI port the accelerometer is attached to
+   * @param range The range (+ or -) that the accelerometer will measure
+   */
+  explicit ADXL345_SPI(SPI::Port port, Range range = kRange_2G);
+
+  ~ADXL345_SPI() override = default;
+
+  ADXL345_SPI(ADXL345_SPI&&) = default;
+  ADXL345_SPI& operator=(ADXL345_SPI&&) = default;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL345 in Gs.
+   */
+  virtual double GetAcceleration(Axes axis);
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the
+   *         ADXL345 in Gs.
+   */
+  virtual AllAxes GetAccelerations();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  SPI m_spi;
+
+  static constexpr int kPowerCtlRegister = 0x2D;
+  static constexpr int kDataFormatRegister = 0x31;
+  static constexpr int kDataRegister = 0x32;
+  static constexpr double kGsPerLSB = 0.00390625;
+
+  enum SPIAddressFields { kAddress_Read = 0x80, kAddress_MultiByte = 0x40 };
+
+  enum PowerCtlFields {
+    kPowerCtl_Link = 0x20,
+    kPowerCtl_AutoSleep = 0x10,
+    kPowerCtl_Measure = 0x08,
+    kPowerCtl_Sleep = 0x04
+  };
+
+  enum DataFormatFields {
+    kDataFormat_SelfTest = 0x80,
+    kDataFormat_SPI = 0x40,
+    kDataFormat_IntInvert = 0x20,
+    kDataFormat_FullRes = 0x08,
+    kDataFormat_Justify = 0x04
+  };
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL362.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL362.h
new file mode 100644
index 0000000..896af15
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXL362.h
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+#include "frc/SPI.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * ADXL362 SPI Accelerometer.
+ *
+ * This class allows access to an Analog Devices ADXL362 3-axis accelerometer.
+ */
+class ADXL362 : public ErrorBase, public SendableBase, public Accelerometer {
+ public:
+  enum Axes { kAxis_X = 0x00, kAxis_Y = 0x02, kAxis_Z = 0x04 };
+  struct AllAxes {
+    double XAxis;
+    double YAxis;
+    double ZAxis;
+  };
+
+ public:
+  /**
+   * Constructor.  Uses the onboard CS1.
+   *
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  explicit ADXL362(Range range = kRange_2G);
+
+  /**
+   * Constructor.
+   *
+   * @param port  The SPI port the accelerometer is attached to
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  explicit ADXL362(SPI::Port port, Range range = kRange_2G);
+
+  virtual ~ADXL362() = default;
+
+  ADXL362(ADXL362&&) = default;
+  ADXL362& operator=(ADXL362&&) = default;
+
+  // Accelerometer interface
+  void SetRange(Range range) override;
+  double GetX() override;
+  double GetY() override;
+  double GetZ() override;
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL362 in Gs.
+   */
+  virtual double GetAcceleration(Axes axis);
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the
+   *         ADXL362 in Gs.
+   */
+  virtual AllAxes GetAccelerations();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  SPI m_spi;
+  double m_gsPerLSB = 0.001;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h
new file mode 100644
index 0000000..e1b70e2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ADXRS450_Gyro.h
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include "frc/GyroBase.h"
+#include "frc/SPI.h"
+
+namespace frc {
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ *
+ * The Gyro class tracks the robots heading based on the starting position. As
+ * the robot rotates the new heading is computed by integrating the rate of
+ * rotation returned by the sensor. When the class is instantiated, it does a
+ * short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to
+ * determine the heading.
+ *
+ * This class is for the digital ADXRS450 gyro sensor that connects via SPI.
+ */
+class ADXRS450_Gyro : public GyroBase {
+ public:
+  /**
+   * Gyro constructor on onboard CS0.
+   */
+  ADXRS450_Gyro();
+
+  /**
+   * Gyro constructor on the specified SPI port.
+   *
+   * @param port The SPI port the gyro is attached to.
+   */
+  explicit ADXRS450_Gyro(SPI::Port port);
+
+  virtual ~ADXRS450_Gyro() = default;
+
+  ADXRS450_Gyro(ADXRS450_Gyro&&) = default;
+  ADXRS450_Gyro& operator=(ADXRS450_Gyro&&) = default;
+
+  /**
+   * Return the actual angle in degrees that the robot is currently facing.
+   *
+   * The angle is based on the current accumulator value corrected by the
+   * oversampling rate, the gyro type and the A/D calibration values.
+   * The angle is continuous, that is it will continue from 360->361 degrees.
+   * This allows algorithms that wouldn't want to see a discontinuity in the
+   * gyro output as it sweeps from 360 to 0 on the second time around.
+   *
+   * @return the current heading of the robot in degrees. This heading is based
+   *         on integration of the returned rate from the gyro.
+   */
+  double GetAngle() const override;
+
+  /**
+   * Return the rate of rotation of the gyro
+   *
+   * The rate is based on the most recent reading of the gyro analog value
+   *
+   * @return the current rate in degrees per second
+   */
+  double GetRate() const override;
+
+  /**
+   * Reset the gyro.
+   *
+   * Resets the gyro to a heading of zero. This can be used if there is
+   * significant drift in the gyro and it needs to be recalibrated after it has
+   * been running.
+   */
+  void Reset() override;
+
+  /**
+   * Initialize the gyro.
+   *
+   * Calibrate the gyro by running for a number of samples and computing the
+   * center value. Then use the center value as the Accumulator center value for
+   * subsequent measurements.
+   *
+   * It's important to make sure that the robot is not moving while the
+   * centering calculations are in progress, this is typically done when the
+   * robot is first turned on while it's sitting at rest before the competition
+   * starts.
+   */
+  void Calibrate() override;
+
+ private:
+  SPI m_spi;
+
+  uint16_t ReadRegister(int reg);
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h
new file mode 100644
index 0000000..80dc98e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogAccelerometer.h
@@ -0,0 +1,119 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "frc/AnalogInput.h"
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Handle operation of an analog accelerometer.
+ *
+ * The accelerometer reads acceleration directly through the sensor. Many
+ * sensors have multiple axis and can be treated as multiple devices. Each is
+ * calibrated by finding the center value over a period of time.
+ */
+class AnalogAccelerometer : public ErrorBase,
+                            public SendableBase,
+                            public PIDSource {
+ public:
+  /**
+   * Create a new instance of an accelerometer.
+   *
+   * The constructor allocates desired analog input.
+   *
+   * @param channel The channel number for the analog input the accelerometer is
+   *                connected to
+   */
+  explicit AnalogAccelerometer(int channel);
+
+  /**
+   * Create a new instance of Accelerometer from an existing AnalogInput.
+   *
+   * Make a new instance of accelerometer given an AnalogInput. This is
+   * particularly useful if the port is going to be read as an analog channel as
+   * well as through the Accelerometer class.
+   *
+   * @param channel The existing AnalogInput object for the analog input the
+   *                accelerometer is connected to
+   */
+  explicit AnalogAccelerometer(AnalogInput* channel);
+
+  /**
+   * Create a new instance of Accelerometer from an existing AnalogInput.
+   *
+   * Make a new instance of accelerometer given an AnalogInput. This is
+   * particularly useful if the port is going to be read as an analog channel as
+   * well as through the Accelerometer class.
+   *
+   * @param channel The existing AnalogInput object for the analog input the
+   *                accelerometer is connected to
+   */
+  explicit AnalogAccelerometer(std::shared_ptr<AnalogInput> channel);
+
+  ~AnalogAccelerometer() override = default;
+
+  AnalogAccelerometer(AnalogAccelerometer&&) = default;
+  AnalogAccelerometer& operator=(AnalogAccelerometer&&) = default;
+
+  /**
+   * Return the acceleration in Gs.
+   *
+   * The acceleration is returned units of Gs.
+   *
+   * @return The current acceleration of the sensor in Gs.
+   */
+  double GetAcceleration() const;
+
+  /**
+   * Set the accelerometer sensitivity.
+   *
+   * This sets the sensitivity of the accelerometer used for calculating the
+   * acceleration. The sensitivity varies by accelerometer model. There are
+   * constants defined for various models.
+   *
+   * @param sensitivity The sensitivity of accelerometer in Volts per G.
+   */
+  void SetSensitivity(double sensitivity);
+
+  /**
+   * Set the voltage that corresponds to 0 G.
+   *
+   * The zero G voltage varies by accelerometer model. There are constants
+   * defined for various models.
+   *
+   * @param zero The zero G voltage.
+   */
+  void SetZero(double zero);
+
+  /**
+   * Get the Acceleration for the PID Source parent.
+   *
+   * @return The current acceleration in Gs.
+   */
+  double PIDGet() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  /**
+   * Common function for initializing the accelerometer.
+   */
+  void InitAccelerometer();
+
+  std::shared_ptr<AnalogInput> m_analogInput;
+  double m_voltsPerG = 1.0;
+  double m_zeroGVoltage = 2.5;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogGyro.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogGyro.h
new file mode 100644
index 0000000..9e18d89
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogGyro.h
@@ -0,0 +1,194 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/GyroBase.h"
+
+namespace frc {
+
+class AnalogInput;
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position.
+ * The Gyro class tracks the robots heading based on the starting position. As
+ * the robot rotates the new heading is computed by integrating the rate of
+ * rotation returned by the sensor. When the class is instantiated, it does a
+ * short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to
+ * determine the heading. This gyro class must be used with a channel that is
+ * assigned one of the Analog accumulators from the FPGA. See AnalogInput for
+ * the current accumulator assignments.
+ *
+ * This class is for gyro sensors that connect to an analog input.
+ */
+class AnalogGyro : public GyroBase {
+ public:
+  static constexpr int kOversampleBits = 10;
+  static constexpr int kAverageBits = 0;
+  static constexpr double kSamplesPerSecond = 50.0;
+  static constexpr double kCalibrationSampleTime = 5.0;
+  static constexpr double kDefaultVoltsPerDegreePerSecond = 0.007;
+
+  /**
+   * Gyro constructor using the Analog Input channel number.
+   *
+   * @param channel The analog channel the gyro is connected to. Gyros can only
+   *                be used on on-board Analog Inputs 0-1.
+   */
+  explicit AnalogGyro(int channel);
+
+  /**
+   * Gyro constructor with a precreated AnalogInput object.
+   *
+   * Use this constructor when the analog channel needs to be shared.
+   * This object will not clean up the AnalogInput object when using this
+   * constructor.
+   *
+   * Gyros can only be used on on-board channels 0-1.
+   *
+   * @param channel A pointer to the AnalogInput object that the gyro is
+   *                connected to.
+   */
+  explicit AnalogGyro(AnalogInput* channel);
+
+  /**
+   * Gyro constructor with a precreated AnalogInput object.
+   *
+   * Use this constructor when the analog channel needs to be shared.
+   * This object will not clean up the AnalogInput object when using this
+   * constructor.
+   *
+   * @param channel A pointer to the AnalogInput object that the gyro is
+   *                connected to.
+   */
+  explicit AnalogGyro(std::shared_ptr<AnalogInput> channel);
+
+  /**
+   * Gyro constructor using the Analog Input channel number with parameters for
+   * presetting the center and offset values. Bypasses calibration.
+   *
+   * @param channel The analog channel the gyro is connected to. Gyros can only
+   *                be used on on-board Analog Inputs 0-1.
+   * @param center  Preset uncalibrated value to use as the accumulator center
+   *                value.
+   * @param offset  Preset uncalibrated value to use as the gyro offset.
+   */
+  AnalogGyro(int channel, int center, double offset);
+
+  /**
+   * Gyro constructor with a precreated AnalogInput object and calibrated
+   * parameters.
+   *
+   * Use this constructor when the analog channel needs to be shared.
+   * This object will not clean up the AnalogInput object when using this
+   * constructor.
+   *
+   * @param channel A pointer to the AnalogInput object that the gyro is
+   *                connected to.
+   * @param center  Preset uncalibrated value to use as the accumulator center
+   *                value.
+   * @param offset  Preset uncalibrated value to use as the gyro offset.
+   */
+  AnalogGyro(std::shared_ptr<AnalogInput> channel, int center, double offset);
+
+  virtual ~AnalogGyro();
+
+  AnalogGyro(AnalogGyro&& rhs);
+  AnalogGyro& operator=(AnalogGyro&& rhs);
+
+  /**
+   * Return the actual angle in degrees that the robot is currently facing.
+   *
+   * The angle is based on the current accumulator value corrected by the
+   * oversampling rate, the gyro type and the A/D calibration values. The angle
+   * is continuous, that is it will continue from 360->361 degrees. This allows
+   * algorithms that wouldn't want to see a discontinuity in the gyro output as
+   * it sweeps from 360 to 0 on the second time around.
+   *
+   * @return The current heading of the robot in degrees. This heading is based
+   *         on integration of the returned rate from the gyro.
+   */
+  double GetAngle() const override;
+
+  /**
+   * Return the rate of rotation of the gyro
+   *
+   * The rate is based on the most recent reading of the gyro analog value
+   *
+   * @return the current rate in degrees per second
+   */
+  double GetRate() const override;
+
+  /**
+   * Return the gyro center value. If run after calibration,
+   * the center value can be used as a preset later.
+   *
+   * @return the current center value
+   */
+  virtual int GetCenter() const;
+
+  /**
+   * Return the gyro offset value. If run after calibration,
+   * the offset value can be used as a preset later.
+   *
+   * @return the current offset value
+   */
+  virtual double GetOffset() const;
+
+  /**
+   * Set the gyro sensitivity.
+   *
+   * This takes the number of volts/degree/second sensitivity of the gyro and
+   * uses it in subsequent calculations to allow the code to work with multiple
+   * gyros. This value is typically found in the gyro datasheet.
+   *
+   * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second
+   */
+  void SetSensitivity(double voltsPerDegreePerSecond);
+
+  /**
+   * Set the size of the neutral zone.
+   *
+   * Any voltage from the gyro less than this amount from the center is
+   * considered stationary.  Setting a deadband will decrease the amount of
+   * drift when the gyro isn't rotating, but will make it less accurate.
+   *
+   * @param volts The size of the deadband in volts
+   */
+  void SetDeadband(double volts);
+
+  /**
+   * Reset the gyro.
+   *
+   * Resets the gyro to a heading of zero. This can be used if there is
+   * significant drift in the gyro and it needs to be recalibrated after it has
+   * been running.
+   */
+  void Reset() override;
+
+  /**
+   * Initialize the gyro.
+   *
+   * Calibration is handled by Calibrate().
+   */
+  virtual void InitGyro();
+
+  void Calibrate() override;
+
+ protected:
+  std::shared_ptr<AnalogInput> m_analog;
+
+ private:
+  HAL_GyroHandle m_gyroHandle = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogInput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogInput.h
new file mode 100644
index 0000000..97ce2a8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogInput.h
@@ -0,0 +1,291 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Analog input class.
+ *
+ * Connected to each analog channel is an averaging and oversampling engine.
+ * This engine accumulates the specified ( by SetAverageBits() and
+ * SetOversampleBits() ) number of samples before returning a new value. This is
+ * not a sliding window average. The only difference between the oversampled
+ * samples and the averaged samples is that the oversampled samples are simply
+ * accumulated effectively increasing the resolution, while the averaged samples
+ * are divided by the number of samples to retain the resolution, but get more
+ * stable values.
+ */
+class AnalogInput : public ErrorBase, public SendableBase, public PIDSource {
+  friend class AnalogTrigger;
+  friend class AnalogGyro;
+
+ public:
+  static constexpr int kAccumulatorModuleNumber = 1;
+  static constexpr int kAccumulatorNumChannels = 2;
+  static constexpr int kAccumulatorChannels[kAccumulatorNumChannels] = {0, 1};
+
+  /**
+   * Construct an analog input.
+   *
+   * @param channel The channel number on the roboRIO to represent. 0-3 are
+   *                on-board 4-7 are on the MXP port.
+   */
+  explicit AnalogInput(int channel);
+
+  ~AnalogInput() override;
+
+  AnalogInput(AnalogInput&& rhs);
+  AnalogInput& operator=(AnalogInput&& rhs);
+
+  /**
+   * Get a sample straight from this channel.
+   *
+   * The sample is a 12-bit value representing the 0V to 5V range of the A/D
+   * converter in the module.  The units are in A/D converter codes.  Use
+   * GetVoltage() to get the analog value in calibrated units.
+   *
+   * @return A sample straight from this channel.
+   */
+  int GetValue() const;
+
+  /**
+   * Get a sample from the output of the oversample and average engine for this
+   * channel.
+   *
+   * The sample is 12-bit + the bits configured in SetOversampleBits().
+   * The value configured in SetAverageBits() will cause this value to be
+   * averaged 2**bits number of samples.
+   *
+   * This is not a sliding window. The sample will not change until
+   * 2**(OversampleBits + AverageBits) samples have been acquired from the
+   * module on this channel.
+   *
+   * Use GetAverageVoltage() to get the analog value in calibrated units.
+   *
+   * @return A sample from the oversample and average engine for this channel.
+   */
+  int GetAverageValue() const;
+
+  /**
+   * Get a scaled sample straight from this channel.
+   *
+   * The value is scaled to units of Volts using the calibrated scaling data
+   * from GetLSBWeight() and GetOffset().
+   *
+   * @return A scaled sample straight from this channel.
+   */
+  double GetVoltage() const;
+
+  /**
+   * Get a scaled sample from the output of the oversample and average engine
+   * for this channel.
+   *
+   * The value is scaled to units of Volts using the calibrated scaling data
+   * from GetLSBWeight() and GetOffset().
+   *
+   * Using oversampling will cause this value to be higher resolution, but it
+   * will update more slowly.
+   *
+   * Using averaging will cause this value to be more stable, but it will update
+   * more slowly.
+   *
+   * @return A scaled sample from the output of the oversample and average
+   * engine for this channel.
+   */
+  double GetAverageVoltage() const;
+
+  /**
+   * Get the channel number.
+   *
+   * @return The channel number.
+   */
+  int GetChannel() const;
+
+  /**
+   * Set the number of averaging bits.
+   *
+   * This sets the number of averaging bits. The actual number of averaged
+   * samples is 2^bits.
+   *
+   * Use averaging to improve the stability of your measurement at the expense
+   * of sampling rate. The averaging is done automatically in the FPGA.
+   *
+   * @param bits Number of bits of averaging.
+   */
+  void SetAverageBits(int bits);
+
+  /**
+   * Get the number of averaging bits previously configured.
+   *
+   * This gets the number of averaging bits from the FPGA. The actual number of
+   * averaged samples is 2^bits. The averaging is done automatically in the
+   * FPGA.
+   *
+   * @return Number of bits of averaging previously configured.
+   */
+  int GetAverageBits() const;
+
+  /**
+   * Set the number of oversample bits.
+   *
+   * This sets the number of oversample bits. The actual number of oversampled
+   * values is 2^bits. Use oversampling to improve the resolution of your
+   * measurements at the expense of sampling rate. The oversampling is done
+   * automatically in the FPGA.
+   *
+   * @param bits Number of bits of oversampling.
+   */
+  void SetOversampleBits(int bits);
+
+  /**
+   * Get the number of oversample bits previously configured.
+   *
+   * This gets the number of oversample bits from the FPGA. The actual number of
+   * oversampled values is 2^bits. The oversampling is done automatically in the
+   * FPGA.
+   *
+   * @return Number of bits of oversampling previously configured.
+   */
+  int GetOversampleBits() const;
+
+  /**
+   * Get the factory scaling least significant bit weight constant.
+   *
+   * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+   *
+   * @return Least significant bit weight.
+   */
+  int GetLSBWeight() const;
+
+  /**
+   * Get the factory scaling offset constant.
+   *
+   * Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+   *
+   * @return Offset constant.
+   */
+  int GetOffset() const;
+
+  /**
+   * Is the channel attached to an accumulator.
+   *
+   * @return The analog input is attached to an accumulator.
+   */
+  bool IsAccumulatorChannel() const;
+
+  /**
+   * Initialize the accumulator.
+   */
+  void InitAccumulator();
+
+  /**
+   * Set an initial value for the accumulator.
+   *
+   * This will be added to all values returned to the user.
+   *
+   * @param initialValue The value that the accumulator should start from when
+   *                     reset.
+   */
+  void SetAccumulatorInitialValue(int64_t value);
+
+  /**
+   * Resets the accumulator to the initial value.
+   */
+  void ResetAccumulator();
+
+  /**
+   * Set the center value of the accumulator.
+   *
+   * The center value is subtracted from each A/D value before it is added to
+   * the accumulator. This is used for the center value of devices like gyros
+   * and accelerometers to take the device offset into account when integrating.
+   *
+   * This center value is based on the output of the oversampled and averaged
+   * source from the accumulator channel. Because of this, any non-zero
+   * oversample bits will affect the size of the value for this field.
+   */
+  void SetAccumulatorCenter(int center);
+
+  /**
+   * Set the accumulator's deadband.
+   */
+  void SetAccumulatorDeadband(int deadband);
+
+  /**
+   * Read the accumulated value.
+   *
+   * Read the value that has been accumulating.
+   * The accumulator is attached after the oversample and average engine.
+   *
+   * @return The 64-bit value accumulated since the last Reset().
+   */
+  int64_t GetAccumulatorValue() const;
+
+  /**
+   * Read the number of accumulated values.
+   *
+   * Read the count of the accumulated values since the accumulator was last
+   * Reset().
+   *
+   * @return The number of times samples from the channel were accumulated.
+   */
+  int64_t GetAccumulatorCount() const;
+
+  /**
+   * Read the accumulated value and the number of accumulated values atomically.
+   *
+   * This function reads the value and count from the FPGA atomically.
+   * This can be used for averaging.
+   *
+   * @param value Reference to the 64-bit accumulated output.
+   * @param count Reference to the number of accumulation cycles.
+   */
+  void GetAccumulatorOutput(int64_t& value, int64_t& count) const;
+
+  /**
+   * Set the sample rate per channel for all analog channels.
+   *
+   * The maximum rate is 500kS/s divided by the number of channels in use.
+   * This is 62500 samples/s per channel.
+   *
+   * @param samplesPerSecond The number of samples per second.
+   */
+  static void SetSampleRate(double samplesPerSecond);
+
+  /**
+   * Get the current sample rate for all channels
+   *
+   * @return Sample rate.
+   */
+  static double GetSampleRate();
+
+  /**
+   * Get the Average value for the PID Source base object.
+   *
+   * @return The average voltage.
+   */
+  double PIDGet() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  HAL_AnalogInputHandle m_port = HAL_kInvalidHandle;
+  int64_t m_accumulatorOffset;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogOutput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogOutput.h
new file mode 100644
index 0000000..3c7b44e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogOutput.h
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * MXP analog output class.
+ */
+class AnalogOutput : public ErrorBase, public SendableBase {
+ public:
+  /**
+   * Construct an analog output on the given channel.
+   *
+   * All analog outputs are located on the MXP port.
+   *
+   * @param channel The channel number on the roboRIO to represent.
+   */
+  explicit AnalogOutput(int channel);
+
+  ~AnalogOutput() override;
+
+  AnalogOutput(AnalogOutput&& rhs);
+  AnalogOutput& operator=(AnalogOutput&& rhs);
+
+  /**
+   * Set the value of the analog output.
+   *
+   * @param voltage The output value in Volts, from 0.0 to +5.0
+   */
+  void SetVoltage(double voltage);
+
+  /**
+   * Get the voltage of the analog output
+   *
+   * @return The value in Volts, from 0.0 to +5.0
+   */
+  double GetVoltage() const;
+
+  /**
+   * Get the channel of this AnalogOutput.
+   */
+  int GetChannel();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  int m_channel;
+  HAL_AnalogOutputHandle m_port = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h
new file mode 100644
index 0000000..a937c69
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogPotentiometer.h
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "frc/AnalogInput.h"
+#include "frc/ErrorBase.h"
+#include "frc/interfaces/Potentiometer.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Class for reading analog potentiometers. Analog potentiometers read in an
+ * analog voltage that corresponds to a position. The position is in whichever
+ * units you choose, by way of the scaling and offset constants passed to the
+ * constructor.
+ */
+class AnalogPotentiometer : public ErrorBase,
+                            public SendableBase,
+                            public Potentiometer {
+ public:
+  /**
+   * Construct an Analog Potentiometer object from a channel number.
+   *
+   * Use the fullRange and offset values so that the output produces meaningful
+   * values. I.E: you have a 270 degree potentiometer and you want the output to
+   * be degrees with the halfway point as 0 degrees. The fullRange value is
+   * 270.0 degrees and the offset is -135.0 since the halfway point after
+   * scaling is 135 degrees.
+   *
+   * This will calculate the result from the fullRange times the fraction of the
+   * supply voltage, plus the offset.
+   *
+   * @param channel   The channel number on the roboRIO to represent. 0-3 are
+   *                  on-board 4-7 are on the MXP port.
+   * @param fullRange The angular value (in desired units) representing the full
+   *                  0-5V range of the input.
+   * @param offset    The angular value (in desired units) representing the
+   *                  angular output at 0V.
+   */
+  explicit AnalogPotentiometer(int channel, double fullRange = 1.0,
+                               double offset = 0.0);
+
+  /**
+   * Construct an Analog Potentiometer object from an existing Analog Input
+   * pointer.
+   *
+   * Use the fullRange and offset values so that the output produces meaningful
+   * values. I.E: you have a 270 degree potentiometer and you want the output to
+   * be degrees with the halfway point as 0 degrees. The fullRange value is
+   * 270.0 degrees and the offset is -135.0 since the halfway point after
+   * scaling is 135 degrees.
+   *
+   * This will calculate the result from the fullRange times the fraction of the
+   * supply voltage, plus the offset.
+   *
+   * @param channel   The existing Analog Input pointer
+   * @param fullRange The angular value (in desired units) representing the full
+   *                  0-5V range of the input.
+   * @param offset    The angular value (in desired units) representing the
+   *                  angular output at 0V.
+   */
+  explicit AnalogPotentiometer(AnalogInput* input, double fullRange = 1.0,
+                               double offset = 0.0);
+
+  /**
+   * Construct an Analog Potentiometer object from an existing Analog Input
+   * pointer.
+   *
+   * Use the fullRange and offset values so that the output produces meaningful
+   * values. I.E: you have a 270 degree potentiometer and you want the output to
+   * be degrees with the halfway point as 0 degrees. The fullRange value is
+   * 270.0 degrees and the offset is -135.0 since the halfway point after
+   * scaling is 135 degrees.
+   *
+   * This will calculate the result from the fullRange times the fraction of the
+   * supply voltage, plus the offset.
+   *
+   * @param channel   The existing Analog Input pointer
+   * @param fullRange The angular value (in desired units) representing the full
+   *                  0-5V range of the input.
+   * @param offset    The angular value (in desired units) representing the
+   *                  angular output at 0V.
+   */
+  explicit AnalogPotentiometer(std::shared_ptr<AnalogInput> input,
+                               double fullRange = 1.0, double offset = 0.0);
+
+  ~AnalogPotentiometer() override = default;
+
+  AnalogPotentiometer(AnalogPotentiometer&&) = default;
+  AnalogPotentiometer& operator=(AnalogPotentiometer&&) = default;
+
+  /**
+   * Get the current reading of the potentiomer.
+   *
+   * @return The current position of the potentiometer (in the units used for
+   *         fullRange and offset).
+   */
+  double Get() const override;
+
+  /**
+   * Implement the PIDSource interface.
+   *
+   * @return The current reading.
+   */
+  double PIDGet() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  std::shared_ptr<AnalogInput> m_analog_input;
+  double m_fullRange, m_offset;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTrigger.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTrigger.h
new file mode 100644
index 0000000..beb48fc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTrigger.h
@@ -0,0 +1,144 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/AnalogTriggerOutput.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class AnalogInput;
+
+class AnalogTrigger : public ErrorBase, public SendableBase {
+  friend class AnalogTriggerOutput;
+
+ public:
+  /**
+   * Constructor for an analog trigger given a channel number.
+   *
+   * @param channel The channel number on the roboRIO to represent. 0-3 are
+   *                on-board 4-7 are on the MXP port.
+   */
+  explicit AnalogTrigger(int channel);
+
+  /**
+   * Construct an analog trigger given an analog input.
+   *
+   * This should be used in the case of sharing an analog channel between the
+   * trigger and an analog input object.
+   *
+   * @param channel The pointer to the existing AnalogInput object
+   */
+  explicit AnalogTrigger(AnalogInput* channel);
+
+  ~AnalogTrigger() override;
+
+  AnalogTrigger(AnalogTrigger&& rhs);
+  AnalogTrigger& operator=(AnalogTrigger&& rhs);
+
+  /**
+   * Set the upper and lower limits of the analog trigger.
+   *
+   * The limits are given as floating point voltage values.
+   *
+   * @param lower The lower limit of the trigger in Volts.
+   * @param upper The upper limit of the trigger in Volts.
+   */
+  void SetLimitsVoltage(double lower, double upper);
+
+  /**
+   * Set the upper and lower limits of the analog trigger.
+   *
+   * The limits are given in ADC codes.  If oversampling is used, the units must
+   * be scaled appropriately.
+   *
+   * @param lower The lower limit of the trigger in ADC codes (12-bit values).
+   * @param upper The upper limit of the trigger in ADC codes (12-bit values).
+   */
+  void SetLimitsRaw(int lower, int upper);
+
+  /**
+   * Configure the analog trigger to use the averaged vs. raw values.
+   *
+   * If the value is true, then the averaged value is selected for the analog
+   * trigger, otherwise the immediate value is used.
+   *
+   * @param useAveragedValue If true, use the Averaged value, otherwise use the
+   *                         instantaneous reading
+   */
+  void SetAveraged(bool useAveragedValue);
+
+  /**
+   * Configure the analog trigger to use a filtered value.
+   *
+   * The analog trigger will operate with a 3 point average rejection filter.
+   * This is designed to help with 360 degree pot applications for the period
+   * where the pot crosses through zero.
+   *
+   * @param useFilteredValue If true, use the 3 point rejection filter,
+   *                         otherwise use the unfiltered value
+   */
+  void SetFiltered(bool useFilteredValue);
+
+  /**
+   * Return the index of the analog trigger.
+   *
+   * This is the FPGA index of this analog trigger instance.
+   *
+   * @return The index of the analog trigger.
+   */
+  int GetIndex() const;
+
+  /**
+   * Return the InWindow output of the analog trigger.
+   *
+   * True if the analog input is between the upper and lower limits.
+   *
+   * @return True if the analog input is between the upper and lower limits.
+   */
+  bool GetInWindow();
+
+  /**
+   * Return the TriggerState output of the analog trigger.
+   *
+   * True if above upper limit.
+   * False if below lower limit.
+   * If in Hysteresis, maintain previous state.
+   *
+   * @return True if above upper limit. False if below lower limit. If in
+   *         Hysteresis, maintain previous state.
+   */
+  bool GetTriggerState();
+
+  /**
+   * Creates an AnalogTriggerOutput object.
+   *
+   * Gets an output object that can be used for routing. Caller is responsible
+   * for deleting the AnalogTriggerOutput object.
+   *
+   * @param type An enum of the type of output object to create.
+   * @return A pointer to a new AnalogTriggerOutput object.
+   */
+  std::shared_ptr<AnalogTriggerOutput> CreateOutput(
+      AnalogTriggerType type) const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_index;
+  HAL_AnalogTriggerHandle m_trigger = HAL_kInvalidHandle;
+  AnalogInput* m_analogInput = nullptr;
+  bool m_ownsAnalog = false;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h
new file mode 100644
index 0000000..fc3d8f2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTriggerOutput.h
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/DigitalSource.h"
+
+namespace frc {
+
+class AnalogTrigger;
+
+/**
+ * Class to represent a specific output from an analog trigger.
+ *
+ * This class is used to get the current output value and also as a
+ * DigitalSource to provide routing of an output to digital subsystems on the
+ * FPGA such as Counter, Encoder, and Interrupt.
+ *
+ * The TriggerState output indicates the primary output value of the trigger.
+ * If the analog signal is less than the lower limit, the output is false. If
+ * the analog value is greater than the upper limit, then the output is true.
+ * If the analog value is in between, then the trigger output state maintains
+ * its most recent value.
+ *
+ * The InWindow output indicates whether or not the analog signal is inside the
+ * range defined by the limits.
+ *
+ * The RisingPulse and FallingPulse outputs detect an instantaneous transition
+ * from above the upper limit to below the lower limit, and vise versa. These
+ * pulses represent a rollover condition of a sensor and can be routed to an up
+ * / down counter or to interrupts. Because the outputs generate a pulse, they
+ * cannot be read directly. To help ensure that a rollover condition is not
+ * missed, there is an average rejection filter available that operates on the
+ * upper 8 bits of a 12 bit number and selects the nearest outlyer of 3 samples.
+ * This will reject a sample that is (due to averaging or sampling) errantly
+ * between the two limits. This filter will fail if more than one sample in a
+ * row is errantly in between the two limits. You may see this problem if
+ * attempting to use this feature with a mechanical rollover sensor, such as a
+ * 360 degree no-stop potentiometer without signal conditioning, because the
+ * rollover transition is not sharp / clean enough. Using the averaging engine
+ * may help with this, but rotational speeds of the sensor will then be limited.
+ */
+class AnalogTriggerOutput : public DigitalSource {
+  friend class AnalogTrigger;
+
+ public:
+  ~AnalogTriggerOutput() override;
+
+  AnalogTriggerOutput(AnalogTriggerOutput&&) = default;
+  AnalogTriggerOutput& operator=(AnalogTriggerOutput&&) = default;
+
+  /**
+   * Get the state of the analog trigger output.
+   *
+   * @return The state of the analog trigger output.
+   */
+  bool Get() const;
+
+  // DigitalSource interface
+  /**
+   * @return The HAL Handle to the specified source.
+   */
+  HAL_Handle GetPortHandleForRouting() const override;
+
+  /**
+   * @return The type of analog trigger output to be used.
+   */
+  AnalogTriggerType GetAnalogTriggerTypeForRouting() const override;
+
+  /**
+   * Is source an AnalogTrigger
+   */
+  bool IsAnalogTrigger() const override;
+
+  /**
+   * @return The channel of the source.
+   */
+  int GetChannel() const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  /**
+   * Create an object that represents one of the four outputs from an analog
+   * trigger.
+   *
+   * Because this class derives from DigitalSource, it can be passed into
+   * routing functions for Counter, Encoder, etc.
+   *
+   * @param trigger    A pointer to the trigger for which this is an output.
+   * @param outputType An enum that specifies the output on the trigger to
+   *                   represent.
+   */
+  AnalogTriggerOutput(const AnalogTrigger& trigger,
+                      AnalogTriggerType outputType);
+
+ private:
+  // Uses reference rather than smart pointer because a user can not construct
+  // an AnalogTriggerOutput themselves and because the AnalogTriggerOutput
+  // should always be in scope at the same time as an AnalogTrigger.
+  const AnalogTrigger& m_trigger;
+  AnalogTriggerType m_outputType;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTriggerType.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTriggerType.h
new file mode 100644
index 0000000..f15fb03
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/AnalogTriggerType.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+enum class AnalogTriggerType {
+  kInWindow = 0,
+  kState = 1,
+  kRisingPulse = 2,
+  kFallingPulse = 3
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Base.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Base.h
new file mode 100644
index 0000000..1fdbe5d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Base.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#if !defined(__clang__) && defined(__GNUC__) && __GNUC__ < 5
+static_assert(0,
+              "GCC must be 5 or greater. If building for the roboRIO, please "
+              "update to the 2018 toolchains.");
+#endif
+
+#if defined(_MSC_VER) && _MSC_VER < 1900
+static_assert(0, "Visual Studio 2015 or greater required.");
+#endif
+
+/** WPILib FRC namespace */
+namespace frc {
+
+// A struct to use as a deleter when a std::shared_ptr must wrap a raw pointer
+// that is being deleted by someone else.
+template <class T>
+struct NullDeleter {
+  void operator()(T*) const noexcept {};
+};
+
+}  // namespace frc
+
+// For backwards compatibility
+#ifdef NO_NAMESPACED_WPILIB
+using namespace frc;  // NOLINT
+#endif
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h
new file mode 100644
index 0000000..3c9fc4a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/BuiltInAccelerometer.h
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Built-in accelerometer.
+ *
+ * This class allows access to the roboRIO's internal accelerometer.
+ */
+class BuiltInAccelerometer : public ErrorBase,
+                             public SendableBase,
+                             public Accelerometer {
+ public:
+  /**
+   * Constructor.
+   *
+   * @param range The range the accelerometer will measure
+   */
+  explicit BuiltInAccelerometer(Range range = kRange_8G);
+
+  BuiltInAccelerometer(BuiltInAccelerometer&&) = default;
+  BuiltInAccelerometer& operator=(BuiltInAccelerometer&&) = default;
+
+  // Accelerometer interface
+  /**
+   * Set the measuring range of the accelerometer.
+   *
+   * @param range The maximum acceleration, positive or negative, that the
+   *              accelerometer will measure. Not all accelerometers support all
+   *              ranges.
+   */
+  void SetRange(Range range) override;
+
+  /**
+   * @return The acceleration of the roboRIO along the X axis in g-forces
+   */
+  double GetX() override;
+
+  /**
+   * @return The acceleration of the roboRIO along the Y axis in g-forces
+   */
+  double GetY() override;
+
+  /**
+   * @return The acceleration of the roboRIO along the Z axis in g-forces
+   */
+  double GetZ() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/CAN.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/CAN.h
new file mode 100644
index 0000000..4cd06e9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/CAN.h
@@ -0,0 +1,149 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/CANAPITypes.h>
+#include <wpi/ArrayRef.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+struct CANData {
+  uint8_t data[8];
+  int32_t length;
+  uint64_t timestamp;
+};
+
+/**
+ * High level class for interfacing with CAN devices conforming to
+ * the standard CAN spec.
+ *
+ * No packets that can be sent gets blocked by the RoboRIO, so all methods
+ * work identically in all robot modes.
+ *
+ * All methods are thread save, however the buffer objects passed in
+ * by the user need to not be modified for the duration of their calls.
+ */
+class CAN : public ErrorBase {
+ public:
+  /**
+   * Create a new CAN communication interface with the specific device ID.
+   * This uses the team manufacturer and device types.
+   * The device ID is 6 bits (0-63)
+   *
+   * @param deviceId The device id
+   */
+  explicit CAN(int deviceId);
+
+  /**
+   * Create a new CAN communication interface with a specific device ID,
+   * manufacturer and device type. The device ID is 6 bits, the
+   * manufacturer is 8 bits, and the device type is 5 bits.
+   *
+   * @param deviceId           The device ID
+   * @param deviceManufacturer The device manufacturer
+   * @param deviceType         The device type
+   */
+  CAN(int deviceId, int deviceManufacturer, int deviceType);
+
+  /**
+   * Closes the CAN communication.
+   */
+  ~CAN() override;
+
+  CAN(CAN&& rhs);
+  CAN& operator=(CAN&& rhs);
+
+  /**
+   * Write a packet to the CAN device with a specific ID. This ID is 10 bits.
+   *
+   * @param data The data to write (8 bytes max)
+   * @param length The data length to write
+   * @param apiId The API ID to write.
+   */
+  void WritePacket(const uint8_t* data, int length, int apiId);
+
+  /**
+   * Write a repeating packet to the CAN device with a specific ID. This ID is
+   * 10 bits. The RoboRIO will automatically repeat the packet at the specified
+   * interval
+   *
+   * @param data The data to write (8 bytes max)
+   * @param length The data length to write
+   * @param apiId The API ID to write.
+   * @param repeatMs The period to repeat the packet at.
+   */
+  void WritePacketRepeating(const uint8_t* data, int length, int apiId,
+                            int repeatMs);
+
+  /**
+   * Stop a repeating packet with a specific ID. This ID is 10 bits.
+   *
+   * @param apiId The API ID to stop repeating
+   */
+  void StopPacketRepeating(int apiId);
+
+  /**
+   * Read a new CAN packet. This will only return properly once per packet
+   * received. Multiple calls without receiving another packet will return
+   * false.
+   *
+   * @param apiId The API ID to read.
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  bool ReadPacketNew(int apiId, CANData* data);
+
+  /**
+   * Read a CAN packet. The will continuously return the last packet received,
+   * without accounting for packet age.
+   *
+   * @param apiId The API ID to read.
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  bool ReadPacketLatest(int apiId, CANData* data);
+
+  /**
+   * Read a CAN packet. The will return the last packet received until the
+   * packet is older then the requested timeout. Then it will return false.
+   *
+   * @param apiId The API ID to read.
+   * @param timeoutMs The timeout time for the packet
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  bool ReadPacketTimeout(int apiId, int timeoutMs, CANData* data);
+
+  /**
+   * Read a CAN packet. The will return the last packet received until the
+   * packet is older then the requested timeout. Then it will return false. The
+   * period parameter is used when you know the packet is sent at specific
+   * intervals, so calls will not attempt to read a new packet from the network
+   * until that period has passed. We do not recommend users use this API unless
+   * they know the implications.
+   *
+   * @param apiId The API ID to read.
+   * @param timeoutMs The timeout time for the packet
+   * @param periodMs The usual period for the packet
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  bool ReadPeriodicPacket(int apiId, int timeoutMs, int periodMs,
+                          CANData* data);
+
+  static constexpr HAL_CANManufacturer kTeamManufacturer = HAL_CAN_Man_kTeamUse;
+  static constexpr HAL_CANDeviceType kTeamDeviceType =
+      HAL_CAN_Dev_kMiscellaneous;
+
+ private:
+  HAL_CANHandle m_handle = HAL_kInvalidHandle;
+};
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Compressor.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Compressor.h
new file mode 100644
index 0000000..97f64d1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Compressor.h
@@ -0,0 +1,179 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/SensorUtil.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Class for operating a compressor connected to a %PCM (Pneumatic Control
+ * Module).
+ *
+ * The PCM will automatically run in closed loop mode by default whenever a
+ * Solenoid object is created. For most cases, a Compressor object does not need
+ * to be instantiated or used in a robot program. This class is only required in
+ * cases where the robot program needs a more detailed status of the compressor
+ * or to enable/disable closed loop control.
+ *
+ * Note: you cannot operate the compressor directly from this class as doing so
+ * would circumvent the safety provided by using the pressure switch and closed
+ * loop control. You can only turn off closed loop control, thereby stopping
+ * the compressor from operating.
+ */
+class Compressor : public ErrorBase, public SendableBase {
+ public:
+  /**
+   * Constructor. The default PCM ID is 0.
+   *
+   * @param module The PCM ID to use (0-62)
+   */
+  explicit Compressor(int pcmID = SensorUtil::GetDefaultSolenoidModule());
+
+  ~Compressor() override = default;
+
+  Compressor(Compressor&&) = default;
+  Compressor& operator=(Compressor&&) = default;
+
+  /**
+   * Starts closed-loop control. Note that closed loop control is enabled by
+   * default.
+   */
+  void Start();
+
+  /**
+   * Stops closed-loop control. Note that closed loop control is enabled by
+   * default.
+   */
+  void Stop();
+
+  /**
+   * Check if compressor output is active.
+   *
+   * @return true if the compressor is on
+   */
+  bool Enabled() const;
+
+  /**
+   * Check if the pressure switch is triggered.
+   *
+   * @return true if pressure is low
+   */
+  bool GetPressureSwitchValue() const;
+
+  /**
+   * Query how much current the compressor is drawing.
+   *
+   * @return The current through the compressor, in amps
+   */
+  double GetCompressorCurrent() const;
+
+  /**
+   * Enables or disables automatically turning the compressor on when the
+   * pressure is low.
+   *
+   * @param on Set to true to enable closed loop control of the compressor.
+   *           False to disable.
+   */
+  void SetClosedLoopControl(bool on);
+
+  /**
+   * Returns true if the compressor will automatically turn on when the
+   * pressure is low.
+   *
+   * @return True if closed loop control of the compressor is enabled. False if
+   *         disabled.
+   */
+  bool GetClosedLoopControl() const;
+
+  /**
+   * Query if the compressor output has been disabled due to high current draw.
+   *
+   * @return true if PCM is in fault state : Compressor Drive is
+   *         disabled due to compressor current being too high.
+   */
+  bool GetCompressorCurrentTooHighFault() const;
+
+  /**
+   * Query if the compressor output has been disabled due to high current draw
+   * (sticky).
+   *
+   * A sticky fault will not clear on device reboot, it must be cleared through
+   * code or the webdash.
+   *
+   * @return true if PCM sticky fault is set : Compressor Drive is
+   *         disabled due to compressor current being too high.
+   */
+  bool GetCompressorCurrentTooHighStickyFault() const;
+
+  /**
+   * Query if the compressor output has been disabled due to a short circuit
+   * (sticky).
+   *
+   * A sticky fault will not clear on device reboot, it must be cleared through
+   * code or the webdash.
+   *
+   * @return true if PCM sticky fault is set : Compressor output
+   *         appears to be shorted.
+   */
+  bool GetCompressorShortedStickyFault() const;
+
+  /**
+   * Query if the compressor output has been disabled due to a short circuit.
+   *
+   * @return true if PCM is in fault state : Compressor output
+   *         appears to be shorted.
+   */
+  bool GetCompressorShortedFault() const;
+
+  /**
+   * Query if the compressor output does not appear to be wired (sticky).
+   *
+   * A sticky fault will not clear on device reboot, it must be cleared through
+   * code or the webdash.
+   *
+   * @return true if PCM sticky fault is set : Compressor does not
+   *         appear to be wired, i.e. compressor is not drawing enough current.
+   */
+  bool GetCompressorNotConnectedStickyFault() const;
+
+  /**
+   * Query if the compressor output does not appear to be wired.
+   *
+   * @return true if PCM is in fault state : Compressor does not
+   *         appear to be wired, i.e. compressor is not drawing enough current.
+   */
+  bool GetCompressorNotConnectedFault() const;
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * If a sticky fault is set, then it will be persistently cleared.  Compressor
+   * drive maybe momentarily disable while flags are being cleared. Care should
+   * be taken to not call this too frequently, otherwise normal compressor
+   * functionality may be prevented.
+   *
+   * If no sticky faults are set then this call will have no effect.
+   */
+  void ClearAllPCMStickyFaults();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  HAL_CompressorHandle m_compressorHandle = HAL_kInvalidHandle;
+
+ private:
+  void SetCompressor(bool on);
+  int m_module;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Controller.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Controller.h
new file mode 100644
index 0000000..b327723
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Controller.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Interface for Controllers.
+ *
+ * Common interface for controllers. Controllers run control loops, the most
+ * common are PID controllers and their variants, but this includes anything
+ * that is controlling an actuator in a separate thread.
+ */
+class Controller {
+ public:
+  Controller() = default;
+  virtual ~Controller() = default;
+
+  Controller(Controller&&) = default;
+  Controller& operator=(Controller&&) = default;
+
+  /**
+   * Allows the control loop to run
+   */
+  virtual void Enable() = 0;
+
+  /**
+   * Stops the control loop from running until explicitly re-enabled by calling
+   * enable()
+   */
+  virtual void Disable() = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ControllerPower.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ControllerPower.h
new file mode 100644
index 0000000..1359961
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ControllerPower.h
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/deprecated.h>
+
+namespace frc {
+
+class ControllerPower {
+ public:
+  /**
+   * Get the input voltage to the robot controller.
+   *
+   * @return The controller input voltage value in Volts
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static double GetInputVoltage();
+
+  /**
+   * Get the input current to the robot controller.
+   *
+   * @return The controller input current value in Amps
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static double GetInputCurrent();
+
+  /**
+   * Get the voltage of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail voltage value in Volts
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static double GetVoltage3V3();
+
+  /**
+   * Get the current output of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail output current value in Amps
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static double GetCurrent3V3();
+
+  /**
+   * Get the enabled state of the 3.3V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 3.3V rail enabled value. True for enabled.
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static bool GetEnabled3V3();
+
+  /**
+   * Get the count of the total current faults on the 3.3V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static int GetFaultCount3V3();
+
+  /**
+   * Get the voltage of the 5V rail.
+   *
+   * @return The controller 5V rail voltage value in Volts
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static double GetVoltage5V();
+
+  /**
+   * Get the current output of the 5V rail.
+   *
+   * @return The controller 5V rail output current value in Amps
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static double GetCurrent5V();
+
+  /**
+   * Get the enabled state of the 5V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 5V rail enabled value. True for enabled.
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static bool GetEnabled5V();
+
+  /**
+   * Get the count of the total current faults on the 5V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static int GetFaultCount5V();
+
+  /**
+   * Get the voltage of the 6V rail.
+   *
+   * @return The controller 6V rail voltage value in Volts
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static double GetVoltage6V();
+
+  /**
+   * Get the current output of the 6V rail.
+   *
+   * @return The controller 6V rail output current value in Amps
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static double GetCurrent6V();
+
+  /**
+   * Get the enabled state of the 6V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 6V rail enabled value. True for enabled.
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static bool GetEnabled6V();
+
+  /**
+   * Get the count of the total current faults on the 6V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults.
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  static int GetFaultCount6V();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Counter.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Counter.h
new file mode 100644
index 0000000..2705a39
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Counter.h
@@ -0,0 +1,436 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/AnalogTrigger.h"
+#include "frc/CounterBase.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class DigitalGlitchFilter;
+
+/**
+ * Class for counting the number of ticks on a digital input channel.
+ *
+ * This is a general purpose class for counting repetitive events. It can return
+ * the number of counts, the period of the most recent cycle, and detect when
+ * the signal being counted has stopped by supplying a maximum cycle time.
+ *
+ * All counters will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class Counter : public ErrorBase, public SendableBase, public CounterBase {
+ public:
+  enum Mode {
+    kTwoPulse = 0,
+    kSemiperiod = 1,
+    kPulseLength = 2,
+    kExternalDirection = 3
+  };
+
+  /**
+   * Create an instance of a counter where no sources are selected.
+   *
+   * They all must be selected by calling functions to specify the upsource and
+   * the downsource independently.
+   *
+   * This creates a ChipObject counter and initializes status variables
+   * appropriately.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param mode The counter mode
+   */
+  explicit Counter(Mode mode = kTwoPulse);
+
+  /**
+   * Create an instance of a Counter object.
+   *
+   * Create an up-Counter instance given a channel.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+   *                10-25 are on the MXP
+   */
+  explicit Counter(int channel);
+
+  /**
+   * Create an instance of a counter from a Digital Source (such as a Digital
+   * Input).
+   *
+   * This is used if an existing digital input is to be shared by multiple other
+   * objects such as encoders or if the Digital Source is not a Digital Input
+   * channel (such as an Analog Trigger).
+   *
+   * The counter will start counting immediately.
+   * @param source A pointer to the existing DigitalSource object. It will be
+   *               set as the Up Source.
+   */
+  explicit Counter(DigitalSource* source);
+
+  /**
+   * Create an instance of a counter from a Digital Source (such as a Digital
+   * Input).
+   *
+   * This is used if an existing digital input is to be shared by multiple other
+   * objects such as encoders or if the Digital Source is not a Digital Input
+   * channel (such as an Analog Trigger).
+   *
+   * The counter will start counting immediately.
+   *
+   * @param source A pointer to the existing DigitalSource object. It will be
+   *               set as the Up Source.
+   */
+  explicit Counter(std::shared_ptr<DigitalSource> source);
+
+  /**
+   * Create an instance of a Counter object.
+   *
+   * Create an instance of a simple up-Counter given an analog trigger.
+   * Use the trigger state output from the analog trigger.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param trigger The reference to the existing AnalogTrigger object.
+   */
+  explicit Counter(const AnalogTrigger& trigger);
+
+  /**
+   * Create an instance of a Counter object.
+   *
+   * Creates a full up-down counter given two Digital Sources.
+   *
+   * @param encodingType The quadrature decoding mode (1x or 2x)
+   * @param upSource     The pointer to the DigitalSource to set as the up
+   *                     source
+   * @param downSource   The pointer to the DigitalSource to set as the down
+   *                     source
+   * @param inverted     True to invert the output (reverse the direction)
+   */
+  Counter(EncodingType encodingType, DigitalSource* upSource,
+          DigitalSource* downSource, bool inverted);
+
+  /**
+   * Create an instance of a Counter object.
+   *
+   * Creates a full up-down counter given two Digital Sources.
+   *
+   * @param encodingType The quadrature decoding mode (1x or 2x)
+   * @param upSource     The pointer to the DigitalSource to set as the up
+   *                     source
+   * @param downSource   The pointer to the DigitalSource to set as the down
+   *                     source
+   * @param inverted     True to invert the output (reverse the direction)
+   */
+  Counter(EncodingType encodingType, std::shared_ptr<DigitalSource> upSource,
+          std::shared_ptr<DigitalSource> downSource, bool inverted);
+
+  ~Counter() override;
+
+  Counter(Counter&& rhs);
+  Counter& operator=(Counter&& rhs);
+
+  /**
+   * Set the upsource for the counter as a digital input channel.
+   *
+   * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+   *                10-25 are on the MXP
+   */
+  void SetUpSource(int channel);
+
+  /**
+   * Set the up counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Up
+   *                      Source
+   * @param triggerType   The analog trigger output that will trigger the
+   *                      counter.
+   */
+  void SetUpSource(AnalogTrigger* analogTrigger, AnalogTriggerType triggerType);
+
+  /**
+   * Set the up counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Up
+   *                      Source
+   * @param triggerType   The analog trigger output that will trigger the
+   *                      counter.
+   */
+  void SetUpSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                   AnalogTriggerType triggerType);
+
+  void SetUpSource(DigitalSource* source);
+
+  /**
+   * Set the source object that causes the counter to count up.
+   *
+   * Set the up counting DigitalSource.
+   *
+   * @param source Pointer to the DigitalSource object to set as the up source
+   */
+  void SetUpSource(std::shared_ptr<DigitalSource> source);
+
+  /**
+   * Set the source object that causes the counter to count up.
+   *
+   * Set the up counting DigitalSource.
+   *
+   * @param source Reference to the DigitalSource object to set as the up source
+   */
+  void SetUpSource(DigitalSource& source);
+
+  /**
+   * Set the edge sensitivity on an up counting source.
+   *
+   * Set the up source to either detect rising edges or falling edges or both.
+   *
+   * @param risingEdge  True to trigger on rising edges
+   * @param fallingEdge True to trigger on falling edges
+   */
+  void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+
+  /**
+   * Disable the up counting source to the counter.
+   */
+  void ClearUpSource();
+
+  /**
+   * Set the down counting source to be a digital input channel.
+   *
+   * @param channel The DIO channel to use as the up source. 0-9 are on-board,
+   *                10-25 are on the MXP
+   */
+  void SetDownSource(int channel);
+
+  /**
+   * Set the down counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Down
+   *                      Source
+   * @param triggerType   The analog trigger output that will trigger the
+   *                      counter.
+   */
+  void SetDownSource(AnalogTrigger* analogTrigger,
+                     AnalogTriggerType triggerType);
+
+  /**
+   * Set the down counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Down
+   *                      Source
+   * @param triggerType   The analog trigger output that will trigger the
+   *                      counter.
+   */
+  void SetDownSource(std::shared_ptr<AnalogTrigger> analogTrigger,
+                     AnalogTriggerType triggerType);
+
+  /**
+   * Set the source object that causes the counter to count down.
+   *
+   * Set the down counting DigitalSource.
+   *
+   * @param source Pointer to the DigitalSource object to set as the down source
+   */
+  void SetDownSource(DigitalSource* source);
+
+  /**
+   * Set the source object that causes the counter to count down.
+   *
+   * Set the down counting DigitalSource.
+   *
+   * @param source Reference to the DigitalSource object to set as the down
+   *               source
+   */
+  void SetDownSource(DigitalSource& source);
+
+  void SetDownSource(std::shared_ptr<DigitalSource> source);
+
+  /**
+   * Set the edge sensitivity on a down counting source.
+   *
+   * Set the down source to either detect rising edges or falling edges.
+   *
+   * @param risingEdge  True to trigger on rising edges
+   * @param fallingEdge True to trigger on falling edges
+   */
+  void SetDownSourceEdge(bool risingEdge, bool fallingEdge);
+
+  /**
+   * Disable the down counting source to the counter.
+   */
+  void ClearDownSource();
+
+  /**
+   * Set standard up / down counting mode on this counter.
+   *
+   * Up and down counts are sourced independently from two inputs.
+   */
+  void SetUpDownCounterMode();
+
+  /**
+   * Set external direction mode on this counter.
+   *
+   * Counts are sourced on the Up counter input.
+   * The Down counter input represents the direction to count.
+   */
+  void SetExternalDirectionMode();
+
+  /**
+   * Set Semi-period mode on this counter.
+   *
+   * Counts up on both rising and falling edges.
+   */
+  void SetSemiPeriodMode(bool highSemiPeriod);
+
+  /**
+   * Configure the counter to count in up or down based on the length of the
+   * input pulse.
+   *
+   * This mode is most useful for direction sensitive gear tooth sensors.
+   *
+   * @param threshold The pulse length beyond which the counter counts the
+   *                  opposite direction. Units are seconds.
+   */
+  void SetPulseLengthMode(double threshold);
+
+  /**
+   * Set the Counter to return reversed sensing on the direction.
+   *
+   * This allows counters to change the direction they are counting in the case
+   * of 1X and 2X quadrature encoding only. Any other counter mode isn't
+   * supported.
+   *
+   * @param reverseDirection true if the value counted should be negated.
+   */
+  void SetReverseDirection(bool reverseDirection);
+
+  /**
+   * Set the Samples to Average which specifies the number of samples of the
+   * timer to average when calculating the period. Perform averaging to account
+   * for mechanical imperfections or as oversampling to increase resolution.
+   *
+   * @param samplesToAverage The number of samples to average from 1 to 127.
+   */
+  void SetSamplesToAverage(int samplesToAverage);
+
+  /**
+   * Get the Samples to Average which specifies the number of samples of the
+   * timer to average when calculating the period.
+   *
+   * Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @return The number of samples being averaged (from 1 to 127)
+   */
+  int GetSamplesToAverage() const;
+
+  int GetFPGAIndex() const;
+
+  // CounterBase interface
+  /**
+   * Read the current counter value.
+   *
+   * Read the value at this instant. It may still be running, so it reflects the
+   * current value. Next time it is read, it might have a different value.
+   */
+  int Get() const override;
+
+  /**
+   * Reset the Counter to zero.
+   *
+   * Set the counter value to zero. This doesn't effect the running state of the
+   * counter, just sets the current value to zero.
+   */
+  void Reset() override;
+
+  /**
+   * Get the Period of the most recent count.
+   *
+   * Returns the time interval of the most recent count. This can be used for
+   * velocity calculations to determine shaft speed.
+   *
+   * @returns The period between the last two pulses in units of seconds.
+   */
+  double GetPeriod() const override;
+
+  /**
+   * Set the maximum period where the device is still considered "moving".
+   *
+   * Sets the maximum period where the device is considered moving. This value
+   * is used to determine the "stopped" state of the counter using the
+   * GetStopped method.
+   *
+   * @param maxPeriod The maximum period where the counted device is considered
+   *                  moving in seconds.
+   */
+  void SetMaxPeriod(double maxPeriod) override;
+
+  /**
+   * Select whether you want to continue updating the event timer output when
+   * there are no samples captured.
+   *
+   * The output of the event timer has a buffer of periods that are averaged and
+   * posted to a register on the FPGA.  When the timer detects that the event
+   * source has stopped (based on the MaxPeriod) the buffer of samples to be
+   * averaged is emptied.  If you enable the update when empty, you will be
+   * notified of the stopped source and the event time will report 0 samples.
+   * If you disable update when empty, the most recent average will remain on
+   * the output until a new sample is acquired.  You will never see 0 samples
+   * output (except when there have been no events since an FPGA reset) and you
+   * will likely not see the stopped bit become true (since it is updated at the
+   * end of an average and there are no samples to average).
+   *
+   * @param enabled True to enable update when empty
+   */
+  void SetUpdateWhenEmpty(bool enabled);
+
+  /**
+   * Determine if the clock is stopped.
+   *
+   * Determine if the clocked input is stopped based on the MaxPeriod value set
+   * using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
+   * device (and counter) are assumed to be stopped and it returns true.
+   *
+   * @return Returns true if the most recent counter period exceeds the
+   *         MaxPeriod value set by SetMaxPeriod.
+   */
+  bool GetStopped() const override;
+
+  /**
+   * The last direction the counter value changed.
+   *
+   * @return The last direction the counter value changed.
+   */
+  bool GetDirection() const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  // Makes the counter count up.
+  std::shared_ptr<DigitalSource> m_upSource;
+
+  // Makes the counter count down.
+  std::shared_ptr<DigitalSource> m_downSource;
+
+  // The FPGA counter object
+  HAL_CounterHandle m_counter = HAL_kInvalidHandle;
+
+ private:
+  int m_index = 0;  // The index of this counter.
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/CounterBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/CounterBase.h
new file mode 100644
index 0000000..7fde3ac
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/CounterBase.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Interface for counting the number of ticks on a digital input channel.
+ *
+ * Encoders, Gear tooth sensors, and counters should all subclass this so it can
+ * be used to build more advanced classes for control and driving.
+ *
+ * All counters will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class CounterBase {
+ public:
+  enum EncodingType { k1X, k2X, k4X };
+
+  CounterBase() = default;
+  virtual ~CounterBase() = default;
+
+  CounterBase(CounterBase&&) = default;
+  CounterBase& operator=(CounterBase&&) = default;
+
+  virtual int Get() const = 0;
+  virtual void Reset() = 0;
+  virtual double GetPeriod() const = 0;
+  virtual void SetMaxPeriod(double maxPeriod) = 0;
+  virtual bool GetStopped() const = 0;
+  virtual bool GetDirection() const = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DMC60.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DMC60.h
new file mode 100644
index 0000000..5a33b5a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DMC60.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Digilent DMC 60 Speed Controller.
+ */
+class DMC60 : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Digilent DMC 60.
+   *
+   * @param channel The PWM channel that the DMC 60 is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit DMC60(int channel);
+
+  DMC60(DMC60&&) = default;
+  DMC60& operator=(DMC60&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h
new file mode 100644
index 0000000..f33955e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalGlitchFilter.h
@@ -0,0 +1,132 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <array>
+
+#include <wpi/mutex.h>
+
+#include "frc/DigitalSource.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class Encoder;
+class Counter;
+
+/**
+ * Class to enable glitch filtering on a set of digital inputs.
+ *
+ * This class will manage adding and removing digital inputs from a FPGA glitch
+ * filter. The filter lets the user configure the time that an input must remain
+ * high or low before it is classified as high or low.
+ */
+class DigitalGlitchFilter : public ErrorBase, public SendableBase {
+ public:
+  DigitalGlitchFilter();
+  ~DigitalGlitchFilter() override;
+
+  DigitalGlitchFilter(DigitalGlitchFilter&& rhs);
+  DigitalGlitchFilter& operator=(DigitalGlitchFilter&& rhs);
+
+  /**
+   * Assigns the DigitalSource to this glitch filter.
+   *
+   * @param input The DigitalSource to add.
+   */
+  void Add(DigitalSource* input);
+
+  /**
+   * Assigns the Encoder to this glitch filter.
+   *
+   * @param input The Encoder to add.
+   */
+  void Add(Encoder* input);
+
+  /**
+   * Assigns the Counter to this glitch filter.
+   *
+   * @param input The Counter to add.
+   */
+  void Add(Counter* input);
+
+  /**
+   * Removes a digital input from this filter.
+   *
+   * Removes the DigitalSource from this glitch filter and re-assigns it to
+   * the default filter.
+   *
+   * @param input The DigitalSource to remove.
+   */
+  void Remove(DigitalSource* input);
+
+  /**
+   * Removes an encoder from this filter.
+   *
+   * Removes the Encoder from this glitch filter and re-assigns it to
+   * the default filter.
+   *
+   * @param input The Encoder to remove.
+   */
+  void Remove(Encoder* input);
+
+  /**
+   * Removes a counter from this filter.
+   *
+   * Removes the Counter from this glitch filter and re-assigns it to
+   * the default filter.
+   *
+   * @param input The Counter to remove.
+   */
+  void Remove(Counter* input);
+
+  /**
+   * Sets the number of cycles that the input must not change state for.
+   *
+   * @param fpgaCycles The number of FPGA cycles.
+   */
+  void SetPeriodCycles(int fpgaCycles);
+
+  /**
+   * Sets the number of nanoseconds that the input must not change state for.
+   *
+   * @param nanoseconds The number of nanoseconds.
+   */
+  void SetPeriodNanoSeconds(uint64_t nanoseconds);
+
+  /**
+   * Gets the number of cycles that the input must not change state for.
+   *
+   * @return The number of cycles.
+   */
+  int GetPeriodCycles();
+
+  /**
+   * Gets the number of nanoseconds that the input must not change state for.
+   *
+   * @return The number of nanoseconds.
+   */
+  uint64_t GetPeriodNanoSeconds();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  // Sets the filter for the input to be the requested index. A value of 0
+  // disables the filter, and the filter value must be between 1 and 3,
+  // inclusive.
+  void DoAdd(DigitalSource* input, int requested_index);
+
+  int m_channelIndex = -1;
+  static wpi::mutex m_mutex;
+  static std::array<bool, 3> m_filterAllocated;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalInput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalInput.h
new file mode 100644
index 0000000..af191aa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalInput.h
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/DigitalSource.h"
+
+namespace frc {
+
+class DigitalGlitchFilter;
+
+/**
+ * Class to read a digital input.
+ *
+ * This class will read digital inputs and return the current value on the
+ * channel. Other devices such as encoders, gear tooth sensors, etc. that are
+ * implemented elsewhere will automatically allocate digital inputs and outputs
+ * as required. This class is only for devices like switches etc. that aren't
+ * implemented anywhere else.
+ */
+class DigitalInput : public DigitalSource {
+ public:
+  /**
+   * Create an instance of a Digital Input class.
+   *
+   * Creates a digital input given a channel.
+   *
+   * @param channel The DIO channel 0-9 are on-board, 10-25 are on the MXP port
+   */
+  explicit DigitalInput(int channel);
+
+  ~DigitalInput() override;
+
+  DigitalInput(DigitalInput&& rhs);
+  DigitalInput& operator=(DigitalInput&& rhs);
+
+  /**
+   * Get the value from a digital input channel.
+   *
+   * Retrieve the value of a single digital input channel from the FPGA.
+   */
+  bool Get() const;
+
+  // Digital Source Interface
+  /**
+   * @return The HAL Handle to the specified source.
+   */
+  HAL_Handle GetPortHandleForRouting() const override;
+
+  /**
+   * @return The type of analog trigger output to be used. 0 for Digitals
+   */
+  AnalogTriggerType GetAnalogTriggerTypeForRouting() const override;
+
+  /**
+   * Is source an AnalogTrigger
+   */
+  bool IsAnalogTrigger() const override;
+
+  /**
+   * @return The GPIO channel number that this object represents.
+   */
+  int GetChannel() const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle = HAL_kInvalidHandle;
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalOutput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalOutput.h
new file mode 100644
index 0000000..49cb67d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalOutput.h
@@ -0,0 +1,131 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Class to write to digital outputs.
+ *
+ * Write values to the digital output channels. Other devices implemented
+ * elsewhere will allocate channels automatically so for those devices it
+ * shouldn't be done here.
+ */
+class DigitalOutput : public ErrorBase, public SendableBase {
+ public:
+  /**
+   * Create an instance of a digital output.
+   *
+   * Create a digital output given a channel.
+   *
+   * @param channel The digital channel 0-9 are on-board, 10-25 are on the MXP
+   *                port
+   */
+  explicit DigitalOutput(int channel);
+
+  ~DigitalOutput() override;
+
+  DigitalOutput(DigitalOutput&& rhs);
+  DigitalOutput& operator=(DigitalOutput&& rhs);
+
+  /**
+   * Set the value of a digital output.
+   *
+   * Set the value of a digital output to either one (true) or zero (false).
+   *
+   * @param value 1 (true) for high, 0 (false) for disabled
+   */
+  void Set(bool value);
+
+  /**
+   * Gets the value being output from the Digital Output.
+   *
+   * @return the state of the digital output.
+   */
+  bool Get() const;
+
+  /**
+   * @return The GPIO channel number that this object represents.
+   */
+  int GetChannel() const;
+
+  /**
+   * Output a single pulse on the digital output line.
+   *
+   * Send a single pulse on the digital output line where the pulse duration is
+   * specified in seconds. Maximum pulse length is 0.0016 seconds.
+   *
+   * @param length The pulse length in seconds
+   */
+  void Pulse(double length);
+
+  /**
+   * Determine if the pulse is still going.
+   *
+   * Determine if a previously started pulse is still going.
+   */
+  bool IsPulsing() const;
+
+  /**
+   * Change the PWM frequency of the PWM output on a Digital Output line.
+   *
+   * The valid range is from 0.6 Hz to 19 kHz.  The frequency resolution is
+   * logarithmic.
+   *
+   * There is only one PWM frequency for all digital channels.
+   *
+   * @param rate The frequency to output all digital output PWM signals.
+   */
+  void SetPWMRate(double rate);
+
+  /**
+   * Enable a PWM Output on this line.
+   *
+   * Allocate one of the 6 DO PWM generator resources from this module.
+   *
+   * Supply the initial duty-cycle to output so as to avoid a glitch when first
+   * starting.
+   *
+   * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or
+   * less) but is reduced the higher the frequency of the PWM signal is.
+   *
+   * @param initialDutyCycle The duty-cycle to start generating. [0..1]
+   */
+  void EnablePWM(double initialDutyCycle);
+
+  /**
+   * Change this line from a PWM output back to a static Digital Output line.
+   *
+   * Free up one of the 6 DO PWM generator resources that were in use.
+   */
+  void DisablePWM();
+
+  /**
+   * Change the duty-cycle that is being generated on the line.
+   *
+   * The resolution of the duty cycle is 8-bit for low frequencies (1kHz or
+   * less) but is reduced the higher the frequency of the PWM signal is.
+   *
+   * @param dutyCycle The duty-cycle to change to. [0..1]
+   */
+  void UpdateDutyCycle(double dutyCycle);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle = HAL_kInvalidHandle;
+  HAL_DigitalPWMHandle m_pwmGenerator = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalSource.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalSource.h
new file mode 100644
index 0000000..5d77daa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DigitalSource.h
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/InterruptableSensorBase.h"
+
+namespace frc {
+
+/**
+ * DigitalSource Interface.
+ *
+ * The DigitalSource represents all the possible inputs for a counter or a
+ * quadrature encoder. The source may be either a digital input or an analog
+ * input. If the caller just provides a channel, then a digital input will be
+ * constructed and freed when finished for the source. The source can either be
+ * a digital input or analog trigger but not both.
+ */
+class DigitalSource : public InterruptableSensorBase {
+ public:
+  DigitalSource() = default;
+  DigitalSource(DigitalSource&&) = default;
+  DigitalSource& operator=(DigitalSource&&) = default;
+
+  virtual HAL_Handle GetPortHandleForRouting() const = 0;
+  virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const = 0;
+  virtual bool IsAnalogTrigger() const = 0;
+  virtual int GetChannel() const = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DoubleSolenoid.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DoubleSolenoid.h
new file mode 100644
index 0000000..87c0c85
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DoubleSolenoid.h
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/SolenoidBase.h"
+
+namespace frc {
+
+/**
+ * DoubleSolenoid class for running 2 channels of high voltage Digital Output
+ * (PCM).
+ *
+ * The DoubleSolenoid class is typically used for pneumatics solenoids that
+ * have two positions controlled by two separate channels.
+ */
+class DoubleSolenoid : public SolenoidBase {
+ public:
+  enum Value { kOff, kForward, kReverse };
+
+  /**
+   * Constructor.
+   *
+   * Uses the default PCM ID of 0.
+   *
+   * @param forwardChannel The forward channel number on the PCM (0..7).
+   * @param reverseChannel The reverse channel number on the PCM (0..7).
+   */
+  explicit DoubleSolenoid(int forwardChannel, int reverseChannel);
+
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber   The CAN ID of the PCM.
+   * @param forwardChannel The forward channel on the PCM to control (0..7).
+   * @param reverseChannel The reverse channel on the PCM to control (0..7).
+   */
+  DoubleSolenoid(int moduleNumber, int forwardChannel, int reverseChannel);
+
+  ~DoubleSolenoid() override;
+
+  DoubleSolenoid(DoubleSolenoid&& rhs);
+  DoubleSolenoid& operator=(DoubleSolenoid&& rhs);
+
+  /**
+   * Set the value of a solenoid.
+   *
+   * @param value The value to set (Off, Forward or Reverse)
+   */
+  virtual void Set(Value value);
+
+  /**
+   * Read the current value of the solenoid.
+   *
+   * @return The current value of the solenoid.
+   */
+  virtual Value Get() const;
+
+  /**
+   * Check if the forward solenoid is blacklisted.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and disabled until
+   * power cycle, or until faults are cleared.
+   *
+   * @see ClearAllPCMStickyFaults()
+   * @return If solenoid is disabled due to short.
+   */
+  bool IsFwdSolenoidBlackListed() const;
+
+  /**
+   * Check if the reverse solenoid is blacklisted.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and disabled until
+   * power cycle, or until faults are cleared.
+   *
+   * @see ClearAllPCMStickyFaults()
+   * @return If solenoid is disabled due to short.
+   */
+  bool IsRevSolenoidBlackListed() const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_forwardChannel;  // The forward channel on the module to control.
+  int m_reverseChannel;  // The reverse channel on the module to control.
+  int m_forwardMask;     // The mask for the forward channel.
+  int m_reverseMask;     // The mask for the reverse channel.
+  HAL_SolenoidHandle m_forwardHandle = HAL_kInvalidHandle;
+  HAL_SolenoidHandle m_reverseHandle = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DriverStation.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DriverStation.h
new file mode 100644
index 0000000..ddbe27a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/DriverStation.h
@@ -0,0 +1,471 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+#include <atomic>
+#include <memory>
+#include <string>
+#include <thread>
+
+#include <hal/DriverStationTypes.h>
+#include <wpi/Twine.h>
+#include <wpi/condition_variable.h>
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/RobotState.h"
+
+namespace frc {
+
+class MatchDataSender;
+
+/**
+ * Provide access to the network communication data to / from the Driver
+ * Station.
+ */
+class DriverStation : public ErrorBase {
+ public:
+  enum Alliance { kRed, kBlue, kInvalid };
+  enum MatchType { kNone, kPractice, kQualification, kElimination };
+
+  ~DriverStation() override;
+
+  DriverStation(const DriverStation&) = delete;
+  DriverStation& operator=(const DriverStation&) = delete;
+
+  /**
+   * Return a reference to the singleton DriverStation.
+   *
+   * @return Reference to the DS instance
+   */
+  static DriverStation& GetInstance();
+
+  /**
+   * Report an error to the DriverStation messages window.
+   *
+   * The error is also printed to the program console.
+   */
+  static void ReportError(const wpi::Twine& error);
+
+  /**
+   * Report a warning to the DriverStation messages window.
+   *
+   * The warning is also printed to the program console.
+   */
+  static void ReportWarning(const wpi::Twine& error);
+
+  /**
+   * Report an error to the DriverStation messages window.
+   *
+   * The error is also printed to the program console.
+   */
+  static void ReportError(bool isError, int code, const wpi::Twine& error,
+                          const wpi::Twine& location, const wpi::Twine& stack);
+
+  static constexpr int kJoystickPorts = 6;
+
+  /**
+   * The state of one joystick button. Button indexes begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @param button The button index, beginning at 1.
+   * @return The state of the joystick button.
+   */
+  bool GetStickButton(int stick, int button);
+
+  /**
+   * Whether one joystick button was pressed since the last check. Button
+   * indexes begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @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);
+
+  /**
+   * Whether one joystick button was released since the last check. Button
+   * indexes begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @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);
+
+  /**
+   * Get the value of the axis on a joystick.
+   *
+   * This depends on the mapping of the joystick connected to the specified
+   * port.
+   *
+   * @param stick The joystick to read.
+   * @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);
+
+  /**
+   * 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);
+
+  /**
+   * The state of the buttons on the joystick.
+   *
+   * @param stick The joystick to read.
+   * @return The state of the buttons on the joystick.
+   */
+  int GetStickButtons(int stick) const;
+
+  /**
+   * Returns the number of axes on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @return The number of axes on the indicated joystick
+   */
+  int GetStickAxisCount(int stick) const;
+
+  /**
+   * Returns the number of POVs on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @return The number of POVs on the indicated joystick
+   */
+  int GetStickPOVCount(int stick) const;
+
+  /**
+   * Returns the number of buttons on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @return The number of buttons on the indicated joystick
+   */
+  int GetStickButtonCount(int stick) const;
+
+  /**
+   * Returns a boolean indicating if the controller is an xbox controller.
+   *
+   * @param stick The joystick port number
+   * @return A boolean that is true if the controller is an xbox controller.
+   */
+  bool GetJoystickIsXbox(int stick) const;
+
+  /**
+   * Returns the type of joystick at a given port.
+   *
+   * @param stick The joystick port number
+   * @return The HID type of joystick at the given port
+   */
+  int GetJoystickType(int stick) const;
+
+  /**
+   * Returns the name of the joystick at the given port.
+   *
+   * @param stick The joystick port number
+   * @return The name of the joystick at the given port
+   */
+  std::string GetJoystickName(int stick) const;
+
+  /**
+   * Returns the types of Axes on a given joystick port.
+   *
+   * @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;
+
+  /**
+   * Check if the DS has enabled the robot.
+   *
+   * @return True if the robot is enabled and the DS is connected
+   */
+  bool IsEnabled() const;
+
+  /**
+   * Check if the robot is disabled.
+   *
+   * @return True if the robot is explicitly disabled or the DS is not connected
+   */
+  bool IsDisabled() const;
+
+  /**
+   * Check if the DS is commanding autonomous mode.
+   *
+   * @return True if the robot is being commanded to be in autonomous mode
+   */
+  bool IsAutonomous() const;
+
+  /**
+   * Check if the DS is commanding teleop mode.
+   *
+   * @return True if the robot is being commanded to be in teleop mode
+   */
+  bool IsOperatorControl() const;
+
+  /**
+   * Check if the DS is commanding test mode.
+   *
+   * @return True if the robot is being commanded to be in test mode
+   */
+  bool IsTest() const;
+
+  /**
+   * Check if the DS is attached.
+   *
+   * @return True if the DS is connected to the robot
+   */
+  bool IsDSAttached() const;
+
+  /**
+   * Has a new control packet from the driver station arrived since the last
+   * time this function was called?
+   *
+   * Warning: If you call this function from more than one place at the same
+   * time, you will not get the intended behavior.
+   *
+   * @return True if the control data has been updated since the last call.
+   */
+  bool IsNewControlData() const;
+
+  /**
+   * Is the driver station attached to a Field Management System?
+   *
+   * @return True if the robot is competing on a field being controlled by a
+   *         Field Management System
+   */
+  bool IsFMSAttached() const;
+
+  /**
+   * Check if the FPGA outputs are enabled.
+   *
+   * The outputs may be disabled if the robot is disabled or e-stopped, the
+   * watchdog has expired, or if the roboRIO browns out.
+   *
+   * @return True if the FPGA outputs are enabled.
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  bool IsSysActive() const;
+
+  /**
+   * Check if the system is browned out.
+   *
+   * @return True if the system is browned out
+   * @deprecated Use RobotController static class method
+   */
+  WPI_DEPRECATED("Use RobotController static class method")
+  bool IsBrownedOut() const;
+
+  /**
+   * Returns the game specific message provided by the FMS.
+   *
+   * @return A string containing the game specific message.
+   */
+  std::string GetGameSpecificMessage() const;
+
+  /**
+   * Returns the name of the competition event provided by the FMS.
+   *
+   * @return A string containing the event name
+   */
+  std::string GetEventName() const;
+
+  /**
+   * Returns the type of match being played provided by the FMS.
+   *
+   * @return The match type enum (kNone, kPractice, kQualification,
+   *         kElimination)
+   */
+  MatchType GetMatchType() const;
+
+  /**
+   * Returns the match number provided by the FMS.
+   *
+   * @return The number of the match
+   */
+  int GetMatchNumber() const;
+
+  /**
+   * Returns the number of times the current match has been replayed from the
+   * FMS.
+   *
+   * @return The number of replays
+   */
+  int GetReplayNumber() const;
+
+  /**
+   * Return the alliance that the driver station says it is on.
+   *
+   * This could return kRed or kBlue.
+   *
+   * @return The Alliance enum (kRed, kBlue or kInvalid)
+   */
+  Alliance GetAlliance() const;
+
+  /**
+   * Return the driver station location on the field.
+   *
+   * This could return 1, 2, or 3.
+   *
+   * @return The location of the driver station (1-3, 0 for invalid)
+   */
+  int GetLocation() const;
+
+  /**
+   * Wait until a new packet comes from the driver station.
+   *
+   * This blocks on a semaphore, so the waiting is efficient.
+   *
+   * This is a good way to delay processing until there is new driver station
+   * data to act on.
+   */
+  void WaitForData();
+
+  /**
+   * Wait until a new packet comes from the driver station, or wait for a
+   * timeout.
+   *
+   * If the timeout is less then or equal to 0, wait indefinitely.
+   *
+   * Timeout is in milliseconds
+   *
+   * This blocks on a semaphore, so the waiting is efficient.
+   *
+   * This is a good way to delay processing until there is new driver station
+   * data to act on.
+   *
+   * @param timeout Timeout time in seconds
+   *
+   * @return true if new data, otherwise false
+   */
+  bool WaitForData(double timeout);
+
+  /**
+   * Return the approximate match time.
+   *
+   * The FMS does not send an official match time to the robots, but does send
+   * an approximate match time. The value will count down the time remaining in
+   * the current period (auto or teleop).
+   *
+   * Warning: This is not an official time (so it cannot be used to dispute ref
+   * calls or guarantee that a function will trigger before the match ends).
+   *
+   * The Practice Match function of the DS approximates the behaviour seen on
+   * the field.
+   *
+   * @return Time remaining in current match period (auto or teleop)
+   */
+  double GetMatchTime() const;
+
+  /**
+   * Read the battery voltage.
+   *
+   * @return The battery voltage in Volts.
+   */
+  double GetBatteryVoltage() const;
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting disabled code; if false, leaving disabled
+   *                 code.
+   */
+  void InDisabled(bool entering) { m_userInDisabled = entering; }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting autonomous code; if false, leaving
+   *                 autonomous code.
+   */
+  void InAutonomous(bool entering) { m_userInAutonomous = entering; }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting teleop code; if false, leaving teleop
+   *                 code.
+   */
+  void InOperatorControl(bool entering) { m_userInTeleop = entering; }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be
+   * executing for diagnostic purposes only.
+   *
+   * @param entering If true, starting test code; if false, leaving test code.
+   */
+  void InTest(bool entering) { m_userInTest = entering; }
+
+ 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();
+
+ 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 ReportJoystickUnpluggedError(const wpi::Twine& message);
+
+  /**
+   * Reports errors related to unplugged joysticks.
+   *
+   * Throttles the errors so that they don't overwhelm the DS.
+   */
+  void ReportJoystickUnpluggedWarning(const wpi::Twine& message);
+
+  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};
+
+  wpi::mutex m_waitForDataMutex;
+  wpi::condition_variable m_waitForDataCond;
+  int m_waitForDataCounter;
+
+  // Robot state status variables
+  bool m_userInDisabled = false;
+  bool m_userInAutonomous = false;
+  bool m_userInTeleop = false;
+  bool m_userInTest = false;
+
+  double m_nextMessageTime = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Encoder.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Encoder.h
new file mode 100644
index 0000000..7096eeb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Encoder.h
@@ -0,0 +1,370 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+
+#include "frc/Counter.h"
+#include "frc/CounterBase.h"
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class DigitalSource;
+class DigitalGlitchFilter;
+
+/**
+ * Class to read quad encoders.
+ *
+ * Quadrature encoders are devices that count shaft rotation and can sense
+ * direction. The output of the QuadEncoder class is an integer that can count
+ * either up or down, and can go negative for reverse direction counting. When
+ * creating QuadEncoders, a direction is supplied that changes the sense of the
+ * output to make code more readable if the encoder is mounted such that forward
+ * movement generates negative values. Quadrature encoders have two digital
+ * outputs, an A Channel and a B Channel that are out of phase with each other
+ * to allow the FPGA to do direction sensing.
+ *
+ * All encoders will immediately start counting - Reset() them if you need them
+ * to be zeroed before use.
+ */
+class Encoder : public ErrorBase,
+                public SendableBase,
+                public CounterBase,
+                public PIDSource {
+ public:
+  enum IndexingType {
+    kResetWhileHigh,
+    kResetWhileLow,
+    kResetOnFallingEdge,
+    kResetOnRisingEdge
+  };
+
+  /**
+   * Encoder constructor.
+   *
+   * Construct a Encoder given a and b channels.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param aChannel         The a channel DIO channel. 0-9 are on-board, 10-25
+   *                         are on the MXP port
+   * @param bChannel         The b channel DIO channel. 0-9 are on-board, 10-25
+   *                         are on the MXP port
+   * @param reverseDirection represents the orientation of the encoder and
+   *                         inverts the output values if necessary so forward
+   *                         represents positive values.
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+   *                         decoding. If 4X is selected, then an encoder FPGA
+   *                         object is used and the returned counts will be 4x
+   *                         the encoder spec'd value since all rising and
+   *                         falling edges are counted. If 1X or 2X are selected
+   *                         then a counter object will be used and the returned
+   *                         value will either exactly match the spec'd count or
+   *                         be double (2x) the spec'd count.
+   */
+  Encoder(int aChannel, int bChannel, bool reverseDirection = false,
+          EncodingType encodingType = k4X);
+
+  /**
+   * Encoder constructor.
+   *
+   * Construct a Encoder given a and b channels as digital inputs. This is used
+   * in the case where the digital inputs are shared. The Encoder class will not
+   * allocate the digital inputs and assume that they already are counted.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param aSource          The source that should be used for the a channel.
+   * @param bSource          the source that should be used for the b channel.
+   * @param reverseDirection represents the orientation of the encoder and
+   *                         inverts the output values if necessary so forward
+   *                         represents positive values.
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+   *                         decoding. If 4X is selected, then an encoder FPGA
+   *                         object is used and the returned counts will be 4x
+   *                         the encoder spec'd value since all rising and
+   *                         falling edges are counted. If 1X or 2X are selected
+   *                         then a counter object will be used and the returned
+   *                         value will either exactly match the spec'd count or
+   *                         be double (2x) the spec'd count.
+   */
+  Encoder(DigitalSource* aSource, DigitalSource* bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+
+  /**
+   * Encoder constructor.
+   *
+   * Construct a Encoder given a and b channels as digital inputs. This is used
+   * in the case where the digital inputs are shared. The Encoder class will not
+   * allocate the digital inputs and assume that they already are counted.
+   *
+   * The counter will start counting immediately.
+   *
+   * @param aSource          The source that should be used for the a channel.
+   * @param bSource          the source that should be used for the b channel.
+   * @param reverseDirection represents the orientation of the encoder and
+   *                         inverts the output values if necessary so forward
+   *                         represents positive values.
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+   *                         decoding. If 4X is selected, then an encoder FPGA
+   *                         object is used and the returned counts will be 4x
+   *                         the encoder spec'd value since all rising and
+   *                         falling edges are counted. If 1X or 2X are selected
+   *                         then a counter object will be used and the returned
+   *                         value will either exactly match the spec'd count or
+   *                         be double (2x) the spec'd count.
+   */
+  Encoder(DigitalSource& aSource, DigitalSource& bSource,
+          bool reverseDirection = false, EncodingType encodingType = k4X);
+
+  Encoder(std::shared_ptr<DigitalSource> aSource,
+          std::shared_ptr<DigitalSource> bSource, bool reverseDirection = false,
+          EncodingType encodingType = k4X);
+
+  ~Encoder() override;
+
+  Encoder(Encoder&& rhs);
+  Encoder& operator=(Encoder&& rhs);
+
+  // CounterBase interface
+  /**
+   * Gets the current count.
+   *
+   * Returns the current count on the Encoder. This method compensates for the
+   * decoding type.
+   *
+   * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale
+   *         factor.
+   */
+  int Get() const override;
+
+  /**
+   * Reset the Encoder distance to zero.
+   *
+   * Resets the current count to zero on the encoder.
+   */
+  void Reset() override;
+
+  /**
+   * Returns the period of the most recent pulse.
+   *
+   * Returns the period of the most recent Encoder pulse in seconds. This method
+   * compensates for the decoding type.
+   *
+   * Warning: This returns unscaled periods. Use GetRate() for rates that are
+   * scaled using the value from SetDistancePerPulse().
+   *
+   * @return Period in seconds of the most recent pulse.
+   */
+  double GetPeriod() const override;
+
+  /**
+   * Sets the maximum period for stopped detection.
+   *
+   * Sets the value that represents the maximum period of the Encoder before it
+   * will assume that the attached device is stopped. This timeout allows users
+   * to determine if the wheels or other shaft has stopped rotating.
+   * This method compensates for the decoding type.
+   *
+   * @deprecated Use SetMinRate() in favor of this method.  This takes unscaled
+   *             periods and SetMinRate() scales using value from
+   *             SetDistancePerPulse().
+   *
+   * @param maxPeriod The maximum time between rising and falling edges before
+   *                  the FPGA will report the device stopped. This is expressed
+   *                  in seconds.
+   */
+  void SetMaxPeriod(double maxPeriod) override;
+
+  /**
+   * Determine if the encoder is stopped.
+   *
+   * Using the MaxPeriod value, a boolean is returned that is true if the
+   * encoder is considered stopped and false if it is still moving. A stopped
+   * encoder is one where the most recent pulse width exceeds the MaxPeriod.
+   *
+   * @return True if the encoder is considered stopped.
+   */
+  bool GetStopped() const override;
+
+  /**
+   * The last direction the encoder value changed.
+   *
+   * @return The last direction the encoder value changed.
+   */
+  bool GetDirection() const override;
+
+  /**
+   * Gets the raw value from the encoder.
+   *
+   * The raw value is the actual count unscaled by the 1x, 2x, or 4x scale
+   * factor.
+   *
+   * @return Current raw count from the encoder
+   */
+  int GetRaw() const;
+
+  /**
+   * The encoding scale factor 1x, 2x, or 4x, per the requested encodingType.
+   *
+   * Used to divide raw edge counts down to spec'd counts.
+   */
+  int GetEncodingScale() const;
+
+  /**
+   * Get the distance the robot has driven since the last reset.
+   *
+   * @return The distance driven since the last reset as scaled by the value
+   *         from SetDistancePerPulse().
+   */
+  double GetDistance() const;
+
+  /**
+   * Get the current rate of the encoder.
+   *
+   * Units are distance per second as scaled by the value from
+   * SetDistancePerPulse().
+   *
+   * @return The current rate of the encoder.
+   */
+  double GetRate() const;
+
+  /**
+   * Set the minimum rate of the device before the hardware reports it stopped.
+   *
+   * @param minRate The minimum rate.  The units are in distance per second as
+   *                scaled by the value from SetDistancePerPulse().
+   */
+  void SetMinRate(double minRate);
+
+  /**
+   * Set the distance per pulse for this encoder.
+   *
+   * This sets the multiplier used to determine the distance driven based on the
+   * count value from the encoder.
+   *
+   * Do not include the decoding type in this scale.  The library already
+   * compensates for the decoding type.
+   *
+   * Set this value based on the encoder's rated Pulses per Revolution and
+   * factor in gearing reductions following the encoder shaft.
+   *
+   * This distance can be in any units you like, linear or angular.
+   *
+   * @param distancePerPulse The scale factor that will be used to convert
+   *                         pulses to useful units.
+   */
+  void SetDistancePerPulse(double distancePerPulse);
+
+  /**
+   * Get the distance per pulse for this encoder.
+   *
+   * @return The scale factor that will be used to convert pulses to useful
+   *         units.
+   */
+  double GetDistancePerPulse() const;
+
+  /**
+   * Set the direction sensing for this encoder.
+   *
+   * This sets the direction sensing on the encoder so that it could count in
+   * the correct software direction regardless of the mounting.
+   *
+   * @param reverseDirection true if the encoder direction should be reversed
+   */
+  void SetReverseDirection(bool reverseDirection);
+
+  /**
+   * Set the Samples to Average which specifies the number of samples of the
+   * timer to average when calculating the period.
+   *
+   * Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @param samplesToAverage The number of samples to average from 1 to 127.
+   */
+  void SetSamplesToAverage(int samplesToAverage);
+
+  /**
+   * Get the Samples to Average which specifies the number of samples of the
+   * timer to average when calculating the period.
+   *
+   * Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @return The number of samples being averaged (from 1 to 127)
+   */
+  int GetSamplesToAverage() const;
+
+  double PIDGet() override;
+
+  /**
+   * Set the index source for the encoder.
+   *
+   * When this source is activated, the encoder count automatically resets.
+   *
+   * @param channel A DIO channel to set as the encoder index
+   * @param type    The state that will cause the encoder to reset
+   */
+  void SetIndexSource(int channel, IndexingType type = kResetOnRisingEdge);
+
+  /**
+   * Set the index source for the encoder.
+   *
+   * When this source is activated, the encoder count automatically resets.
+   *
+   * @param channel A digital source to set as the encoder index
+   * @param type    The state that will cause the encoder to reset
+   */
+  void SetIndexSource(const DigitalSource& source,
+                      IndexingType type = kResetOnRisingEdge);
+
+  int GetFPGAIndex() const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  /**
+   * Common initialization code for Encoders.
+   *
+   * This code allocates resources for Encoders and is common to all
+   * constructors. The counter will start counting immediately.
+   *
+   * @param reverseDirection If true, counts down instead of up (this is all
+   *                         relative)
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X
+   *                         decoding. If 4X is selected, then an encoder FPGA
+   *                         object is used and the returned counts will be 4x
+   *                         the encoder spec'd value since all rising and
+   *                         falling edges are counted. If 1X or 2X are selected
+   *                         then a counter object will be used and the returned
+   *                         value will either exactly match the spec'd count or
+   *                         be double (2x) the spec'd count.
+   */
+  void InitEncoder(bool reverseDirection, EncodingType encodingType);
+
+  /**
+   * The scale needed to convert a raw counter value into a number of encoder
+   * pulses.
+   */
+  double DecodingScaleFactor() const;
+
+  std::shared_ptr<DigitalSource> m_aSource;  // The A phase of the quad encoder
+  std::shared_ptr<DigitalSource> m_bSource;  // The B phase of the quad encoder
+  std::shared_ptr<DigitalSource> m_indexSource = nullptr;
+  HAL_EncoderHandle m_encoder = HAL_kInvalidHandle;
+
+  friend class DigitalGlitchFilter;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Error.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Error.h
new file mode 100644
index 0000000..8eafd10
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Error.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <string>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#ifdef _WIN32
+#pragma push_macro("GetMessage")
+#undef GetMessage
+#endif
+
+#include "frc/Base.h"
+
+namespace frc {
+
+class ErrorBase;
+
+/**
+ * Error object represents a library error.
+ */
+class Error {
+ public:
+  using Code = int;
+
+  Error() = default;
+  Error(Code code, const wpi::Twine& contextMessage, wpi::StringRef filename,
+        wpi::StringRef function, int lineNumber,
+        const ErrorBase* originatingObject);
+
+  bool operator<(const Error& rhs) const;
+
+  Code GetCode() const;
+  std::string GetMessage() const;
+  std::string GetFilename() const;
+  std::string GetFunction() const;
+  int GetLineNumber() const;
+  const ErrorBase* GetOriginatingObject() const;
+  double GetTimestamp() const;
+  void Clear();
+  void Set(Code code, const wpi::Twine& contextMessage, wpi::StringRef filename,
+           wpi::StringRef function, int lineNumber,
+           const ErrorBase* originatingObject);
+
+ private:
+  void Report();
+
+  Code m_code = 0;
+  std::string m_message;
+  std::string m_filename;
+  std::string m_function;
+  int m_lineNumber = 0;
+  const ErrorBase* m_originatingObject = nullptr;
+  double m_timestamp = 0.0;
+};
+
+}  // namespace frc
+
+#ifdef _WIN32
+#pragma pop_macro("GetMessage")
+#endif
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ErrorBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ErrorBase.h
new file mode 100644
index 0000000..3be9765
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/ErrorBase.h
@@ -0,0 +1,202 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+#include "frc/Error.h"
+
+#define wpi_setErrnoErrorWithContext(context) \
+  this->SetErrnoError((context), __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setErrnoError() wpi_setErrnoErrorWithContext("")
+#define wpi_setImaqErrorWithContext(code, context)                             \
+  do {                                                                         \
+    if ((code) != 0)                                                           \
+      this->SetImaqError((code), (context), __FILE__, __FUNCTION__, __LINE__); \
+  } while (0)
+#define wpi_setErrorWithContext(code, context)                             \
+  do {                                                                     \
+    if ((code) != 0)                                                       \
+      this->SetError((code), (context), __FILE__, __FUNCTION__, __LINE__); \
+  } while (0)
+#define wpi_setErrorWithContextRange(code, min, max, req, context)          \
+  do {                                                                      \
+    if ((code) != 0)                                                        \
+      this->SetErrorRange((code), (min), (max), (req), (context), __FILE__, \
+                          __FUNCTION__, __LINE__);                          \
+  } while (0)
+#define wpi_setError(code) wpi_setErrorWithContext(code, "")
+#define wpi_setStaticErrorWithContext(object, code, context)                 \
+  do {                                                                       \
+    if ((code) != 0)                                                         \
+      object->SetError((code), (context), __FILE__, __FUNCTION__, __LINE__); \
+  } while (0)
+#define wpi_setStaticError(object, code) \
+  wpi_setStaticErrorWithContext(object, code, "")
+#define wpi_setGlobalErrorWithContext(code, context)                \
+  do {                                                              \
+    if ((code) != 0)                                                \
+      ::frc::ErrorBase::SetGlobalError((code), (context), __FILE__, \
+                                       __FUNCTION__, __LINE__);     \
+  } while (0)
+#define wpi_setGlobalError(code) wpi_setGlobalErrorWithContext(code, "")
+#define wpi_setWPIErrorWithContext(error, context)                    \
+  this->SetWPIError((wpi_error_s_##error), (wpi_error_value_##error), \
+                    (context), __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setWPIError(error) (wpi_setWPIErrorWithContext(error, ""))
+#define wpi_setStaticWPIErrorWithContext(object, error, context)  \
+  object->SetWPIError((wpi_error_s_##error), (context), __FILE__, \
+                      __FUNCTION__, __LINE__)
+#define wpi_setStaticWPIError(object, error) \
+  wpi_setStaticWPIErrorWithContext(object, error, "")
+#define wpi_setGlobalWPIErrorWithContext(error, context)                \
+  ::frc::ErrorBase::SetGlobalWPIError((wpi_error_s_##error), (context), \
+                                      __FILE__, __FUNCTION__, __LINE__)
+#define wpi_setGlobalWPIError(error) wpi_setGlobalWPIErrorWithContext(error, "")
+
+namespace frc {
+
+/**
+ * Base class for most objects.
+ *
+ * ErrorBase is the base class for most objects since it holds the generated
+ * error for that object. In addition, there is a single instance of a global
+ * error object.
+ */
+class ErrorBase {
+  // TODO: Consider initializing instance variables and cleanup in destructor
+ public:
+  ErrorBase();
+  virtual ~ErrorBase() = default;
+
+  ErrorBase(ErrorBase&&) = default;
+  ErrorBase& operator=(ErrorBase&&) = default;
+
+  /**
+   * @brief Retrieve the current error.
+   *
+   * Get the current error information associated with this sensor.
+   */
+  virtual Error& GetError();
+
+  /**
+   * @brief Retrieve the current error.
+   *
+   * Get the current error information associated with this sensor.
+   */
+  virtual const Error& GetError() const;
+
+  /**
+   * @brief Clear the current error information associated with this sensor.
+   */
+  virtual void ClearError() const;
+
+  /**
+   * @brief Set error information associated with a C library call that set an
+   *        error to the "errno" global variable.
+   *
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetErrnoError(const wpi::Twine& contextMessage,
+                             wpi::StringRef filename, wpi::StringRef function,
+                             int lineNumber) const;
+
+  /**
+   * @brief Set the current error information associated from the nivision Imaq
+   *        API.
+   *
+   * @param success        The return from the function
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetImaqError(int success, const wpi::Twine& contextMessage,
+                            wpi::StringRef filename, wpi::StringRef function,
+                            int lineNumber) const;
+
+  /**
+   * @brief Set the current error information associated with this sensor.
+   *
+   * @param code           The error code
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetError(Error::Code code, const wpi::Twine& contextMessage,
+                        wpi::StringRef filename, wpi::StringRef function,
+                        int lineNumber) const;
+
+  /**
+   * @brief Set the current error information associated with this sensor.
+   * Range versions use for initialization code.
+   *
+   * @param code           The error code
+   * @param minRange       The minimum allowed allocation range
+   * @param maxRange       The maximum allowed allocation range
+   * @param requestedValue The requested value to allocate
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetErrorRange(Error::Code code, int32_t minRange,
+                             int32_t maxRange, int32_t requestedValue,
+                             const wpi::Twine& contextMessage,
+                             wpi::StringRef filename, wpi::StringRef function,
+                             int lineNumber) const;
+
+  /**
+   * @brief Set the current error information associated with this sensor.
+   *
+   * @param errorMessage   The error message from WPIErrors.h
+   * @param contextMessage A custom message from the code that set the error.
+   * @param filename       Filename of the error source
+   * @param function       Function of the error source
+   * @param lineNumber     Line number of the error source
+   */
+  virtual void SetWPIError(const wpi::Twine& errorMessage, Error::Code code,
+                           const wpi::Twine& contextMessage,
+                           wpi::StringRef filename, wpi::StringRef function,
+                           int lineNumber) const;
+
+  virtual void CloneError(const ErrorBase& rhs) const;
+
+  /**
+   * @brief Check if the current error code represents a fatal error.
+   *
+   * @return true if the current error is fatal.
+   */
+  virtual bool StatusIsFatal() const;
+
+  static void SetGlobalError(Error::Code code, const wpi::Twine& contextMessage,
+                             wpi::StringRef filename, wpi::StringRef function,
+                             int lineNumber);
+
+  static void SetGlobalWPIError(const wpi::Twine& errorMessage,
+                                const wpi::Twine& contextMessage,
+                                wpi::StringRef filename,
+                                wpi::StringRef function, int lineNumber);
+
+  /**
+   * Retrieve the current global error.
+   */
+  static const Error& GetGlobalError();
+
+ protected:
+  mutable Error m_error;
+};
+
+}  // namespace frc
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
new file mode 100644
index 0000000..baf8044
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Filesystem.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/SmallVector.h>
+
+#include "frc/RobotBase.h"
+
+namespace frc {
+namespace filesystem {
+
+/**
+ * Obtains the current working path that the program was launched with.
+ * This is analogous to the `pwd` command on unix.
+ *
+ * @param result The result of the current working path lookup.
+ */
+void GetLaunchDirectory(wpi::SmallVectorImpl<char>& result);
+
+/**
+ * Obtains the operating directory of the program. On the roboRIO, this
+ * is /home/lvuser. In simulation, it is where the simulation was launched
+ * from (`pwd`).
+ *
+ * @param result The result of the operating directory lookup.
+ */
+void GetOperatingDirectory(wpi::SmallVectorImpl<char>& result);
+
+/**
+ * Obtains the deploy directory of the program, which is the remote location
+ * src/main/deploy is deployed to by default. On the roboRIO, this is
+ * /home/lvuser/deploy. In simulation, it is where the simulation was launched
+ * from, in the subdirectory "deploy" (`pwd`/deploy).
+ *
+ * @param result The result of the operating directory lookup
+ */
+void GetDeployDirectory(wpi::SmallVectorImpl<char>& result);
+
+}  // namespace filesystem
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GamepadBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GamepadBase.h
new file mode 100644
index 0000000..9681c84
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GamepadBase.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/deprecated.h>
+
+#include "frc/GenericHID.h"
+
+namespace frc {
+
+/**
+ * Gamepad Interface.
+ */
+class GamepadBase : public GenericHID {
+ public:
+  WPI_DEPRECATED("Inherit directly from GenericHID instead.")
+  explicit GamepadBase(int port);
+  virtual ~GamepadBase() = default;
+
+  GamepadBase(GamepadBase&&) = default;
+  GamepadBase& operator=(GamepadBase&&) = default;
+
+  virtual bool GetBumper(JoystickHand hand = kRightHand) const = 0;
+  virtual bool GetStickButton(JoystickHand hand) const = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GearTooth.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GearTooth.h
new file mode 100644
index 0000000..230f6d1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GearTooth.h
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include "frc/Counter.h"
+
+namespace frc {
+
+/**
+ * Alias for counter class.
+ *
+ * Implements the gear tooth sensor supplied by FIRST. Currently there is no
+ * reverse sensing on the gear tooth sensor, but in future versions we might
+ * implement the necessary timing in the FPGA to sense direction.
+ */
+class GearTooth : public Counter {
+ public:
+  // 55 uSec for threshold
+  static constexpr double kGearToothThreshold = 55e-6;
+
+  /**
+   * Construct a GearTooth sensor given a channel.
+   *
+   * @param channel            The DIO channel that the sensor is connected to.
+   *                           0-9 are on-board, 10-25 are on the MXP.
+   * @param directionSensitive True to enable the pulse length decoding in
+   *                           hardware to specify count direction.
+   */
+  explicit GearTooth(int channel, bool directionSensitive = false);
+
+  /**
+   * Construct a GearTooth sensor given a digital input.
+   *
+   * This should be used when sharing digital inputs.
+   *
+   * @param source             A pointer to the existing DigitalSource object
+   *                           (such as a DigitalInput)
+   * @param directionSensitive True to enable the pulse length decoding in
+   *                           hardware to specify count direction.
+   */
+  explicit GearTooth(DigitalSource* source, bool directionSensitive = false);
+
+  /**
+   * Construct a GearTooth sensor given a digital input.
+   *
+   * This should be used when sharing digital inputs.
+   *
+   * @param source             A reference to the existing DigitalSource object
+   *                           (such as a DigitalInput)
+   * @param directionSensitive True to enable the pulse length decoding in
+   *                           hardware to specify count direction.
+   */
+  explicit GearTooth(std::shared_ptr<DigitalSource> source,
+                     bool directionSensitive = false);
+
+  GearTooth(GearTooth&&) = default;
+  GearTooth& operator=(GearTooth&&) = default;
+
+  /**
+   * Common code called by the constructors.
+   */
+  void EnableDirectionSensing(bool directionSensitive);
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GenericHID.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GenericHID.h
new file mode 100644
index 0000000..74e5271
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GenericHID.h
@@ -0,0 +1,189 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <string>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+class DriverStation;
+
+/**
+ * GenericHID Interface.
+ */
+class GenericHID : public ErrorBase {
+ public:
+  enum RumbleType { kLeftRumble, kRightRumble };
+
+  enum HIDType {
+    kUnknown = -1,
+    kXInputUnknown = 0,
+    kXInputGamepad = 1,
+    kXInputWheel = 2,
+    kXInputArcadeStick = 3,
+    kXInputFlightStick = 4,
+    kXInputDancePad = 5,
+    kXInputGuitar = 6,
+    kXInputGuitar2 = 7,
+    kXInputDrumKit = 8,
+    kXInputGuitar3 = 11,
+    kXInputArcadePad = 19,
+    kHIDJoystick = 20,
+    kHIDGamepad = 21,
+    kHIDDriving = 22,
+    kHIDFlight = 23,
+    kHID1stPerson = 24
+  };
+
+  enum JoystickHand { kLeftHand = 0, kRightHand = 1 };
+
+  explicit GenericHID(int port);
+  virtual ~GenericHID() = default;
+
+  GenericHID(GenericHID&&) = default;
+  GenericHID& operator=(GenericHID&&) = default;
+
+  virtual double GetX(JoystickHand hand = kRightHand) const = 0;
+  virtual double GetY(JoystickHand hand = kRightHand) const = 0;
+
+  /**
+   * Get the button value (starting at button 1).
+   *
+   * The buttons are returned in a single 16 bit value with one bit representing
+   * the state of each button. The appropriate button is returned as a boolean
+   * value.
+   *
+   * @param button The button number to be read (starting at 1)
+   * @return The state of the button.
+   */
+  bool GetRawButton(int button) const;
+
+  /**
+   * Whether the button was pressed since the last check. Button indexes begin
+   * at 1.
+   *
+   * @param button The button index, beginning at 1.
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetRawButtonPressed(int button);
+
+  /**
+   * Whether the button was released since the last check. Button indexes begin
+   * at 1.
+   *
+   * @param button The button index, beginning at 1.
+   * @return Whether the button was released since the last check.
+   */
+  bool GetRawButtonReleased(int button);
+
+  /**
+   * Get the value of the axis.
+   *
+   * @param axis The axis to read, starting at 0.
+   * @return The value of the axis.
+   */
+  double GetRawAxis(int axis) const;
+
+  /**
+   * Get the angle in degrees of a POV on the HID.
+   *
+   * The POV angles start at 0 in the up direction, and increase clockwise
+   * (e.g. right is 90, upper-left is 315).
+   *
+   * @param pov The index of the POV to read (starting at 0)
+   * @return the angle of the POV in degrees, or -1 if the POV is not pressed.
+   */
+  int GetPOV(int pov = 0) const;
+
+  /**
+   * Get the number of axes for the HID.
+   *
+   * @return the number of axis for the current HID
+   */
+  int GetAxisCount() const;
+
+  /**
+   * Get the number of POVs for the HID.
+   *
+   * @return the number of POVs for the current HID
+   */
+  int GetPOVCount() const;
+
+  /**
+   * Get the number of buttons for the HID.
+   *
+   * @return the number of buttons on the current HID
+   */
+  int GetButtonCount() const;
+
+  /**
+   * Get the type of the HID.
+   *
+   * @return the type of the HID.
+   */
+  GenericHID::HIDType GetType() const;
+
+  /**
+   * Get the name of the HID.
+   *
+   * @return the name of the HID.
+   */
+  std::string GetName() const;
+
+  /**
+   * Get the axis type of a joystick axis.
+   *
+   * @return the axis type of a joystick axis.
+   */
+  int GetAxisType(int axis) const;
+
+  /**
+   * Get the port number of the HID.
+   *
+   * @return The port number of the HID.
+   */
+  int GetPort() const;
+
+  /**
+   * Set a single HID output value for the HID.
+   *
+   * @param outputNumber The index of the output to set (1-32)
+   * @param value        The value to set the output to
+   */
+  void SetOutput(int outputNumber, bool value);
+
+  /**
+   * Set all output values for the HID.
+   *
+   * @param value The 32 bit output value (1 bit for each output)
+   */
+  void SetOutputs(int value);
+
+  /**
+   * Set the rumble output for the HID.
+   *
+   * The DS currently supports 2 rumble values, left rumble and right rumble.
+   *
+   * @param type  Which rumble value to set
+   * @param value The normalized value (0 to 1) to set the rumble to
+   */
+  void SetRumble(RumbleType type, double value);
+
+ private:
+  DriverStation& m_ds;
+  int m_port;
+  int m_outputs = 0;
+  uint16_t m_leftRumble = 0;
+  uint16_t m_rightRumble = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GyroBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GyroBase.h
new file mode 100644
index 0000000..d27c7d9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/GyroBase.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/interfaces/Gyro.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * GyroBase is the common base class for Gyro implementations such as
+ * AnalogGyro.
+ */
+class GyroBase : public Gyro,
+                 public ErrorBase,
+                 public SendableBase,
+                 public PIDSource {
+ public:
+  GyroBase() = default;
+  GyroBase(GyroBase&&) = default;
+  GyroBase& operator=(GyroBase&&) = default;
+
+  // PIDSource interface
+  /**
+   * Get the PIDOutput for the PIDSource base object. Can be set to return
+   * angle or rate using SetPIDSourceType(). Defaults to angle.
+   *
+   * @return The PIDOutput (angle or rate, defaults to angle)
+   */
+  double PIDGet() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/I2C.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/I2C.h
new file mode 100644
index 0000000..4623c44
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/I2C.h
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/I2CTypes.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * I2C bus interface class.
+ *
+ * This class is intended to be used by sensor (and other I2C device) drivers.
+ * It probably should not be used directly.
+ */
+class I2C : public ErrorBase {
+ public:
+  enum Port { kOnboard = 0, kMXP };
+
+  /**
+   * Constructor.
+   *
+   * @param port          The I2C port to which the device is connected.
+   * @param deviceAddress The address of the device on the I2C bus.
+   */
+  I2C(Port port, int deviceAddress);
+
+  ~I2C() override;
+
+  I2C(I2C&& rhs);
+  I2C& operator=(I2C&& rhs);
+
+  /**
+   * Generic transaction.
+   *
+   * This is a lower-level interface to the I2C hardware giving you more control
+   * over each transaction.
+   *
+   * @param dataToSend   Buffer of data to send as part of the transaction.
+   * @param sendSize     Number of bytes to send as part of the transaction.
+   * @param dataReceived Buffer to read data into.
+   * @param receiveSize  Number of bytes to read from the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool Transaction(uint8_t* dataToSend, int sendSize, uint8_t* dataReceived,
+                   int receiveSize);
+
+  /**
+   * Attempt to address a device on the I2C bus.
+   *
+   * This allows you to figure out if there is a device on the I2C bus that
+   * responds to the address specified in the constructor.
+   *
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool AddressOnly();
+
+  /**
+   * Execute a write transaction with the device.
+   *
+   * Write a single byte to a register on a device and wait until the
+   *   transaction is complete.
+   *
+   * @param registerAddress The address of the register on the device to be
+   *                        written.
+   * @param data            The byte to write to the register on the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool Write(int registerAddress, uint8_t data);
+
+  /**
+   * Execute a bulk write transaction with the device.
+   *
+   * Write multiple bytes to a device and wait until the
+   *   transaction is complete.
+   *
+   * @param data  The data to write to the register on the device.
+   * @param count The number of bytes to be written.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool WriteBulk(uint8_t* data, int count);
+
+  /**
+   * Execute a read transaction with the device.
+   *
+   * Read bytes from a device.
+   * Most I2C devices will auto-increment the register pointer internally
+   * allowing you to read consecutive registers on a device in a single
+   * transaction.
+   *
+   * @param registerAddress The register to read first in the transaction.
+   * @param count           The number of bytes to read in the transaction.
+   * @param buffer          A pointer to the array of bytes to store the data
+   *                        read from the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool Read(int registerAddress, int count, uint8_t* data);
+
+  /**
+   * Execute a read only transaction with the device.
+   *
+   * Read bytes from a device. This method does not write any data to prompt the
+   * device.
+   *
+   * @param buffer A pointer to the array of bytes to store the data read from
+   *               the device.
+   * @param count  The number of bytes to read in the transaction.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  bool ReadOnly(int count, uint8_t* buffer);
+
+  /**
+   * Verify that a device's registers contain expected values.
+   *
+   * Most devices will have a set of registers that contain a known value that
+   * can be used to identify them.  This allows an I2C device driver to easily
+   * verify that the device contains the expected value.
+   *
+   * @pre The device must support and be configured to use register
+   * auto-increment.
+   *
+   * @param registerAddress The base register to start reading from the device.
+   * @param count           The size of the field to be verified.
+   * @param expected        A buffer containing the values expected from the
+   *                        device.
+   */
+  bool VerifySensor(int registerAddress, int count, const uint8_t* expected);
+
+ private:
+  HAL_I2CPort m_port = HAL_I2C_kInvalid;
+  int m_deviceAddress;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h
new file mode 100644
index 0000000..7c9e364
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/InterruptableSensorBase.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Interrupts.h>
+
+#include "frc/AnalogTriggerType.h"
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class InterruptableSensorBase : public ErrorBase, public SendableBase {
+ public:
+  enum WaitResult {
+    kTimeout = 0x0,
+    kRisingEdge = 0x1,
+    kFallingEdge = 0x100,
+    kBoth = 0x101,
+  };
+
+  InterruptableSensorBase() = default;
+
+  InterruptableSensorBase(InterruptableSensorBase&&) = default;
+  InterruptableSensorBase& operator=(InterruptableSensorBase&&) = default;
+
+  virtual HAL_Handle GetPortHandleForRouting() const = 0;
+  virtual AnalogTriggerType GetAnalogTriggerTypeForRouting() const = 0;
+
+  /**
+   * Request one of the 8 interrupts asynchronously on this digital input.
+   *
+   * Request interrupts in asynchronous mode where the user's interrupt handler
+   * will be called when the interrupt fires. Users that want control over the
+   * thread priority should use the synchronous method with their own spawned
+   * thread. The default is interrupt on rising edges only.
+   */
+  virtual void RequestInterrupts(HAL_InterruptHandlerFunction handler,
+                                 void* param);
+
+  /**
+   * Request one of the 8 interrupts synchronously on this digital input.
+   *
+   * Request interrupts in synchronous mode where the user program will have to
+   * explicitly wait for the interrupt to occur using WaitForInterrupt.
+   * The default is interrupt on rising edges only.
+   */
+  virtual void RequestInterrupts();
+
+  /**
+   * Cancel interrupts on this device.
+   *
+   * This deallocates all the chipobject structures and disables any interrupts.
+   */
+  virtual void CancelInterrupts();
+
+  /**
+   * In synchronous mode, wait for the defined interrupt to occur.
+   *
+   * You should <b>NOT</b> attempt to read the sensor from another thread while
+   * waiting for an interrupt. This is not threadsafe, and can cause memory
+   * corruption
+   *
+   * @param timeout        Timeout in seconds
+   * @param ignorePrevious If true, ignore interrupts that happened before
+   *                       WaitForInterrupt was called.
+   * @return What interrupts fired
+   */
+  virtual WaitResult WaitForInterrupt(double timeout,
+                                      bool ignorePrevious = true);
+
+  /**
+   * Enable interrupts to occur on this input.
+   *
+   * Interrupts are disabled when the RequestInterrupt call is made. This gives
+   * time to do the setup of the other options before starting to field
+   * interrupts.
+   */
+  virtual void EnableInterrupts();
+
+  /**
+   * Disable Interrupts without without deallocating structures.
+   */
+  virtual void DisableInterrupts();
+
+  /**
+   * Return the timestamp for the rising interrupt that occurred most recently.
+   *
+   * This is in the same time domain as GetClock().
+   * The rising-edge interrupt should be enabled with
+   * {@link #DigitalInput.SetUpSourceEdge}
+   *
+   * @return Timestamp in seconds since boot.
+   */
+  virtual double ReadRisingTimestamp();
+
+  /**
+   * Return the timestamp for the falling interrupt that occurred most recently.
+   *
+   * This is in the same time domain as GetClock().
+   * The falling-edge interrupt should be enabled with
+   * {@link #DigitalInput.SetUpSourceEdge}
+   *
+   * @return Timestamp in seconds since boot.
+   */
+  virtual double ReadFallingTimestamp();
+
+  /**
+   * Set which edge to trigger interrupts on
+   *
+   * @param risingEdge  true to interrupt on rising edge
+   * @param fallingEdge true to interrupt on falling edge
+   */
+  virtual void SetUpSourceEdge(bool risingEdge, bool fallingEdge);
+
+ protected:
+  HAL_InterruptHandle m_interrupt = HAL_kInvalidHandle;
+
+  void AllocateInterrupts(bool watcher);
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/IterativeRobot.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/IterativeRobot.h
new file mode 100644
index 0000000..8ce6356
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/IterativeRobot.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/IterativeRobotBase.h"
+
+namespace frc {
+
+/**
+ * IterativeRobot implements the IterativeRobotBase robot program framework.
+ *
+ * The IterativeRobot class is intended to be subclassed by a user creating a
+ * robot program.
+ *
+ * Periodic() functions from the base class are called each time a new packet is
+ * received from the driver station.
+ */
+class IterativeRobot : public IterativeRobotBase {
+ public:
+  WPI_DEPRECATED(
+      "Use TimedRobot instead. It's a drop-in replacement that provides more "
+      "regular execution periods.")
+  IterativeRobot();
+  virtual ~IterativeRobot() = default;
+
+  IterativeRobot(IterativeRobot&&) = default;
+  IterativeRobot& operator=(IterativeRobot&&) = default;
+
+  /**
+   * Provide an alternate "main loop" via StartCompetition().
+   *
+   * This specific StartCompetition() implements "main loop" behaviour synced
+   * with the DS packets.
+   */
+  void StartCompetition() override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/IterativeRobotBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
new file mode 100644
index 0000000..6ff5816
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/IterativeRobotBase.h
@@ -0,0 +1,164 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/RobotBase.h"
+#include "frc/Watchdog.h"
+
+namespace frc {
+
+/**
+ * IterativeRobotBase implements a specific type of robot program framework,
+ * extending the RobotBase class.
+ *
+ * The IterativeRobotBase class does not implement StartCompetition(), so it
+ * should not be used by teams directly.
+ *
+ * This class provides the following functions which are called by the main
+ * loop, StartCompetition(), at the appropriate times:
+ *
+ * RobotInit() -- provide for initialization at robot power-on
+ *
+ * Init() functions -- each of the following functions is called once when the
+ *                     appropriate mode is entered:
+ *   - DisabledInit()   -- called each and every time disabled is entered from
+ *                         another mode
+ *   - AutonomousInit() -- called each and every time autonomous is entered from
+ *                         another mode
+ *   - TeleopInit()     -- called each and every time teleop is entered from
+ *                         another mode
+ *   - TestInit()       -- called each and every time test is entered from
+ *                         another mode
+ *
+ * Periodic() functions -- each of these functions is called on an interval:
+ *   - RobotPeriodic()
+ *   - DisabledPeriodic()
+ *   - AutonomousPeriodic()
+ *   - TeleopPeriodic()
+ *   - TestPeriodic()
+ */
+class IterativeRobotBase : public RobotBase {
+ public:
+  /**
+   * Robot-wide initialization code should go here.
+   *
+   * Users should override this method for default Robot-wide initialization
+   * which will be called when the robot is first powered on. It will be called
+   * exactly one time.
+   *
+   * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
+   * indicators will be off until RobotInit() exits. Code in RobotInit() that
+   * waits for enable will cause the robot to never indicate that the code is
+   * ready, causing the robot to be bypassed in a match.
+   */
+  virtual void RobotInit();
+
+  /**
+   * Initialization code for disabled mode should go here.
+   *
+   * Users should override this method for initialization code which will be
+   * called each time
+   * the robot enters disabled mode.
+   */
+  virtual void DisabledInit();
+
+  /**
+   * Initialization code for autonomous mode should go here.
+   *
+   * Users should override this method for initialization code which will be
+   * called each time the robot enters autonomous mode.
+   */
+  virtual void AutonomousInit();
+
+  /**
+   * Initialization code for teleop mode should go here.
+   *
+   * Users should override this method for initialization code which will be
+   * called each time the robot enters teleop mode.
+   */
+  virtual void TeleopInit();
+
+  /**
+   * Initialization code for test mode should go here.
+   *
+   * Users should override this method for initialization code which will be
+   * called each time the robot enters test mode.
+   */
+  virtual void TestInit();
+
+  /**
+   * Periodic code for all modes should go here.
+   *
+   * This function is called each time a new packet is received from the driver
+   * station.
+   */
+  virtual void RobotPeriodic();
+
+  /**
+   * Periodic code for disabled mode should go here.
+   *
+   * Users should override this method for code which will be called each time a
+   * new packet is received from the driver station and the robot is in disabled
+   * mode.
+   */
+  virtual void DisabledPeriodic();
+
+  /**
+   * Periodic code for autonomous mode should go here.
+   *
+   * Users should override this method for code which will be called each time a
+   * new packet is received from the driver station and the robot is in
+   * autonomous mode.
+   */
+  virtual void AutonomousPeriodic();
+
+  /**
+   * Periodic code for teleop mode should go here.
+   *
+   * Users should override this method for code which will be called each time a
+   * new packet is received from the driver station and the robot is in teleop
+   * mode.
+   */
+  virtual void TeleopPeriodic();
+
+  /**
+   * Periodic code for test mode should go here.
+   *
+   * Users should override this method for code which will be called each time a
+   * new packet is received from the driver station and the robot is in test
+   * mode.
+   */
+  virtual void TestPeriodic();
+
+ protected:
+  /**
+   * Constructor for IterativeRobotBase.
+   *
+   * @param period Period in seconds.
+   */
+  explicit IterativeRobotBase(double period);
+
+  virtual ~IterativeRobotBase() = default;
+
+  IterativeRobotBase(IterativeRobotBase&&) = default;
+  IterativeRobotBase& operator=(IterativeRobotBase&&) = default;
+
+  void LoopFunc();
+
+  double m_period;
+
+ private:
+  enum class Mode { kNone, kDisabled, kAutonomous, kTeleop, kTest };
+
+  Mode m_lastMode = Mode::kNone;
+  Watchdog m_watchdog;
+
+  void PrintLoopOverrunMessage();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Jaguar.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Jaguar.h
new file mode 100644
index 0000000..f22eb42
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Jaguar.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Luminary Micro / Vex Robotics Jaguar Speed Controller with PWM control.
+ */
+class Jaguar : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Jaguar connected via PWM.
+   *
+   * @param channel The PWM channel that the Jaguar is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit Jaguar(int channel);
+
+  Jaguar(Jaguar&&) = default;
+  Jaguar& operator=(Jaguar&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Joystick.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Joystick.h
new file mode 100644
index 0000000..4c17589
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Joystick.h
@@ -0,0 +1,291 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <array>
+
+#include <wpi/deprecated.h>
+
+#include "frc/GenericHID.h"
+
+namespace frc {
+
+/**
+ * Handle input from standard Joysticks connected to the Driver Station.
+ *
+ * This class handles standard input that comes from the Driver Station. Each
+ * time a value is requested the most recent value is returned. There is a
+ * single class instance for each joystick and the mapping of ports to hardware
+ * buttons depends on the code in the Driver Station.
+ */
+class Joystick : public GenericHID {
+ public:
+  static constexpr int kDefaultXChannel = 0;
+  static constexpr int kDefaultYChannel = 1;
+  static constexpr int kDefaultZChannel = 2;
+  static constexpr int kDefaultTwistChannel = 2;
+  static constexpr int kDefaultThrottleChannel = 3;
+
+  WPI_DEPRECATED("Use kDefaultXChannel instead.")
+  static constexpr int kDefaultXAxis = 0;
+  WPI_DEPRECATED("Use kDefaultYChannel instead.")
+  static constexpr int kDefaultYAxis = 1;
+  WPI_DEPRECATED("Use kDefaultZChannel instead.")
+  static constexpr int kDefaultZAxis = 2;
+  WPI_DEPRECATED("Use kDefaultTwistChannel instead.")
+  static constexpr int kDefaultTwistAxis = 2;
+  WPI_DEPRECATED("Use kDefaultThrottleChannel instead.")
+  static constexpr int kDefaultThrottleAxis = 3;
+
+  enum AxisType { kXAxis, kYAxis, kZAxis, kTwistAxis, kThrottleAxis };
+  enum ButtonType { kTriggerButton, kTopButton };
+
+  /**
+   * Construct an instance of a joystick.
+   *
+   * The joystick index is the USB port on the Driver Station.
+   *
+   * @param port The port on the Driver Station that the joystick is plugged
+   *             into (0-5).
+   */
+  explicit Joystick(int port);
+
+  virtual ~Joystick() = default;
+
+  Joystick(Joystick&&) = default;
+  Joystick& operator=(Joystick&&) = default;
+
+  /**
+   * Set the channel associated with the X axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  void SetXChannel(int channel);
+
+  /**
+   * Set the channel associated with the Y axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  void SetYChannel(int channel);
+
+  /**
+   * Set the channel associated with the Z axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  void SetZChannel(int channel);
+
+  /**
+   * Set the channel associated with the twist axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  void SetTwistChannel(int channel);
+
+  /**
+   * Set the channel associated with the throttle axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  void SetThrottleChannel(int channel);
+
+  /**
+   * Set the channel associated with a specified axis.
+   *
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  WPI_DEPRECATED("Use the more specific axis channel setter functions.")
+  void SetAxisChannel(AxisType axis, int channel);
+
+  /**
+   * Get the channel currently associated with the X axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetXChannel() const;
+
+  /**
+   * Get the channel currently associated with the Y axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetYChannel() const;
+
+  /**
+   * Get the channel currently associated with the Z axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetZChannel() const;
+
+  /**
+   * Get the channel currently associated with the twist axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetTwistChannel() const;
+
+  /**
+   * Get the channel currently associated with the throttle axis.
+   *
+   * @return The channel for the axis.
+   */
+  int GetThrottleChannel() const;
+
+  /**
+   * Get the X value of the joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   *
+   * @param hand This parameter is ignored for the Joystick class and is only
+   *             here to complete the GenericHID interface.
+   */
+  double GetX(JoystickHand hand = kRightHand) const override;
+
+  /**
+   * Get the Y value of the joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   *
+   * @param hand This parameter is ignored for the Joystick class and is only
+   *             here to complete the GenericHID interface.
+   */
+  double GetY(JoystickHand hand = kRightHand) const override;
+
+  /**
+   * Get the Z value of the current joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   */
+  double GetZ() const;
+
+  /**
+   * Get the twist value of the current joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   */
+  double GetTwist() const;
+
+  /**
+   * Get the throttle value of the current joystick.
+   *
+   * This depends on the mapping of the joystick connected to the current port.
+   */
+  double GetThrottle() const;
+
+  /**
+   * For the current joystick, return the axis determined by the argument.
+   *
+   * This is for cases where the joystick axis is returned programatically,
+   * otherwise one of the previous functions would be preferable (for example
+   * GetX()).
+   *
+   * @param axis The axis to read.
+   * @return The value of the axis.
+   */
+  WPI_DEPRECATED("Use the more specific axis channel getter functions.")
+  double GetAxis(AxisType axis) const;
+
+  /**
+   * Read the state of the trigger on the joystick.
+   *
+   * Look up which button has been assigned to the trigger and read its state.
+   *
+   * @return The state of the trigger.
+   */
+  bool GetTrigger() const;
+
+  /**
+   * Whether the trigger was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetTriggerPressed();
+
+  /**
+   * Whether the trigger was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetTriggerReleased();
+
+  /**
+   * Read the state of the top button on the joystick.
+   *
+   * Look up which button has been assigned to the top and read its state.
+   *
+   * @return The state of the top button.
+   */
+  bool GetTop() const;
+
+  /**
+   * Whether the top button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetTopPressed();
+
+  /**
+   * Whether the top button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetTopReleased();
+
+  WPI_DEPRECATED("Use Joystick instances instead.")
+  static Joystick* GetStickForPort(int port);
+
+  /**
+   * Get buttons based on an enumerated type.
+   *
+   * The button type will be looked up in the list of buttons and then read.
+   *
+   * @param button The type of button to read.
+   * @return The state of the button.
+   */
+  WPI_DEPRECATED("Use the more specific button getter functions.")
+  bool GetButton(ButtonType button) const;
+
+  /**
+   * Get the magnitude of the direction vector formed by the joystick's
+   * current position relative to its origin.
+   *
+   * @return The magnitude of the direction vector
+   */
+  double GetMagnitude() const;
+
+  /**
+   * Get the direction of the vector formed by the joystick and its origin
+   * in radians.
+   *
+   * @return The direction of the vector in radians
+   */
+  double GetDirectionRadians() const;
+
+  /**
+   * Get the direction of the vector formed by the joystick and its origin
+   * in degrees.
+   *
+   * @return The direction of the vector in degrees
+   */
+  double GetDirectionDegrees() const;
+
+ private:
+  enum Axis { kX, kY, kZ, kTwist, kThrottle, kNumAxes };
+  enum Button { kTrigger = 1, kTop = 2 };
+
+  std::array<int, Axis::kNumAxes> m_axes;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/JoystickBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/JoystickBase.h
new file mode 100644
index 0000000..cba5a7e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/JoystickBase.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/deprecated.h>
+
+#include "frc/GenericHID.h"
+
+namespace frc {
+
+/**
+ * Joystick Interface.
+ */
+class JoystickBase : public GenericHID {
+ public:
+  WPI_DEPRECATED("Inherit directly from GenericHID instead.")
+  explicit JoystickBase(int port);
+  virtual ~JoystickBase() = default;
+
+  JoystickBase(JoystickBase&&) = default;
+  JoystickBase& operator=(JoystickBase&&) = default;
+
+  virtual double GetZ(JoystickHand hand = kRightHand) const = 0;
+  virtual double GetTwist() const = 0;
+  virtual double GetThrottle() const = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/MotorSafety.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/MotorSafety.h
new file mode 100644
index 0000000..afd0853
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/MotorSafety.h
@@ -0,0 +1,113 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/mutex.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/Timer.h"
+
+namespace frc {
+
+/**
+ * This base class runs a watchdog timer and calls the subclass's StopMotor()
+ * function if the timeout expires.
+ *
+ * The subclass should call Feed() whenever the motor value is updated.
+ */
+class MotorSafety : public ErrorBase {
+ public:
+  MotorSafety();
+  virtual ~MotorSafety();
+
+  MotorSafety(MotorSafety&& rhs);
+  MotorSafety& operator=(MotorSafety&& rhs);
+
+  /**
+   * Feed the motor safety object.
+   *
+   * Resets the timer on this object that is used to do the timeouts.
+   */
+  void Feed();
+
+  /**
+   * Set the expiration time for the corresponding motor safety object.
+   *
+   * @param expirationTime The timeout value in seconds.
+   */
+  void SetExpiration(double expirationTime);
+
+  /**
+   * Retrieve the timeout value for the corresponding motor safety object.
+   *
+   * @return the timeout value in seconds.
+   */
+  double GetExpiration() const;
+
+  /**
+   * Determine if the motor is still operating or has timed out.
+   *
+   * @return true if the motor is still operating normally and hasn't timed out.
+   */
+  bool IsAlive() const;
+
+  /**
+   * Enable/disable motor safety for this device.
+   *
+   * Turn on and off the motor safety option for this PWM object.
+   *
+   * @param enabled True if motor safety is enforced for this object.
+   */
+  void SetSafetyEnabled(bool enabled);
+
+  /**
+   * Return the state of the motor safety enabled flag.
+   *
+   * Return if the motor safety is currently enabled for this device.
+   *
+   * @return True if motor safety is enforced for this device.
+   */
+  bool IsSafetyEnabled() const;
+
+  /**
+   * Check if this motor has exceeded its timeout.
+   *
+   * This method is called periodically to determine if this motor has exceeded
+   * its timeout value. If it has, the stop method is called, and the motor is
+   * shut down until its value is updated again.
+   */
+  void Check();
+
+  /**
+   * Check the motors to see if any have timed out.
+   *
+   * This static method is called periodically to poll all the motors and stop
+   * any that have timed out.
+   */
+  static void CheckMotors();
+
+  virtual void StopMotor() = 0;
+  virtual void GetDescription(wpi::raw_ostream& desc) const = 0;
+
+ private:
+  static constexpr double kDefaultSafetyExpiration = 0.1;
+
+  // The expiration time for this object
+  double m_expiration = kDefaultSafetyExpiration;
+
+  // True if motor safety is enabled for this motor
+  bool m_enabled = false;
+
+  // The FPGA clock value when the motor has expired
+  double m_stopTime = Timer::GetFPGATimestamp();
+
+  mutable wpi::mutex m_thisMutex;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/NidecBrushless.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/NidecBrushless.h
new file mode 100644
index 0000000..1d63c31
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/NidecBrushless.h
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+
+#include "frc/DigitalOutput.h"
+#include "frc/ErrorBase.h"
+#include "frc/MotorSafety.h"
+#include "frc/PWM.h"
+#include "frc/SpeedController.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Nidec Brushless Motor.
+ */
+class NidecBrushless : public SendableBase,
+                       public SpeedController,
+                       public MotorSafety {
+ public:
+  /**
+   * Constructor.
+   *
+   * @param pwmChannel The PWM channel that the Nidec Brushless controller is
+   *                   attached to. 0-9 are on-board, 10-19 are on the MXP port.
+   * @param dioChannel The DIO channel that the Nidec Brushless controller is
+   *                   attached to. 0-9 are on-board, 10-25 are on the MXP port.
+   */
+  NidecBrushless(int pwmChannel, int dioChannel);
+
+  ~NidecBrushless() override = default;
+
+  NidecBrushless(NidecBrushless&&) = default;
+  NidecBrushless& operator=(NidecBrushless&&) = default;
+
+  // SpeedController interface
+  /**
+   * Set the PWM value.
+   *
+   * The PWM value is set using a range of -1.0 to 1.0, appropriately scaling
+   * the value for the FPGA.
+   *
+   * @param speed The speed value between -1.0 and 1.0 to set.
+   */
+  void Set(double speed) override;
+
+  /**
+   * Get the recently set value of the PWM.
+   *
+   * @return The most recently set value for the PWM between -1.0 and 1.0.
+   */
+  double Get() const override;
+
+  void SetInverted(bool isInverted) override;
+
+  bool GetInverted() const override;
+
+  /**
+   * Disable the motor. The Enable() function must be called to re-enable the
+   * motor.
+   */
+  void Disable() override;
+
+  /**
+   * Re-enable the motor after Disable() has been called. The Set() function
+   * must be called to set a new motor speed.
+   */
+  void Enable();
+
+  // PIDOutput interface
+  /**
+   * Write out the PID value as seen in the PIDOutput base object.
+   *
+   * @param output Write out the PWM value as was found in the PIDController
+   */
+  void PIDWrite(double output) override;
+
+  // MotorSafety interface
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  /**
+   * Gets the channel number associated with the object.
+   *
+   * @return The channel number.
+   */
+  int GetChannel() const;
+
+  // Sendable interface
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  bool m_isInverted = false;
+  std::atomic_bool m_disabled{false};
+  DigitalOutput m_dio;
+  PWM m_pwm;
+  double m_speed = 0.0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Notifier.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Notifier.h
new file mode 100644
index 0000000..47380bc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Notifier.h
@@ -0,0 +1,123 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <atomic>
+#include <functional>
+#include <thread>
+#include <utility>
+
+#include <hal/Types.h>
+#include <wpi/mutex.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+using TimerEventHandler = std::function<void()>;
+
+class Notifier : public ErrorBase {
+ public:
+  /**
+   * Create a Notifier for timer event notification.
+   *
+   * @param handler The handler is called at the notification time which is set
+   *                using StartSingle or StartPeriodic.
+   */
+  explicit Notifier(TimerEventHandler handler);
+
+  template <typename Callable, typename Arg, typename... Args>
+  Notifier(Callable&& f, Arg&& arg, Args&&... args)
+      : Notifier(std::bind(std::forward<Callable>(f), std::forward<Arg>(arg),
+                           std::forward<Args>(args)...)) {}
+
+  /**
+   * Free the resources for a timer event.
+   */
+  virtual ~Notifier();
+
+  Notifier(Notifier&& rhs);
+  Notifier& operator=(Notifier&& rhs);
+
+  /**
+   * Change the handler function.
+   *
+   * @param handler Handler
+   */
+  void SetHandler(TimerEventHandler handler);
+
+  /**
+   * Register for single event notification.
+   *
+   * A timer event is queued for a single event after the specified delay.
+   *
+   * @param delay Seconds to wait before the handler is called.
+   */
+  void StartSingle(double delay);
+
+  /**
+   * Register for periodic event notification.
+   *
+   * A timer event is queued for periodic event notification. Each time the
+   * interrupt occurs, the event will be immediately requeued for the same time
+   * interval.
+   *
+   * @param period Period in seconds to call the handler starting one period
+   *               after the call to this method.
+   */
+  void StartPeriodic(double period);
+
+  /**
+   * Stop timer events from occuring.
+   *
+   * Stop any repeating timer events from occuring. This will also remove any
+   * single notification events from the queue.
+   *
+   * If a timer-based call to the registered handler is in progress, this
+   * function will block until the handler call is complete.
+   */
+  void Stop();
+
+ private:
+  /**
+   * Update the HAL alarm time.
+   *
+   * @param triggerTime the time at which the next alarm will be triggered
+   */
+  void UpdateAlarm(uint64_t triggerTime);
+
+  /**
+   * Update the HAL alarm time based on m_expirationTime.
+   */
+  void UpdateAlarm();
+
+  // The thread waiting on the HAL alarm
+  std::thread m_thread;
+
+  // Held while updating process information
+  wpi::mutex m_processMutex;
+
+  // HAL handle, atomic for proper destruction
+  std::atomic<HAL_NotifierHandle> m_notifier{0};
+
+  // Address of the handler
+  TimerEventHandler m_handler;
+
+  // The absolute expiration time
+  double m_expirationTime = 0;
+
+  // The relative time (either periodic or single)
+  double m_period = 0;
+
+  // True if this is a periodic event
+  bool m_periodic = false;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDBase.h
new file mode 100644
index 0000000..f29b56e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDBase.h
@@ -0,0 +1,404 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+#include "frc/PIDInterface.h"
+#include "frc/PIDOutput.h"
+#include "frc/PIDSource.h"
+#include "frc/Timer.h"
+#include "frc/filters/LinearDigitalFilter.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Class implements a PID Control Loop.
+ *
+ * Creates a separate thread which reads the given PIDSource and takes care of
+ * the integral calculations, as well as writing the given PIDOutput.
+ *
+ * This feedback controller runs in discrete time, so time deltas are not used
+ * in the integral and derivative calculations. Therefore, the sample rate
+ * affects the controller's behavior for a given set of PID constants.
+ */
+class PIDBase : public SendableBase, public PIDInterface, public PIDOutput {
+ public:
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   */
+  PIDBase(double p, double i, double d, PIDSource& source, PIDOutput& output);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   */
+  PIDBase(double p, double i, double d, double f, PIDSource& source,
+          PIDOutput& output);
+
+  ~PIDBase() override = default;
+
+  PIDBase(PIDBase&&) = default;
+  PIDBase& operator=(PIDBase&&) = default;
+
+  /**
+   * Return the current PID result.
+   *
+   * This is always centered on zero and constrained the the max and min outs.
+   *
+   * @return the latest calculated output
+   */
+  virtual double Get() const;
+
+  /**
+   * Set the PID controller to consider the input to be continuous,
+   *
+   * Rather then using the max and min input range as constraints, it considers
+   * them to be the same point and automatically calculates the shortest route
+   * to the setpoint.
+   *
+   * @param continuous true turns on continuous, false turns off continuous
+   */
+  virtual void SetContinuous(bool continuous = true);
+
+  /**
+   * Sets the maximum and minimum values expected from the input.
+   *
+   * @param minimumInput the minimum value expected from the input
+   * @param maximumInput the maximum value expected from the output
+   */
+  virtual void SetInputRange(double minimumInput, double maximumInput);
+
+  /**
+   * Sets the minimum and maximum values to write.
+   *
+   * @param minimumOutput the minimum value to write to the output
+   * @param maximumOutput the maximum value to write to the output
+   */
+  virtual void SetOutputRange(double minimumOutput, double maximumOutput);
+
+  /**
+   * Set the PID Controller gain parameters.
+   *
+   * Set the proportional, integral, and differential coefficients.
+   *
+   * @param p Proportional coefficient
+   * @param i Integral coefficient
+   * @param d Differential coefficient
+   */
+  void SetPID(double p, double i, double d) override;
+
+  /**
+   * Set the PID Controller gain parameters.
+   *
+   * Set the proportional, integral, and differential coefficients.
+   *
+   * @param p Proportional coefficient
+   * @param i Integral coefficient
+   * @param d Differential coefficient
+   * @param f Feed forward coefficient
+   */
+  virtual void SetPID(double p, double i, double d, double f);
+
+  /**
+   * Set the Proportional coefficient of the PID controller gain.
+   *
+   * @param p proportional coefficient
+   */
+  void SetP(double p);
+
+  /**
+   * Set the Integral coefficient of the PID controller gain.
+   *
+   * @param i integral coefficient
+   */
+  void SetI(double i);
+
+  /**
+   * Set the Differential coefficient of the PID controller gain.
+   *
+   * @param d differential coefficient
+   */
+  void SetD(double d);
+
+  /**
+   * Get the Feed forward coefficient of the PID controller gain.
+   *
+   * @param f Feed forward coefficient
+   */
+  void SetF(double f);
+
+  /**
+   * Get the Proportional coefficient.
+   *
+   * @return proportional coefficient
+   */
+  double GetP() const override;
+
+  /**
+   * Get the Integral coefficient.
+   *
+   * @return integral coefficient
+   */
+  double GetI() const override;
+
+  /**
+   * Get the Differential coefficient.
+   *
+   * @return differential coefficient
+   */
+  double GetD() const override;
+
+  /**
+   * Get the Feed forward coefficient.
+   *
+   * @return Feed forward coefficient
+   */
+  virtual double GetF() const;
+
+  /**
+   * Set the setpoint for the PIDBase.
+   *
+   * @param setpoint the desired setpoint
+   */
+  void SetSetpoint(double setpoint) override;
+
+  /**
+   * Returns the current setpoint of the PIDBase.
+   *
+   * @return the current setpoint
+   */
+  double GetSetpoint() const override;
+
+  /**
+   * Returns the change in setpoint over time of the PIDBase.
+   *
+   * @return the change in setpoint over time
+   */
+  double GetDeltaSetpoint() const;
+
+  /**
+   * Returns the current difference of the input from the setpoint.
+   *
+   * @return the current error
+   */
+  virtual double GetError() const;
+
+  /**
+   * Returns the current average of the error over the past few iterations.
+   *
+   * You can specify the number of iterations to average with
+   * SetToleranceBuffer() (defaults to 1). This is the same value that is used
+   * for OnTarget().
+   *
+   * @return the average error
+   */
+  WPI_DEPRECATED("Use a LinearDigitalFilter as the input and GetError().")
+  virtual double GetAvgError() const;
+
+  /**
+   * Sets what type of input the PID controller will use.
+   */
+  virtual void SetPIDSourceType(PIDSourceType pidSource);
+
+  /**
+   * Returns the type of input the PID controller is using.
+   *
+   * @return the PID controller input type
+   */
+  virtual PIDSourceType GetPIDSourceType() const;
+
+  /**
+   * Set the percentage error which is considered tolerable for use with
+   * OnTarget.
+   *
+   * @param percentage error which is tolerable
+   */
+  WPI_DEPRECATED("Use SetPercentTolerance() instead.")
+  virtual void SetTolerance(double percent);
+
+  /**
+   * Set the absolute error which is considered tolerable for use with
+   * OnTarget.
+   *
+   * @param percentage error which is tolerable
+   */
+  virtual void SetAbsoluteTolerance(double absValue);
+
+  /**
+   * Set the percentage error which is considered tolerable for use with
+   * OnTarget.
+   *
+   * @param percentage error which is tolerable
+   */
+  virtual void SetPercentTolerance(double percentValue);
+
+  /**
+   * Set the number of previous error samples to average for tolerancing. When
+   * determining whether a mechanism is on target, the user may want to use a
+   * rolling average of previous measurements instead of a precise position or
+   * velocity. This is useful for noisy sensors which return a few erroneous
+   * measurements when the mechanism is on target. However, the mechanism will
+   * not register as on target for at least the specified bufLength cycles.
+   *
+   * @param bufLength Number of previous cycles to average. Defaults to 1.
+   */
+  WPI_DEPRECATED("Use a LinearDigitalFilter as the input.")
+  virtual void SetToleranceBuffer(int buf = 1);
+
+  /**
+   * Return true if the error is within the percentage of the total input range,
+   * determined by SetTolerance. This asssumes that the maximum and minimum
+   * input were set using SetInput.
+   *
+   * Currently this just reports on target as the actual value passes through
+   * the setpoint. Ideally it should be based on being within the tolerance for
+   * some period of time.
+   *
+   * This will return false until at least one input value has been computed.
+   */
+  virtual bool OnTarget() const;
+
+  /**
+   * Reset the previous error, the integral term, and disable the controller.
+   */
+  void Reset() override;
+
+  /**
+   * Passes the output directly to SetSetpoint().
+   *
+   * PIDControllers can be nested by passing a PIDController as another
+   * PIDController's output. In that case, the output of the parent controller
+   * becomes the input (i.e., the reference) of the child.
+   *
+   * It is the caller's responsibility to put the data into a valid form for
+   * SetSetpoint().
+   */
+  void PIDWrite(double output) override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ protected:
+  // Is the pid controller enabled
+  bool m_enabled = false;
+
+  mutable wpi::mutex m_thisMutex;
+
+  // Ensures when Disable() is called, PIDWrite() won't run if Calculate()
+  // is already running at that time.
+  mutable wpi::mutex m_pidWriteMutex;
+
+  PIDSource* m_pidInput;
+  PIDOutput* m_pidOutput;
+  Timer m_setpointTimer;
+
+  /**
+   * Read the input, calculate the output accordingly, and write to the output.
+   * This should only be called by the Notifier.
+   */
+  virtual void Calculate();
+
+  /**
+   * Calculate the feed forward term.
+   *
+   * Both of the provided feed forward calculations are velocity feed forwards.
+   * If a different feed forward calculation is desired, the user can override
+   * this function and provide his or her own. This function does no
+   * synchronization because the PIDBase class only calls it in synchronized
+   * code, so be careful if calling it oneself.
+   *
+   * If a velocity PID controller is being used, the F term should be set to 1
+   * over the maximum setpoint for the output. If a position PID controller is
+   * being used, the F term should be set to 1 over the maximum speed for the
+   * output measured in setpoint units per this controller's update period (see
+   * the default period in this class's constructor).
+   */
+  virtual double CalculateFeedForward();
+
+  /**
+   * Wraps error around for continuous inputs. The original error is returned if
+   * continuous mode is disabled. This is an unsynchronized function.
+   *
+   * @param error The current error of the PID controller.
+   * @return Error for continuous inputs.
+   */
+  double GetContinuousError(double error) const;
+
+ private:
+  // Factor for "proportional" control
+  double m_P;
+
+  // Factor for "integral" control
+  double m_I;
+
+  // Factor for "derivative" control
+  double m_D;
+
+  // Factor for "feed forward" control
+  double m_F;
+
+  // |maximum output|
+  double m_maximumOutput = 1.0;
+
+  // |minimum output|
+  double m_minimumOutput = -1.0;
+
+  // Maximum input - limit setpoint to this
+  double m_maximumInput = 0;
+
+  // Minimum input - limit setpoint to this
+  double m_minimumInput = 0;
+
+  // input range - difference between maximum and minimum
+  double m_inputRange = 0;
+
+  // Do the endpoints wrap around? eg. Absolute encoder
+  bool m_continuous = false;
+
+  // The prior error (used to compute velocity)
+  double m_prevError = 0;
+
+  // The sum of the errors for use in the integral calc
+  double m_totalError = 0;
+
+  enum {
+    kAbsoluteTolerance,
+    kPercentTolerance,
+    kNoTolerance
+  } m_toleranceType = kNoTolerance;
+
+  // The percetage or absolute error that is considered on target.
+  double m_tolerance = 0.05;
+
+  double m_setpoint = 0;
+  double m_prevSetpoint = 0;
+  double m_error = 0;
+  double m_result = 0;
+
+  std::shared_ptr<PIDSource> m_origSource;
+  LinearDigitalFilter m_filter{nullptr, {}, {}};
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDController.h
new file mode 100644
index 0000000..e9eea8b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDController.h
@@ -0,0 +1,137 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+#include "frc/Controller.h"
+#include "frc/Notifier.h"
+#include "frc/PIDBase.h"
+#include "frc/PIDSource.h"
+#include "frc/Timer.h"
+#include "frc/filters/LinearDigitalFilter.h"
+
+namespace frc {
+
+class PIDOutput;
+
+/**
+ * Class implements a PID Control Loop.
+ *
+ * Creates a separate thread which reads the given PIDSource and takes care of
+ * the integral calculations, as well as writing the given PIDOutput.
+ *
+ * This feedback controller runs in discrete time, so time deltas are not used
+ * in the integral and derivative calculations. Therefore, the sample rate
+ * affects the controller's behavior for a given set of PID constants.
+ */
+class PIDController : public PIDBase, public Controller {
+ public:
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   * @param period the loop time for doing calculations in seconds. This
+   *               particularly affects calculations of the integral and
+   *               differental terms. The default is 0.05 (50ms).
+   */
+  PIDController(double p, double i, double d, PIDSource* source,
+                PIDOutput* output, double period = 0.05);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   * @param period the loop time for doing calculations in seconds. This
+   *               particularly affects calculations of the integral and
+   *               differental terms. The default is 0.05 (50ms).
+   */
+  PIDController(double p, double i, double d, double f, PIDSource* source,
+                PIDOutput* output, double period = 0.05);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   * @param period the loop time for doing calculations in seconds. This
+   *               particularly affects calculations of the integral and
+   *               differental terms. The default is 0.05 (50ms).
+   */
+  PIDController(double p, double i, double d, PIDSource& source,
+                PIDOutput& output, double period = 0.05);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output value
+   * @param period the loop time for doing calculations in seconds. This
+   *               particularly affects calculations of the integral and
+   *               differental terms. The default is 0.05 (50ms).
+   */
+  PIDController(double p, double i, double d, double f, PIDSource& source,
+                PIDOutput& output, double period = 0.05);
+
+  ~PIDController() override;
+
+  PIDController(PIDController&&) = default;
+  PIDController& operator=(PIDController&&) = default;
+
+  /**
+   * Begin running the PIDController.
+   */
+  void Enable() override;
+
+  /**
+   * Stop running the PIDController, this sets the output to zero before
+   * stopping.
+   */
+  void Disable() override;
+
+  /**
+   * Set the enabled state of the PIDController.
+   */
+  void SetEnabled(bool enable);
+
+  /**
+   * Return true if PIDController is enabled.
+   */
+  bool IsEnabled() const;
+
+  /**
+   * Reset the previous error, the integral term, and disable the controller.
+   */
+  void Reset() override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  std::unique_ptr<Notifier> m_controlLoop;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDInterface.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDInterface.h
new file mode 100644
index 0000000..72d8beb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDInterface.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+class PIDInterface {
+ public:
+  PIDInterface() = default;
+  PIDInterface(PIDInterface&&) = default;
+  PIDInterface& operator=(PIDInterface&&) = default;
+
+  virtual void SetPID(double p, double i, double d) = 0;
+  virtual double GetP() const = 0;
+  virtual double GetI() const = 0;
+  virtual double GetD() const = 0;
+
+  virtual void SetSetpoint(double setpoint) = 0;
+  virtual double GetSetpoint() const = 0;
+
+  virtual void Reset() = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDOutput.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDOutput.h
new file mode 100644
index 0000000..37fb2a1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDOutput.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/Base.h"
+
+namespace frc {
+
+/**
+ * PIDOutput interface is a generic output for the PID class.
+ *
+ * PWMs use this class. Users implement this interface to allow for a
+ * PIDController to read directly from the inputs.
+ */
+class PIDOutput {
+ public:
+  virtual void PIDWrite(double output) = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDSource.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDSource.h
new file mode 100644
index 0000000..1a807b1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PIDSource.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+enum class PIDSourceType { kDisplacement, kRate };
+
+/**
+ * PIDSource interface is a generic sensor source for the PID class.
+ *
+ * All sensors that can be used with the PID class will implement the PIDSource
+ * that returns a standard value that will be used in the PID code.
+ */
+class PIDSource {
+ public:
+  virtual ~PIDSource() = default;
+
+  /**
+   * Set which parameter you are using as a process control variable.
+   *
+   * @param pidSource An enum to select the parameter.
+   */
+  virtual void SetPIDSourceType(PIDSourceType pidSource);
+
+  virtual PIDSourceType GetPIDSourceType() const;
+
+  virtual double PIDGet() = 0;
+
+ protected:
+  PIDSourceType m_pidSource = PIDSourceType::kDisplacement;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWM.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWM.h
new file mode 100644
index 0000000..99f213e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWM.h
@@ -0,0 +1,237 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <hal/Types.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/MotorSafety.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Class implements the PWM generation in the FPGA.
+ *
+ * The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They
+ * are mapped to the hardware dependent values, in this case 0-2000 for the
+ * FPGA. Changes are immediately sent to the FPGA, and the update occurs at the
+ * next FPGA cycle (5.005ms). There is no delay.
+ *
+ * As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-2000 values as
+ * follows:
+ *   - 2000 = maximum pulse width
+ *   - 1999 to 1001 = linear scaling from "full forward" to "center"
+ *   - 1000 = center value
+ *   - 999 to 2 = linear scaling from "center" to "full reverse"
+ *   - 1 = minimum pulse width (currently .5ms)
+ *   - 0 = disabled (i.e. PWM output is held low)
+ */
+class PWM : public MotorSafety, public SendableBase {
+ public:
+  /**
+   * Represents the amount to multiply the minimum servo-pulse pwm period by.
+   */
+  enum PeriodMultiplier {
+    /**
+     * Don't skip pulses. PWM pulses occur every 5.005 ms
+     */
+    kPeriodMultiplier_1X = 1,
+    /**
+     * Skip every other pulse. PWM pulses occur every 10.010 ms
+     */
+    kPeriodMultiplier_2X = 2,
+    /**
+     * Skip three out of four pulses. PWM pulses occur every 20.020 ms
+     */
+    kPeriodMultiplier_4X = 4
+  };
+
+  /**
+   * Allocate a PWM given a channel number.
+   *
+   * Checks channel value range and allocates the appropriate channel.
+   * The allocation is only done to help users ensure that they don't double
+   * assign channels.
+   *
+   * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the
+   *                MXP port
+   */
+  explicit PWM(int channel);
+
+  /**
+   * Free the PWM channel.
+   *
+   * Free the resource associated with the PWM channel and set the value to 0.
+   */
+  ~PWM() override;
+
+  PWM(PWM&& rhs);
+  PWM& operator=(PWM&& rhs);
+
+  // MotorSafety interface
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  /**
+   * Set the PWM value directly to the hardware.
+   *
+   * Write a raw value to a PWM channel.
+   *
+   * @param value Raw PWM value.
+   */
+  virtual void SetRaw(uint16_t value);
+
+  /**
+   * Get the PWM value directly from the hardware.
+   *
+   * Read a raw value from a PWM channel.
+   *
+   * @return Raw PWM control value.
+   */
+  virtual uint16_t GetRaw() const;
+
+  /**
+   * Set the PWM value based on a position.
+   *
+   * This is intended to be used by servos.
+   *
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinNegativePwm() called.
+   *
+   * @param pos The position to set the servo between 0.0 and 1.0.
+   */
+  virtual void SetPosition(double pos);
+
+  /**
+   * Get the PWM value in terms of a position.
+   *
+   * This is intended to be used by servos.
+   *
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinNegativePwm() called.
+   *
+   * @return The position the servo is set to between 0.0 and 1.0.
+   */
+  virtual double GetPosition() const;
+
+  /**
+   * Set the PWM value based on a speed.
+   *
+   * This is intended to be used by speed controllers.
+   *
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinPositivePwm() called.
+   * @pre SetCenterPwm() called.
+   * @pre SetMaxNegativePwm() called.
+   * @pre SetMinNegativePwm() called.
+   *
+   * @param speed The speed to set the speed controller between -1.0 and 1.0.
+   */
+  virtual void SetSpeed(double speed);
+
+  /**
+   * Get the PWM value in terms of speed.
+   *
+   * This is intended to be used by speed controllers.
+   *
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinPositivePwm() called.
+   * @pre SetMaxNegativePwm() called.
+   * @pre SetMinNegativePwm() called.
+   *
+   * @return The most recently set speed between -1.0 and 1.0.
+   */
+  virtual double GetSpeed() const;
+
+  /**
+   * Temporarily disables the PWM output. The next set call will reenable
+   * the output.
+   */
+  virtual void SetDisabled();
+
+  /**
+   * Slow down the PWM signal for old devices.
+   *
+   * @param mult The period multiplier to apply to this channel
+   */
+  void SetPeriodMultiplier(PeriodMultiplier mult);
+
+  void SetZeroLatch();
+
+  /**
+   * Optionally eliminate the deadband from a speed controller.
+   *
+   * @param eliminateDeadband If true, set the motor curve on the Jaguar to
+   *                          eliminate the deadband in the middle of the range.
+   *                          Otherwise, keep the full range without modifying
+   *                          any values.
+   */
+  void EnableDeadbandElimination(bool eliminateDeadband);
+
+  /**
+   * Set the bounds on the PWM pulse widths.
+   *
+   * This sets the bounds on the PWM values for a particular type of controller.
+   * The values determine the upper and lower speeds as well as the deadband
+   * bracket.
+   *
+   * @param max         The max PWM pulse width in ms
+   * @param deadbandMax The high end of the deadband range pulse width in ms
+   * @param center      The center (off) pulse width in ms
+   * @param deadbandMin The low end of the deadband pulse width in ms
+   * @param min         The minimum pulse width in ms
+   */
+  void SetBounds(double max, double deadbandMax, double center,
+                 double deadbandMin, double min);
+
+  /**
+   * Set the bounds on the PWM values.
+   *
+   * This sets the bounds on the PWM values for a particular each type of
+   * controller. The values determine the upper and lower speeds as well as the
+   * deadband bracket.
+   *
+   * @param max         The Minimum pwm value
+   * @param deadbandMax The high end of the deadband range
+   * @param center      The center speed (off)
+   * @param deadbandMin The low end of the deadband range
+   * @param min         The minimum pwm value
+   */
+  void SetRawBounds(int max, int deadbandMax, int center, int deadbandMin,
+                    int min);
+
+  /**
+   * Get the bounds on the PWM values.
+   *
+   * This Gets the bounds on the PWM values for a particular each type of
+   * controller. The values determine the upper and lower speeds as well as the
+   * deadband bracket.
+   *
+   * @param max         The Minimum pwm value
+   * @param deadbandMax The high end of the deadband range
+   * @param center      The center speed (off)
+   * @param deadbandMin The low end of the deadband range
+   * @param min         The minimum pwm value
+   */
+  void GetRawBounds(int32_t* max, int32_t* deadbandMax, int32_t* center,
+                    int32_t* deadbandMin, int32_t* min);
+
+  int GetChannel() const;
+
+ protected:
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  HAL_DigitalHandle m_handle = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMSpeedController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMSpeedController.h
new file mode 100644
index 0000000..5222559
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMSpeedController.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWM.h"
+#include "frc/SpeedController.h"
+
+namespace frc {
+
+/**
+ * Common base class for all PWM Speed Controllers.
+ */
+class PWMSpeedController : public PWM, public SpeedController {
+ public:
+  PWMSpeedController(PWMSpeedController&&) = default;
+  PWMSpeedController& operator=(PWMSpeedController&&) = default;
+
+  /**
+   * Set the PWM value.
+   *
+   * The PWM value is set using a range of -1.0 to 1.0, appropriately scaling
+   * the value for the FPGA.
+   *
+   * @param speed The speed value between -1.0 and 1.0 to set.
+   */
+  void Set(double value) override;
+
+  /**
+   * Get the recently set value of the PWM.
+   *
+   * @return The most recently set value for the PWM between -1.0 and 1.0.
+   */
+  double Get() const override;
+
+  void SetInverted(bool isInverted) override;
+
+  bool GetInverted() const override;
+
+  void Disable() override;
+
+  void StopMotor() override;
+
+  /**
+   * Write out the PID value as seen in the PIDOutput base object.
+   *
+   * @param output Write out the PWM value as was found in the PIDController
+   */
+  void PIDWrite(double output) override;
+
+ protected:
+  /**
+   * Constructor for a PWM Speed Controller connected via PWM.
+   *
+   * @param channel The PWM channel that the controller is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit PWMSpeedController(int channel);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  bool m_isInverted = false;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMTalonSRX.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMTalonSRX.h
new file mode 100644
index 0000000..9260e1e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMTalonSRX.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM
+ * control.
+ */
+class PWMTalonSRX : public PWMSpeedController {
+ public:
+  /**
+   * Construct a PWMTalonSRX connected via PWM.
+   *
+   * @param channel The PWM channel that the PWMTalonSRX is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit PWMTalonSRX(int channel);
+
+  PWMTalonSRX(PWMTalonSRX&&) = default;
+  PWMTalonSRX& operator=(PWMTalonSRX&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMVictorSPX.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMVictorSPX.h
new file mode 100644
index 0000000..d7112c9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PWMVictorSPX.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Victor SPX Speed Controller with PWM
+ * control.
+ */
+class PWMVictorSPX : public PWMSpeedController {
+ public:
+  /**
+   * Construct a PWMVictorSPX connected via PWM.
+   *
+   * @param channel The PWM channel that the PWMVictorSPX is attached to. 0-9
+   *                are on-board, 10-19 are on the MXP port
+   */
+  explicit PWMVictorSPX(int channel);
+
+  PWMVictorSPX(PWMVictorSPX&&) = default;
+  PWMVictorSPX& operator=(PWMVictorSPX&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h
new file mode 100644
index 0000000..2d7f65c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/PowerDistributionPanel.h
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Class for getting voltage, current, temperature, power and energy from the
+ * CAN PDP.
+ */
+class PowerDistributionPanel : public ErrorBase, public SendableBase {
+ public:
+  PowerDistributionPanel();
+  explicit PowerDistributionPanel(int module);
+
+  PowerDistributionPanel(PowerDistributionPanel&&) = default;
+  PowerDistributionPanel& operator=(PowerDistributionPanel&&) = default;
+
+  /**
+   * Query the input voltage of the PDP.
+   *
+   * @return The voltage of the PDP in volts
+   */
+  double GetVoltage() const;
+
+  /**
+   * Query the temperature of the PDP.
+   *
+   * @return The temperature of the PDP in degrees Celsius
+   */
+  double GetTemperature() const;
+
+  /**
+   * Query the current of a single channel of the PDP.
+   *
+   * @return The current of one of the PDP channels (channels 0-15) in Amperes
+   */
+  double GetCurrent(int channel) const;
+
+  /**
+   * Query the total current of all monitored PDP channels (0-15).
+   *
+   * @return The the total current drawn from the PDP channels in Amperes
+   */
+  double GetTotalCurrent() const;
+
+  /**
+   * Query the total power drawn from the monitored PDP channels.
+   *
+   * @return The the total power drawn from the PDP channels in Watts
+   */
+  double GetTotalPower() const;
+
+  /**
+   * Query the total energy drawn from the monitored PDP channels.
+   *
+   * @return The the total energy drawn from the PDP channels in Joules
+   */
+  double GetTotalEnergy() const;
+
+  /**
+   * Reset the total energy drawn from the PDP.
+   *
+   * @see PowerDistributionPanel#GetTotalEnergy
+   */
+  void ResetTotalEnergy();
+
+  /**
+   * Remove all of the fault flags on the PDP.
+   */
+  void ClearStickyFaults();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  HAL_PDPHandle m_handle = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Preferences.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Preferences.h
new file mode 100644
index 0000000..57678a8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Preferences.h
@@ -0,0 +1,206 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTable.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * The preferences class provides a relatively simple way to save important
+ * values to the roboRIO to access the next time the roboRIO is booted.
+ *
+ * This class loads and saves from a file inside the roboRIO.  The user cannot
+ * access the file directly, but may modify values at specific fields which will
+ * then be automatically periodically saved to the file by the NetworkTable
+ * server.
+ *
+ * This class is thread safe.
+ *
+ * This will also interact with {@link NetworkTable} by creating a table called
+ * "Preferences" with all the key-value pairs.
+ */
+class Preferences : public ErrorBase {
+ public:
+  /**
+   * Get the one and only {@link Preferences} object.
+   *
+   * @return pointer to the {@link Preferences}
+   */
+  static Preferences* GetInstance();
+
+  /**
+   * Returns a vector of all the keys.
+   *
+   * @return a vector of the keys
+   */
+  std::vector<std::string> GetKeys();
+
+  /**
+   * Returns the string at the given key.  If this table does not have a value
+   * for that position, then the given defaultValue will be returned.
+   *
+   * @param key          the key
+   * @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(wpi::StringRef key, wpi::StringRef defaultValue = "");
+
+  /**
+   * Returns the int at the given key.  If this table does not have a value for
+   * that position, then the given defaultValue value will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  int GetInt(wpi::StringRef key, int defaultValue = 0);
+
+  /**
+   * Returns the double at the given key.  If this table does not have a value
+   * for that position, then the given defaultValue value will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  double GetDouble(wpi::StringRef key, double defaultValue = 0.0);
+
+  /**
+   * Returns the float at the given key.  If this table does not have a value
+   * for that position, then the given defaultValue value will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  float GetFloat(wpi::StringRef key, float defaultValue = 0.0);
+
+  /**
+   * Returns the boolean at the given key.  If this table does not have a value
+   * for that position, then the given defaultValue value will be returned.
+   *
+   * @param key          the key
+   * @param defaultValue the value to return if none exists in the table
+   * @return either the value in the table, or the defaultValue
+   */
+  bool GetBoolean(wpi::StringRef key, bool defaultValue = false);
+
+  /**
+   * Returns the long (int64_t) at the given key.  If this table does not have a
+   * value for that position, then the given defaultValue value will be
+   * returned.
+   *
+   * @param key          the key
+   * @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(wpi::StringRef key, int64_t defaultValue = 0);
+
+  /**
+   * Puts the given string into the preferences table.
+   *
+   * The value may not have quotation marks, nor may the key have any whitespace
+   * nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutString(wpi::StringRef key, wpi::StringRef value);
+
+  /**
+   * Puts the given int into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutInt(wpi::StringRef key, int value);
+
+  /**
+   * Puts the given double into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutDouble(wpi::StringRef key, double value);
+
+  /**
+   * Puts the given float into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutFloat(wpi::StringRef key, float value);
+
+  /**
+   * Puts the given boolean into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutBoolean(wpi::StringRef key, bool value);
+
+  /**
+   * Puts the given long (int64_t) into the preferences table.
+   *
+   * The key may not have any whitespace nor an equals sign.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  void PutLong(wpi::StringRef key, int64_t value);
+
+  /**
+   * Returns whether or not there is a key with the given name.
+   *
+   * @param key the key
+   * @return if there is a value at the given key
+   */
+  bool ContainsKey(wpi::StringRef key);
+
+  /**
+   * Remove a preference.
+   *
+   * @param key the key
+   */
+  void Remove(wpi::StringRef key);
+
+  /**
+   * Remove all preferences.
+   */
+  void RemoveAll();
+
+ protected:
+  Preferences();
+  virtual ~Preferences() = default;
+
+  Preferences(Preferences&&) = default;
+  Preferences& operator=(Preferences&&) = default;
+
+ private:
+  std::shared_ptr<nt::NetworkTable> m_table;
+  NT_EntryListener m_listener;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Relay.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Relay.h
new file mode 100644
index 0000000..6fb21b5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Relay.h
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <hal/Types.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/MotorSafety.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * Class for Spike style relay outputs.
+ *
+ * Relays are intended to be connected to spikes or similar relays. The relay
+ * channels controls a pair of pins that are either both off, one on, the other
+ * on, or both on. This translates into two spike outputs at 0v, one at 12v and
+ * one at 0v, one at 0v and the other at 12v, or two spike outputs at 12V. This
+ * allows off, full forward, or full reverse control of motors without variable
+ * speed. It also allows the two channels (forward and reverse) to be used
+ * independently for something that does not care about voltage polarity (like
+ * a solenoid).
+ */
+class Relay : public MotorSafety, public SendableBase {
+ public:
+  enum Value { kOff, kOn, kForward, kReverse };
+  enum Direction { kBothDirections, kForwardOnly, kReverseOnly };
+
+  /**
+   * Relay constructor given a channel.
+   *
+   * This code initializes the relay and reserves all resources that need to be
+   * locked. Initially the relay is set to both lines at 0v.
+   *
+   * @param channel   The channel number (0-3).
+   * @param direction The direction that the Relay object will control.
+   */
+  explicit Relay(int channel, Direction direction = kBothDirections);
+
+  /**
+   * Free the resource associated with a relay.
+   *
+   * The relay channels are set to free and the relay output is turned off.
+   */
+  ~Relay() override;
+
+  Relay(Relay&& rhs);
+  Relay& operator=(Relay&& rhs);
+
+  /**
+   * Set the relay state.
+   *
+   * Valid values depend on which directions of the relay are controlled by the
+   * object.
+   *
+   * When set to kBothDirections, the relay can be any of the four states:
+   * 0v-0v, 0v-12v, 12v-0v, 12v-12v
+   *
+   * When set to kForwardOnly or kReverseOnly, you can specify the constant for
+   * the direction or you can simply specify kOff and kOn.  Using only kOff and
+   * kOn is recommended.
+   *
+   * @param value The state to set the relay.
+   */
+  void Set(Value value);
+
+  /**
+   * Get the Relay State
+   *
+   * Gets the current state of the relay.
+   *
+   * When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff not
+   * kForward/kReverse (per the recommendation in Set).
+   *
+   * @return The current state of the relay as a Relay::Value
+   */
+  Value Get() const;
+
+  int GetChannel() const;
+
+  // MotorSafety interface
+  void StopMotor() override;
+
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  int m_channel;
+  Direction m_direction;
+
+  HAL_RelayHandle m_forwardHandle = HAL_kInvalidHandle;
+  HAL_RelayHandle m_reverseHandle = HAL_kInvalidHandle;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Resource.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Resource.h
new file mode 100644
index 0000000..9df2196
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Resource.h
@@ -0,0 +1,95 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <wpi/mutex.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * The Resource class is a convenient way to track allocated resources.
+ *
+ * It tracks them as indicies in the range [0 .. elements - 1]. E.g. the library
+ * uses this to track hardware channel allocation.
+ *
+ * The Resource class does not allocate the hardware channels or other
+ * resources; it just tracks which indices were marked in use by Allocate and
+ * not yet freed by Free.
+ */
+class Resource : public ErrorBase {
+ public:
+  virtual ~Resource() = default;
+
+  Resource(Resource&&) = default;
+  Resource& operator=(Resource&&) = default;
+
+  /**
+   * Factory method to create a Resource allocation-tracker *if* needed.
+   *
+   * @param r        address of the caller's Resource pointer. If *r == nullptr,
+   *                 this will construct a Resource and make *r point to it. If
+   *                 *r != nullptr, i.e. the caller already has a Resource
+   *                 instance, this won't do anything.
+   * @param elements the number of elements for this Resource allocator to
+   *                 track, that is, it will allocate resource numbers in the
+   *                 range [0 .. elements - 1].
+   */
+  static void CreateResourceObject(std::unique_ptr<Resource>& r,
+                                   uint32_t elements);
+
+  /**
+   * Allocate storage for a new instance of Resource.
+   *
+   * Allocate a bool array of values that will get initialized to indicate that
+   * no resources have been allocated yet. The indicies of the resources are
+   * [0 .. elements - 1].
+   */
+  explicit Resource(uint32_t size);
+
+  /**
+   * Allocate a resource.
+   *
+   * When a resource is requested, mark it allocated. In this case, a free
+   * resource value within the range is located and returned after it is marked
+   * allocated.
+   */
+  uint32_t Allocate(const std::string& resourceDesc);
+
+  /**
+   * Allocate a specific resource value.
+   *
+   * The user requests a specific resource value, i.e. channel number and it is
+   * verified unallocated, then returned.
+   */
+  uint32_t Allocate(uint32_t index, const std::string& resourceDesc);
+
+  /**
+   * Free an allocated resource.
+   *
+   * After a resource is no longer needed, for example a destructor is called
+   * for a channel assignment class, Free will release the resource value so it
+   * can be reused somewhere else in the program.
+   */
+  void Free(uint32_t index);
+
+ private:
+  std::vector<bool> m_isAllocated;
+  wpi::mutex m_allocateMutex;
+
+  static wpi::mutex m_createMutex;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotBase.h
new file mode 100644
index 0000000..eee07d6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotBase.h
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <thread>
+
+#include <wpi/raw_ostream.h>
+
+#include "frc/Base.h"
+
+namespace frc {
+
+class DriverStation;
+
+int RunHALInitialization();
+
+template <class Robot>
+int StartRobot() {
+  int halInit = RunHALInitialization();
+  if (halInit != 0) {
+    return halInit;
+  }
+  static Robot robot;
+  robot.StartCompetition();
+
+  return 0;
+}
+
+#define START_ROBOT_CLASS(_ClassName_)                                 \
+  WPI_DEPRECATED("Call frc::StartRobot<" #_ClassName_                  \
+                 ">() in your own main() instead of using the "        \
+                 "START_ROBOT_CLASS(" #_ClassName_ ") macro.")         \
+  int StartRobotClassImpl() { return frc::StartRobot<_ClassName_>(); } \
+  int main() { return StartRobotClassImpl(); }
+
+/**
+ * Implement a Robot Program framework.
+ *
+ * The RobotBase class is intended to be subclassed by a user creating a robot
+ * program. Overridden Autonomous() and OperatorControl() methods are called at
+ * the appropriate time as the match proceeds. In the current implementation,
+ * the Autonomous code will run to completion before the OperatorControl code
+ * could start. In the future the Autonomous code might be spawned as a task,
+ * then killed at the end of the Autonomous period.
+ */
+class RobotBase {
+ public:
+  /**
+   * Determine if the Robot is currently enabled.
+   *
+   * @return True if the Robot is currently enabled by the field controls.
+   */
+  bool IsEnabled() const;
+
+  /**
+   * Determine if the Robot is currently disabled.
+   *
+   * @return True if the Robot is currently disabled by the field controls.
+   */
+  bool IsDisabled() const;
+
+  /**
+   * Determine if the robot is currently in Autonomous mode.
+   *
+   * @return True if the robot is currently operating Autonomously as determined
+   *         by the field controls.
+   */
+  bool IsAutonomous() const;
+
+  /**
+   * Determine if the robot is currently in Operator Control mode.
+   *
+   * @return True if the robot is currently operating in Tele-Op mode as
+   *         determined by the field controls.
+   */
+  bool IsOperatorControl() const;
+
+  /**
+   * Determine if the robot is currently in Test mode.
+   *
+   * @return True if the robot is currently running tests as determined by the
+   *         field controls.
+   */
+  bool IsTest() const;
+
+  /**
+   * Indicates if new data is available from the driver station.
+   *
+   * @return Has new data arrived over the network since the last time this
+   *         function was called?
+   */
+  bool IsNewDataAvailable() const;
+
+  /**
+   * Gets the ID of the main robot thread.
+   */
+  static std::thread::id GetThreadId();
+
+  virtual void StartCompetition() = 0;
+
+  static constexpr bool IsReal() {
+#ifdef __FRC_ROBORIO__
+    return true;
+#else
+    return false;
+#endif
+  }
+
+  static constexpr bool IsSimulation() { return !IsReal(); }
+
+ protected:
+  /**
+   * 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
+   * completion before Autonomous is entered.
+   *
+   * This must be used to ensure that the communications code starts. In the
+   * future it would be nice to put this code into it's own task that loads on
+   * boot so ensure that it runs.
+   */
+  RobotBase();
+
+  virtual ~RobotBase();
+
+  // 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&&);
+  RobotBase& operator=(RobotBase&&);
+
+  DriverStation& m_ds;
+
+  static std::thread::id m_threadId;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotController.h
new file mode 100644
index 0000000..fae136b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotController.h
@@ -0,0 +1,188 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+namespace frc {
+
+struct CANStatus {
+  float percentBusUtilization;
+  int busOffCount;
+  int txFullCount;
+  int receiveErrorCount;
+  int transmitErrorCount;
+};
+
+class RobotController {
+ public:
+  RobotController() = delete;
+
+  /**
+   * Return the FPGA Version number.
+   *
+   * For now, expect this to be competition year.
+   *
+   * @return FPGA Version number.
+   */
+  static int GetFPGAVersion();
+
+  /**
+   * Return the FPGA Revision number.
+   *
+   * The format of the revision is 3 numbers. The 12 most significant bits are
+   * the Major Revision. The next 8 bits are the Minor Revision. The 12 least
+   * significant bits are the Build Number.
+   *
+   * @return FPGA Revision number.
+   */
+  static int64_t GetFPGARevision();
+
+  /**
+   * Read the microsecond-resolution timer on the FPGA.
+   *
+   * @return The current time in microseconds according to the FPGA (since FPGA
+   *         reset).
+   */
+  static uint64_t GetFPGATime();
+
+  /**
+   * Get the state of the "USER" button on the roboRIO.
+   *
+   * @return True if the button is currently pressed down
+   */
+  static bool GetUserButton();
+
+  /**
+   * Check if the FPGA outputs are enabled.
+   *
+   * The outputs may be disabled if the robot is disabled or e-stopped, the
+   * watchdog has expired, or if the roboRIO browns out.
+   *
+   * @return True if the FPGA outputs are enabled.
+   */
+  static bool IsSysActive();
+
+  /**
+   * Check if the system is browned out.
+   *
+   * @return True if the system is browned out
+   */
+  static bool IsBrownedOut();
+
+  /**
+   * Get the input voltage to the robot controller.
+   *
+   * @return The controller input voltage value in Volts
+   */
+  static double GetInputVoltage();
+
+  /**
+   * Get the input current to the robot controller.
+   *
+   * @return The controller input current value in Amps
+   */
+  static double GetInputCurrent();
+
+  /**
+   * Get the voltage of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail voltage value in Volts
+   */
+  static double GetVoltage3V3();
+
+  /**
+   * Get the current output of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail output current value in Amps
+   */
+  static double GetCurrent3V3();
+
+  /**
+   * Get the enabled state of the 3.3V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 3.3V rail enabled value. True for enabled.
+   */
+  static bool GetEnabled3V3();
+
+  /**
+   * Get the count of the total current faults on the 3.3V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults
+   */
+  static int GetFaultCount3V3();
+
+  /**
+   * Get the voltage of the 5V rail.
+   *
+   * @return The controller 5V rail voltage value in Volts
+   */
+  static double GetVoltage5V();
+
+  /**
+   * Get the current output of the 5V rail.
+   *
+   * @return The controller 5V rail output current value in Amps
+   */
+  static double GetCurrent5V();
+
+  /**
+   * Get the enabled state of the 5V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 5V rail enabled value. True for enabled.
+   */
+  static bool GetEnabled5V();
+
+  /**
+   * Get the count of the total current faults on the 5V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults
+   */
+  static int GetFaultCount5V();
+
+  /**
+   * Get the voltage of the 6V rail.
+   *
+   * @return The controller 6V rail voltage value in Volts
+   */
+  static double GetVoltage6V();
+
+  /**
+   * Get the current output of the 6V rail.
+   *
+   * @return The controller 6V rail output current value in Amps
+   */
+  static double GetCurrent6V();
+
+  /**
+   * Get the enabled state of the 6V rail. The rail may be disabled due to a
+   * controller brownout, a short circuit on the rail, or controller
+   * over-voltage.
+   *
+   * @return The controller 6V rail enabled value. True for enabled.
+   */
+  static bool GetEnabled6V();
+
+  /**
+   * Get the count of the total current faults on the 6V rail since the
+   * controller has booted.
+   *
+   * @return The number of faults.
+   */
+  static int GetFaultCount6V();
+
+  static CANStatus GetCANStatus();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotDrive.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotDrive.h
new file mode 100644
index 0000000..3580003
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotDrive.h
@@ -0,0 +1,453 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/deprecated.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/MotorSafety.h"
+
+namespace frc {
+
+class SpeedController;
+class GenericHID;
+
+/**
+ * Utility class for handling Robot drive based on a definition of the motor
+ * configuration.
+ *
+ * The robot drive class handles basic driving for a robot. Currently, 2 and 4
+ * motor tank and mecanum drive trains are supported. In the future other drive
+ * types like swerve might be implemented. Motor channel numbers are passed
+ * supplied on creation of the class. Those are used for either the Drive
+ * function (intended for hand created drive code, such as autonomous) or with
+ * the Tank/Arcade functions intended to be used for Operator Control driving.
+ */
+class RobotDrive : public MotorSafety {
+ public:
+  enum MotorType {
+    kFrontLeftMotor = 0,
+    kFrontRightMotor = 1,
+    kRearLeftMotor = 2,
+    kRearRightMotor = 3
+  };
+
+  /**
+   * Constructor for RobotDrive with 2 motors specified with channel numbers.
+   *
+   * Set up parameters for a two wheel drive system where the
+   * left and right motor pwm channels are specified in the call.
+   * This call assumes Talons for controlling the motors.
+   *
+   * @param leftMotorChannel  The PWM channel number that drives the left motor.
+   *                          0-9 are on-board, 10-19 are on the MXP port
+   * @param rightMotorChannel The PWM channel number that drives the right
+   *                          motor. 0-9 are on-board, 10-19 are on the MXP port
+   */
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(int leftMotorChannel, int rightMotorChannel);
+
+  /**
+   * Constructor for RobotDrive with 4 motors specified with channel numbers.
+   *
+   * Set up parameters for a four wheel drive system where all four motor
+   * pwm channels are specified in the call.
+   * This call assumes Talons for controlling the motors.
+   *
+   * @param frontLeftMotor  Front left motor channel number. 0-9 are on-board,
+   *                        10-19 are on the MXP port
+   * @param rearLeftMotor   Rear Left motor channel number. 0-9 are on-board,
+   *                        10-19 are on the MXP port
+   * @param frontRightMotor Front right motor channel number. 0-9 are on-board,
+   *                        10-19 are on the MXP port
+   * @param rearRightMotor  Rear Right motor channel number. 0-9 are on-board,
+   *                        10-19 are on the MXP port
+   */
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(int frontLeftMotorChannel, int rearLeftMotorChannel,
+             int frontRightMotorChannel, int rearRightMotorChannel);
+
+  /**
+   * Constructor for RobotDrive with 2 motors specified as SpeedController
+   * objects.
+   *
+   * The SpeedController version of the constructor enables programs to use the
+   * RobotDrive classes with subclasses of the SpeedController objects, for
+   * example, versions with ramping or reshaping of the curve to suit motor bias
+   * or deadband elimination.
+   *
+   * @param leftMotor  The left SpeedController object used to drive the robot.
+   * @param rightMotor The right SpeedController object used to drive the robot.
+   */
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(SpeedController* leftMotor, SpeedController* rightMotor);
+
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(SpeedController& leftMotor, SpeedController& rightMotor);
+
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(std::shared_ptr<SpeedController> leftMotor,
+             std::shared_ptr<SpeedController> rightMotor);
+
+  /**
+   * Constructor for RobotDrive with 4 motors specified as SpeedController
+   * objects.
+   *
+   * Speed controller input version of RobotDrive (see previous comments).
+   *
+   * @param frontLeftMotor  The front left SpeedController object used to drive
+   *                        the robot.
+   * @param rearLeftMotor   The back left SpeedController object used to drive
+   *                        the robot.
+   * @param frontRightMotor The front right SpeedController object used to drive
+   *                        the robot.
+   * @param rearRightMotor  The back right SpeedController object used to drive
+   *                        the robot.
+   */
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(SpeedController* frontLeftMotor, SpeedController* rearLeftMotor,
+             SpeedController* frontRightMotor, SpeedController* rearRightMotor);
+
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(SpeedController& frontLeftMotor, SpeedController& rearLeftMotor,
+             SpeedController& frontRightMotor, SpeedController& rearRightMotor);
+
+  WPI_DEPRECATED("Use DifferentialDrive or MecanumDrive classes instead.")
+  RobotDrive(std::shared_ptr<SpeedController> frontLeftMotor,
+             std::shared_ptr<SpeedController> rearLeftMotor,
+             std::shared_ptr<SpeedController> frontRightMotor,
+             std::shared_ptr<SpeedController> rearRightMotor);
+
+  virtual ~RobotDrive() = default;
+
+  RobotDrive(RobotDrive&&) = default;
+  RobotDrive& operator=(RobotDrive&&) = default;
+
+  /**
+   * Drive the motors at "outputMagnitude" and "curve".
+   *
+   * Both outputMagnitude and curve are -1.0 to +1.0 values, where 0.0
+   * represents stopped and not turning. curve < 0 will turn left and curve > 0
+   * will turn right.
+   *
+   * The algorithm for steering provides a constant turn radius for any normal
+   * speed range, both forward and backward. Increasing m_sensitivity causes
+   * sharper turns for fixed values of curve.
+   *
+   * This function will most likely be used in an autonomous routine.
+   *
+   * @param outputMagnitude The speed setting for the outside wheel in a turn,
+   *                        forward or backwards, +1 to -1.
+   * @param curve           The rate of turn, constant for different forward
+   *                        speeds. Set curve < 0 for left turn or curve > 0 for
+   *                        right turn.
+   *
+   * Set curve = e^(-r/w) to get a turn radius r for wheelbase w of your robot.
+   * Conversely, turn radius r = -ln(curve)*w for a given value of curve and
+   * wheelbase w.
+   */
+  void Drive(double outputMagnitude, double curve);
+
+  /**
+   * Provide tank steering using the stored robot configuration.
+   *
+   * Drive the robot using two joystick inputs. The Y-axis will be selected from
+   * each Joystick object.
+   *
+   * @param leftStick  The joystick to control the left side of the robot.
+   * @param rightStick The joystick to control the right side of the robot.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void TankDrive(GenericHID* leftStick, GenericHID* rightStick,
+                 bool squaredInputs = true);
+
+  /**
+   * Provide tank steering using the stored robot configuration.
+   *
+   * Drive the robot using two joystick inputs. The Y-axis will be selected from
+   * each Joystick object.
+   *
+   * @param leftStick  The joystick to control the left side of the robot.
+   * @param rightStick The joystick to control the right side of the robot.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void TankDrive(GenericHID& leftStick, GenericHID& rightStick,
+                 bool squaredInputs = true);
+
+  /**
+   * Provide tank steering using the stored robot configuration.
+   *
+   * This function lets you pick the axis to be used on each Joystick object for
+   * the left and right sides of the robot.
+   *
+   * @param leftStick  The Joystick object to use for the left side of the
+   *                   robot.
+   * @param leftAxis   The axis to select on the left side Joystick object.
+   * @param rightStick The Joystick object to use for the right side of the
+   *                   robot.
+   * @param rightAxis  The axis to select on the right side Joystick object.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void TankDrive(GenericHID* leftStick, int leftAxis, GenericHID* rightStick,
+                 int rightAxis, bool squaredInputs = true);
+
+  void TankDrive(GenericHID& leftStick, int leftAxis, GenericHID& rightStick,
+                 int rightAxis, bool squaredInputs = true);
+
+  /**
+   * Provide tank steering using the stored robot configuration.
+   *
+   * This function lets you directly provide joystick values from any source.
+   *
+   * @param leftValue  The value of the left stick.
+   * @param rightValue The value of the right stick.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void TankDrive(double leftValue, double rightValue,
+                 bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * Given a single Joystick, the class assumes the Y axis for the move value
+   * and the X axis for the rotate value. (Should add more information here
+   * regarding the way that arcade drive works.)
+   *
+   * @param stick         The joystick to use for Arcade single-stick driving.
+   *                      The Y-axis will be selected for forwards/backwards and
+   *                      the X-axis will be selected for rotation rate.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void ArcadeDrive(GenericHID* stick, bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * Given a single Joystick, the class assumes the Y axis for the move value
+   * and the X axis for the rotate value. (Should add more information here
+   * regarding the way that arcade drive works.)
+   *
+   * @param stick         The joystick to use for Arcade single-stick driving.
+   *                      The Y-axis will be selected for forwards/backwards and
+   *                      the X-axis will be selected for rotation rate.
+   * @param squaredInputs If true, the sensitivity will be decreased for small
+   *                      values
+   */
+  void ArcadeDrive(GenericHID& stick, bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * Given two joystick instances and two axis, compute the values to send to
+   * either two or four motors.
+   *
+   * @param moveStick     The Joystick object that represents the
+   *                      forward/backward direction
+   * @param moveAxis      The axis on the moveStick object to use for
+   *                      forwards/backwards (typically Y_AXIS)
+   * @param rotateStick   The Joystick object that represents the rotation value
+   * @param rotateAxis    The axis on the rotation object to use for the rotate
+   *                      right/left (typically X_AXIS)
+   * @param squaredInputs Setting this parameter to true increases the
+   *                      sensitivity at lower speeds
+   */
+  void ArcadeDrive(GenericHID* moveStick, int moveChannel,
+                   GenericHID* rotateStick, int rotateChannel,
+                   bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * Given two joystick instances and two axis, compute the values to send to
+   * either two or four motors.
+   *
+   * @param moveStick     The Joystick object that represents the
+   *                      forward/backward direction
+   * @param moveAxis      The axis on the moveStick object to use for
+   *                      forwards/backwards (typically Y_AXIS)
+   * @param rotateStick   The Joystick object that represents the rotation value
+   * @param rotateAxis    The axis on the rotation object to use for the rotate
+   *                      right/left (typically X_AXIS)
+   * @param squaredInputs Setting this parameter to true increases the
+   *                      sensitivity at lower speeds
+   */
+  void ArcadeDrive(GenericHID& moveStick, int moveChannel,
+                   GenericHID& rotateStick, int rotateChannel,
+                   bool squaredInputs = true);
+
+  /**
+   * Arcade drive implements single stick driving.
+   *
+   * This function lets you directly provide joystick values from any source.
+   *
+   * @param moveValue     The value to use for fowards/backwards
+   * @param rotateValue   The value to use for the rotate right/left
+   * @param squaredInputs If set, increases the sensitivity at low speeds
+   */
+  void ArcadeDrive(double moveValue, double rotateValue,
+                   bool squaredInputs = true);
+
+  /**
+   * Drive method for Mecanum wheeled robots.
+   *
+   * A method for driving with Mecanum wheeled robots. There are 4 wheels
+   * on the robot, arranged so that the front and back wheels are toed in 45
+   * degrees.
+   * When looking at the wheels from the top, the roller axles should form an X
+   * across the robot.
+   *
+   * This is designed to be directly driven by joystick axes.
+   *
+   * @param x         The speed that the robot should drive in the X direction.
+   *                  [-1.0..1.0]
+   * @param y         The speed that the robot should drive in the Y direction.
+   *                  This input is inverted to match the forward == -1.0 that
+   *                  joysticks produce. [-1.0..1.0]
+   * @param rotation  The rate of rotation for the robot that is completely
+   *                  independent of the translation. [-1.0..1.0]
+   * @param gyroAngle The current angle reading from the gyro.  Use this to
+   *                  implement field-oriented controls.
+   */
+  void MecanumDrive_Cartesian(double x, double y, double rotation,
+                              double gyroAngle = 0.0);
+
+  /**
+   * Drive method for Mecanum wheeled robots.
+   *
+   * A method for driving with Mecanum wheeled robots. There are 4 wheels
+   * on the robot, arranged so that the front and back wheels are toed in 45
+   * degrees.
+   * When looking at the wheels from the top, the roller axles should form an X
+   * across the robot.
+   *
+   * @param magnitude The speed that the robot should drive in a given
+   *                  direction. [-1.0..1.0]
+   * @param direction The direction the robot should drive in degrees. The
+   *                  direction and maginitute are independent of the rotation
+   *                  rate.
+   * @param rotation  The rate of rotation for the robot that is completely
+   *                  independent of the magnitute or direction. [-1.0..1.0]
+   */
+  void MecanumDrive_Polar(double magnitude, double direction, double rotation);
+
+  /**
+   * Holonomic Drive method for Mecanum wheeled robots.
+   *
+   * This is an alias to MecanumDrive_Polar() for backward compatability
+   *
+   * @param magnitude The speed that the robot should drive in a given
+   *                  direction. [-1.0..1.0]
+   * @param direction The direction the robot should drive. The direction and
+   *                  magnitude are independent of the rotation rate.
+   * @param rotation  The rate of rotation for the robot that is completely
+   *                  independent of the magnitude or direction.  [-1.0..1.0]
+   */
+  void HolonomicDrive(double magnitude, double direction, double rotation);
+
+  /**
+   * Set the speed of the right and left motors.
+   *
+   * This is used once an appropriate drive setup function is called such as
+   * TwoWheelDrive(). The motors are set to "leftOutput" and "rightOutput"
+   * and includes flipping the direction of one side for opposing motors.
+   *
+   * @param leftOutput  The speed to send to the left side of the robot.
+   * @param rightOutput The speed to send to the right side of the robot.
+   */
+  virtual void SetLeftRightMotorOutputs(double leftOutput, double rightOutput);
+
+  /*
+   * Invert a motor direction.
+   *
+   * This is used when a motor should run in the opposite direction as the drive
+   * code would normally run it. Motors that are direct drive would be inverted,
+   * the Drive code assumes that the motors are geared with one reversal.
+   *
+   * @param motor      The motor index to invert.
+   * @param isInverted True if the motor should be inverted when operated.
+   */
+  void SetInvertedMotor(MotorType motor, bool isInverted);
+
+  /**
+   * Set the turning sensitivity.
+   *
+   * This only impacts the Drive() entry-point.
+   *
+   * @param sensitivity Effectively sets the turning sensitivity (or turn radius
+   *                    for a given value)
+   */
+  void SetSensitivity(double sensitivity);
+
+  /**
+   * Configure the scaling factor for using RobotDrive with motor controllers in
+   * a mode other than PercentVbus.
+   *
+   * @param maxOutput Multiplied with the output percentage computed by the
+   *                  drive functions.
+   */
+  void SetMaxOutput(double maxOutput);
+
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+ protected:
+  /**
+   * Common function to initialize all the robot drive constructors.
+   *
+   * Create a motor safety object (the real reason for the common code) and
+   * initialize all the motor assignments. The default timeout is set for the
+   * robot drive.
+   */
+  void InitRobotDrive();
+
+  /**
+   * Limit motor values to the -1.0 to +1.0 range.
+   */
+  double Limit(double number);
+
+  /**
+   * Normalize all wheel speeds if the magnitude of any wheel is greater than
+   * 1.0.
+   */
+  void Normalize(double* wheelSpeeds);
+
+  /**
+   * Rotate a vector in Cartesian space.
+   */
+  void RotateVector(double& x, double& y, double angle);
+
+  static constexpr int kMaxNumberOfMotors = 4;
+
+  double m_sensitivity = 0.5;
+  double m_maxOutput = 1.0;
+
+  std::shared_ptr<SpeedController> m_frontLeftMotor;
+  std::shared_ptr<SpeedController> m_frontRightMotor;
+  std::shared_ptr<SpeedController> m_rearLeftMotor;
+  std::shared_ptr<SpeedController> m_rearRightMotor;
+
+ private:
+  int GetNumMotors() {
+    int motors = 0;
+    if (m_frontLeftMotor) motors++;
+    if (m_frontRightMotor) motors++;
+    if (m_rearLeftMotor) motors++;
+    if (m_rearRightMotor) motors++;
+    return motors;
+  }
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotState.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotState.h
new file mode 100644
index 0000000..6b91692
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/RobotState.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+namespace frc {
+
+class RobotState {
+ public:
+  static bool IsDisabled();
+  static bool IsEnabled();
+  static bool IsOperatorControl();
+  static bool IsAutonomous();
+  static bool IsTest();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SD540.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SD540.h
new file mode 100644
index 0000000..91666b4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SD540.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Mindsensors SD540 Speed Controller.
+ */
+class SD540 : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a SD540.
+   *
+   * @param channel The PWM channel that the SD540 is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit SD540(int channel);
+
+  SD540(SD540&&) = default;
+  SD540& operator=(SD540&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SPI.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SPI.h
new file mode 100644
index 0000000..88cd4d9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SPI.h
@@ -0,0 +1,360 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#include <memory>
+
+#include <hal/SPITypes.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/deprecated.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+class DigitalSource;
+
+/**
+ * SPI bus interface class.
+ *
+ * This class is intended to be used by sensor (and other SPI device) drivers.
+ * It probably should not be used directly.
+ *
+ */
+class SPI : public ErrorBase {
+ public:
+  enum Port { kOnboardCS0 = 0, kOnboardCS1, kOnboardCS2, kOnboardCS3, kMXP };
+
+  /**
+   * Constructor
+   *
+   * @param port the physical SPI port
+   */
+  explicit SPI(Port port);
+
+  ~SPI() override;
+
+  SPI(SPI&& rhs);
+  SPI& operator=(SPI&& rhs);
+
+  /**
+   * Configure the rate of the generated clock signal.
+   *
+   * The default value is 500,000Hz.
+   * The maximum value is 4,000,000Hz.
+   *
+   * @param hz The clock rate in Hertz.
+   */
+  void SetClockRate(double hz);
+
+  /**
+   * Configure the order that bits are sent and received on the wire
+   * to be most significant bit first.
+   */
+  void SetMSBFirst();
+
+  /**
+   * Configure the order that bits are sent and received on the wire
+   * to be least significant bit first.
+   */
+  void SetLSBFirst();
+
+  /**
+   * Configure that the data is stable on the leading edge and the data
+   * changes on the trailing edge.
+   */
+  void SetSampleDataOnLeadingEdge();
+
+  /**
+   * Configure that the data is stable on the trailing edge and the data
+   * changes on the leading edge.
+   */
+  void SetSampleDataOnTrailingEdge();
+
+  /**
+   * Configure that the data is stable on the falling edge and the data
+   * changes on the rising edge.
+   */
+  WPI_DEPRECATED("Use SetSampleDataOnTrailingEdge in most cases.")
+  void SetSampleDataOnFalling();
+
+  /**
+   * Configure that the data is stable on the rising edge and the data
+   * changes on the falling edge.
+   */
+  WPI_DEPRECATED("Use SetSampleDataOnLeadingEdge in most cases")
+  void SetSampleDataOnRising();
+
+  /**
+   * Configure the clock output line to be active low.
+   * This is sometimes called clock polarity high or clock idle high.
+   */
+  void SetClockActiveLow();
+
+  /**
+   * Configure the clock output line to be active high.
+   * This is sometimes called clock polarity low or clock idle low.
+   */
+  void SetClockActiveHigh();
+
+  /**
+   * Configure the chip select line to be active high.
+   */
+  void SetChipSelectActiveHigh();
+
+  /**
+   * Configure the chip select line to be active low.
+   */
+  void SetChipSelectActiveLow();
+
+  /**
+   * Write data to the slave device.  Blocks until there is space in the
+   * output FIFO.
+   *
+   * If not running in output only mode, also saves the data received
+   * on the MISO input during the transfer into the receive FIFO.
+   */
+  virtual int Write(uint8_t* data, int size);
+
+  /**
+   * Read a word from the receive FIFO.
+   *
+   * Waits for the current transfer to complete if the receive FIFO is empty.
+   *
+   * If the receive FIFO is empty, there is no active transfer, and initiate
+   * is false, errors.
+   *
+   * @param initiate If true, this function pushes "0" into the transmit buffer
+   *                 and initiates a transfer. If false, this function assumes
+   *                 that data is already in the receive FIFO from a previous
+   *                 write.
+   */
+  virtual int Read(bool initiate, uint8_t* dataReceived, int size);
+
+  /**
+   * Perform a simultaneous read/write transaction with the device
+   *
+   * @param dataToSend   The data to be written out to the device
+   * @param dataReceived Buffer to receive data from the device
+   * @param size         The length of the transaction, in bytes
+   */
+  virtual int Transaction(uint8_t* dataToSend, uint8_t* dataReceived, int size);
+
+  /**
+   * Initialize automatic SPI transfer engine.
+   *
+   * Only a single engine is available, and use of it blocks use of all other
+   * chip select usage on the same physical SPI port while it is running.
+   *
+   * @param bufferSize buffer size in bytes
+   */
+  void InitAuto(int bufferSize);
+
+  /**
+   * Frees the automatic SPI transfer engine.
+   */
+  void FreeAuto();
+
+  /**
+   * Set the data to be transmitted by the engine.
+   *
+   * Up to 16 bytes are configurable, and may be followed by up to 127 zero
+   * bytes.
+   *
+   * @param dataToSend data to send (maximum 16 bytes)
+   * @param zeroSize number of zeros to send after the data
+   */
+  void SetAutoTransmitData(wpi::ArrayRef<uint8_t> dataToSend, int zeroSize);
+
+  /**
+   * Start running the automatic SPI transfer engine at a periodic rate.
+   *
+   * InitAuto() and SetAutoTransmitData() must be called before calling this
+   * function.
+   *
+   * @param period period between transfers, in seconds (us resolution)
+   */
+  void StartAutoRate(double period);
+
+  /**
+   * Start running the automatic SPI transfer engine when a trigger occurs.
+   *
+   * InitAuto() and SetAutoTransmitData() must be called before calling this
+   * function.
+   *
+   * @param source digital source for the trigger (may be an analog trigger)
+   * @param rising trigger on the rising edge
+   * @param falling trigger on the falling edge
+   */
+  void StartAutoTrigger(DigitalSource& source, bool rising, bool falling);
+
+  /**
+   * Stop running the automatic SPI transfer engine.
+   */
+  void StopAuto();
+
+  /**
+   * Force the engine to make a single transfer.
+   */
+  void ForceAutoRead();
+
+  /**
+   * Read data that has been transferred by the automatic SPI transfer engine.
+   *
+   * Transfers may be made a byte at a time, so it's necessary for the caller
+   * to handle cases where an entire transfer has not been completed.
+   *
+   * Each received data sequence consists of a timestamp followed by the
+   * received data bytes, one byte per word (in the least significant byte).
+   * The length of each received data sequence is the same as the combined
+   * size of the data and zeroSize set in SetAutoTransmitData().
+   *
+   * Blocks until numToRead words have been read or timeout expires.
+   * May be called with numToRead=0 to retrieve how many words are available.
+   *
+   * @param buffer buffer where read words are stored
+   * @param numToRead number of words to read
+   * @param timeout timeout in seconds (ms resolution)
+   * @return Number of words remaining to be read
+   */
+  int ReadAutoReceivedData(uint32_t* buffer, int numToRead, double timeout);
+
+  /**
+   * Get the number of bytes dropped by the automatic SPI transfer engine due
+   * to the receive buffer being full.
+   *
+   * @return Number of bytes dropped
+   */
+  int GetAutoDroppedCount();
+
+  /**
+   * Initialize the accumulator.
+   *
+   * @param period    Time between reads
+   * @param cmd       SPI command to send to request data
+   * @param xferSize  SPI transfer size, in bytes
+   * @param validMask Mask to apply to received data for validity checking
+   * @param validData After valid_mask is applied, required matching value for
+   *                  validity checking
+   * @param dataShift Bit shift to apply to received data to get actual data
+   *                  value
+   * @param dataSize  Size (in bits) of data field
+   * @param isSigned  Is data field signed?
+   * @param bigEndian Is device big endian?
+   */
+  void InitAccumulator(double period, int cmd, int xferSize, int validMask,
+                       int validValue, int dataShift, int dataSize,
+                       bool isSigned, bool bigEndian);
+
+  /**
+   * Frees the accumulator.
+   */
+  void FreeAccumulator();
+
+  /**
+   * Resets the accumulator to zero.
+   */
+  void ResetAccumulator();
+
+  /**
+   * Set the center value of the accumulator.
+   *
+   * The center value is subtracted from each value before it is added to the
+   * accumulator. This is used for the center value of devices like gyros and
+   * accelerometers to make integration work and to take the device offset into
+   * account when integrating.
+   */
+  void SetAccumulatorCenter(int center);
+
+  /**
+   * Set the accumulator's deadband.
+   */
+  void SetAccumulatorDeadband(int deadband);
+
+  /**
+   * Read the last value read by the accumulator engine.
+   */
+  int GetAccumulatorLastValue() const;
+
+  /**
+   * Read the accumulated value.
+   *
+   * @return The 64-bit value accumulated since the last Reset().
+   */
+  int64_t GetAccumulatorValue() const;
+
+  /**
+   * Read the number of accumulated values.
+   *
+   * Read the count of the accumulated values since the accumulator was last
+   * Reset().
+   *
+   * @return The number of times samples from the channel were accumulated.
+   */
+  int64_t GetAccumulatorCount() const;
+
+  /**
+   * Read the average of the accumulated value.
+   *
+   * @return The accumulated average value (value / count).
+   */
+  double GetAccumulatorAverage() const;
+
+  /**
+   * Read the accumulated value and the number of accumulated values atomically.
+   *
+   * This function reads the value and count atomically.
+   * This can be used for averaging.
+   *
+   * @param value Pointer to the 64-bit accumulated output.
+   * @param count Pointer to the number of accumulation cycles.
+   */
+  void GetAccumulatorOutput(int64_t& value, int64_t& count) const;
+
+  /**
+   * Set the center value of the accumulator integrator.
+   *
+   * The center value is subtracted from each value*dt before it is added to the
+   * integrated value. This is used for the center value of devices like gyros
+   * and accelerometers to take the device offset into account when integrating.
+   */
+  void SetAccumulatorIntegratedCenter(double center);
+
+  /**
+   * Read the integrated value.  This is the sum of (each value * time between
+   * values).
+   *
+   * @return The integrated value accumulated since the last Reset().
+   */
+  double GetAccumulatorIntegratedValue() const;
+
+  /**
+   * Read the average of the integrated value.  This is the sum of (each value
+   * times the time between values), divided by the count.
+   *
+   * @return The average of the integrated value accumulated since the last
+   *         Reset().
+   */
+  double GetAccumulatorIntegratedAverage() const;
+
+ protected:
+  HAL_SPIPort m_port = HAL_SPI_kInvalid;
+  bool m_msbFirst = false;          // Default little-endian
+  bool m_sampleOnTrailing = false;  // Default data updated on falling edge
+  bool m_clockIdleHigh = false;     // Default clock active high
+
+ private:
+  void Init();
+
+  class Accumulator;
+  std::unique_ptr<Accumulator> m_accum;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SampleRobot.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SampleRobot.h
new file mode 100644
index 0000000..4bce0f3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SampleRobot.h
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/deprecated.h>
+
+#include "frc/RobotBase.h"
+
+namespace frc {
+
+class SampleRobot : public RobotBase {
+ public:
+  /**
+   * Start a competition.
+   *
+   * This code needs to track the order of the field starting to ensure that
+   * everything happens in the right order. Repeatedly run the correct method,
+   * either Autonomous or OperatorControl or Test when the robot is enabled.
+   * After running the correct method, wait for some state to change, either the
+   * other mode starts or the robot is disabled. Then go back and wait for the
+   * robot to be enabled again.
+   */
+  void StartCompetition() override;
+
+  /**
+   * Robot-wide initialization code should go here.
+   *
+   * Users should override this method for default Robot-wide initialization
+   * which will be called when the robot is first powered on. It will be called
+   * exactly one time.
+   *
+   * Warning: the Driver Station "Robot Code" light and FMS "Robot Ready"
+   * indicators will be off until RobotInit() exits. Code in RobotInit() that
+   * waits for enable will cause the robot to never indicate that the code is
+   * ready, causing the robot to be bypassed in a match.
+   */
+  virtual void RobotInit();
+
+  /**
+   * Disabled should go here.
+   *
+   * Programmers should override this method to run code that should run while
+   * the field is disabled.
+   */
+  virtual void Disabled();
+
+  /**
+   * Autonomous should go here.
+   *
+   * Programmers should override this method to run code that should run while
+   * the field is in the autonomous period. This will be called once each time
+   * the robot enters the autonomous state.
+   */
+  virtual void Autonomous();
+
+  /**
+   * Operator control (tele-operated) code should go here.
+   *
+   * Programmers should override this method to run code that should run while
+   * the field is in the Operator Control (tele-operated) period. This is called
+   * once each time the robot enters the teleop state.
+   */
+  virtual void OperatorControl();
+
+  /**
+   * Test program should go here.
+   *
+   * Programmers should override this method to run code that executes while the
+   * robot is in test mode. This will be called once whenever the robot enters
+   * test mode
+   */
+  virtual void Test();
+
+  /**
+   * Robot main program for free-form programs.
+   *
+   * This should be overridden by user subclasses if the intent is to not use
+   * the Autonomous() and OperatorControl() methods. In that case, the program
+   * is responsible for sensing when to run the autonomous and operator control
+   * functions in their program.
+   *
+   * This method will be called immediately after the constructor is called. If
+   * it has not been overridden by a user subclass (i.e. the default version
+   * runs), then the Autonomous() and OperatorControl() methods will be called.
+   */
+  virtual void RobotMain();
+
+ protected:
+  WPI_DEPRECATED(
+      "WARNING: While it may look like a good choice to use for your code if "
+      "you're inexperienced, don't. Unless you know what you are doing, "
+      "complex code will be much more difficult under this system. Use "
+      "TimedRobot or Command-Based instead.")
+  SampleRobot();
+  virtual ~SampleRobot() = default;
+
+  SampleRobot(SampleRobot&&) = default;
+  SampleRobot& operator=(SampleRobot&&) = default;
+
+ private:
+  bool m_robotMainOverridden = true;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SensorUtil.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SensorUtil.h
new file mode 100644
index 0000000..a38b542
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SensorUtil.h
@@ -0,0 +1,117 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Stores most recent status information as well as containing utility functions
+ * for checking channels and error processing.
+ */
+class SensorUtil final {
+ public:
+  /**
+   * Get the number of the default solenoid module.
+   *
+   * @return The number of the default solenoid module.
+   */
+  static int GetDefaultSolenoidModule();
+
+  /**
+   * Check that the solenoid module number is valid. module numbers are 0-based
+   *
+   * @return Solenoid module is valid and present
+   */
+  static bool CheckSolenoidModule(int moduleNumber);
+
+  /**
+   * Check that the digital channel number is valid.
+   *
+   * Verify that the channel number is one of the legal channel numbers. Channel
+   * numbers are 0-based.
+   *
+   * @return Digital channel is valid
+   */
+  static bool CheckDigitalChannel(int channel);
+
+  /**
+   * Check that the relay channel number is valid.
+   *
+   * Verify that the channel number is one of the legal channel numbers. Channel
+   * numbers are 0-based.
+   *
+   * @return Relay channel is valid
+   */
+  static bool CheckRelayChannel(int channel);
+
+  /**
+   * Check that the digital channel number is valid.
+   *
+   * Verify that the channel number is one of the legal channel numbers. Channel
+   * numbers are 0-based.
+   *
+   * @return PWM channel is valid
+   */
+  static bool CheckPWMChannel(int channel);
+
+  /**
+   * Check that the analog input number is value.
+   *
+   * Verify that the analog input number is one of the legal channel numbers.
+   * Channel numbers are 0-based.
+   *
+   * @return Analog channel is valid
+   */
+  static bool CheckAnalogInputChannel(int channel);
+
+  /**
+   * Check that the analog output number is valid.
+   *
+   * Verify that the analog output number is one of the legal channel numbers.
+   * Channel numbers are 0-based.
+   *
+   * @return Analog channel is valid
+   */
+  static bool CheckAnalogOutputChannel(int channel);
+
+  /**
+   * Verify that the solenoid channel number is within limits.
+   *
+   * @return Solenoid channel is valid
+   */
+  static bool CheckSolenoidChannel(int channel);
+
+  /**
+   * Verify that the power distribution channel number is within limits.
+   *
+   * @return PDP channel is valid
+   */
+  static bool CheckPDPChannel(int channel);
+
+  /**
+   * Verify that the PDP module number is within limits. module numbers are
+   * 0-based
+   *
+   * @return PDP module is valid
+   */
+  static bool CheckPDPModule(int module);
+
+  static const int kDigitalChannels;
+  static const int kAnalogInputs;
+  static const int kAnalogOutputs;
+  static const int kSolenoidChannels;
+  static const int kSolenoidModules;
+  static const int kPwmChannels;
+  static const int kRelayChannels;
+  static const int kPDPChannels;
+
+ private:
+  SensorUtil() = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SerialPort.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SerialPort.h
new file mode 100644
index 0000000..e9e38ef
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SerialPort.h
@@ -0,0 +1,223 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+
+#include "frc/ErrorBase.h"
+
+namespace frc {
+
+/**
+ * Driver for the RS-232 serial port on the roboRIO.
+ *
+ * The current implementation uses the VISA formatted I/O mode.  This means that
+ * all traffic goes through the fomatted buffers.  This allows the intermingled
+ * use of Printf(), Scanf(), and the raw buffer accessors Read() and Write().
+ *
+ * More information can be found in the NI-VISA User Manual here:
+ *   http://www.ni.com/pdf/manuals/370423a.pdf
+ * and the NI-VISA Programmer's Reference Manual here:
+ *   http://www.ni.com/pdf/manuals/370132c.pdf
+ */
+class SerialPort : public ErrorBase {
+ public:
+  enum Parity {
+    kParity_None = 0,
+    kParity_Odd = 1,
+    kParity_Even = 2,
+    kParity_Mark = 3,
+    kParity_Space = 4
+  };
+
+  enum StopBits {
+    kStopBits_One = 10,
+    kStopBits_OnePointFive = 15,
+    kStopBits_Two = 20
+  };
+
+  enum FlowControl {
+    kFlowControl_None = 0,
+    kFlowControl_XonXoff = 1,
+    kFlowControl_RtsCts = 2,
+    kFlowControl_DtrDsr = 4
+  };
+
+  enum WriteBufferMode { kFlushOnAccess = 1, kFlushWhenFull = 2 };
+
+  enum Port { kOnboard = 0, kMXP = 1, kUSB = 2, kUSB1 = 2, kUSB2 = 3 };
+
+  /**
+   * Create an instance of a Serial Port class.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   * @param port     The physical port to use
+   * @param dataBits The number of data bits per transfer.  Valid values are
+   *                 between 5 and 8 bits.
+   * @param parity   Select the type of parity checking to use.
+   * @param stopBits The number of stop bits to use as defined by the enum
+   *                 StopBits.
+   */
+  SerialPort(int baudRate, Port port = kOnboard, int dataBits = 8,
+             Parity parity = kParity_None, StopBits stopBits = kStopBits_One);
+
+  /**
+   * Create an instance of a Serial Port class.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   * @param port     The physical port to use
+   * @param portName The direct port name to use
+   * @param dataBits The number of data bits per transfer.  Valid values are
+   *                 between 5 and 8 bits.
+   * @param parity   Select the type of parity checking to use.
+   * @param stopBits The number of stop bits to use as defined by the enum
+   *                 StopBits.
+   */
+  WPI_DEPRECATED("Will be removed for 2020")
+  SerialPort(int baudRate, const wpi::Twine& portName, Port port = kOnboard,
+             int dataBits = 8, Parity parity = kParity_None,
+             StopBits stopBits = kStopBits_One);
+
+  ~SerialPort();
+
+  SerialPort(SerialPort&& rhs);
+  SerialPort& operator=(SerialPort&& rhs);
+
+  /**
+   * Set the type of flow control to enable on this port.
+   *
+   * By default, flow control is disabled.
+   */
+  void SetFlowControl(FlowControl flowControl);
+
+  /**
+   * Enable termination and specify the termination character.
+   *
+   * Termination is currently only implemented for receive.
+   * When the the terminator is recieved, the Read() or Scanf() will return
+   * fewer bytes than requested, stopping after the terminator.
+   *
+   * @param terminator The character to use for termination.
+   */
+  void EnableTermination(char terminator = '\n');
+
+  /**
+   * Disable termination behavior.
+   */
+  void DisableTermination();
+
+  /**
+   * Get the number of bytes currently available to read from the serial port.
+   *
+   * @return The number of bytes available to read
+   */
+  int GetBytesReceived();
+
+  /**
+   * Read raw bytes out of the buffer.
+   *
+   * @param buffer Pointer to the buffer to store the bytes in.
+   * @param count  The maximum number of bytes to read.
+   * @return The number of bytes actually read into the buffer.
+   */
+  int Read(char* buffer, int count);
+
+  /**
+   * Write raw bytes to the buffer.
+   *
+   * @param buffer Pointer to the buffer to read the bytes from.
+   * @param count  The maximum number of bytes to write.
+   * @return The number of bytes actually written into the port.
+   */
+  int Write(const char* buffer, int count);
+
+  /**
+   * Write raw bytes to the buffer.
+   *
+   * Use Write({data, len}) to get a buffer that is shorter than the length of
+   * the string.
+   *
+   * @param buffer StringRef to the buffer to read the bytes from.
+   * @return The number of bytes actually written into the port.
+   */
+  int Write(wpi::StringRef buffer);
+
+  /**
+   * Configure the timeout of the serial port.
+   *
+   * This defines the timeout for transactions with the hardware.
+   * It will affect reads and very large writes.
+   *
+   * @param timeout The number of seconds to to wait for I/O.
+   */
+  void SetTimeout(double timeout);
+
+  /**
+   * Specify the size of the input buffer.
+   *
+   * Specify the amount of data that can be stored before data
+   * from the device is returned to Read or Scanf.  If you want
+   * data that is recieved to be returned immediately, set this to 1.
+   *
+   * It the buffer is not filled before the read timeout expires, all
+   * data that has been received so far will be returned.
+   *
+   * @param size The read buffer size.
+   */
+  void SetReadBufferSize(int size);
+
+  /**
+   * Specify the size of the output buffer.
+   *
+   * Specify the amount of data that can be stored before being
+   * transmitted to the device.
+   *
+   * @param size The write buffer size.
+   */
+  void SetWriteBufferSize(int size);
+
+  /**
+   * Specify the flushing behavior of the output buffer.
+   *
+   * When set to kFlushOnAccess, data is synchronously written to the serial
+   * port after each call to either Printf() or Write().
+   *
+   * When set to kFlushWhenFull, data will only be written to the serial port
+   * when the buffer is full or when Flush() is called.
+   *
+   * @param mode The write buffer mode.
+   */
+  void SetWriteBufferMode(WriteBufferMode mode);
+
+  /**
+   * Force the output buffer to be written to the port.
+   *
+   * This is used when SetWriteBufferMode() is set to kFlushWhenFull to force a
+   * flush before the buffer is full.
+   */
+  void Flush();
+
+  /**
+   * Reset the serial port driver to a known state.
+   *
+   * Empty the transmit and receive buffers in the device and formatted I/O.
+   */
+  void Reset();
+
+ private:
+  int m_resourceManagerHandle = 0;
+  int m_portHandle = 0;
+  bool m_consoleModeEnabled = false;
+  Port m_port = kOnboard;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Servo.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Servo.h
new file mode 100644
index 0000000..ae5c599
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Servo.h
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWM.h"
+#include "frc/SpeedController.h"
+
+namespace frc {
+
+/**
+ * Standard hobby style servo.
+ *
+ * The range parameters default to the appropriate values for the Hitec HS-322HD
+ * servo provided in the FIRST Kit of Parts in 2008.
+ */
+class Servo : public PWM {
+ public:
+  /**
+   * @param channel The PWM channel to which the servo is attached. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit Servo(int channel);
+
+  Servo(Servo&&) = default;
+  Servo& operator=(Servo&&) = default;
+
+  /**
+   * Set the servo position.
+   *
+   * Servo values range from 0.0 to 1.0 corresponding to the range of full left
+   * to full right.
+   *
+   * @param value Position from 0.0 to 1.0.
+   */
+  void Set(double value);
+
+  /**
+   * Set the servo to offline.
+   *
+   * Set the servo raw value to 0 (undriven)
+   */
+  void SetOffline();
+
+  /**
+   * Get the servo position.
+   *
+   * Servo values range from 0.0 to 1.0 corresponding to the range of full left
+   * to full right.
+   *
+   * @return Position from 0.0 to 1.0.
+   */
+  double Get() const;
+
+  /**
+   * Set the servo angle.
+   *
+   * Assume that the servo angle is linear with respect to the PWM value (big
+   * assumption, need to test).
+   *
+   * Servo angles that are out of the supported range of the servo simply
+   * "saturate" in that direction. In other words, if the servo has a range of
+   * (X degrees to Y degrees) than angles of less than X result in an angle of
+   * X being set and angles of more than Y degrees result in an angle of Y being
+   * set.
+   *
+   * @param degrees The angle in degrees to set the servo.
+   */
+  void SetAngle(double angle);
+
+  /**
+   * Get the servo angle.
+   *
+   * Assume that the servo angle is linear with respect to the PWM value (big
+   * assumption, need to test).
+   *
+   * @return The angle in degrees to which the servo is set.
+   */
+  double GetAngle() const;
+
+  /**
+   * Get the maximum angle of the servo.
+   *
+   * @return The maximum angle of the servo in degrees.
+   */
+  double GetMaxAngle() const;
+
+  /**
+   * Get the minimum angle of the servo.
+   *
+   * @return The minimum angle of the servo in degrees.
+   */
+  double GetMinAngle() const;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  double GetServoAngleRange() const;
+
+  static constexpr double kMaxServoAngle = 180.0;
+  static constexpr double kMinServoAngle = 0.0;
+
+  static constexpr double kDefaultMaxServoPWM = 2.4;
+  static constexpr double kDefaultMinServoPWM = .6;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Solenoid.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Solenoid.h
new file mode 100644
index 0000000..8a90b26
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Solenoid.h
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/SolenoidBase.h"
+
+namespace frc {
+
+/**
+ * Solenoid class for running high voltage Digital Output (PCM).
+ *
+ * The Solenoid class is typically used for pneumatics solenoids, but could be
+ * used for any device within the current spec of the PCM.
+ */
+class Solenoid : public SolenoidBase {
+ public:
+  /**
+   * Constructor using the default PCM ID (0).
+   *
+   * @param channel The channel on the PCM to control (0..7).
+   */
+  explicit Solenoid(int channel);
+
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber The CAN ID of the PCM the solenoid is attached to
+   * @param channel      The channel on the PCM to control (0..7).
+   */
+  Solenoid(int moduleNumber, int channel);
+
+  ~Solenoid() override;
+
+  Solenoid(Solenoid&& rhs);
+  Solenoid& operator=(Solenoid&& rhs);
+
+  /**
+   * Set the value of a solenoid.
+   *
+   * @param on Turn the solenoid output off or on.
+   */
+  virtual void Set(bool on);
+
+  /**
+   * Read the current value of the solenoid.
+   *
+   * @return The current value of the solenoid.
+   */
+  virtual bool Get() const;
+
+  /**
+   * Check if solenoid is blacklisted.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and
+   * disabled until power cycle, or until faults are cleared.
+   *
+   * @see ClearAllPCMStickyFaults()
+   *
+   * @return If solenoid is disabled due to short.
+   */
+  bool IsBlackListed() const;
+
+  /**
+   * Set the pulse duration in the PCM. This is used in conjunction with
+   * the startPulse method to allow the PCM to control the timing of a pulse.
+   * The timing can be controlled in 0.01 second increments.
+   *
+   * @param durationSeconds The duration of the pulse, from 0.01 to 2.55
+   *                        seconds.
+   *
+   * @see startPulse()
+   */
+  void SetPulseDuration(double durationSeconds);
+
+  /**
+   * Trigger the PCM to generate a pulse of the duration set in
+   * setPulseDuration.
+   *
+   * @see setPulseDuration()
+   */
+  void StartPulse();
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  HAL_SolenoidHandle m_solenoidHandle = HAL_kInvalidHandle;
+  int m_channel;  // The channel on the module to control
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SolenoidBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SolenoidBase.h
new file mode 100644
index 0000000..fe9f32e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SolenoidBase.h
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * SolenoidBase class is the common base class for the Solenoid and
+ * DoubleSolenoid classes.
+ */
+class SolenoidBase : public ErrorBase, public SendableBase {
+ public:
+  /**
+   * Read all 8 solenoids as a single byte
+   *
+   * @param module the module to read from
+   * @return The current value of all 8 solenoids on the module.
+   */
+  static int GetAll(int module);
+
+  /**
+   * Read all 8 solenoids as a single byte
+   *
+   * @return The current value of all 8 solenoids on the module.
+   */
+  int GetAll() const;
+
+  /**
+   * Reads complete solenoid blacklist for all 8 solenoids as a single byte.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and
+   * disabled until power cycle, or until faults are cleared.
+   * @see ClearAllPCMStickyFaults()
+   *
+   * @param module the module to read from
+   * @return The solenoid blacklist of all 8 solenoids on the module.
+   */
+  static int GetPCMSolenoidBlackList(int module);
+
+  /**
+   * Reads complete solenoid blacklist for all 8 solenoids as a single byte.
+   *
+   * If a solenoid is shorted, it is added to the blacklist and
+   * disabled until power cycle, or until faults are cleared.
+   * @see ClearAllPCMStickyFaults()
+   *
+   * @return The solenoid blacklist of all 8 solenoids on the module.
+   */
+  int GetPCMSolenoidBlackList() const;
+
+  /**
+   * @param module the module to read from
+   * @return true if PCM sticky fault is set : The common highside solenoid
+   *         voltage rail is too low, most likely a solenoid channel is shorted.
+   */
+  static bool GetPCMSolenoidVoltageStickyFault(int module);
+
+  /**
+   * @return true if PCM sticky fault is set : The common highside solenoid
+   *         voltage rail is too low, most likely a solenoid channel is shorted.
+   */
+  bool GetPCMSolenoidVoltageStickyFault() const;
+
+  /**
+   * @param module the module to read from
+   * @return true if PCM is in fault state : The common highside solenoid
+   *         voltage rail is too low, most likely a solenoid channel is shorted.
+   */
+  static bool GetPCMSolenoidVoltageFault(int module);
+
+  /**
+   * @return true if PCM is in fault state : The common highside solenoid
+   *         voltage rail is too low, most likely a solenoid channel is shorted.
+   */
+  bool GetPCMSolenoidVoltageFault() const;
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * If a sticky fault is set, then it will be persistently cleared.  Compressor
+   * drive maybe momentarily disable while flags are being cleared. Care should
+   * be taken to not call this too frequently, otherwise normal compressor
+   * functionality may be prevented.
+   *
+   * If no sticky faults are set then this call will have no effect.
+   *
+   * @param module the module to read from
+   */
+  static void ClearAllPCMStickyFaults(int module);
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * If a sticky fault is set, then it will be persistently cleared.  Compressor
+   * drive maybe momentarily disable while flags are being cleared. Care should
+   * be taken to not call this too frequently, otherwise normal compressor
+   * functionality may be prevented.
+   *
+   * If no sticky faults are set then this call will have no effect.
+   */
+  void ClearAllPCMStickyFaults();
+
+ protected:
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber The CAN PCM ID.
+   */
+  explicit SolenoidBase(int pcmID);
+
+  SolenoidBase(SolenoidBase&&) = default;
+  SolenoidBase& operator=(SolenoidBase&&) = default;
+
+  static constexpr int m_maxModules = 63;
+  static constexpr int m_maxPorts = 8;
+
+  int m_moduleNumber;  // PCM module number
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Spark.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Spark.h
new file mode 100644
index 0000000..640696f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Spark.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * REV Robotics Speed Controller.
+ */
+class Spark : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Spark.
+   *
+   * @param channel The PWM channel that the Spark is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit Spark(int channel);
+
+  Spark(Spark&&) = default;
+  Spark& operator=(Spark&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedController.h
new file mode 100644
index 0000000..49a828b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedController.h
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PIDOutput.h"
+
+namespace frc {
+
+/**
+ * Interface for speed controlling devices.
+ */
+class SpeedController : public PIDOutput {
+ public:
+  virtual ~SpeedController() = default;
+
+  /**
+   * Common interface for setting the speed of a speed controller.
+   *
+   * @param speed The speed to set.  Value should be between -1.0 and 1.0.
+   */
+  virtual void Set(double speed) = 0;
+
+  /**
+   * Common interface for getting the current set speed of a speed controller.
+   *
+   * @return The current set speed.  Value is between -1.0 and 1.0.
+   */
+  virtual double Get() const = 0;
+
+  /**
+   * Common interface for inverting direction of a speed controller.
+   *
+   * @param isInverted The state of inversion, true is inverted.
+   */
+  virtual void SetInverted(bool isInverted) = 0;
+
+  /**
+   * Common interface for returning the inversion state of a speed controller.
+   *
+   * @return isInverted The state of inversion, true is inverted.
+   */
+  virtual bool GetInverted() const = 0;
+
+  /**
+   * Common interface for disabling a motor.
+   */
+  virtual void Disable() = 0;
+
+  /**
+   * Common interface to stop the motor until Set is called again.
+   */
+  virtual void StopMotor() = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h
new file mode 100644
index 0000000..3f0c699
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedControllerGroup.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <vector>
+
+#include "frc/SpeedController.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class SpeedControllerGroup : public SendableBase, public SpeedController {
+ public:
+  template <class... SpeedControllers>
+  explicit SpeedControllerGroup(SpeedController& speedController,
+                                SpeedControllers&... speedControllers);
+  ~SpeedControllerGroup() override = default;
+
+  SpeedControllerGroup(SpeedControllerGroup&&) = default;
+  SpeedControllerGroup& operator=(SpeedControllerGroup&&) = default;
+
+  void Set(double speed) override;
+  double Get() const override;
+  void SetInverted(bool isInverted) override;
+  bool GetInverted() const override;
+  void Disable() override;
+  void StopMotor() override;
+  void PIDWrite(double output) override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  bool m_isInverted = false;
+  std::vector<std::reference_wrapper<SpeedController>> m_speedControllers;
+};
+
+}  // namespace frc
+
+#include "frc/SpeedControllerGroup.inc"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc
new file mode 100644
index 0000000..ba4b766
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/SpeedControllerGroup.inc
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+template <class... SpeedControllers>
+SpeedControllerGroup::SpeedControllerGroup(
+    SpeedController& speedController, SpeedControllers&... speedControllers)
+    : m_speedControllers{speedController, speedControllers...} {
+  for (auto& speedController : m_speedControllers)
+    AddChild(&speedController.get());
+  static int instances = 0;
+  ++instances;
+  SetName("SpeedControllerGroup", instances);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Talon.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Talon.h
new file mode 100644
index 0000000..9a5400f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Talon.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Cross the Road Electronics (CTRE) Talon and Talon SR Speed Controller.
+ */
+class Talon : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Talon (original or Talon SR).
+   *
+   * @param channel The PWM channel number that the Talon is attached to. 0-9
+   *                are on-board, 10-19 are on the MXP port
+   */
+  explicit Talon(int channel);
+
+  Talon(Talon&&) = default;
+  Talon& operator=(Talon&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Threads.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Threads.h
new file mode 100644
index 0000000..3c44961
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Threads.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <thread>
+
+namespace frc {
+
+/**
+ * Get the thread priority for the specified thread.
+ *
+ * @param thread     Reference to the thread to get the priority for.
+ * @param isRealTime Set to true if thread is realtime, otherwise false.
+ * @return The current thread priority. Scaled 1-99, with 1 being highest.
+ */
+int GetThreadPriority(std::thread& thread, bool* isRealTime);
+
+/**
+ * Get the thread priority for the current thread
+ *
+ * @param isRealTime Set to true if thread is realtime, otherwise false.
+ * @return The current thread priority. Scaled 1-99.
+ */
+int GetCurrentThreadPriority(bool* isRealTime);
+
+/**
+ * Sets the thread priority for the specified thread
+ *
+ * @param thread   Reference to the thread to set the priority of.
+ * @param realTime Set to true to set a realtime priority, false for standard
+ *                 priority.
+ * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+ *                 highest. On RoboRIO, priority is ignored for non realtime
+ *                 setting.
+ *
+ * @return The success state of setting the priority
+ */
+bool SetThreadPriority(std::thread& thread, bool realTime, int priority);
+
+/**
+ * Sets the thread priority for the current thread
+ *
+ * @param realTime Set to true to set a realtime priority, false for standard
+ *                 priority.
+ * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+ *                 highest. On RoboRIO, priority is ignored for non realtime
+ *                 setting.
+ *
+ * @return The success state of setting the priority
+ */
+bool SetCurrentThreadPriority(bool realTime, int priority);
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/TimedRobot.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/TimedRobot.h
new file mode 100644
index 0000000..a6da5ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/TimedRobot.h
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <hal/Types.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/IterativeRobotBase.h"
+
+namespace frc {
+
+/**
+ * TimedRobot implements the IterativeRobotBase robot program framework.
+ *
+ * The TimedRobot class is intended to be subclassed by a user creating a
+ * robot program.
+ *
+ * Periodic() functions from the base class are called on an interval by a
+ * Notifier instance.
+ */
+class TimedRobot : public IterativeRobotBase, public ErrorBase {
+ public:
+  static constexpr double kDefaultPeriod = 0.02;
+
+  /**
+   * Provide an alternate "main loop" via StartCompetition().
+   */
+  void StartCompetition() override;
+
+  /**
+   * Get the time period between calls to Periodic() functions.
+   */
+  double GetPeriod() const;
+
+  /**
+   * Constructor for TimedRobot.
+   *
+   * @param period Period in seconds.
+   */
+  explicit TimedRobot(double period = kDefaultPeriod);
+
+  ~TimedRobot() override;
+
+  TimedRobot(TimedRobot&& rhs);
+  TimedRobot& operator=(TimedRobot&& rhs);
+
+ private:
+  HAL_NotifierHandle m_notifier{0};
+
+  // The absolute expiration time
+  double m_expirationTime = 0;
+
+  /**
+   * Update the HAL alarm time.
+   */
+  void UpdateAlarm();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Timer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Timer.h
new file mode 100644
index 0000000..f665c83
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Timer.h
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/deprecated.h>
+#include <wpi/mutex.h>
+
+#include "frc/Base.h"
+
+namespace frc {
+
+using TimerInterruptHandler = void (*)(void* param);
+
+/**
+ * Pause the task for a specified time.
+ *
+ * Pause the execution of the program for a specified period of time given in
+ * seconds. Motors will continue to run at their last assigned values, and
+ * sensors will continue to update. Only the task containing the wait will pause
+ * until the wait time is expired.
+ *
+ * @param seconds Length of time to pause, in seconds.
+ */
+void Wait(double seconds);
+
+/**
+ * Return the FPGA system clock time in seconds.
+ *
+ * This is deprecated and just forwards to Timer::GetFPGATimestamp().
+ *
+ * @return Robot running time in seconds.
+ */
+WPI_DEPRECATED("Use Timer::GetFPGATimestamp() instead.")
+double GetClock();
+
+/**
+ * @brief  Gives real-time clock system time with nanosecond resolution
+ * @return The time, just in case you want the robot to start autonomous at 8pm
+ *         on Saturday.
+ */
+double GetTime();
+
+/**
+ * Timer objects measure accumulated time in seconds.
+ *
+ * The timer object functions like a stopwatch. It can be started, stopped, and
+ * cleared. When the timer is running its value counts up in seconds. When
+ * stopped, the timer holds the current value. The implementation simply records
+ * the time when started and subtracts the current time whenever the value is
+ * requested.
+ */
+class Timer {
+ public:
+  /**
+   * Create a new timer object.
+   *
+   * Create a new timer object and reset the time to zero. The timer is
+   * initially not running and must be started.
+   */
+  Timer();
+
+  virtual ~Timer() = default;
+
+  Timer(Timer&&) = default;
+  Timer& operator=(Timer&&) = default;
+
+  /**
+   * Get the current time from the timer. If the clock is running it is derived
+   * from the current system clock the start time stored in the timer class. If
+   * the clock is not running, then return the time when it was last stopped.
+   *
+   * @return Current time value for this timer in seconds
+   */
+  double Get() const;
+
+  /**
+   * Reset the timer by setting the time to 0.
+   *
+   * Make the timer startTime the current time so new requests will be relative
+   * to now.
+   */
+  void Reset();
+
+  /**
+   * Start the timer running.
+   *
+   * Just set the running flag to true indicating that all time requests should
+   * be relative to the system clock.
+   */
+  void Start();
+
+  /**
+   * Stop the timer.
+   *
+   * This computes the time as of now and clears the running flag, causing all
+   * subsequent time requests to be read from the accumulated time rather than
+   * looking at the system clock.
+   */
+  void Stop();
+
+  /**
+   * Check if the period specified has passed and if it has, advance the start
+   * time by that period. This is useful to decide if it's time to do periodic
+   * work without drifting later by the time it took to get around to checking.
+   *
+   * @param period The period to check for (in seconds).
+   * @return       True if the period has passed.
+   */
+  bool HasPeriodPassed(double period);
+
+  /**
+   * Return the FPGA system clock time in seconds.
+   *
+   * Return the time from the FPGA hardware clock in seconds since the FPGA
+   * started. Rolls over after 71 minutes.
+   *
+   * @returns Robot running time in seconds.
+   */
+  static double GetFPGATimestamp();
+
+  /**
+   * Return the approximate match time.
+   *
+   * The FMS does not send an official match time to the robots, but does send
+   * an approximate match time. The value will count down the time remaining in
+   * the current period (auto or teleop).
+   *
+   * Warning: This is not an official time (so it cannot be used to dispute ref
+   * calls or guarantee that a function will trigger before the match ends).
+   *
+   * The Practice Match function of the DS approximates the behavior seen on the
+   * field.
+   *
+   * @return Time remaining in current match period (auto or teleop)
+   */
+  static double GetMatchTime();
+
+  // The time, in seconds, at which the 32-bit FPGA timestamp rolls over to 0
+  static const double kRolloverTime;
+
+ private:
+  double m_startTime = 0.0;
+  double m_accumulatedTime = 0.0;
+  bool m_running = false;
+  mutable wpi::mutex m_mutex;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Ultrasonic.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Ultrasonic.h
new file mode 100644
index 0000000..82ae6ca
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Ultrasonic.h
@@ -0,0 +1,231 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <memory>
+#include <thread>
+#include <vector>
+
+#include "frc/Counter.h"
+#include "frc/ErrorBase.h"
+#include "frc/PIDSource.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class DigitalInput;
+class DigitalOutput;
+
+/**
+ * Ultrasonic rangefinder class.
+ *
+ * The Ultrasonic rangefinder measures absolute distance based on the round-trip
+ * time of a ping generated by the controller. These sensors use two
+ * transducers, a speaker and a microphone both tuned to the ultrasonic range. A
+ * common ultrasonic sensor, the Daventech SRF04 requires a short pulse to be
+ * generated on a digital channel. This causes the chirp to be emitted. A second
+ * line becomes high as the ping is transmitted and goes low when the echo is
+ * received. The time that the line is high determines the round trip distance
+ * (time of flight).
+ */
+class Ultrasonic : public ErrorBase, public SendableBase, public PIDSource {
+ public:
+  enum DistanceUnit { kInches = 0, kMilliMeters = 1 };
+
+  /**
+   * Create an instance of the Ultrasonic Sensor.
+   *
+   * This is designed to support the Daventech SRF04 and Vex ultrasonic sensors.
+   *
+   * @param pingChannel The digital output channel that sends the pulse to
+   *                    initiate the sensor sending the ping.
+   * @param echoChannel The digital input channel that receives the echo. The
+   *                    length of time that the echo is high represents the
+   *                    round trip time of the ping, and the distance.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  Ultrasonic(int pingChannel, int echoChannel, DistanceUnit units = kInches);
+
+  /**
+   * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+   * channel and a DigitalOutput for the ping channel.
+   *
+   * @param pingChannel The digital output object that starts the sensor doing a
+   *                    ping. Requires a 10uS pulse to start.
+   * @param echoChannel The digital input object that times the return pulse to
+   *                    determine the range.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  Ultrasonic(DigitalOutput* pingChannel, DigitalInput* echoChannel,
+             DistanceUnit units = kInches);
+
+  /**
+   * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+   * channel and a DigitalOutput for the ping channel.
+   *
+   * @param pingChannel The digital output object that starts the sensor doing a
+   *                    ping. Requires a 10uS pulse to start.
+   * @param echoChannel The digital input object that times the return pulse to
+   *                    determine the range.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  Ultrasonic(DigitalOutput& pingChannel, DigitalInput& echoChannel,
+             DistanceUnit units = kInches);
+
+  /**
+   * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo
+   * channel and a DigitalOutput for the ping channel.
+   *
+   * @param pingChannel The digital output object that starts the sensor doing a
+   *                    ping. Requires a 10uS pulse to start.
+   * @param echoChannel The digital input object that times the return pulse to
+   *                    determine the range.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  Ultrasonic(std::shared_ptr<DigitalOutput> pingChannel,
+             std::shared_ptr<DigitalInput> echoChannel,
+             DistanceUnit units = kInches);
+
+  ~Ultrasonic() override;
+
+  Ultrasonic(Ultrasonic&&) = default;
+  Ultrasonic& operator=(Ultrasonic&&) = default;
+
+  /**
+   * Single ping to ultrasonic sensor.
+   *
+   * Send out a single ping to the ultrasonic sensor. This only works if
+   * automatic (round robin) mode is disabled. A single ping is sent out, and
+   * the counter should count the semi-period when it comes in. The counter is
+   * reset to make the current value invalid.
+   */
+  void Ping();
+
+  /**
+   * Check if there is a valid range measurement.
+   *
+   * The ranges are accumulated in a counter that will increment on each edge of
+   * the echo (return) signal. If the count is not at least 2, then the range
+   * has not yet been measured, and is invalid.
+   */
+  bool IsRangeValid() const;
+
+  /**
+   * Turn Automatic mode on/off.
+   *
+   * When in Automatic mode, all sensors will fire in round robin, waiting a set
+   * time between each sensor.
+   *
+   * @param enabling Set to true if round robin scheduling should start for all
+   *                 the ultrasonic sensors. This scheduling method assures that
+   *                 the sensors are non-interfering because no two sensors fire
+   *                 at the same time. If another scheduling algorithm is
+   *                 prefered, it can be implemented by pinging the sensors
+   *                 manually and waiting for the results to come back.
+   */
+  static void SetAutomaticMode(bool enabling);
+
+  /**
+   * Get the range in inches from the ultrasonic sensor.
+   *
+   * @return Range in inches of the target returned from the ultrasonic sensor.
+   *         If there is no valid value yet, i.e. at least one measurement
+   *         hasn't completed, then return 0.
+   */
+  double GetRangeInches() const;
+
+  /**
+   * Get the range in millimeters from the ultrasonic sensor.
+   *
+   * @return Range in millimeters of the target returned by the ultrasonic
+   *         sensor. If there is no valid value yet, i.e. at least one
+   *         measurement hasn't completed, then return 0.
+   */
+  double GetRangeMM() const;
+
+  bool IsEnabled() const;
+
+  void SetEnabled(bool enable);
+
+  /**
+   * Set the current DistanceUnit that should be used for the PIDSource base
+   * object.
+   *
+   * @param units The DistanceUnit that should be used.
+   */
+  void SetDistanceUnits(DistanceUnit units);
+
+  /**
+   * Get the current DistanceUnit that is used for the PIDSource base object.
+   *
+   * @return The type of DistanceUnit that is being used.
+   */
+  DistanceUnit GetDistanceUnits() const;
+
+  /**
+   * Get the range in the current DistanceUnit for the PIDSource base object.
+   *
+   * @return The range in DistanceUnit
+   */
+  double PIDGet() override;
+
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  /**
+   * Initialize the Ultrasonic Sensor.
+   *
+   * This is the common code that initializes the ultrasonic sensor given that
+   * there are two digital I/O channels allocated. If the system was running in
+   * automatic mode (round robin) when the new sensor is added, it is stopped,
+   * the sensor is added, then automatic mode is restored.
+   */
+  void Initialize();
+
+  /**
+   * Background task that goes through the list of ultrasonic sensors and pings
+   * each one in turn. The counter is configured to read the timing of the
+   * returned echo pulse.
+   *
+   * DANGER WILL ROBINSON, DANGER WILL ROBINSON:
+   * This code runs as a task and assumes that none of the ultrasonic sensors
+   * will change while it's running. Make sure to disable automatic mode before
+   * touching the list.
+   */
+  static void UltrasonicChecker();
+
+  // Time (sec) for the ping trigger pulse.
+  static constexpr double kPingTime = 10 * 1e-6;
+
+  // Priority that the ultrasonic round robin task runs.
+  static constexpr int kPriority = 64;
+
+  // Max time (ms) between readings.
+  static constexpr double kMaxUltrasonicTime = 0.1;
+  static constexpr double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
+
+  // Thread doing the round-robin automatic sensing
+  static std::thread m_thread;
+
+  // Ultrasonic sensors
+  static std::vector<Ultrasonic*> m_sensors;
+
+  // Automatic round-robin mode
+  static std::atomic<bool> m_automaticEnabled;
+
+  std::shared_ptr<DigitalOutput> m_pingChannel;
+  std::shared_ptr<DigitalInput> m_echoChannel;
+  bool m_enabled = false;
+  Counter m_counter;
+  DistanceUnit m_units;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Utility.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Utility.h
new file mode 100644
index 0000000..9cb7abb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Utility.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/**
+ * @file Contains global utility functions
+ */
+
+#include <stdint.h>
+
+#include <string>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+
+#define wpi_assert(condition) \
+  wpi_assert_impl(condition, #condition, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertWithMessage(condition, message)                     \
+  wpi_assert_impl(condition, #condition, message, __FILE__, __LINE__, \
+                  __FUNCTION__)
+
+#define wpi_assertEqual(a, b) \
+  wpi_assertEqual_impl(a, b, #a, #b, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertEqualWithMessage(a, b, message) \
+  wpi_assertEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, __FUNCTION__)
+
+#define wpi_assertNotEqual(a, b) \
+  wpi_assertNotEqual_impl(a, b, #a, #b, "", __FILE__, __LINE__, __FUNCTION__)
+#define wpi_assertNotEqualWithMessage(a, b, message)                 \
+  wpi_assertNotEqual_impl(a, b, #a, #b, message, __FILE__, __LINE__, \
+                          __FUNCTION__)
+
+/**
+ * Assert implementation.
+ *
+ * This allows breakpoints to be set on an assert. The users don't call this,
+ * but instead use the wpi_assert macros in Utility.h.
+ */
+bool wpi_assert_impl(bool conditionValue, const wpi::Twine& conditionText,
+                     const wpi::Twine& message, wpi::StringRef fileName,
+                     int lineNumber, wpi::StringRef funcName);
+
+/**
+ * Assert equal implementation.
+ *
+ * This determines whether the two given integers are equal. If not, the value
+ * of each is printed along with an optional message string. The users don't
+ * call this, but instead use the wpi_assertEqual macros in Utility.h.
+ */
+bool wpi_assertEqual_impl(int valueA, int valueB,
+                          const wpi::Twine& valueAString,
+                          const wpi::Twine& valueBString,
+                          const wpi::Twine& message, wpi::StringRef fileName,
+                          int lineNumber, wpi::StringRef funcName);
+
+/**
+ * Assert not equal implementation.
+ *
+ * This determines whether the two given integers are equal. If so, the value of
+ * each is printed along with an optional message string. The users don't call
+ * this, but instead use the wpi_assertNotEqual macros in Utility.h.
+ */
+bool wpi_assertNotEqual_impl(int valueA, int valueB,
+                             const wpi::Twine& valueAString,
+                             const wpi::Twine& valueBString,
+                             const wpi::Twine& message, wpi::StringRef fileName,
+                             int lineNumber, wpi::StringRef funcName);
+
+namespace frc {
+
+/**
+ * Return the FPGA Version number.
+ *
+ * For now, expect this to be competition year.
+ *
+ * @return FPGA Version number.
+ * @deprecated Use RobotController static class method
+ */
+WPI_DEPRECATED("Use RobotController static class method")
+int GetFPGAVersion();
+
+/**
+ * Return the FPGA Revision number.
+ *
+ * The format of the revision is 3 numbers. The 12 most significant bits are the
+ * Major Revision. The next 8 bits are the Minor Revision. The 12 least
+ * significant bits are the Build Number.
+ *
+ * @return FPGA Revision number.
+ * @deprecated Use RobotController static class method
+ */
+WPI_DEPRECATED("Use RobotController static class method")
+int64_t GetFPGARevision();
+
+/**
+ * Read the microsecond-resolution timer on the FPGA.
+ *
+ * @return The current time in microseconds according to the FPGA (since FPGA
+ *         reset).
+ * @deprecated Use RobotController static class method
+ */
+WPI_DEPRECATED("Use RobotController static class method")
+uint64_t GetFPGATime();
+
+/**
+ * Get the state of the "USER" button on the roboRIO.
+ *
+ * @return True if the button is currently pressed down
+ * @deprecated Use RobotController static class method
+ */
+WPI_DEPRECATED("Use RobotController static class method")
+bool GetUserButton();
+
+/**
+ * Get a stack trace, ignoring the first "offset" symbols.
+ *
+ * @param offset The number of symbols at the top of the stack to ignore
+ */
+std::string GetStackTrace(int offset);
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Victor.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Victor.h
new file mode 100644
index 0000000..5b6cba4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Victor.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Vex Robotics Victor 888 Speed Controller.
+ *
+ * The Vex Robotics Victor 884 Speed Controller can also be used with this
+ * class but may need to be calibrated per the Victor 884 user manual.
+ */
+class Victor : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a Victor.
+   *
+   * @param channel The PWM channel number that the Victor is attached to. 0-9
+   *                are on-board, 10-19 are on the MXP port
+   */
+  explicit Victor(int channel);
+
+  Victor(Victor&&) = default;
+  Victor& operator=(Victor&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/VictorSP.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/VictorSP.h
new file mode 100644
index 0000000..b23fba1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/VictorSP.h
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PWMSpeedController.h"
+
+namespace frc {
+
+/**
+ * Vex Robotics Victor SP Speed Controller.
+ */
+class VictorSP : public PWMSpeedController {
+ public:
+  /**
+   * Constructor for a VictorSP.
+   *
+   * @param channel The PWM channel that the VictorSP is attached to. 0-9 are
+   *                on-board, 10-19 are on the MXP port
+   */
+  explicit VictorSP(int channel);
+
+  VictorSP(VictorSP&&) = default;
+  VictorSP& operator=(VictorSP&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/WPIErrors.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/WPIErrors.h
new file mode 100644
index 0000000..a7c4f16
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/WPIErrors.h
@@ -0,0 +1,101 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+#ifdef WPI_ERRORS_DEFINE_STRINGS
+#define S(label, offset, message)            \
+  const char* wpi_error_s_##label = message; \
+  constexpr int wpi_error_value_##label = offset
+#else
+#define S(label, offset, message)         \
+  extern const char* wpi_error_s_##label; \
+  constexpr int wpi_error_value_##label = offset
+#endif
+
+// Fatal errors
+S(ModuleIndexOutOfRange, -1,
+  "Allocating module that is out of range or not found");
+S(ChannelIndexOutOfRange, -1, "Allocating channel that is out of range");
+S(NotAllocated, -2, "Attempting to free unallocated resource");
+S(ResourceAlreadyAllocated, -3, "Attempted to reuse an allocated resource");
+S(NoAvailableResources, -4, "No available resources to allocate");
+S(NullParameter, -5, "A pointer parameter to a method is nullptr");
+S(Timeout, -6, "A timeout has been exceeded");
+S(CompassManufacturerError, -7, "Compass manufacturer doesn't match HiTechnic");
+S(CompassTypeError, -8,
+  "Compass type doesn't match expected type for HiTechnic compass");
+S(IncompatibleMode, -9, "The object is in an incompatible mode");
+S(AnalogTriggerLimitOrderError, -10,
+  "AnalogTrigger limits error.  Lower limit > Upper Limit");
+S(AnalogTriggerPulseOutputError, -11,
+  "Attempted to read AnalogTrigger pulse output.");
+S(TaskError, -12, "Task can't be started");
+S(TaskIDError, -13, "Task error: Invalid ID.");
+S(TaskDeletedError, -14, "Task error: Task already deleted.");
+S(TaskOptionsError, -15, "Task error: Invalid options.");
+S(TaskMemoryError, -16, "Task can't be started due to insufficient memory.");
+S(TaskPriorityError, -17, "Task error: Invalid priority [1-255].");
+S(DriveUninitialized, -18, "RobotDrive not initialized for the C interface");
+S(CompressorNonMatching, -19,
+  "Compressor slot/channel doesn't match previous instance");
+S(CompressorAlreadyDefined, -20, "Creating a second compressor instance");
+S(CompressorUndefined, -21,
+  "Using compressor functions without defining compressor");
+S(InconsistentArrayValueAdded, -22,
+  "When packing data into an array to the dashboard, not all values added were "
+  "of the same type.");
+S(MismatchedComplexTypeClose, -23,
+  "When packing data to the dashboard, a Close for a complex type was called "
+  "without a matching Open.");
+S(DashboardDataOverflow, -24,
+  "When packing data to the dashboard, too much data was packed and the buffer "
+  "overflowed.");
+S(DashboardDataCollision, -25,
+  "The same buffer was used for packing data and for printing.");
+S(EnhancedIOMissing, -26, "IO is not attached or Enhanced IO is not enabled.");
+S(LineNotOutput, -27,
+  "Cannot SetDigitalOutput for a line not configured for output.");
+S(ParameterOutOfRange, -28, "A parameter is out of range.");
+S(SPIClockRateTooLow, -29, "SPI clock rate was below the minimum supported");
+S(JaguarVersionError, -30, "Jaguar firmware version error");
+S(JaguarMessageNotFound, -31, "Jaguar message not found");
+S(NetworkTablesReadError, -40, "Error reading NetworkTables socket");
+S(NetworkTablesBufferFull, -41, "Buffer full writing to NetworkTables socket");
+S(NetworkTablesWrongType, -42,
+  "The wrong type was read from the NetworkTables entry");
+S(NetworkTablesCorrupt, -43, "NetworkTables data stream is corrupt");
+S(SmartDashboardMissingKey, -43, "SmartDashboard data does not exist");
+S(CommandIllegalUse, -50, "Illegal use of Command");
+S(UnsupportedInSimulation, -80, "Unsupported in simulation");
+S(CameraServerError, -90, "CameraServer error");
+S(InvalidParameter, -100, "Invalid parameter value");
+
+// Warnings
+S(SampleRateTooHigh, 1, "Analog module sample rate is too high");
+S(VoltageOutOfRange, 2,
+  "Voltage to convert to raw value is out of range [-10; 10]");
+S(CompressorTaskError, 3, "Compressor task won't start");
+S(LoopTimingError, 4, "Digital module loop timing is not the expected value");
+S(NonBinaryDigitalValue, 5, "Digital output value is not 0 or 1");
+S(IncorrectBatteryChannel, 6,
+  "Battery measurement channel is not correct value");
+S(BadJoystickIndex, 7, "Joystick index is out of range, should be 0-3");
+S(BadJoystickAxis, 8, "Joystick axis or POV is out of range");
+S(InvalidMotorIndex, 9, "Motor index is out of range, should be 0-3");
+S(DriverStationTaskError, 10, "Driver Station task won't start");
+S(EnhancedIOPWMPeriodOutOfRange, 11,
+  "Driver Station Enhanced IO PWM Output period out of range.");
+S(SPIWriteNoMOSI, 12, "Cannot write to SPI port with no MOSI output");
+S(SPIReadNoMISO, 13, "Cannot read from SPI port with no MISO input");
+S(SPIReadNoData, 14, "No data available to read from SPI");
+S(IncompatibleState, 15,
+  "Incompatible State: The operation cannot be completed");
+
+#undef S
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/WPILib.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/WPILib.h
new file mode 100644
index 0000000..27c7b69
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/WPILib.h
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cameraserver/CameraServer.h>
+#include <vision/VisionRunner.h>
+
+#include "frc/ADXL345_I2C.h"
+#include "frc/ADXL345_SPI.h"
+#include "frc/ADXL362.h"
+#include "frc/ADXRS450_Gyro.h"
+#include "frc/AnalogAccelerometer.h"
+#include "frc/AnalogGyro.h"
+#include "frc/AnalogInput.h"
+#include "frc/AnalogOutput.h"
+#include "frc/AnalogPotentiometer.h"
+#include "frc/AnalogTrigger.h"
+#include "frc/AnalogTriggerOutput.h"
+#include "frc/BuiltInAccelerometer.h"
+#include "frc/Compressor.h"
+#include "frc/ControllerPower.h"
+#include "frc/Counter.h"
+#include "frc/DMC60.h"
+#include "frc/DigitalInput.h"
+#include "frc/DigitalOutput.h"
+#include "frc/DigitalSource.h"
+#include "frc/DoubleSolenoid.h"
+#include "frc/DriverStation.h"
+#include "frc/Encoder.h"
+#include "frc/ErrorBase.h"
+#include "frc/GearTooth.h"
+#include "frc/GenericHID.h"
+#include "frc/I2C.h"
+#include "frc/InterruptableSensorBase.h"
+#include "frc/IterativeRobot.h"
+#include "frc/Jaguar.h"
+#include "frc/Joystick.h"
+#include "frc/NidecBrushless.h"
+#include "frc/Notifier.h"
+#include "frc/PIDController.h"
+#include "frc/PIDOutput.h"
+#include "frc/PIDSource.h"
+#include "frc/PWM.h"
+#include "frc/PWMSpeedController.h"
+#include "frc/PWMTalonSRX.h"
+#include "frc/PWMVictorSPX.h"
+#include "frc/PowerDistributionPanel.h"
+#include "frc/Preferences.h"
+#include "frc/Relay.h"
+#include "frc/RobotBase.h"
+#include "frc/RobotController.h"
+#include "frc/RobotDrive.h"
+#include "frc/SD540.h"
+#include "frc/SPI.h"
+#include "frc/SampleRobot.h"
+#include "frc/SensorUtil.h"
+#include "frc/SerialPort.h"
+#include "frc/Servo.h"
+#include "frc/Solenoid.h"
+#include "frc/Spark.h"
+#include "frc/SpeedController.h"
+#include "frc/SpeedControllerGroup.h"
+#include "frc/Talon.h"
+#include "frc/Threads.h"
+#include "frc/TimedRobot.h"
+#include "frc/Timer.h"
+#include "frc/Ultrasonic.h"
+#include "frc/Utility.h"
+#include "frc/Victor.h"
+#include "frc/VictorSP.h"
+#include "frc/WPIErrors.h"
+#include "frc/XboxController.h"
+#include "frc/buttons/InternalButton.h"
+#include "frc/buttons/JoystickButton.h"
+#include "frc/buttons/NetworkButton.h"
+#include "frc/commands/Command.h"
+#include "frc/commands/CommandGroup.h"
+#include "frc/commands/PIDCommand.h"
+#include "frc/commands/PIDSubsystem.h"
+#include "frc/commands/PrintCommand.h"
+#include "frc/commands/Scheduler.h"
+#include "frc/commands/StartCommand.h"
+#include "frc/commands/Subsystem.h"
+#include "frc/commands/WaitCommand.h"
+#include "frc/commands/WaitForChildren.h"
+#include "frc/commands/WaitUntilCommand.h"
+#include "frc/drive/DifferentialDrive.h"
+#include "frc/drive/KilloughDrive.h"
+#include "frc/drive/MecanumDrive.h"
+#include "frc/filters/LinearDigitalFilter.h"
+#include "frc/interfaces/Accelerometer.h"
+#include "frc/interfaces/Gyro.h"
+#include "frc/interfaces/Potentiometer.h"
+#include "frc/smartdashboard/SendableChooser.h"
+#include "frc/smartdashboard/SmartDashboard.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Watchdog.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Watchdog.h
new file mode 100644
index 0000000..e15da1f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/Watchdog.h
@@ -0,0 +1,141 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <chrono>
+#include <functional>
+#include <utility>
+
+#include <hal/cpp/fpga_clock.h>
+#include <wpi/SafeThread.h>
+#include <wpi/StringMap.h>
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+/**
+ * A class that's a wrapper around a watchdog timer.
+ *
+ * When the timer expires, a message is printed to the console and an optional
+ * user-provided callback is invoked.
+ *
+ * The watchdog is initialized disabled, so the user needs to call Enable()
+ * before use.
+ */
+class Watchdog {
+ public:
+  /**
+   * Watchdog constructor.
+   *
+   * @param timeout  The watchdog's timeout in seconds with microsecond
+   *                 resolution.
+   * @param callback This function is called when the timeout expires.
+   */
+  Watchdog(double timeout, std::function<void()> callback);
+
+  template <typename Callable, typename Arg, typename... Args>
+  Watchdog(double timeout, Callable&& f, Arg&& arg, Args&&... args)
+      : Watchdog(timeout,
+                 std::bind(std::forward<Callable>(f), std::forward<Arg>(arg),
+                           std::forward<Args>(args)...)) {}
+
+  ~Watchdog();
+
+  Watchdog(Watchdog&&) = default;
+  Watchdog& operator=(Watchdog&&) = default;
+
+  /**
+   * Returns the time in seconds since the watchdog was last fed.
+   */
+  double GetTime() const;
+
+  /**
+   * Sets the watchdog's timeout.
+   *
+   * @param timeout The watchdog's timeout in seconds with microsecond
+   *                resolution.
+   */
+  void SetTimeout(double timeout);
+
+  /**
+   * Returns the watchdog's timeout in seconds.
+   */
+  double GetTimeout() const;
+
+  /**
+   * Returns true if the watchdog timer has expired.
+   */
+  bool IsExpired() const;
+
+  /**
+   * Adds time since last epoch to the list printed by PrintEpochs().
+   *
+   * Epochs are a way to partition the time elapsed so that when overruns occur,
+   * one can determine which parts of an operation consumed the most time.
+   *
+   * @param epochName The name to associate with the epoch.
+   */
+  void AddEpoch(wpi::StringRef epochName);
+
+  /**
+   * Prints list of epochs added so far and their times.
+   */
+  void PrintEpochs();
+
+  /**
+   * Resets the watchdog timer.
+   *
+   * This also enables the timer if it was previously disabled.
+   */
+  void Reset();
+
+  /**
+   * Enables the watchdog timer.
+   */
+  void Enable();
+
+  /**
+   * Disables the watchdog timer.
+   */
+  void Disable();
+
+  /**
+   * Enable or disable suppression of the generic timeout message.
+   *
+   * This may be desirable if the user-provided callback already prints a more
+   * specific message.
+   *
+   * @param suppress Whether to suppress generic timeout message.
+   */
+  void SuppressTimeoutMessage(bool suppress);
+
+ private:
+  // Used for timeout print rate-limiting
+  static constexpr std::chrono::milliseconds kMinPrintPeriod{1000};
+
+  hal::fpga_clock::time_point m_startTime;
+  std::chrono::microseconds m_timeout;
+  hal::fpga_clock::time_point m_expirationTime;
+  std::function<void()> m_callback;
+  hal::fpga_clock::time_point m_lastTimeoutPrintTime = hal::fpga_clock::epoch();
+  hal::fpga_clock::time_point m_lastEpochsPrintTime = hal::fpga_clock::epoch();
+
+  wpi::StringMap<std::chrono::microseconds> m_epochs;
+  bool m_isExpired = false;
+
+  bool m_suppressTimeoutMessage = false;
+
+  class Thread;
+  wpi::SafeThreadOwner<Thread>* m_owner;
+
+  bool operator>(const Watchdog& rhs);
+
+  static wpi::SafeThreadOwner<Thread>& GetThreadOwner();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/XboxController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/XboxController.h
new file mode 100644
index 0000000..8aa2d5b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/XboxController.h
@@ -0,0 +1,250 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/GenericHID.h"
+
+namespace frc {
+
+/**
+ * Handle input from Xbox 360 or Xbox One controllers connected to the Driver
+ * Station.
+ *
+ * This class handles Xbox input that comes from the Driver Station. Each time a
+ * value is requested the most recent value is returned. There is a single class
+ * instance for each controller and the mapping of ports to hardware buttons
+ * depends on the code in the Driver Station.
+ */
+class XboxController : public GenericHID {
+ public:
+  /**
+   * Construct an instance of an Xbox controller.
+   *
+   * The controller index is the USB port on the Driver Station.
+   *
+   * @param port The port on the Driver Station that the controller is plugged
+   *             into (0-5).
+   */
+  explicit XboxController(int port);
+
+  virtual ~XboxController() = default;
+
+  XboxController(XboxController&&) = default;
+  XboxController& operator=(XboxController&&) = default;
+
+  /**
+   * Get the X axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   */
+  double GetX(JoystickHand hand) const override;
+
+  /**
+   * Get the Y axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   */
+  double GetY(JoystickHand hand) const override;
+
+  /**
+   * Get the trigger axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   */
+  double GetTriggerAxis(JoystickHand hand) const;
+
+  /**
+   * Read the value of the bumper button on the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   */
+  bool GetBumper(JoystickHand hand) const;
+
+  /**
+   * Whether the bumper was pressed since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetBumperPressed(JoystickHand hand);
+
+  /**
+   * Whether the bumper was released since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBumperReleased(JoystickHand hand);
+
+  /**
+   * Read the value of the stick button on the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The state of the button.
+   */
+  bool GetStickButton(JoystickHand hand) const;
+
+  /**
+   * Whether the stick button was pressed since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetStickButtonPressed(JoystickHand hand);
+
+  /**
+   * Whether the stick button was released since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was released since the last check.
+   */
+  bool GetStickButtonReleased(JoystickHand hand);
+
+  /**
+   * Read the value of the A button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetAButton() const;
+
+  /**
+   * Whether the A button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetAButtonPressed();
+
+  /**
+   * Whether the A button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetAButtonReleased();
+
+  /**
+   * Read the value of the B button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetBButton() const;
+
+  /**
+   * Whether the B button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetBButtonPressed();
+
+  /**
+   * Whether the B button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBButtonReleased();
+
+  /**
+   * Read the value of the X button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetXButton() const;
+
+  /**
+   * Whether the X button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetXButtonPressed();
+
+  /**
+   * Whether the X button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetXButtonReleased();
+
+  /**
+   * Read the value of the Y button on the controller.
+   *
+   * @return The state of the button.
+   */
+  bool GetYButton() const;
+
+  /**
+   * Whether the Y button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetYButtonPressed();
+
+  /**
+   * Whether the Y button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetYButtonReleased();
+
+  /**
+   * Whether the Y button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBackButton() const;
+
+  /**
+   * Whether the back button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetBackButtonPressed();
+
+  /**
+   * Whether the back button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetBackButtonReleased();
+
+  /**
+   * Read the value of the start button on the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The state of the button.
+   */
+  bool GetStartButton() const;
+
+  /**
+   * Whether the start button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  bool GetStartButtonPressed();
+
+  /**
+   * Whether the start button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  bool GetStartButtonReleased();
+
+ private:
+  enum class Button {
+    kBumperLeft = 5,
+    kBumperRight = 6,
+    kStickLeft = 9,
+    kStickRight = 10,
+    kA = 1,
+    kB = 2,
+    kX = 3,
+    kY = 4,
+    kBack = 7,
+    kStart = 8
+  };
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/Button.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/Button.h
new file mode 100644
index 0000000..71641e9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/Button.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/buttons/Trigger.h"
+#include "frc/commands/Command.h"
+
+namespace frc {
+
+/**
+ * This class provides an easy way to link commands to OI inputs.
+ *
+ * It is very easy to link a button to a command.  For instance, you could link
+ * the trigger button of a joystick to a "score" command.
+ *
+ * This class represents a subclass of Trigger that is specifically aimed at
+ * buttons on an operator interface as a common use case of the more generalized
+ * Trigger objects. This is a simple wrapper around Trigger with the method
+ * names renamed to fit the Button object use.
+ */
+class Button : public Trigger {
+ public:
+  Button() = default;
+  Button(Button&&) = default;
+  Button& operator=(Button&&) = default;
+
+  /**
+   * Specifies the command to run when a button is first pressed.
+   *
+   * @param command The pointer to the command to run
+   */
+  virtual void WhenPressed(Command* command);
+
+  /**
+   * Specifies the command to be scheduled while the button is pressed.
+   *
+   * The command will be scheduled repeatedly while the button is pressed and
+   * will be canceled when the button is released.
+   *
+   * @param command The pointer to the command to run
+   */
+  virtual void WhileHeld(Command* command);
+
+  /**
+   * Specifies the command to run when the button is released.
+   *
+   * The command will be scheduled a single time.
+   *
+   * @param command The pointer to the command to run
+   */
+  virtual void WhenReleased(Command* command);
+
+  /**
+   * Cancels the specificed command when the button is pressed.
+   *
+   * @param command The command to be canceled
+   */
+  virtual void CancelWhenPressed(Command* command);
+
+  /**
+   * Toggle the specified command when the button is pressed.
+   *
+   * @param command The command to be toggled
+   */
+  virtual void ToggleWhenPressed(Command* command);
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ButtonScheduler.h
new file mode 100644
index 0000000..ec2e35b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ButtonScheduler.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class ButtonScheduler {
+ public:
+  ButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~ButtonScheduler() = default;
+
+  ButtonScheduler(ButtonScheduler&&) = default;
+  ButtonScheduler& operator=(ButtonScheduler&&) = default;
+
+  virtual void Execute() = 0;
+  void Start();
+
+ protected:
+  bool m_pressedLast;
+  Trigger* m_button;
+  Command* m_command;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/CancelButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/CancelButtonScheduler.h
new file mode 100644
index 0000000..69b8a11
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/CancelButtonScheduler.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class CancelButtonScheduler : public ButtonScheduler {
+ public:
+  CancelButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~CancelButtonScheduler() = default;
+
+  CancelButtonScheduler(CancelButtonScheduler&&) = default;
+  CancelButtonScheduler& operator=(CancelButtonScheduler&&) = default;
+
+  virtual void Execute();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/HeldButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/HeldButtonScheduler.h
new file mode 100644
index 0000000..ad4a160
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/HeldButtonScheduler.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class HeldButtonScheduler : public ButtonScheduler {
+ public:
+  HeldButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~HeldButtonScheduler() = default;
+
+  HeldButtonScheduler(HeldButtonScheduler&&) = default;
+  HeldButtonScheduler& operator=(HeldButtonScheduler&&) = default;
+
+  virtual void Execute();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/InternalButton.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/InternalButton.h
new file mode 100644
index 0000000..430a21e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/InternalButton.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/buttons/Button.h"
+
+namespace frc {
+
+class InternalButton : public Button {
+ public:
+  InternalButton() = default;
+  explicit InternalButton(bool inverted);
+  virtual ~InternalButton() = default;
+
+  InternalButton(InternalButton&&) = default;
+  InternalButton& operator=(InternalButton&&) = default;
+
+  void SetInverted(bool inverted);
+  void SetPressed(bool pressed);
+
+  virtual bool Get();
+
+ private:
+  bool m_pressed = false;
+  bool m_inverted = false;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/JoystickButton.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/JoystickButton.h
new file mode 100644
index 0000000..1b4264f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/JoystickButton.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/GenericHID.h"
+#include "frc/buttons/Button.h"
+
+namespace frc {
+
+class JoystickButton : public Button {
+ public:
+  JoystickButton(GenericHID* joystick, int buttonNumber);
+  virtual ~JoystickButton() = default;
+
+  JoystickButton(JoystickButton&&) = default;
+  JoystickButton& operator=(JoystickButton&&) = default;
+
+  virtual bool Get();
+
+ private:
+  GenericHID* m_joystick;
+  int m_buttonNumber;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/NetworkButton.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/NetworkButton.h
new file mode 100644
index 0000000..fef8065
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/NetworkButton.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <wpi/Twine.h>
+
+#include "frc/buttons/Button.h"
+
+namespace frc {
+
+class NetworkButton : public Button {
+ public:
+  NetworkButton(const wpi::Twine& tableName, const wpi::Twine& field);
+  NetworkButton(std::shared_ptr<nt::NetworkTable> table,
+                const wpi::Twine& field);
+  virtual ~NetworkButton() = default;
+
+  NetworkButton(NetworkButton&&) = default;
+  NetworkButton& operator=(NetworkButton&&) = default;
+
+  virtual bool Get();
+
+ private:
+  nt::NetworkTableEntry m_entry;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/POVButton.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/POVButton.h
new file mode 100644
index 0000000..15c4bf8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/POVButton.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/GenericHID.h"
+#include "frc/buttons/Button.h"
+
+namespace frc {
+class POVButton : public Button {
+ public:
+  /**
+   * Creates a POV button for triggering commands.
+   *
+   * @param joystick The GenericHID object that has the POV
+   * @param angle The desired angle in degrees (e.g. 90, 270)
+   * @param povNumber The POV number (@see GenericHID#GetPOV)
+   */
+  POVButton(GenericHID& joystick, int angle, int povNumber = 0);
+  virtual ~POVButton() = default;
+
+  POVButton(POVButton&&) = default;
+  POVButton& operator=(POVButton&&) = default;
+
+  bool Get() override;
+
+ private:
+  GenericHID* m_joystick;
+  int m_angle;
+  int m_povNumber;
+};
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/PressedButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/PressedButtonScheduler.h
new file mode 100644
index 0000000..0c1fb03
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/PressedButtonScheduler.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class PressedButtonScheduler : public ButtonScheduler {
+ public:
+  PressedButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~PressedButtonScheduler() = default;
+
+  PressedButtonScheduler(PressedButtonScheduler&&) = default;
+  PressedButtonScheduler& operator=(PressedButtonScheduler&&) = default;
+
+  virtual void Execute();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h
new file mode 100644
index 0000000..899a483
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ReleasedButtonScheduler.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class ReleasedButtonScheduler : public ButtonScheduler {
+ public:
+  ReleasedButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~ReleasedButtonScheduler() = default;
+
+  ReleasedButtonScheduler(ReleasedButtonScheduler&&) = default;
+  ReleasedButtonScheduler& operator=(ReleasedButtonScheduler&&) = default;
+
+  virtual void Execute();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ToggleButtonScheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ToggleButtonScheduler.h
new file mode 100644
index 0000000..aeb93b3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/ToggleButtonScheduler.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/buttons/ButtonScheduler.h"
+
+namespace frc {
+
+class Trigger;
+class Command;
+
+class ToggleButtonScheduler : public ButtonScheduler {
+ public:
+  ToggleButtonScheduler(bool last, Trigger* button, Command* orders);
+  virtual ~ToggleButtonScheduler() = default;
+
+  ToggleButtonScheduler(ToggleButtonScheduler&&) = default;
+  ToggleButtonScheduler& operator=(ToggleButtonScheduler&&) = default;
+
+  virtual void Execute();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/Trigger.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/Trigger.h
new file mode 100644
index 0000000..8f8c477
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/buttons/Trigger.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class Command;
+
+/**
+ * This class provides an easy way to link commands to inputs.
+ *
+ * It is very easy to link a polled input to a command. For instance, you could
+ * link the trigger button of a joystick to a "score" command or an encoder
+ * reaching a particular value.
+ *
+ * It is encouraged that teams write a subclass of Trigger if they want to have
+ * something unusual (for instance, if they want to react to the user holding
+ * a button while the robot is reading a certain sensor input). For this, they
+ * only have to write the {@link Trigger#Get()} method to get the full
+ * functionality of the Trigger class.
+ */
+class Trigger : public SendableBase {
+ public:
+  Trigger() = default;
+  ~Trigger() override = default;
+
+  Trigger(Trigger&&) = default;
+  Trigger& operator=(Trigger&&) = default;
+
+  bool Grab();
+  virtual bool Get() = 0;
+  void WhenActive(Command* command);
+  void WhileActive(Command* command);
+  void WhenInactive(Command* command);
+  void CancelWhenActive(Command* command);
+  void ToggleWhenActive(Command* command);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  std::atomic_bool m_sendablePressed{false};
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/circular_buffer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/circular_buffer.h
new file mode 100644
index 0000000..b5ebd16
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/circular_buffer.h
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cstddef>
+#include <vector>
+
+namespace frc {
+
+/**
+ * This is a simple circular buffer so we don't need to "bucket brigade" copy
+ * old values.
+ */
+template <class T>
+class circular_buffer {
+ public:
+  explicit circular_buffer(size_t size);
+
+  using value_type = T;
+  using reference = value_type&;
+  using const_reference = const value_type&;
+  using pointer = value_type*;
+  using size_type = size_t;
+  using iterator_category = std::forward_iterator_tag;
+  using difference_type = std::ptrdiff_t;
+
+  size_type size() const;
+  T& front();
+  const T& front() const;
+  T& back();
+  const T& back() const;
+  void push_front(T value);
+  void push_back(T value);
+  T pop_front();
+  T pop_back();
+  void resize(size_t size);
+  void reset();
+
+  T& operator[](size_t index);
+  const T& operator[](size_t index) const;
+
+ private:
+  std::vector<T> m_data;
+
+  // Index of element at front of buffer
+  size_t m_front = 0;
+
+  // Number of elements used in buffer
+  size_t m_length = 0;
+
+  size_t ModuloInc(size_t index);
+  size_t ModuloDec(size_t index);
+};
+
+}  // namespace frc
+
+#include "frc/circular_buffer.inc"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/circular_buffer.inc b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/circular_buffer.inc
new file mode 100644
index 0000000..4af5040
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/circular_buffer.inc
@@ -0,0 +1,239 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <algorithm>
+
+namespace frc {
+
+template <class T>
+circular_buffer<T>::circular_buffer(size_t size) : m_data(size, 0) {}
+
+/**
+ * Returns number of elements in buffer
+ */
+template <class T>
+typename circular_buffer<T>::size_type circular_buffer<T>::size() const {
+  return m_length;
+}
+
+/**
+ * Returns value at front of buffer
+ */
+template <class T>
+T& circular_buffer<T>::front() {
+  return (*this)[0];
+}
+
+/**
+ * Returns value at front of buffer
+ */
+template <class T>
+const T& circular_buffer<T>::front() const {
+  return (*this)[0];
+}
+
+/**
+ * Returns value at back of buffer
+ */
+template <class T>
+T& circular_buffer<T>::back() {
+  // If there are no elements in the buffer, do nothing
+  if (m_length == 0) {
+    return 0;
+  }
+
+  return m_data[(m_front + m_length - 1) % m_data.size()];
+}
+
+/**
+ * Returns value at back of buffer
+ */
+template <class T>
+const T& circular_buffer<T>::back() const {
+  // If there are no elements in the buffer, do nothing
+  if (m_length == 0) {
+    return 0;
+  }
+
+  return m_data[(m_front + m_length - 1) % m_data.size()];
+}
+
+/**
+ * Push new value onto front of the buffer. The value at the back is overwritten
+ * if the buffer is full.
+ */
+template <class T>
+void circular_buffer<T>::push_front(T value) {
+  if (m_data.size() == 0) {
+    return;
+  }
+
+  m_front = ModuloDec(m_front);
+
+  m_data[m_front] = value;
+
+  if (m_length < m_data.size()) {
+    m_length++;
+  }
+}
+
+/**
+ * Push new value onto back of the buffer. The value at the front is overwritten
+ * if the buffer is full.
+ */
+template <class T>
+void circular_buffer<T>::push_back(T value) {
+  if (m_data.size() == 0) {
+    return;
+  }
+
+  m_data[(m_front + m_length) % m_data.size()] = value;
+
+  if (m_length < m_data.size()) {
+    m_length++;
+  } else {
+    // Increment front if buffer is full to maintain size
+    m_front = ModuloInc(m_front);
+  }
+}
+
+/**
+ * Pop value at front of buffer.
+ */
+template <class T>
+T circular_buffer<T>::pop_front() {
+  // If there are no elements in the buffer, do nothing
+  if (m_length == 0) {
+    return 0;
+  }
+
+  T& temp = m_data[m_front];
+  m_front = ModuloInc(m_front);
+  m_length--;
+  return temp;
+}
+
+/**
+ * Pop value at back of buffer.
+ */
+template <class T>
+T circular_buffer<T>::pop_back() {
+  // If there are no elements in the buffer, do nothing
+  if (m_length == 0) {
+    return 0;
+  }
+
+  m_length--;
+  return m_data[(m_front + m_length) % m_data.size()];
+}
+
+/**
+ * Resizes internal buffer to given size.
+ */
+template <class T>
+void circular_buffer<T>::resize(size_t size) {
+  if (size > m_data.size()) {
+    // Find end of buffer
+    size_t insertLocation = (m_front + m_length) % m_data.size();
+
+    // If insertion location precedes front of buffer, push front index back
+    if (insertLocation <= m_front) {
+      m_front += size - m_data.size();
+    }
+
+    // Add elements to end of buffer
+    m_data.insert(m_data.begin() + insertLocation, size - m_data.size(), 0);
+  } else if (size < m_data.size()) {
+    /* 1) Shift element block start at "front" left as many blocks as were
+     *    removed up to but not exceeding buffer[0]
+     * 2) Shrink buffer, which will remove even more elements automatically if
+     *    necessary
+     */
+    size_t elemsToRemove = m_data.size() - size;
+    auto frontIter = m_data.begin() + m_front;
+    if (m_front < elemsToRemove) {
+      /* Remove elements from end of buffer before shifting start of element
+       * block. Doing so saves a few copies.
+       */
+      m_data.erase(frontIter + size, m_data.end());
+
+      // Shift start of element block to left
+      m_data.erase(m_data.begin(), frontIter);
+
+      // Update metadata
+      m_front = 0;
+    } else {
+      // Shift start of element block to left
+      m_data.erase(frontIter - elemsToRemove, frontIter);
+
+      // Update metadata
+      m_front -= elemsToRemove;
+    }
+
+    /* Length only changes during a shrink if all unused spaces have been
+     * removed. Length decreases as used spaces are removed to meet the
+     * required size.
+     */
+    if (m_length > size) {
+      m_length = size;
+    }
+  }
+}
+
+/**
+ * Sets internal buffer contents to zero.
+ */
+template <class T>
+void circular_buffer<T>::reset() {
+  std::fill(m_data.begin(), m_data.end(), 0);
+  m_front = 0;
+  m_length = 0;
+}
+
+/**
+ * @return Element at index starting from front of buffer.
+ */
+template <class T>
+T& circular_buffer<T>::operator[](size_t index) {
+  return m_data[(m_front + index) % m_data.size()];
+}
+
+/**
+ * @return Element at index starting from front of buffer.
+ */
+template <class T>
+const T& circular_buffer<T>::operator[](size_t index) const {
+  return m_data[(m_front + index) % m_data.size()];
+}
+
+/**
+ * Increment an index modulo the length of the buffer.
+ *
+ * @return The result of the modulo operation.
+ */
+template <class T>
+size_t circular_buffer<T>::ModuloInc(size_t index) {
+  return (index + 1) % m_data.size();
+}
+
+/**
+ * Decrement an index modulo the length of the buffer.
+ *
+ * @return The result of the modulo operation.
+ */
+template <class T>
+size_t circular_buffer<T>::ModuloDec(size_t index) {
+  if (index == 0) {
+    return m_data.size() - 1;
+  } else {
+    return index - 1;
+  }
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Command.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Command.h
new file mode 100644
index 0000000..f1990c7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Command.h
@@ -0,0 +1,461 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <wpi/SmallPtrSet.h>
+#include <wpi/Twine.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/commands/Subsystem.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class CommandGroup;
+
+/**
+ * The Command class is at the very core of the entire command framework.
+ *
+ * Every command can be started with a call to Start(). Once a command is
+ * started it will call Initialize(), and then will repeatedly call Execute()
+ * until the IsFinished() returns true. Once it does,End() will be called.
+ *
+ * However, if at any point while it is running Cancel() is called, then the
+ * command will be stopped and Interrupted() will be called.
+ *
+ * If a command uses a Subsystem, then it should specify that it does so by
+ * calling the Requires() method in its constructor. Note that a Command may
+ * have multiple requirements, and Requires() should be called for each one.
+ *
+ * If a command is running and a new command with shared requirements is
+ * started, then one of two things will happen. If the active command is
+ * interruptible, then Cancel() will be called and the command will be removed
+ * to make way for the new one. If the active command is not interruptible, the
+ * other one will not even be started, and the active one will continue
+ * functioning.
+ *
+ * @see CommandGroup
+ * @see Subsystem
+ */
+class Command : public ErrorBase, public SendableBase {
+  friend class CommandGroup;
+  friend class Scheduler;
+
+ public:
+  /**
+   * Creates a new command.
+   *
+   * The name of this command will be default.
+   */
+  Command();
+
+  /**
+   * Creates a new command with the given name and no timeout.
+   *
+   * @param name the name for this command
+   */
+  explicit Command(const wpi::Twine& name);
+
+  /**
+   * Creates a new command with the given timeout and a default name.
+   *
+   * @param timeout the time (in seconds) before this command "times out"
+   * @see IsTimedOut()
+   */
+  explicit Command(double timeout);
+
+  /**
+   * Creates a new command with the given timeout and a default name.
+   *
+   * @param subsystem the subsystem that the command requires
+   */
+  explicit Command(Subsystem& subsystem);
+
+  /**
+   * Creates a new command with the given name and timeout.
+   *
+   * @param name    the name of the command
+   * @param timeout the time (in seconds) before this command "times out"
+   * @see IsTimedOut()
+   */
+  Command(const wpi::Twine& name, double timeout);
+
+  /**
+   * Creates a new command with the given name and timeout.
+   *
+   * @param name      the name of the command
+   * @param subsystem the subsystem that the command requires
+   */
+  Command(const wpi::Twine& name, Subsystem& subsystem);
+
+  /**
+   * Creates a new command with the given name and timeout.
+   *
+   * @param timeout   the time (in seconds) before this command "times out"
+   * @param subsystem the subsystem that the command requires @see IsTimedOut()
+   */
+  Command(double timeout, Subsystem& subsystem);
+
+  /**
+   * Creates a new command with the given name and timeout.
+   *
+   * @param name      the name of the command
+   * @param timeout   the time (in seconds) before this command "times out"
+   * @param subsystem the subsystem that the command requires @see IsTimedOut()
+   */
+  Command(const wpi::Twine& name, double timeout, Subsystem& subsystem);
+
+  ~Command() override = default;
+
+  Command(Command&&) = default;
+  Command& operator=(Command&&) = default;
+
+  /**
+   * Returns the time since this command was initialized (in seconds).
+   *
+   * This function will work even if there is no specified timeout.
+   *
+   * @return the time since this command was initialized (in seconds).
+   */
+  double TimeSinceInitialized() const;
+
+  /**
+   * This method specifies that the given Subsystem is used by this command.
+   *
+   * This method is crucial to the functioning of the Command System in general.
+   *
+   * Note that the recommended way to call this method is in the constructor.
+   *
+   * @param subsystem The Subsystem required
+   * @see Subsystem
+   */
+  void Requires(Subsystem* s);
+
+  /**
+   * Starts up the command. Gets the command ready to start.
+   *
+   * Note that the command will eventually start, however it will not
+   * necessarily do so immediately, and may in fact be canceled before
+   * initialize is even called.
+   */
+  void Start();
+
+  /**
+   * The run method is used internally to actually run the commands.
+   *
+   * @return Whether or not the command should stay within the Scheduler.
+   */
+  bool Run();
+
+  /**
+   * This will cancel the current command.
+   *
+   * This will cancel the current command eventually. It can be called multiple
+   * times. And it can be called when the command is not running. If the command
+   * is running though, then the command will be marked as canceled and
+   * eventually removed.
+   *
+   * A command can not be canceled if it is a part of a command group, you must
+   * cancel the command group instead.
+   */
+  void Cancel();
+
+  /**
+   * Returns whether or not the command is running.
+   *
+   * This may return true even if the command has just been canceled, as it may
+   * not have yet called Interrupted().
+   *
+   * @return whether or not the command is running
+   */
+  bool IsRunning() const;
+
+  /**
+   * Returns whether or not the command has been initialized.
+   *
+   * @return whether or not the command has been initialized.
+   */
+  bool IsInitialized() const;
+
+  /**
+   * Returns whether or not the command has completed running.
+   *
+   * @return whether or not the command has completed running.
+   */
+  bool IsCompleted() const;
+
+  /**
+   * Returns whether or not this has been canceled.
+   *
+   * @return whether or not this has been canceled
+   */
+  bool IsCanceled() const;
+
+  /**
+   * Returns whether or not this command can be interrupted.
+   *
+   * @return whether or not this command can be interrupted
+   */
+  bool IsInterruptible() const;
+
+  /**
+   * Sets whether or not this command can be interrupted.
+   *
+   * @param interruptible whether or not this command can be interrupted
+   */
+  void SetInterruptible(bool interruptible);
+
+  /**
+   * Checks if the command requires the given Subsystem.
+   *
+   * @param system the system
+   * @return whether or not the subsystem is required (false if given nullptr)
+   */
+  bool DoesRequire(Subsystem* subsystem) const;
+
+  using SubsystemSet = wpi::SmallPtrSetImpl<Subsystem*>;
+
+  /**
+   * Returns the requirements (as an std::set of Subsystem pointers) of this
+   * command.
+   *
+   * @return The requirements (as an std::set of Subsystem pointers) of this
+   *         command
+   */
+  const SubsystemSet& GetRequirements() const;
+
+  /**
+   * Returns the CommandGroup that this command is a part of.
+   *
+   * Will return null if this Command is not in a group.
+   *
+   * @return The CommandGroup that this command is a part of (or null if not in
+   *         group)
+   */
+  CommandGroup* GetGroup() const;
+
+  /**
+   * Sets whether or not this Command should run when the robot is disabled.
+   *
+   * By default a command will not run when the robot is disabled, and will in
+   * fact be canceled.
+   *
+   * @param run Whether this command should run when the robot is disabled.
+   */
+  void SetRunWhenDisabled(bool run);
+
+  /**
+   * Returns whether or not this Command will run when the robot is disabled, or
+   * if it will cancel itself.
+   *
+   * @return Whether this Command will run when the robot is disabled, or if it
+   * will cancel itself.
+   */
+  bool WillRunWhenDisabled() const;
+
+  /**
+   * Get the ID (sequence number) for this command.
+   *
+   * The ID is a unique sequence number that is incremented for each command.
+   *
+   * @return The ID of this command
+   */
+  int GetID() const;
+
+ protected:
+  /**
+   * Sets the timeout of this command.
+   *
+   * @param timeout the timeout (in seconds)
+   * @see IsTimedOut()
+   */
+  void SetTimeout(double timeout);
+
+  /**
+   * Returns whether or not the TimeSinceInitialized() method returns a number
+   * which is greater than or equal to the timeout for the command.
+   *
+   * If there is no timeout, this will always return false.
+   *
+   * @return whether the time has expired
+   */
+  bool IsTimedOut() const;
+
+  /**
+   * If changes are locked, then this will generate a CommandIllegalUse error.
+   *
+   * @param message The message to report on error (it is appended by a default
+   *                message)
+   * @return True if assert passed, false if assert failed.
+   */
+  bool AssertUnlocked(const std::string& message);
+
+  /**
+   * Sets the parent of this command. No actual change is made to the group.
+   *
+   * @param parent the parent
+   */
+  void SetParent(CommandGroup* parent);
+
+  /**
+   * Returns whether the command has a parent.
+   *
+   * @param True if the command has a parent.
+   */
+  bool IsParented() const;
+
+  /**
+   * Clears list of subsystem requirements.
+   *
+   * This is only used by ConditionalCommand so cancelling the chosen command
+   * works properly in CommandGroup.
+   */
+  void ClearRequirements();
+
+  /**
+   * The initialize method is called the first time this Command is run after
+   * being started.
+   */
+  virtual void Initialize();
+
+  /**
+   * The execute method is called repeatedly until this Command either finishes
+   * or is canceled.
+   */
+  virtual void Execute();
+
+  /**
+   * Returns whether this command is finished.
+   *
+   * If it is, then the command will be removed and End() will be called.
+   *
+   * It may be useful for a team to reference the IsTimedOut() method for
+   * time-sensitive commands.
+   *
+   * Returning false will result in the command never ending automatically.
+   * It may still be cancelled manually or interrupted by another command.
+   * Returning true will result in the command executing once and finishing
+   * immediately. We recommend using InstantCommand for this.
+   *
+   * @return Whether this command is finished.
+   * @see IsTimedOut()
+   */
+  virtual bool IsFinished() = 0;
+
+  /**
+   * Called when the command ended peacefully.
+   *
+   * This is where you may want to wrap up loose ends, like shutting off a motor
+   * that was being used in the command.
+   */
+  virtual void End();
+
+  /**
+   * Called when the command ends because somebody called Cancel() or another
+   * command shared the same requirements as this one, and booted it out.
+   *
+   * This is where you may want to wrap up loose ends, like shutting off a motor
+   * that was being used in the command.
+   *
+   * Generally, it is useful to simply call the End() method within this method,
+   * as done here.
+   */
+  virtual void Interrupted();
+
+  virtual void _Initialize();
+  virtual void _Interrupted();
+  virtual void _Execute();
+  virtual void _End();
+
+  /**
+   * This works like Cancel(), except that it doesn't throw an exception if it
+   * is a part of a command group.
+   *
+   * Should only be called by the parent command group.
+   */
+  virtual void _Cancel();
+
+  friend class ConditionalCommand;
+
+ private:
+  /**
+   * Prevents further changes from being made.
+   */
+  void LockChanges();
+
+  /**
+   * Called when the command has been removed.
+   *
+   * This will call Interrupted() or End().
+   */
+  void Removed();
+
+  /**
+   * This is used internally to mark that the command has been started.
+   *
+   * The lifecycle of a command is:
+   *
+   * StartRunning() is called. Run() is called (multiple times potentially).
+   * Removed() is called.
+   *
+   * It is very important that StartRunning() and Removed() be called in order
+   * or some assumptions of the code will be broken.
+   */
+  void StartRunning();
+
+  /**
+   * Called to indicate that the timer should start.
+   *
+   * This is called right before Initialize() is, inside the Run() method.
+   */
+  void StartTiming();
+
+  // The time since this command was initialized
+  double m_startTime = -1;
+
+  // The time (in seconds) before this command "times out" (-1 if no timeout)
+  double m_timeout;
+
+  // Whether or not this command has been initialized
+  bool m_initialized = false;
+
+  // The requirements (or null if no requirements)
+  wpi::SmallPtrSet<Subsystem*, 4> m_requirements;
+
+  // Whether or not it is running
+  bool m_running = false;
+
+  // Whether or not it is interruptible
+  bool m_interruptible = true;
+
+  // Whether or not it has been canceled
+  bool m_canceled = false;
+
+  // Whether or not it has been locked
+  bool m_locked = false;
+
+  // Whether this command should run when the robot is disabled
+  bool m_runWhenDisabled = false;
+
+  // The CommandGroup this is in
+  CommandGroup* m_parent = nullptr;
+
+  // Whether or not this command has completed running
+  bool m_completed = false;
+
+  int m_commandID = m_commandCounter++;
+  static int m_commandCounter;
+
+ public:
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/CommandGroup.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/CommandGroup.h
new file mode 100644
index 0000000..690ae6d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/CommandGroup.h
@@ -0,0 +1,180 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <vector>
+
+#include <wpi/Twine.h>
+
+#include "frc/commands/Command.h"
+#include "frc/commands/CommandGroupEntry.h"
+
+namespace frc {
+
+/**
+ * A CommandGroup is a list of commands which are executed in sequence.
+ *
+ * Commands in a CommandGroup are added using the AddSequential() method and are
+ * called sequentially. CommandGroups are themselves Commands and can be given
+ * to other CommandGroups.
+ *
+ * CommandGroups will carry all of the requirements of their Command
+ * subcommands. Additional requirements can be specified by calling Requires()
+ * normally in the constructor.
+ *
+ * CommandGroups can also execute commands in parallel, simply by adding them
+ * using AddParallel().
+ *
+ * @see Command
+ * @see Subsystem
+ */
+class CommandGroup : public Command {
+ public:
+  CommandGroup() = default;
+
+  /**
+   * Creates a new CommandGroup with the given name.
+   *
+   * @param name The name for this command group
+   */
+  explicit CommandGroup(const wpi::Twine& name);
+
+  virtual ~CommandGroup() = default;
+
+  CommandGroup(CommandGroup&&) = default;
+  CommandGroup& operator=(CommandGroup&&) = default;
+
+  /**
+   * Adds a new Command to the group. The Command will be started after all the
+   * previously added Commands.
+   *
+   * Note that any requirements the given Command has will be added to the
+   * group. For this reason, a Command's requirements can not be changed after
+   * being added to a group.
+   *
+   * It is recommended that this method be called in the constructor.
+   *
+   * @param command The Command to be added
+   */
+  void AddSequential(Command* command);
+
+  /**
+   * Adds a new Command to the group with a given timeout. The Command will be
+   * started after all the previously added commands.
+   *
+   * Once the Command is started, it will be run until it finishes or the time
+   * expires, whichever is sooner.  Note that the given Command will have no
+   * knowledge that it is on a timer.
+   *
+   * Note that any requirements the given Command has will be added to the
+   * group. For this reason, a Command's requirements can not be changed after
+   * being added to a group.
+   *
+   * It is recommended that this method be called in the constructor.
+   *
+   * @param command The Command to be added
+   * @param timeout The timeout (in seconds)
+   */
+  void AddSequential(Command* command, double timeout);
+
+  /**
+   * Adds a new child Command to the group. The Command will be started after
+   * all the previously added Commands.
+   *
+   * Instead of waiting for the child to finish, a CommandGroup will have it run
+   * at the same time as the subsequent Commands. The child will run until
+   * either it finishes, a new child with conflicting requirements is started,
+   * or the main sequence runs a Command with conflicting requirements. In the
+   * latter two cases, the child will be canceled even if it says it can't be
+   * interrupted.
+   *
+   * Note that any requirements the given Command has will be added to the
+   * group. For this reason, a Command's requirements can not be changed after
+   * being added to a group.
+   *
+   * It is recommended that this method be called in the constructor.
+   *
+   * @param command The command to be added
+   */
+  void AddParallel(Command* command);
+
+  /**
+   * Adds a new child Command to the group with the given timeout. The Command
+   * will be started after all the previously added Commands.
+   *
+   * Once the Command is started, it will run until it finishes, is interrupted,
+   * or the time expires, whichever is sooner. Note that the given Command will
+   * have no knowledge that it is on a timer.
+   *
+   * Instead of waiting for the child to finish, a CommandGroup will have it run
+   * at the same time as the subsequent Commands. The child will run until
+   * either it finishes, the timeout expires, a new child with conflicting
+   * requirements is started, or the main sequence runs a Command with
+   * conflicting requirements. In the latter two cases, the child will be
+   * canceled even if it says it can't be interrupted.
+   *
+   * Note that any requirements the given Command has will be added to the
+   * group. For this reason, a Command's requirements can not be changed after
+   * being added to a group.
+   *
+   * It is recommended that this method be called in the constructor.
+   *
+   * @param command The command to be added
+   * @param timeout The timeout (in seconds)
+   */
+  void AddParallel(Command* command, double timeout);
+
+  bool IsInterruptible() const;
+
+  int GetSize() const;
+
+ protected:
+  /**
+   * Can be overridden by teams.
+   */
+  virtual void Initialize();
+
+  /**
+   * Can be overridden by teams.
+   */
+  virtual void Execute();
+
+  /**
+   * Can be overridden by teams.
+   */
+  virtual bool IsFinished();
+
+  /**
+   * Can be overridden by teams.
+   */
+  virtual void End();
+
+  /**
+   * Can be overridden by teams.
+   */
+  virtual void Interrupted();
+
+  virtual void _Initialize();
+  virtual void _Execute();
+  virtual void _End();
+  virtual void _Interrupted();
+
+ private:
+  void CancelConflicts(Command* command);
+
+  // The commands in this group (stored in entries)
+  std::vector<CommandGroupEntry> m_commands;
+
+  // The active children in this group (stored in entries)
+  std::vector<CommandGroupEntry*> m_children;
+
+  // The current command, -1 signifies that none have been run
+  int m_currentCommandIndex = -1;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/CommandGroupEntry.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/CommandGroupEntry.h
new file mode 100644
index 0000000..2de1e43
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/CommandGroupEntry.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+class Command;
+
+class CommandGroupEntry {
+ public:
+  enum Sequence {
+    kSequence_InSequence,
+    kSequence_BranchPeer,
+    kSequence_BranchChild
+  };
+
+  CommandGroupEntry() = default;
+  CommandGroupEntry(Command* command, Sequence state, double timeout = -1.0);
+
+  CommandGroupEntry(CommandGroupEntry&&) = default;
+  CommandGroupEntry& operator=(CommandGroupEntry&&) = default;
+
+  bool IsTimedOut() const;
+
+  double m_timeout = -1.0;
+  Command* m_command = nullptr;
+  Sequence m_state = kSequence_InSequence;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/ConditionalCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/ConditionalCommand.h
new file mode 100644
index 0000000..142c5b0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/ConditionalCommand.h
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+#include "frc/commands/Command.h"
+
+namespace frc {
+
+/**
+ * A ConditionalCommand is a Command that starts one of two commands.
+ *
+ * A ConditionalCommand uses the Condition method to determine whether it should
+ * run onTrue or onFalse.
+ *
+ * A ConditionalCommand adds the proper Command to the Scheduler during
+ * Initialize() and then IsFinished() will return true once that Command has
+ * finished executing.
+ *
+ * If no Command is specified for onFalse, the occurrence of that condition
+ * will be a no-op.
+ *
+ * A CondtionalCommand will require the superset of subsystems of the onTrue
+ * and onFalse commands.
+ *
+ * @see Command
+ * @see Scheduler
+ */
+class ConditionalCommand : public Command {
+ public:
+  /**
+   * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
+   *
+   * @param onTrue  The Command to execute if Condition() returns true
+   * @param onFalse The Command to execute if Condition() returns false
+   */
+  explicit ConditionalCommand(Command* onTrue, Command* onFalse = nullptr);
+
+  /**
+   * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
+   *
+   * @param name    The name for this command group
+   * @param onTrue  The Command to execute if Condition() returns true
+   * @param onFalse The Command to execute if Condition() returns false
+   */
+  ConditionalCommand(const wpi::Twine& name, Command* onTrue,
+                     Command* onFalse = nullptr);
+
+  virtual ~ConditionalCommand() = default;
+
+  ConditionalCommand(ConditionalCommand&&) = default;
+  ConditionalCommand& operator=(ConditionalCommand&&) = default;
+
+ protected:
+  /**
+   * The Condition to test to determine which Command to run.
+   *
+   * @return true if m_onTrue should be run or false if m_onFalse should be run.
+   */
+  virtual bool Condition() = 0;
+
+  void _Initialize() override;
+  void _Cancel() override;
+  bool IsFinished() override;
+  void _Interrupted() override;
+
+ private:
+  // The Command to execute if Condition() returns true
+  Command* m_onTrue;
+
+  // The Command to execute if Condition() returns false
+  Command* m_onFalse;
+
+  // Stores command chosen by condition
+  Command* m_chosenCommand = nullptr;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/InstantCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/InstantCommand.h
new file mode 100644
index 0000000..987dc18
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/InstantCommand.h
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+
+#include <wpi/Twine.h>
+
+#include "frc/commands/Command.h"
+#include "frc/commands/Subsystem.h"
+
+namespace frc {
+
+/**
+ * This command will execute once, then finish immediately afterward.
+ *
+ * Subclassing InstantCommand is shorthand for returning true from IsFinished().
+ */
+class InstantCommand : public Command {
+ public:
+  /**
+   * Creates a new InstantCommand with the given name.
+   *
+   * @param name The name for this command
+   */
+  explicit InstantCommand(const wpi::Twine& name);
+
+  /**
+   * Creates a new InstantCommand with the given requirement.
+   *
+   * @param subsystem The subsystem that the command requires
+   */
+  explicit InstantCommand(Subsystem& subsystem);
+
+  /**
+   * Creates a new InstantCommand with the given name.
+   *
+   * @param name      The name for this command
+   * @param subsystem The subsystem that the command requires
+   */
+  InstantCommand(const wpi::Twine& name, Subsystem& subsystem);
+
+  /**
+   * Create a command that calls the given function when run.
+   *
+   * @param func The function to run when Initialize() is run.
+   */
+  explicit InstantCommand(std::function<void()> func);
+
+  /**
+   * Create a command that calls the given function when run.
+   *
+   * @param subsystem The subsystems that this command runs on.
+   * @param func      The function to run when Initialize() is run.
+   */
+  InstantCommand(Subsystem& subsystem, std::function<void()> func);
+
+  /**
+   * Create a command that calls the given function when run.
+   *
+   * @param name   The name of the command.
+   * @param func   The function to run when Initialize() is run.
+   */
+  InstantCommand(const wpi::Twine& name, std::function<void()> func);
+
+  /**
+   * Create a command that calls the given function when run.
+   *
+   * @param name      The name of the command.
+   * @param subsystem The subsystems that this command runs on.
+   * @param func      The function to run when Initialize() is run.
+   */
+  InstantCommand(const wpi::Twine& name, Subsystem& subsystem,
+                 std::function<void()> func);
+
+  InstantCommand() = default;
+  virtual ~InstantCommand() = default;
+
+  InstantCommand(InstantCommand&&) = default;
+  InstantCommand& operator=(InstantCommand&&) = default;
+
+ protected:
+  std::function<void()> m_func = nullptr;
+  void _Initialize() override;
+  bool IsFinished() override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PIDCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PIDCommand.h
new file mode 100644
index 0000000..02f1710
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PIDCommand.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/Twine.h>
+
+#include "frc/PIDController.h"
+#include "frc/PIDOutput.h"
+#include "frc/PIDSource.h"
+#include "frc/commands/Command.h"
+
+namespace frc {
+
+class PIDCommand : public Command, public PIDOutput, public PIDSource {
+ public:
+  PIDCommand(const wpi::Twine& name, double p, double i, double d);
+  PIDCommand(const wpi::Twine& name, double p, double i, double d,
+             double period);
+  PIDCommand(const wpi::Twine& name, double p, double i, double d, double f,
+             double period);
+  PIDCommand(double p, double i, double d);
+  PIDCommand(double p, double i, double d, double period);
+  PIDCommand(double p, double i, double d, double f, double period);
+  PIDCommand(const wpi::Twine& name, double p, double i, double d,
+             Subsystem& subsystem);
+  PIDCommand(const wpi::Twine& name, double p, double i, double d,
+             double period, Subsystem& subsystem);
+  PIDCommand(const wpi::Twine& name, double p, double i, double d, double f,
+             double period, Subsystem& subsystem);
+  PIDCommand(double p, double i, double d, Subsystem& subsystem);
+  PIDCommand(double p, double i, double d, double period, Subsystem& subsystem);
+  PIDCommand(double p, double i, double d, double f, double period,
+             Subsystem& subsystem);
+  virtual ~PIDCommand() = default;
+
+  PIDCommand(PIDCommand&&) = default;
+  PIDCommand& operator=(PIDCommand&&) = default;
+
+  void SetSetpointRelative(double deltaSetpoint);
+
+  // PIDOutput interface
+  void PIDWrite(double output) override;
+
+  // PIDSource interface
+  double PIDGet() override;
+
+ protected:
+  std::shared_ptr<PIDController> GetPIDController() const;
+  void _Initialize() override;
+  void _Interrupted() override;
+  void _End() override;
+  void SetSetpoint(double setpoint);
+  double GetSetpoint() const;
+  double GetPosition();
+
+  virtual double ReturnPIDInput() = 0;
+  virtual void UsePIDOutput(double output) = 0;
+
+ private:
+  // The internal PIDController
+  std::shared_ptr<PIDController> m_controller;
+
+ public:
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PIDSubsystem.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PIDSubsystem.h
new file mode 100644
index 0000000..1965492
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PIDSubsystem.h
@@ -0,0 +1,236 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/Twine.h>
+
+#include "frc/PIDController.h"
+#include "frc/PIDOutput.h"
+#include "frc/PIDSource.h"
+#include "frc/commands/Subsystem.h"
+
+namespace frc {
+
+/**
+ * This class is designed to handle the case where there is a Subsystem which
+ * uses a single PIDController almost constantly (for instance, an elevator
+ * which attempts to stay at a constant height).
+ *
+ * It provides some convenience methods to run an internal PIDController. It
+ * also allows access to the internal PIDController in order to give total
+ * control to the programmer.
+ */
+class PIDSubsystem : public Subsystem, public PIDOutput, public PIDSource {
+ public:
+  /**
+   * Instantiates a PIDSubsystem that will use the given P, I, and D values.
+   *
+   * @param name the name
+   * @param p    the proportional value
+   * @param i    the integral value
+   * @param d    the derivative value
+   */
+  PIDSubsystem(const wpi::Twine& name, double p, double i, double d);
+
+  /**
+   * Instantiates a PIDSubsystem that will use the given P, I, and D values.
+   *
+   * @param name the name
+   * @param p    the proportional value
+   * @param i    the integral value
+   * @param d    the derivative value
+   * @param f    the feedforward value
+   */
+  PIDSubsystem(const wpi::Twine& name, double p, double i, double d, double f);
+
+  /**
+   * Instantiates a PIDSubsystem that will use the given P, I, and D values.
+   *
+   * It will also space the time between PID loop calculations to be equal to
+   * the given period.
+   *
+   * @param name   the name
+   * @param p      the proportional value
+   * @param i      the integral value
+   * @param d      the derivative value
+   * @param f      the feedfoward value
+   * @param period the time (in seconds) between calculations
+   */
+  PIDSubsystem(const wpi::Twine& name, double p, double i, double d, double f,
+               double period);
+
+  /**
+   * Instantiates a PIDSubsystem that will use the given P, I, and D values.
+   *
+   * It will use the class name as its name.
+   *
+   * @param p the proportional value
+   * @param i the integral value
+   * @param d the derivative value
+   */
+  PIDSubsystem(double p, double i, double d);
+
+  /**
+   * Instantiates a PIDSubsystem that will use the given P, I, and D values.
+   *
+   * It will use the class name as its name.
+   *
+   * @param p the proportional value
+   * @param i the integral value
+   * @param d the derivative value
+   * @param f the feedforward value
+   */
+  PIDSubsystem(double p, double i, double d, double f);
+
+  /**
+   * Instantiates a PIDSubsystem that will use the given P, I, and D values.
+   *
+   * It will use the class name as its name. It will also space the time
+   * between PID loop calculations to be equal to the given period.
+   *
+   * @param p      the proportional value
+   * @param i      the integral value
+   * @param d      the derivative value
+   * @param f      the feedforward value
+   * @param period the time (in seconds) between calculations
+   */
+  PIDSubsystem(double p, double i, double d, double f, double period);
+
+  ~PIDSubsystem() override = default;
+
+  PIDSubsystem(PIDSubsystem&&) = default;
+  PIDSubsystem& operator=(PIDSubsystem&&) = default;
+
+  /**
+   * Enables the internal PIDController.
+   */
+  void Enable();
+
+  /**
+   * Disables the internal PIDController.
+   */
+  void Disable();
+
+  // PIDOutput interface
+  void PIDWrite(double output) override;
+
+  // PIDSource interface
+
+  double PIDGet() override;
+
+  /**
+   * Sets the setpoint to the given value.
+   *
+   * If SetRange() was called, then the given setpoint will be trimmed to fit
+   * within the range.
+   *
+   * @param setpoint the new setpoint
+   */
+  void SetSetpoint(double setpoint);
+
+  /**
+   * Adds the given value to the setpoint.
+   *
+   * If SetRange() was used, then the bounds will still be honored by this
+   * method.
+   *
+   * @param deltaSetpoint the change in the setpoint
+   */
+  void SetSetpointRelative(double deltaSetpoint);
+
+  /**
+   * Sets the maximum and minimum values expected from the input.
+   *
+   * @param minimumInput the minimum value expected from the input
+   * @param maximumInput the maximum value expected from the output
+   */
+  void SetInputRange(double minimumInput, double maximumInput);
+
+  /**
+   * Sets the maximum and minimum values to write.
+   *
+   * @param minimumOutput the minimum value to write to the output
+   * @param maximumOutput the maximum value to write to the output
+   */
+  void SetOutputRange(double minimumOutput, double maximumOutput);
+
+  /**
+   * Return the current setpoint.
+   *
+   * @return The current setpoint
+   */
+  double GetSetpoint();
+
+  /**
+   * Returns the current position.
+   *
+   * @return the current position
+   */
+  double GetPosition();
+
+  /**
+   * Returns the current rate.
+   *
+   * @return the current rate
+   */
+  double GetRate();
+
+  /**
+   * Set the absolute error which is considered tolerable for use with
+   * OnTarget.
+   *
+   * @param absValue absolute error which is tolerable
+   */
+  virtual void SetAbsoluteTolerance(double absValue);
+
+  /**
+   * Set the percentage error which is considered tolerable for use with
+   * OnTarget().
+   *
+   * @param percent percentage error which is tolerable
+   */
+  virtual void SetPercentTolerance(double percent);
+
+  /**
+   * Return true if the error is within the percentage of the total input range,
+   * determined by SetTolerance().
+   *
+   * This asssumes that the maximum and minimum input were set using SetInput().
+   * Use OnTarget() in the IsFinished() method of commands that use this
+   * subsystem.
+   *
+   * Currently this just reports on target as the actual value passes through
+   * the setpoint. Ideally it should be based on being within the tolerance for
+   * some period of time.
+   *
+   * @return True if the error is within the percentage tolerance of the input
+   *         range
+   */
+  virtual bool OnTarget() const;
+
+ protected:
+  /**
+   * Returns the PIDController used by this PIDSubsystem.
+   *
+   * Use this if you would like to fine tune the PID loop.
+   *
+   * @return The PIDController used by this PIDSubsystem
+   */
+  std::shared_ptr<PIDController> GetPIDController();
+
+  virtual double ReturnPIDInput() = 0;
+  virtual void UsePIDOutput(double output) = 0;
+
+ private:
+  // The internal PIDController
+  std::shared_ptr<PIDController> m_controller;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PrintCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PrintCommand.h
new file mode 100644
index 0000000..13156c9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/PrintCommand.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <wpi/Twine.h>
+
+#include "frc/commands/InstantCommand.h"
+
+namespace frc {
+
+class PrintCommand : public InstantCommand {
+ public:
+  explicit PrintCommand(const wpi::Twine& message);
+  virtual ~PrintCommand() = default;
+
+  PrintCommand(PrintCommand&&) = default;
+  PrintCommand& operator=(PrintCommand&&) = default;
+
+ protected:
+  virtual void Initialize();
+
+ private:
+  std::string m_message;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Scheduler.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Scheduler.h
new file mode 100644
index 0000000..c5c97ba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Scheduler.h
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class ButtonScheduler;
+class Command;
+class Subsystem;
+
+class Scheduler : public ErrorBase, public SendableBase {
+ public:
+  /**
+   * Returns the Scheduler, creating it if one does not exist.
+   *
+   * @return the Scheduler
+   */
+  static Scheduler* GetInstance();
+
+  /**
+   * Add a command to be scheduled later.
+   *
+   * In any pass through the scheduler, all commands are added to the additions
+   * list, then at the end of the pass, they are all scheduled.
+   *
+   * @param command The command to be scheduled
+   */
+  void AddCommand(Command* command);
+
+  void AddButton(ButtonScheduler* button);
+
+  /**
+   * Registers a Subsystem to this Scheduler, so that the Scheduler might know
+   * if a default Command needs to be run.
+   *
+   * All Subsystems should call this.
+   *
+   * @param system the system
+   */
+  void RegisterSubsystem(Subsystem* subsystem);
+
+  /**
+   * Runs a single iteration of the loop.
+   *
+   * This method should be called often in order to have a functioning
+   * Command system. The loop has five stages:
+   *
+   * <ol>
+   *   <li>Poll the Buttons</li>
+   *   <li>Execute/Remove the Commands</li>
+   *   <li>Send values to SmartDashboard</li>
+   *   <li>Add Commands</li>
+   *   <li>Add Defaults</li>
+   * </ol>
+   */
+  void Run();
+
+  /**
+   * Removes the Command from the Scheduler.
+   *
+   * @param command the command to remove
+   */
+  void Remove(Command* command);
+
+  void RemoveAll();
+
+  /**
+   * Completely resets the scheduler. Undefined behavior if running.
+   */
+  void ResetAll();
+
+  void SetEnabled(bool enabled);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  Scheduler();
+  ~Scheduler() override;
+
+  Scheduler(Scheduler&&) = default;
+  Scheduler& operator=(Scheduler&&) = default;
+
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/StartCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/StartCommand.h
new file mode 100644
index 0000000..4f0b676
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/StartCommand.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/commands/InstantCommand.h"
+
+namespace frc {
+
+class StartCommand : public InstantCommand {
+ public:
+  explicit StartCommand(Command* commandToStart);
+  virtual ~StartCommand() = default;
+
+  StartCommand(StartCommand&&) = default;
+  StartCommand& operator=(StartCommand&&) = default;
+
+ protected:
+  virtual void Initialize();
+
+ private:
+  Command* m_commandToFork;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Subsystem.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Subsystem.h
new file mode 100644
index 0000000..bb6d166
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/Subsystem.h
@@ -0,0 +1,168 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/StringRef.h>
+#include <wpi/Twine.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class Command;
+
+class Subsystem : public ErrorBase, public SendableBase {
+  friend class Scheduler;
+
+ public:
+  /**
+   * Creates a subsystem with the given name.
+   *
+   * @param name the name of the subsystem
+   */
+  explicit Subsystem(const wpi::Twine& name);
+
+  Subsystem(Subsystem&&) = default;
+  Subsystem& operator=(Subsystem&&) = default;
+
+  /**
+   * Sets the default command. If this is not called or is called with null,
+   * then there will be no default command for the subsystem.
+   *
+   * <b>WARNING:</b> This should <b>NOT</b> be called in a constructor if the
+   * subsystem is a singleton.
+   *
+   * @param command the default command (or null if there should be none)
+   */
+  void SetDefaultCommand(Command* command);
+
+  /**
+   * Returns the default command (or null if there is none).
+   *
+   * @return the default command
+   */
+  Command* GetDefaultCommand();
+
+  /**
+   * Returns the default command name, or empty string is there is none.
+   *
+   * @return the default command name
+   */
+  wpi::StringRef GetDefaultCommandName();
+
+  /**
+   * Sets the current command.
+   *
+   * @param command the new current command
+   */
+  void SetCurrentCommand(Command* command);
+
+  /**
+   * Returns the command which currently claims this subsystem.
+   *
+   * @return the command which currently claims this subsystem
+   */
+  Command* GetCurrentCommand() const;
+
+  /**
+   * Returns the current command name, or empty string if no current command.
+   *
+   * @return the current command name
+   */
+  wpi::StringRef GetCurrentCommandName() const;
+
+  /**
+   * When the run method of the scheduler is called this method will be called.
+   */
+  virtual void Periodic();
+
+  /**
+   * Initialize the default command for this subsystem.
+   *
+   * This is meant to be the place to call SetDefaultCommand in a subsystem and
+   * will be called on all the subsystems by the CommandBase method before the
+   * program starts running by using the list of all registered Subsystems
+   * inside the Scheduler.
+   *
+   * This should be overridden by a Subsystem that has a default Command
+   */
+  virtual void InitDefaultCommand();
+
+  /**
+   * Associate a Sendable with this Subsystem.
+   * Also update the child's name.
+   *
+   * @param name name to give child
+   * @param child sendable
+   */
+  void AddChild(const wpi::Twine& name, std::shared_ptr<Sendable> child);
+
+  /**
+   * Associate a Sendable with this Subsystem.
+   * Also update the child's name.
+   *
+   * @param name name to give child
+   * @param child sendable
+   */
+  void AddChild(const wpi::Twine& name, Sendable* child);
+
+  /**
+   * Associate a Sendable with this Subsystem.
+   * Also update the child's name.
+   *
+   * @param name name to give child
+   * @param child sendable
+   */
+  void AddChild(const wpi::Twine& name, Sendable& child);
+
+  /**
+   * Associate a {@link Sendable} with this Subsystem.
+   *
+   * @param child sendable
+   */
+  void AddChild(std::shared_ptr<Sendable> child);
+
+  /**
+   * Associate a {@link Sendable} with this Subsystem.
+   *
+   * @param child sendable
+   */
+  void AddChild(Sendable* child);
+
+  /**
+   * Associate a {@link Sendable} with this Subsystem.
+   *
+   * @param child sendable
+   */
+  void AddChild(Sendable& child);
+
+ private:
+  /**
+   * Call this to alert Subsystem that the current command is actually the
+   * command.
+   *
+   * Sometimes, the Subsystem is told that it has no command while the Scheduler
+   * is going through the loop, only to be soon after given a new one. This will
+   * avoid that situation.
+   */
+  void ConfirmCommand();
+
+  Command* m_currentCommand = nullptr;
+  bool m_currentCommandChanged = true;
+  Command* m_defaultCommand = nullptr;
+  bool m_initializedDefaultCommand = false;
+
+ public:
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/TimedCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/TimedCommand.h
new file mode 100644
index 0000000..d2be010
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/TimedCommand.h
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+#include "frc/commands/Command.h"
+
+namespace frc {
+
+/**
+ * A TimedCommand will wait for a timeout before finishing.
+ *
+ * TimedCommand is used to execute a command for a given amount of time.
+ */
+class TimedCommand : public Command {
+ public:
+  /**
+   * Creates a new TimedCommand with the given name and timeout.
+   *
+   * @param name    the name of the command
+   * @param timeout the time (in seconds) before this command "times out"
+   */
+  TimedCommand(const wpi::Twine& name, double timeout);
+
+  /**
+   * Creates a new WaitCommand with the given timeout.
+   *
+   * @param timeout the time (in seconds) before this command "times out"
+   */
+  explicit TimedCommand(double timeout);
+
+  /**
+   * Creates a new TimedCommand with the given name and timeout.
+   *
+   * @param name      the name of the command
+   * @param timeout   the time (in seconds) before this command "times out"
+   * @param subsystem the subsystem that the command requires
+   */
+  TimedCommand(const wpi::Twine& name, double timeout, Subsystem& subsystem);
+
+  /**
+   * Creates a new WaitCommand with the given timeout.
+   *
+   * @param timeout   the time (in seconds) before this command "times out"
+   * @param subsystem the subsystem that the command requires
+   */
+  TimedCommand(double timeout, Subsystem& subsystem);
+
+  virtual ~TimedCommand() = default;
+
+  TimedCommand(TimedCommand&&) = default;
+  TimedCommand& operator=(TimedCommand&&) = default;
+
+ protected:
+  /**
+   * Ends command when timed out.
+   */
+  bool IsFinished() override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitCommand.h
new file mode 100644
index 0000000..481b1c6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitCommand.h
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+#include "frc/commands/TimedCommand.h"
+
+namespace frc {
+
+class WaitCommand : public TimedCommand {
+ public:
+  /**
+   * Creates a new WaitCommand with the given name and timeout.
+   *
+   * @param name    the name of the command
+   * @param timeout the time (in seconds) before this command "times out"
+   */
+  explicit WaitCommand(double timeout);
+
+  /**
+   * Creates a new WaitCommand with the given timeout.
+   *
+   * @param timeout the time (in seconds) before this command "times out"
+   */
+  WaitCommand(const wpi::Twine& name, double timeout);
+
+  virtual ~WaitCommand() = default;
+
+  WaitCommand(WaitCommand&&) = default;
+  WaitCommand& operator=(WaitCommand&&) = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitForChildren.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitForChildren.h
new file mode 100644
index 0000000..6f2e285
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitForChildren.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+#include "frc/commands/Command.h"
+
+namespace frc {
+
+class WaitForChildren : public Command {
+ public:
+  explicit WaitForChildren(double timeout);
+  WaitForChildren(const wpi::Twine& name, double timeout);
+  virtual ~WaitForChildren() = default;
+
+  WaitForChildren(WaitForChildren&&) = default;
+  WaitForChildren& operator=(WaitForChildren&&) = default;
+
+ protected:
+  virtual bool IsFinished();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitUntilCommand.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitUntilCommand.h
new file mode 100644
index 0000000..1231750
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/commands/WaitUntilCommand.h
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+#include "frc/commands/Command.h"
+
+namespace frc {
+
+class WaitUntilCommand : public Command {
+ public:
+  /**
+   * A WaitCommand will wait until a certain match time before finishing.
+   *
+   * This will wait until the game clock reaches some value, then continue to
+   * the next command.
+   *
+   * @see CommandGroup
+   */
+  explicit WaitUntilCommand(double time);
+
+  WaitUntilCommand(const wpi::Twine& name, double time);
+
+  virtual ~WaitUntilCommand() = default;
+
+  WaitUntilCommand(WaitUntilCommand&&) = default;
+  WaitUntilCommand& operator=(WaitUntilCommand&&) = default;
+
+ protected:
+  /**
+   * Check if we've reached the actual finish time.
+   */
+  virtual bool IsFinished();
+
+ private:
+  double m_time;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
new file mode 100644
index 0000000..1120659
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/DifferentialDrive.h
@@ -0,0 +1,220 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/raw_ostream.h>
+
+#include "frc/drive/RobotDriveBase.h"
+
+namespace frc {
+
+class SpeedController;
+
+/**
+ * A class for driving differential drive/skid-steer drive platforms such as
+ * the Kit of Parts drive base, "tank drive", or West Coast Drive.
+ *
+ * These drive bases typically have drop-center / skid-steer with two or more
+ * wheels per side (e.g., 6WD or 8WD). This class takes a SpeedController per
+ * side. For four and six motor drivetrains, construct and pass in
+ * SpeedControllerGroup instances as follows.
+ *
+ * Four motor drivetrain:
+ * @code{.cpp}
+ * class Robot {
+ *  public:
+ *   frc::Spark m_frontLeft{1};
+ *   frc::Spark m_rearLeft{2};
+ *   frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
+ *
+ *   frc::Spark m_frontRight{3};
+ *   frc::Spark m_rearRight{4};
+ *   frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight};
+ *
+ *   frc::DifferentialDrive m_drive{m_left, m_right};
+ * };
+ * @endcode
+ *
+ * Six motor drivetrain:
+ * @code{.cpp}
+ * class Robot {
+ *  public:
+ *   frc::Spark m_frontLeft{1};
+ *   frc::Spark m_midLeft{2};
+ *   frc::Spark m_rearLeft{3};
+ *   frc::SpeedControllerGroup m_left{m_frontLeft, m_midLeft, m_rearLeft};
+ *
+ *   frc::Spark m_frontRight{4};
+ *   frc::Spark m_midRight{5};
+ *   frc::Spark m_rearRight{6};
+ *   frc::SpeedControllerGroup m_right{m_frontRight, m_midRight, m_rearRight};
+ *
+ *   frc::DifferentialDrive m_drive{m_left, m_right};
+ * };
+ * @endcode
+ *
+ * A differential drive robot has left and right wheels separated by an
+ * arbitrary width.
+ *
+ * Drive base diagram:
+ * <pre>
+ * |_______|
+ * | |   | |
+ *   |   |
+ * |_|___|_|
+ * |       |
+ * </pre>
+ *
+ * Each Drive() function provides different inverse kinematic relations for a
+ * differential drive robot. Motor outputs for the right side are negated, so
+ * motor direction inversion by the user is usually unnecessary.
+ *
+ * This library uses the NED axes convention (North-East-Down as external
+ * reference in the world frame):
+ * http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * The positive X axis points ahead, the positive Y axis points to the right,
+ * and the positive Z axis points down. Rotations follow the right-hand rule, so
+ * clockwise rotation around the Z axis is positive.
+ *
+ * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
+ * so that the full range is still used. This deadband value can be changed
+ * with SetDeadband().
+ *
+ * <p>RobotDrive porting guide:
+ * <br>TankDrive(double, double, bool) is equivalent to
+ * RobotDrive#TankDrive(double, double, bool) if a deadband of 0 is used.
+ * <br>ArcadeDrive(double, double, bool) is equivalent to
+ * RobotDrive#ArcadeDrive(double, double, bool) if a deadband of 0 is used
+ * and the the rotation input is inverted eg ArcadeDrive(y, -rotation, false)
+ * <br>CurvatureDrive(double, double, bool) is similar in concept to
+ * RobotDrive#Drive(double, double) with the addition of a quick turn
+ * mode. However, it is not designed to give exactly the same response.
+ */
+class DifferentialDrive : public RobotDriveBase {
+ public:
+  static constexpr double kDefaultQuickStopThreshold = 0.2;
+  static constexpr double kDefaultQuickStopAlpha = 0.1;
+
+  /**
+   * Construct a DifferentialDrive.
+   *
+   * To pass multiple motors per side, use a SpeedControllerGroup. If a motor
+   * needs to be inverted, do so before passing it in.
+   */
+  DifferentialDrive(SpeedController& leftMotor, SpeedController& rightMotor);
+
+  ~DifferentialDrive() override = default;
+
+  DifferentialDrive(DifferentialDrive&&) = default;
+  DifferentialDrive& operator=(DifferentialDrive&&) = default;
+
+  /**
+   * Arcade drive method for differential drive platform.
+   *
+   * Note: Some drivers may prefer inverted rotation controls. This can be done
+   * by negating the value passed for rotation.
+   *
+   * @param xSpeed        The speed at which the robot should drive along the X
+   *                      axis [-1.0..1.0]. Forward is negative.
+   * @param zRotation     The rotation rate of the robot around the Z axis
+   *                      [-1.0..1.0]. Clockwise is positive.
+   * @param squareInputs If set, decreases the input sensitivity at low speeds.
+   */
+  void ArcadeDrive(double xSpeed, double zRotation, bool squareInputs = true);
+
+  /**
+   * Curvature drive method for differential drive platform.
+   *
+   * The rotation argument controls the curvature of the robot's path rather
+   * than its rate of heading change. This makes the robot more controllable at
+   * high speeds. Also handles the robot's quick turn functionality - "quick
+   * turn" overrides constant-curvature turning for turn-in-place maneuvers.
+   *
+   * @param xSpeed      The robot's speed along the X axis [-1.0..1.0]. Forward
+   *                    is positive.
+   * @param zRotation   The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                    Clockwise is positive.
+   * @param isQuickTurn If set, overrides constant-curvature turning for
+   *                    turn-in-place maneuvers.
+   */
+  void CurvatureDrive(double xSpeed, double zRotation, bool isQuickTurn);
+
+  /**
+   * Tank drive method for differential drive platform.
+   *
+   * @param leftSpeed     The robot left side's speed along the X axis
+   *                      [-1.0..1.0]. Forward is positive.
+   * @param rightSpeed    The robot right side's speed along the X axis
+   *                      [-1.0..1.0]. Forward is positive.
+   * @param squareInputs If set, decreases the input sensitivity at low speeds.
+   */
+  void TankDrive(double leftSpeed, double rightSpeed, bool squareInputs = true);
+
+  /**
+   * Sets the QuickStop speed threshold in curvature drive.
+   *
+   * QuickStop compensates for the robot's moment of inertia when stopping after
+   * a QuickTurn.
+   *
+   * While QuickTurn is enabled, the QuickStop accumulator takes on the rotation
+   * rate value outputted by the low-pass filter when the robot's speed along
+   * the X axis is below the threshold. When QuickTurn is disabled, the
+   * accumulator's value is applied against the computed angular power request
+   * to slow the robot's rotation.
+   *
+   * @param threshold X speed below which quick stop accumulator will receive
+   *                  rotation rate values [0..1.0].
+   */
+  void SetQuickStopThreshold(double threshold);
+
+  /**
+   * Sets the low-pass filter gain for QuickStop in curvature drive.
+   *
+   * The low-pass filter filters incoming rotation rate commands to smooth out
+   * high frequency changes.
+   *
+   * @param alpha Low-pass filter gain [0.0..2.0]. Smaller values result in
+   *              slower output changes. Values between 1.0 and 2.0 result in
+   *              output oscillation. Values below 0.0 and above 2.0 are
+   *              unstable.
+   */
+  void SetQuickStopAlpha(double alpha);
+
+  /**
+   * Gets if the power sent to the right side of the drivetrain is multipled by
+   * -1.
+   *
+   * @return true if the right side is inverted
+   */
+  bool IsRightSideInverted() const;
+
+  /**
+   * Sets if the power sent to the right side of the drivetrain should be
+   * multipled by -1.
+   *
+   * @param rightSideInverted true if right side power should be multipled by -1
+   */
+  void SetRightSideInverted(bool rightSideInverted);
+
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  SpeedController& m_leftMotor;
+  SpeedController& m_rightMotor;
+
+  double m_quickStopThreshold = kDefaultQuickStopThreshold;
+  double m_quickStopAlpha = kDefaultQuickStopAlpha;
+  double m_quickStopAccumulator = 0.0;
+  double m_rightSideInvertMultiplier = -1.0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h
new file mode 100644
index 0000000..2fa356d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/KilloughDrive.h
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/raw_ostream.h>
+
+#include "frc/drive/RobotDriveBase.h"
+#include "frc/drive/Vector2d.h"
+
+namespace frc {
+
+class SpeedController;
+
+/**
+ * A class for driving Killough drive platforms.
+ *
+ * Killough drives are triangular with one omni wheel on each corner.
+ *
+ * Drive base diagram:
+ * <pre>
+ *  /_____\
+ * / \   / \
+ *    \ /
+ *    ---
+ * </pre>
+ *
+ * Each Drive() function provides different inverse kinematic relations for a
+ * Killough drive. The default wheel vectors are parallel to their respective
+ * opposite sides, but can be overridden. See the constructor for more
+ * information.
+ *
+ * This library uses the NED axes convention (North-East-Down as external
+ * reference in the world frame):
+ * http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * The positive X axis points ahead, the positive Y axis points right, and the
+ * and the positive Z axis points down. Rotations follow the right-hand rule, so
+ * clockwise rotation around the Z axis is positive.
+ */
+class KilloughDrive : public RobotDriveBase {
+ public:
+  static constexpr double kDefaultLeftMotorAngle = 60.0;
+  static constexpr double kDefaultRightMotorAngle = 120.0;
+  static constexpr double kDefaultBackMotorAngle = 270.0;
+
+  /**
+   * Construct a Killough drive with the given motors and default motor angles.
+   *
+   * The default motor angles make the wheels on each corner parallel to their
+   * respective opposite sides.
+   *
+   * If a motor needs to be inverted, do so before passing it in.
+   *
+   * @param leftMotor  The motor on the left corner.
+   * @param rightMotor The motor on the right corner.
+   * @param backMotor  The motor on the back corner.
+   */
+  KilloughDrive(SpeedController& leftMotor, SpeedController& rightMotor,
+                SpeedController& backMotor);
+
+  /**
+   * Construct a Killough drive with the given motors.
+   *
+   * Angles are measured in degrees clockwise from the positive X axis.
+   *
+   * @param leftMotor       The motor on the left corner.
+   * @param rightMotor      The motor on the right corner.
+   * @param backMotor       The motor on the back corner.
+   * @param leftMotorAngle  The angle of the left wheel's forward direction of
+   *                        travel.
+   * @param rightMotorAngle The angle of the right wheel's forward direction of
+   *                        travel.
+   * @param backMotorAngle  The angle of the back wheel's forward direction of
+   *                        travel.
+   */
+  KilloughDrive(SpeedController& leftMotor, SpeedController& rightMotor,
+                SpeedController& backMotor, double leftMotorAngle,
+                double rightMotorAngle, double backMotorAngle);
+
+  ~KilloughDrive() override = default;
+
+  KilloughDrive(KilloughDrive&&) = default;
+  KilloughDrive& operator=(KilloughDrive&&) = default;
+
+  /**
+   * Drive method for Killough platform.
+   *
+   * Angles are measured clockwise from the positive X axis. The robot's speed
+   * is independent from its angle or rotation rate.
+   *
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is
+   *                  positive.
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is
+   *                  positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                  Clockwise is positive.
+   * @param gyroAngle The current angle reading from the gyro in degrees around
+   *                  the Z axis. Use this to implement field-oriented controls.
+   */
+  void DriveCartesian(double ySpeed, double xSpeed, double zRotation,
+                      double gyroAngle = 0.0);
+
+  /**
+   * Drive method for Killough platform.
+   *
+   * Angles are measured clockwise from the positive X axis. The robot's speed
+   * is independent from its angle or rotation rate.
+   *
+   * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
+   *                  positive.
+   * @param angle     The angle around the Z axis at which the robot drives in
+   *                  degrees [-180..180].
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                  Clockwise is positive.
+   */
+  void DrivePolar(double magnitude, double angle, double zRotation);
+
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  SpeedController& m_leftMotor;
+  SpeedController& m_rightMotor;
+  SpeedController& m_backMotor;
+
+  Vector2d m_leftVec;
+  Vector2d m_rightVec;
+  Vector2d m_backVec;
+
+  bool reported = false;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
new file mode 100644
index 0000000..e0acaca
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/MecanumDrive.h
@@ -0,0 +1,146 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/raw_ostream.h>
+
+#include "frc/drive/RobotDriveBase.h"
+
+namespace frc {
+
+class SpeedController;
+
+/**
+ * A class for driving Mecanum drive platforms.
+ *
+ * Mecanum drives are rectangular with one wheel on each corner. Each wheel has
+ * rollers toed in 45 degrees toward the front or back. When looking at the
+ * wheels from the top, the roller axles should form an X across the robot.
+ *
+ * Drive base diagram:
+ * <pre>
+ * \\_______/
+ * \\ |   | /
+ *   |   |
+ * /_|___|_\\
+ * /       \\
+ * </pre>
+ *
+ * Each Drive() function provides different inverse kinematic relations for a
+ * Mecanum drive robot. Motor outputs for the right side are negated, so motor
+ * direction inversion by the user is usually unnecessary.
+ *
+ * This library uses the NED axes convention (North-East-Down as external
+ * reference in the world frame):
+ * http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * The positive X axis points ahead, the positive Y axis points to the right,
+ * and the positive Z axis points down. Rotations follow the right-hand rule, so
+ * clockwise rotation around the Z axis is positive.
+ *
+ * Inputs smaller then 0.02 will be set to 0, and larger values will be scaled
+ * so that the full range is still used. This deadband value can be changed
+ * with SetDeadband().
+ *
+ * RobotDrive porting guide:
+ * <br>In MecanumDrive, the right side speed controllers are automatically
+ * inverted, while in RobotDrive, no speed controllers are automatically
+ * inverted.
+ * <br>DriveCartesian(double, double, double, double) is equivalent to
+ * RobotDrive#MecanumDrive_Cartesian(double, double, double, double)
+ * if a deadband of 0 is used, and the ySpeed and gyroAngle values are inverted
+ * compared to RobotDrive (eg DriveCartesian(xSpeed, -ySpeed, zRotation,
+ * -gyroAngle).
+ * <br>DrivePolar(double, double, double) is equivalent to
+ * RobotDrive#MecanumDrive_Polar(double, double, double) if a
+ * deadband of 0 is used.
+ */
+class MecanumDrive : public RobotDriveBase {
+ public:
+  /**
+   * Construct a MecanumDrive.
+   *
+   * If a motor needs to be inverted, do so before passing it in.
+   */
+  MecanumDrive(SpeedController& frontLeftMotor, SpeedController& rearLeftMotor,
+               SpeedController& frontRightMotor,
+               SpeedController& rearRightMotor);
+
+  ~MecanumDrive() override = default;
+
+  MecanumDrive(MecanumDrive&&) = default;
+  MecanumDrive& operator=(MecanumDrive&&) = default;
+
+  /**
+   * Drive method for Mecanum platform.
+   *
+   * Angles are measured clockwise from the positive X axis. The robot's speed
+   * is independent from its angle or rotation rate.
+   *
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is
+   *                  positive.
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is
+   *                  positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                  Clockwise is positive.
+   * @param gyroAngle The current angle reading from the gyro in degrees around
+   *                  the Z axis. Use this to implement field-oriented controls.
+   */
+  void DriveCartesian(double ySpeed, double xSpeed, double zRotation,
+                      double gyroAngle = 0.0);
+
+  /**
+   * Drive method for Mecanum platform.
+   *
+   * Angles are measured clockwise from the positive X axis. The robot's speed
+   * is independent from its angle or rotation rate.
+   *
+   * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is
+   *                  positive.
+   * @param angle     The angle around the Z axis at which the robot drives in
+   *                  degrees [-180..180].
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0].
+   *                  Clockwise is positive.
+   */
+  void DrivePolar(double magnitude, double angle, double zRotation);
+
+  /**
+   * Gets if the power sent to the right side of the drivetrain is multipled by
+   * -1.
+   *
+   * @return true if the right side is inverted
+   */
+  bool IsRightSideInverted() const;
+
+  /**
+   * Sets if the power sent to the right side of the drivetrain should be
+   * multipled by -1.
+   *
+   * @param rightSideInverted true if right side power should be multipled by -1
+   */
+  void SetRightSideInverted(bool rightSideInverted);
+
+  void StopMotor() override;
+  void GetDescription(wpi::raw_ostream& desc) const override;
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  SpeedController& m_frontLeftMotor;
+  SpeedController& m_rearLeftMotor;
+  SpeedController& m_frontRightMotor;
+  SpeedController& m_rearRightMotor;
+
+  double m_rightSideInvertMultiplier = -1.0;
+
+  bool reported = false;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
new file mode 100644
index 0000000..206434e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/RobotDriveBase.h
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/ArrayRef.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/MotorSafety.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class SpeedController;
+
+/**
+ * Common base class for drive platforms.
+ */
+class RobotDriveBase : public MotorSafety, public SendableBase {
+ public:
+  /**
+   * The location of a motor on the robot for the purpose of driving.
+   */
+  enum MotorType {
+    kFrontLeft = 0,
+    kFrontRight = 1,
+    kRearLeft = 2,
+    kRearRight = 3,
+    kLeft = 0,
+    kRight = 1,
+    kBack = 2
+  };
+
+  RobotDriveBase();
+  ~RobotDriveBase() override = default;
+
+  RobotDriveBase(RobotDriveBase&&) = default;
+  RobotDriveBase& operator=(RobotDriveBase&&) = default;
+
+  /**
+   * Sets the deadband applied to the drive inputs (e.g., joystick values).
+   *
+   * The default value is 0.02. Inputs smaller than the deadband are set to 0.0
+   * while inputs larger than the deadband are scaled from 0.0 to 1.0. See
+   * ApplyDeadband().
+   *
+   * @param deadband The deadband to set.
+   */
+  void SetDeadband(double deadband);
+
+  /**
+   * Configure the scaling factor for using RobotDrive with motor controllers in
+   * a mode other than PercentVbus or to limit the maximum output.
+   *
+   * @param maxOutput Multiplied with the output percentage computed by the
+   *                  drive functions.
+   */
+  void SetMaxOutput(double maxOutput);
+
+  /**
+   * Feed the motor safety object. Resets the timer that will stop the motors if
+   * it completes.
+   *
+   * @see MotorSafetyHelper::Feed()
+   */
+  void FeedWatchdog();
+
+  void StopMotor() override = 0;
+  void GetDescription(wpi::raw_ostream& desc) const override = 0;
+
+ protected:
+  /**
+   * Limit motor values to the -1.0 to +1.0 range.
+   */
+  double Limit(double number);
+
+  /**
+   * Returns 0.0 if the given value is within the specified range around zero.
+   * The remaining range between the deadband and 1.0 is scaled from 0.0 to 1.0.
+   *
+   * @param value    value to clip
+   * @param deadband range around zero
+   */
+  double ApplyDeadband(double number, double deadband);
+
+  /**
+   * Normalize all wheel speeds if the magnitude of any wheel is greater than
+   * 1.0.
+   */
+  void Normalize(wpi::MutableArrayRef<double> wheelSpeeds);
+
+  double m_deadband = 0.02;
+  double m_maxOutput = 1.0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/Vector2d.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/Vector2d.h
new file mode 100644
index 0000000..c9bd08a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/drive/Vector2d.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * This is a 2D vector struct that supports basic vector operations.
+ */
+struct Vector2d {
+  Vector2d() = default;
+  Vector2d(double x, double y);
+
+  /**
+   * Rotate a vector in Cartesian space.
+   *
+   * @param angle angle in degrees by which to rotate vector counter-clockwise.
+   */
+  void Rotate(double angle);
+
+  /**
+   * Returns dot product of this vector with argument.
+   *
+   * @param vec Vector with which to perform dot product.
+   */
+  double Dot(const Vector2d& vec) const;
+
+  /**
+   * Returns magnitude of vector.
+   */
+  double Magnitude() const;
+
+  /**
+   * Returns scalar projection of this vector onto argument.
+   *
+   * @param vec Vector onto which to project this vector.
+   */
+  double ScalarProject(const Vector2d& vec) const;
+
+  double x = 0.0;
+  double y = 0.0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/filters/Filter.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/filters/Filter.h
new file mode 100644
index 0000000..b0c0c11
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/filters/Filter.h
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "frc/PIDSource.h"
+
+namespace frc {
+
+/**
+ * Interface for filters
+ */
+class Filter : public PIDSource {
+ public:
+  explicit Filter(PIDSource& source);
+  explicit Filter(std::shared_ptr<PIDSource> source);
+  virtual ~Filter() = default;
+
+  Filter(Filter&&) = default;
+  Filter& operator=(Filter&&) = default;
+
+  // PIDSource interface
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+  PIDSourceType GetPIDSourceType() const override;
+  double PIDGet() override = 0;
+
+  /**
+   * Returns the current filter estimate without also inserting new data as
+   * PIDGet() would do.
+   *
+   * @return The current filter estimate
+   */
+  virtual double Get() const = 0;
+
+  /**
+   * Reset the filter state
+   */
+  virtual void Reset() = 0;
+
+ protected:
+  /**
+   * Calls PIDGet() of source
+   *
+   * @return Current value of source
+   */
+  double PIDGetSource();
+
+ private:
+  std::shared_ptr<PIDSource> m_source;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h
new file mode 100644
index 0000000..472d53b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/filters/LinearDigitalFilter.h
@@ -0,0 +1,197 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <vector>
+
+#include <wpi/ArrayRef.h>
+
+#include "frc/circular_buffer.h"
+#include "frc/filters/Filter.h"
+
+namespace frc {
+
+/**
+ * This class implements a linear, digital filter. All types of FIR and IIR
+ * filters are supported. Static factory methods are provided to create commonly
+ * used types of filters.
+ *
+ * Filters are of the form:<br>
+ *  y[n] = (b0 * x[n] + b1 * x[n-1] + ... + bP * x[n-P]) -
+ *         (a0 * y[n-1] + a2 * y[n-2] + ... + aQ * y[n-Q])
+ *
+ * Where:<br>
+ *  y[n] is the output at time "n"<br>
+ *  x[n] is the input at time "n"<br>
+ *  y[n-1] is the output from the LAST time step ("n-1")<br>
+ *  x[n-1] is the input from the LAST time step ("n-1")<br>
+ *  b0...bP are the "feedforward" (FIR) gains<br>
+ *  a0...aQ are the "feedback" (IIR) gains<br>
+ * IMPORTANT! Note the "-" sign in front of the feedback term! This is a common
+ *            convention in signal processing.
+ *
+ * What can linear filters do? Basically, they can filter, or diminish, the
+ * effects of undesirable input frequencies. High frequencies, or rapid changes,
+ * can be indicative of sensor noise or be otherwise undesirable. A "low pass"
+ * filter smooths out the signal, reducing the impact of these high frequency
+ * components.  Likewise, a "high pass" filter gets rid of slow-moving signal
+ * components, letting you detect large changes more easily.
+ *
+ * Example FRC applications of filters:
+ *  - Getting rid of noise from an analog sensor input (note: the roboRIO's FPGA
+ *    can do this faster in hardware)
+ *  - Smoothing out joystick input to prevent the wheels from slipping or the
+ *    robot from tipping
+ *  - Smoothing motor commands so that unnecessary strain isn't put on
+ *    electrical or mechanical components
+ *  - If you use clever gains, you can make a PID controller out of this class!
+ *
+ * For more on filters, I highly recommend the following articles:<br>
+ *  http://en.wikipedia.org/wiki/Linear_filter<br>
+ *  http://en.wikipedia.org/wiki/Iir_filter<br>
+ *  http://en.wikipedia.org/wiki/Fir_filter<br>
+ *
+ * Note 1: PIDGet() should be called by the user on a known, regular period.
+ * You can set up a Notifier to do this (look at the WPILib PIDController
+ * class), or do it "inline" with code in a periodic function.
+ *
+ * Note 2: For ALL filters, gains are necessarily a function of frequency. If
+ * you make a filter that works well for you at, say, 100Hz, you will most
+ * definitely need to adjust the gains if you then want to run it at 200Hz!
+ * Combining this with Note 1 - the impetus is on YOU as a developer to make
+ * sure PIDGet() gets called at the desired, constant frequency!
+ */
+class LinearDigitalFilter : public Filter {
+ public:
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param source  The PIDSource object that is used to get values
+   * @param ffGains The "feed forward" or FIR gains
+   * @param fbGains The "feed back" or IIR gains
+   */
+  LinearDigitalFilter(PIDSource& source, wpi::ArrayRef<double> ffGains,
+                      wpi::ArrayRef<double> fbGains);
+
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param source  The PIDSource object that is used to get values
+   * @param ffGains The "feed forward" or FIR gains
+   * @param fbGains The "feed back" or IIR gains
+   */
+  LinearDigitalFilter(std::shared_ptr<PIDSource> source,
+                      wpi::ArrayRef<double> ffGains,
+                      wpi::ArrayRef<double> fbGains);
+
+  LinearDigitalFilter(LinearDigitalFilter&&) = default;
+  LinearDigitalFilter& operator=(LinearDigitalFilter&&) = default;
+
+  // Static methods to create commonly used filters
+  /**
+   * Creates a one-pole IIR low-pass filter of the form:<br>
+   *   y[n] = (1 - gain) * x[n] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  static LinearDigitalFilter SinglePoleIIR(PIDSource& source,
+                                           double timeConstant, double period);
+
+  /**
+   * Creates a first-order high-pass filter of the form:<br>
+   *   y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  static LinearDigitalFilter HighPass(PIDSource& source, double timeConstant,
+                                      double period);
+
+  /**
+   * Creates a K-tap FIR moving average filter of the form:<br>
+   *   y[n] = 1/k * (x[k] + x[k-1] + … + x[0])
+   *
+   * This filter is always stable.
+   *
+   * @param source The PIDSource object that is used to get values
+   * @param taps   The number of samples to average over. Higher = smoother but
+   *               slower
+   */
+  static LinearDigitalFilter MovingAverage(PIDSource& source, int taps);
+
+  /**
+   * Creates a one-pole IIR low-pass filter of the form:<br>
+   *   y[n] = (1 - gain) * x[n] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  static LinearDigitalFilter SinglePoleIIR(std::shared_ptr<PIDSource> source,
+                                           double timeConstant, double period);
+
+  /**
+   * Creates a first-order high-pass filter of the form:<br>
+   *   y[n] = gain * x[n] + (-gain) * x[n-1] + gain * y[n-1]<br>
+   * where gain = e<sup>-dt / T</sup>, T is the time constant in seconds
+   *
+   * This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  static LinearDigitalFilter HighPass(std::shared_ptr<PIDSource> source,
+                                      double timeConstant, double period);
+
+  /**
+   * Creates a K-tap FIR moving average filter of the form:<br>
+   *   y[n] = 1/k * (x[k] + x[k-1] + … + x[0])
+   *
+   * This filter is always stable.
+   *
+   * @param source The PIDSource object that is used to get values
+   * @param taps   The number of samples to average over. Higher = smoother but
+   *               slower
+   */
+  static LinearDigitalFilter MovingAverage(std::shared_ptr<PIDSource> source,
+                                           int taps);
+
+  // Filter interface
+  double Get() const override;
+  void Reset() override;
+
+  // PIDSource interface
+  /**
+   * Calculates the next value of the filter
+   *
+   * @return The filtered value at this step
+   */
+  double PIDGet() override;
+
+ private:
+  circular_buffer<double> m_inputs;
+  circular_buffer<double> m_outputs;
+  std::vector<double> m_inputGains;
+  std::vector<double> m_outputGains;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h
new file mode 100644
index 0000000..499ba5b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Accelerometer.h
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Interface for 3-axis accelerometers.
+ */
+class Accelerometer {
+ public:
+  Accelerometer() = default;
+  virtual ~Accelerometer() = default;
+
+  Accelerometer(Accelerometer&&) = default;
+  Accelerometer& operator=(Accelerometer&&) = default;
+
+  enum Range { kRange_2G = 0, kRange_4G = 1, kRange_8G = 2, kRange_16G = 3 };
+
+  /**
+   * Common interface for setting the measuring range of an accelerometer.
+   *
+   * @param range The maximum acceleration, positive or negative, that the
+   *              accelerometer will measure. Not all accelerometers support all
+   *              ranges.
+   */
+  virtual void SetRange(Range range) = 0;
+
+  /**
+   * Common interface for getting the x axis acceleration.
+   *
+   * @return The acceleration along the x axis in g-forces
+   */
+  virtual double GetX() = 0;
+
+  /**
+   * Common interface for getting the y axis acceleration.
+   *
+   * @return The acceleration along the y axis in g-forces
+   */
+  virtual double GetY() = 0;
+
+  /**
+   * Common interface for getting the z axis acceleration.
+   *
+   * @return The acceleration along the z axis in g-forces
+   */
+  virtual double GetZ() = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Gyro.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Gyro.h
new file mode 100644
index 0000000..b5aa332
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Gyro.h
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+/**
+ * Interface for yaw rate gyros.
+ */
+class Gyro {
+ public:
+  Gyro() = default;
+  virtual ~Gyro() = default;
+
+  Gyro(Gyro&&) = default;
+  Gyro& operator=(Gyro&&) = default;
+
+  /**
+   * Calibrate the gyro by running for a number of samples and computing the
+   * center value. Then use the center value as the Accumulator center value for
+   * subsequent measurements. It's important to make sure that the robot is not
+   * moving while the centering calculations are in progress, this is typically
+   * done when the robot is first turned on while it's sitting at rest before
+   * the competition starts.
+   */
+  virtual void Calibrate() = 0;
+
+  /**
+   * Reset the gyro. Resets the gyro to a heading of zero. This can be used if
+   * there is significant drift in the gyro and it needs to be recalibrated
+   * after it has been running.
+   */
+  virtual void Reset() = 0;
+
+  /**
+   * Return the actual angle in degrees that the robot is currently facing.
+   *
+   * The angle is based on the current accumulator value corrected by the
+   * oversampling rate, the gyro type and the A/D calibration values. The angle
+   * is continuous, that is it will continue from 360 to 361 degrees. This
+   * allows algorithms that wouldn't want to see a discontinuity in the gyro
+   * output as it sweeps past from 360 to 0 on the second time around.
+   *
+   * The angle is expected to increase as the gyro turns clockwise when looked
+   * at from the top. It needs to follow NED axis conventions in order to work
+   * properly with dependent control loops.
+   *
+   * @return the current heading of the robot in degrees. This heading is based
+   *         on integration of the returned rate from the gyro.
+   */
+  virtual double GetAngle() const = 0;
+
+  /**
+   * Return the rate of rotation of the gyro.
+   *
+   * The rate is based on the most recent reading of the gyro analog value.
+   *
+   * The rate is expected to be positive as the gyro turns clockwise when looked
+   * at from the top. It needs to follow NED axis conventions in order to work
+   * properly with dependent control loops.
+   *
+   * @return the current rate in degrees per second
+   */
+  virtual double GetRate() const = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h
new file mode 100644
index 0000000..219e6ba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/interfaces/Potentiometer.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/PIDSource.h"
+
+namespace frc {
+
+/**
+ * Interface for potentiometers.
+ */
+class Potentiometer : public PIDSource {
+ public:
+  Potentiometer() = default;
+  virtual ~Potentiometer() = default;
+
+  Potentiometer(Potentiometer&&) = default;
+  Potentiometer& operator=(Potentiometer&&) = default;
+
+  /**
+   * Common interface for getting the current value of a potentiometer.
+   *
+   * @return The current set speed. Value is between -1.0 and 1.0.
+   */
+  virtual double Get() const = 0;
+
+  void SetPIDSourceType(PIDSourceType pidSource) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
new file mode 100644
index 0000000..465a4bb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/livewindow/LiveWindow.h
@@ -0,0 +1,218 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2012-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/Twine.h>
+#include <wpi/deprecated.h>
+
+#include "frc/smartdashboard/Sendable.h"
+
+namespace frc {
+
+/**
+ * The LiveWindow class is the public interface for putting sensors and
+ * actuators on the LiveWindow.
+ */
+class LiveWindow {
+ public:
+  LiveWindow(const LiveWindow&) = delete;
+  LiveWindow& operator=(const LiveWindow&) = delete;
+
+  /**
+   * 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.
+   */
+  static LiveWindow* GetInstance();
+
+  WPI_DEPRECATED("no longer required")
+  void Run();
+
+  /**
+   * Add a Sensor associated with the subsystem and call it by the given name.
+   *
+   * @param subsystem The subsystem this component is part of.
+   * @param name      The name of this component.
+   * @param component A Sendable component that represents a sensor.
+   */
+  WPI_DEPRECATED("use Sendable::SetName() instead")
+  void AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
+                 Sendable* component);
+
+  /**
+   * Add a Sensor associated with the subsystem and call it by the given name.
+   *
+   * @param subsystem The subsystem this component is part of.
+   * @param name      The name of this component.
+   * @param component A Sendable component that represents a sensor.
+   */
+  WPI_DEPRECATED("use Sendable::SetName() instead")
+  void AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
+                 Sendable& component);
+
+  /**
+   * Add a Sensor associated with the subsystem and call it by the given name.
+   *
+   * @param subsystem The subsystem this component is part of.
+   * @param name      The name of this component.
+   * @param component A Sendable component that represents a sensor.
+   */
+  WPI_DEPRECATED("use Sendable::SetName() instead")
+  void AddSensor(const wpi::Twine& subsystem, const wpi::Twine& name,
+                 std::shared_ptr<Sendable> component);
+
+  /**
+   * Add an Actuator associated with the subsystem and call it by the given
+   * name.
+   *
+   * @param subsystem The subsystem this component is part of.
+   * @param name      The name of this component.
+   * @param component A Sendable component that represents a actuator.
+   */
+  WPI_DEPRECATED("use Sendable::SetName() instead")
+  void AddActuator(const wpi::Twine& subsystem, const wpi::Twine& name,
+                   Sendable* component);
+
+  /**
+   * Add an Actuator associated with the subsystem and call it by the given
+   * name.
+   *
+   * @param subsystem The subsystem this component is part of.
+   * @param name      The name of this component.
+   * @param component A Sendable component that represents a actuator.
+   */
+  WPI_DEPRECATED("use Sendable::SetName() instead")
+  void AddActuator(const wpi::Twine& subsystem, const wpi::Twine& name,
+                   Sendable& component);
+
+  /**
+   * Add an Actuator associated with the subsystem and call it by the given
+   * name.
+   *
+   * @param subsystem The subsystem this component is part of.
+   * @param name      The name of this component.
+   * @param component A Sendable component that represents a actuator.
+   */
+  WPI_DEPRECATED("use Sendable::SetName() instead")
+  void AddActuator(const wpi::Twine& subsystem, const wpi::Twine& name,
+                   std::shared_ptr<Sendable> component);
+
+  /**
+   * Meant for internal use in other WPILib classes.
+   *
+   * @deprecated Use SendableBase::SetName() instead.
+   */
+  WPI_DEPRECATED("use SensorUtil::SetName() instead")
+  void AddSensor(const wpi::Twine& type, int channel, Sendable* component);
+
+  /**
+   * Meant for internal use in other WPILib classes.
+   *
+   * @deprecated Use SendableBase::SetName() instead.
+   */
+  WPI_DEPRECATED("use SensorUtil::SetName() instead")
+  void AddActuator(const wpi::Twine& type, int channel, Sendable* component);
+
+  /**
+   * Meant for internal use in other WPILib classes.
+   *
+   * @deprecated Use SendableBase::SetName() instead.
+   */
+  WPI_DEPRECATED("use SensorUtil::SetName() instead")
+  void AddActuator(const wpi::Twine& type, int module, int channel,
+                   Sendable* component);
+
+  /**
+   * Add a component to the LiveWindow.
+   *
+   * @param sendable component to add
+   */
+  void Add(std::shared_ptr<Sendable> component);
+
+  /**
+   * Add a component to the LiveWindow.
+   *
+   * @param sendable component to add
+   */
+  void Add(Sendable* component);
+
+  /**
+   * Add a child component to a component.
+   *
+   * @param parent parent component
+   * @param child child component
+   */
+  void AddChild(Sendable* parent, std::shared_ptr<Sendable> component);
+
+  /**
+   * Add a child component to a component.
+   *
+   * @param parent parent component
+   * @param child child component
+   */
+  void AddChild(Sendable* parent, void* component);
+
+  /**
+   * Remove the component from the LiveWindow.
+   *
+   * @param sendable component to remove
+   */
+  void Remove(Sendable* component);
+
+  /**
+   * Enable telemetry for a single component.
+   *
+   * @param sendable component
+   */
+  void EnableTelemetry(Sendable* component);
+
+  /**
+   * Disable telemetry for a single component.
+   *
+   * @param sendable component
+   */
+  void DisableTelemetry(Sendable* component);
+
+  /**
+   * Disable ALL telemetry.
+   */
+  void DisableAllTelemetry();
+
+  bool IsEnabled() const;
+
+  /**
+   * Change the enabled status of LiveWindow.
+   *
+   * If it changes to enabled, start livewindow running otherwise stop it
+   */
+  void SetEnabled(bool enabled);
+
+  /**
+   * Tell all the sensors to update (send) their values.
+   *
+   * Actuators are handled through callbacks on their value changing from the
+   * SmartDashboard widgets.
+   */
+  void UpdateValues();
+
+ private:
+  LiveWindow();
+
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+
+  /**
+   * Updates the entries, without using a mutex or lock.
+   */
+  void UpdateValuesUnsafe();
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/livewindow/LiveWindowSendable.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/livewindow/LiveWindowSendable.h
new file mode 100644
index 0000000..172e0cb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/livewindow/LiveWindowSendable.h
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2012-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <wpi/deprecated.h>
+
+#include "frc/smartdashboard/Sendable.h"
+
+namespace frc {
+
+/**
+ * Live Window Sendable is a special type of object sendable to the live window.
+ * @deprecated Use Sendable directly instead
+ */
+class LiveWindowSendable : public Sendable {
+ public:
+  WPI_DEPRECATED("use Sendable directly instead")
+  LiveWindowSendable() = default;
+  LiveWindowSendable(LiveWindowSendable&&) = default;
+  LiveWindowSendable& operator=(LiveWindowSendable&&) = default;
+
+  /**
+   * Update the table for this sendable object with the latest values.
+   */
+  virtual void UpdateTable() = 0;
+
+  /**
+   * Start having this sendable object automatically respond to value changes
+   * reflect the value on the table.
+   */
+  virtual void StartLiveWindowMode() = 0;
+
+  /**
+   * Stop having this sendable object automatically respond to value changes.
+   */
+  virtual void StopLiveWindowMode() = 0;
+
+  std::string GetName() const override;
+  void SetName(const wpi::Twine& name) override;
+  std::string GetSubsystem() const override;
+  void SetSubsystem(const wpi::Twine& subsystem) override;
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
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
new file mode 100644
index 0000000..6a61b87
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInLayouts.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/shuffleboard/LayoutType.h"
+
+namespace frc {
+
+/**
+ * The types of layouts bundled with Shuffleboard.
+ *
+ * <pre>{@code
+ * ShuffleboardLayout myList = Shuffleboard::GetTab("My Tab")
+ *   .GetLayout(BuiltinLayouts::kList, "My List");
+ * }</pre>
+ */
+class BuiltInLayouts {
+ public:
+  /**
+   * 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>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Label position</td><td>String</td><td>"BOTTOM"</td>
+   * <td>The position of component labels inside the grid. One of
+   * {@code ["TOP", "LEFT", "BOTTOM", "RIGHT", "HIDDEN"}</td></tr>
+   * </table>
+   */
+  static const LayoutType kList;
+
+  /**
+   * Groups components in an <i>n</i> x <i>m</i> grid. Grid layouts default to
+   * 3x3. <br>Custom properties: <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Number of columns</td><td>Number</td><td>3</td><td>Must be in the
+   * range [1,15]</td>
+   * </tr>
+   * <tr><td>Number of rows</td><td>Number</td><td>3</td><td>Must be in the
+   * range [1,15]</td></tr> <tr> <td>Label position</td> <td>String</td>
+   * <td>"BOTTOM"</td>
+   * <td>The position of component labels inside the grid.
+   * One of {@code ["TOP", "LEFT", "BOTTOM", "RIGHT", "HIDDEN"}</td>
+   * </tr>
+   * </table>
+   */
+  static const LayoutType 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
new file mode 100644
index 0000000..1fd720f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/BuiltInWidgets.h
@@ -0,0 +1,387 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/shuffleboard/WidgetType.h"
+
+namespace frc {
+
+/**
+ * The types of the widgets bundled with Shuffleboard.
+ *
+ * <p>For example, setting a number to be displayed with a slider:
+ * <pre>{@code
+ * NetworkTableEntry example = Shuffleboard.getTab("My Tab")
+ *   .add("My Number", 0)
+ *   .withWidget(BuiltInWidgets.kNumberSlider)
+ *   .getEntry();
+ * }</pre>
+ *
+ * <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:
+  /**
+   * Displays a value with a simple text field.
+   * <br>Supported types:
+   * <ul>
+   * <li>String</li>
+   * <li>Number</li>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType kTextView;
+  /**
+   * Displays a number with a controllable slider.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1.0</td><td>The minimum value of the
+   * slider</td></tr> <tr><td>Max</td><td>Number</td><td>1.0</td><td>The maximum
+   * value of the slider</td></tr> <tr><td>Block
+   * increment</td><td>Number</td><td>0.0625</td> <td>How much to move the
+   * slider by with the arrow keys</td></tr>
+   * </table>
+   */
+  static const WidgetType kNumberSlider;
+  /**
+   * Displays a number with a view-only bar.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1.0</td><td>The minimum value of the
+   * bar</td></tr> <tr><td>Max</td><td>Number</td><td>1.0</td><td>The maximum
+   * value of the bar</td></tr>
+   * <tr><td>Center</td><td>Number</td><td>0</td><td>The center ("zero") value
+   * of the bar</td></tr>
+   * </table>
+   */
+  static const WidgetType kNumberBar;
+  /**
+   * Displays a number with a view-only dial. Displayed values are rounded to
+   * the nearest integer. <br>Supported types: <ul> <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>0</td><td>The minimum value of the
+   * dial</td></tr> <tr><td>Max</td><td>Number</td><td>100</td><td>The maximum
+   * value of the dial</td></tr> <tr><td>Show
+   * value</td><td>Boolean</td><td>true</td> <td>Whether or not to show the
+   * value as text</td></tr>
+   * </table>
+   */
+  static const WidgetType 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
+   * points to a minimum. Making the widget smaller also helps with performance,
+   * but may cause the graph to become difficult to read. <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * <li>Number array</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Visible time</td><td>Number</td><td>30</td>
+   * <td>How long, in seconds, should past data be visible for</td></tr>
+   * </table>
+   */
+  static const WidgetType kGraph;
+  /**
+   * Displays a boolean value as a large colored box.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Color when true</td><td>Color</td><td>"green"</td>
+   * <td>Can be specified as a string ({@code "#00FF00"}) or a rgba integer
+   * ({@code 0x00FF0000})
+   * </td></tr>
+   * <tr><td>Color when false</td><td>Color</td><td>"red"</td>
+   * <td>Can be specified as a string or a number</td></tr>
+   * </table>
+   */
+  static const WidgetType kBooleanBox;
+  /**
+   * Displays a boolean with a large interactive toggle button.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType kToggleButton;
+  /**
+   * Displays a boolean with a fixed-size toggle switch.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType kToggleSwitch;
+  /**
+   * Displays an analog input or a raw number with a number bar.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogInput}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>0</td><td>The minimum value of the
+   * bar</td></tr> <tr><td>Max</td><td>Number</td><td>5</td><td>The maximum
+   * value of the bar</td></tr>
+   * <tr><td>Center</td><td>Number</td><td>0</td><td>The center ("zero") value
+   * of the bar</td></tr>
+   * <tr><td>Orientation</td><td>String</td><td>"HORIZONTAL"</td>
+   * <td>The orientation of the bar. One of {@code ["HORIZONTAL",
+   * "VERTICAL"]}</td></tr> <tr><td>Number of tick
+   * marks</td><td>Number</td><td>5</td> <td>The number of discrete ticks on the
+   * bar</td></tr>
+   * </table>
+   */
+  static const WidgetType kVoltageView;
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.PowerDistributionPanel
+   * PowerDistributionPanel}. <br>Supported types: <ul> <li>{@link
+   * edu.wpi.first.wpilibj.PowerDistributionPanel}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show voltage and current values</td><td>Boolean</td><td>true</td>
+   * <td>Whether or not to display the voltage and current draw</td></tr>
+   * </table>
+   */
+  static const WidgetType kPowerDistributionPanel;
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser
+   * SendableChooser} with a dropdown combo box with a list of options.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType kComboBoxChooser;
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser
+   * SendableChooser} with a toggle button for each available option.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType kSplitButtonChooser;
+  /**
+   * Displays an {@link edu.wpi.first.wpilibj.Encoder} displaying its speed,
+   * total travelled distance, and its distance per tick. <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.Encoder}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType kEncoder;
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.SpeedController SpeedController}.
+   * The speed controller will be controllable from the dashboard when test mode
+   * is enabled, but will otherwise be view-only. <br>Supported types: <ul>
+   * <li>{@link edu.wpi.first.wpilibj.PWMSpeedController}</li>
+   * <li>{@link edu.wpi.first.wpilibj.DMC60}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Jaguar}</li>
+   * <li>{@link edu.wpi.first.wpilibj.PWMTalonSRX}</li>
+   * <li>{@link edu.wpi.first.wpilibj.PWMVictorSPX}</li>
+   * <li>{@link edu.wpi.first.wpilibj.SD540}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Spark}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Talon}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Victor}</li>
+   * <li>{@link edu.wpi.first.wpilibj.VictorSP}</li>
+   * <li>{@link edu.wpi.first.wpilibj.SpeedControllerGroup}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Orientation</td><td>String</td><td>"HORIZONTAL"</td>
+   * <td>One of {@code ["HORIZONTAL", "VERTICAL"]}</td></tr>
+   * </table>
+   */
+  static const WidgetType kSpeedController;
+  /**
+   * Displays a command with a toggle button. Pressing the button will start the
+   * command, and the button will automatically release when the command
+   * completes. <br>Supported types: <ul> <li>{@link
+   * edu.wpi.first.wpilibj.command.Command}</li> <li>{@link
+   * edu.wpi.first.wpilibj.command.CommandGroup}</li> <li>Any custom subclass of
+   * {@code Command} or {@code CommandGroup}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType 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
+   * will automatically deselect when the command completes. <br>Supported
+   * types: <ul> <li>{@link edu.wpi.first.wpilibj.command.PIDCommand}</li>
+   * <li>Any custom subclass of {@code PIDCommand}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType kPIDCommand;
+  /**
+   * Displays a PID controller with an editor for the PIDF constants and a
+   * toggle switch for enabling and disabling the controller. <br>Supported
+   * types: <ul> <li>{@link edu.wpi.first.wpilibj.PIDController}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType kPIDController;
+  /**
+   * Displays an accelerometer with a number bar displaying the magnitude of the
+   * acceleration and text displaying the exact value. <br>Supported types: <ul>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogAccelerometer}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1</td>
+   * <td>The minimum acceleration value to display</td></tr>
+   * <tr><td>Max</td><td>Number</td><td>1</td>
+   * <td>The maximum acceleration value to display</td></tr>
+   * <tr><td>Show text</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide the acceleration values</td></tr>
+   * <tr><td>Precision</td><td>Number</td><td>2</td>
+   * <td>How many numbers to display after the decimal point</td></tr>
+   * <tr><td>Show tick marks</td><td>Boolean</td><td>false</td>
+   * <td>Show or hide the tick marks on the number bars</td></tr>
+   * </table>
+   */
+  static const WidgetType kAccelerometer;
+  /**
+   * Displays a 3-axis accelerometer with a number bar for each axis'
+   * accleration. <br>Supported types: <ul> <li>{@link
+   * edu.wpi.first.wpilibj.ADXL345_I2C}</li> <li>{@link
+   * edu.wpi.first.wpilibj.ADXL345_SPI}</li> <li>{@link
+   * edu.wpi.first.wpilibj.ADXL362}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Range</td><td>{@link Range}</td><td>k16G</td><td>The accelerometer
+   * range</td></tr> <tr><td>Show value</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide the acceleration values</td></tr>
+   * <tr><td>Precision</td><td>Number</td><td>2</td>
+   * <td>How many numbers to display after the decimal point</td></tr>
+   * <tr><td>Show tick marks</td><td>Boolean</td><td>false</td>
+   * <td>Show or hide the tick marks on the number bars</td></tr>
+   * </table>
+   */
+  static const WidgetType k3AxisAccelerometer;
+  /**
+   * Displays a gyro with a dial from 0 to 360 degrees.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.ADXRS450_Gyro}</li>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogGyro}</li>
+   * <li>Any custom subclass of {@code GyroBase} (such as a MXP gyro)</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Major tick
+   * spacing</td><td>Number</td><td>45</td><td>Degrees</td></tr>
+   * <tr><td>Starting angle</td><td>Number</td><td>180</td>
+   * <td>How far to rotate the entire dial, in degrees</td></tr>
+   * <tr><td>Show tick mark ring</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  static const WidgetType kGyro;
+  /**
+   * Displays a relay with toggle buttons for each supported mode (off, on,
+   * forward, reverse). <br>Supported types: <ul> <li>{@link
+   * edu.wpi.first.wpilibj.Relay}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  static const WidgetType 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
+   * drivebase. The widget will be controllable if the robot is in test mode.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.drive.DifferentialDrive}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Number of wheels</td><td>Number</td><td>4</td><td>Must be a
+   * positive even integer
+   * </td></tr>
+   * <tr><td>Wheel diameter</td><td>Number</td><td>80</td><td>Pixels</td></tr>
+   * <tr><td>Show velocity vectors</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  static const WidgetType 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
+   * widget will be controllable if the robot is in test mode. <br>Supported
+   * types: <ul> <li>{@link edu.wpi.first.wpilibj.drive.MecanumDrive}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show velocity vectors</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  static const WidgetType kMecanumDrive;
+  /**
+   * Displays a camera stream.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.cscore.VideoSource} (as long as it is streaming on an
+   * MJPEG server)</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show crosshair</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide a crosshair on the image</td></tr>
+   * <tr><td>Crosshair color</td><td>Color</td><td>"white"</td>
+   * <td>Can be a string or a rgba integer</td></tr>
+   * <tr><td>Show controls</td><td>Boolean</td><td>true</td><td>Show or hide the
+   * stream controls
+   * </td></tr>
+   * <tr><td>Rotation</td><td>String</td><td>"NONE"</td>
+   * <td>Rotates the displayed image. One of {@code ["NONE", "QUARTER_CW",
+   * "QUARTER_CCW", "HALF"]}
+   * </td></tr>
+   * </table>
+   */
+  static const WidgetType kCameraStream;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h
new file mode 100644
index 0000000..218ed2f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ComplexWidget.h
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardWidget.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableBuilderImpl.h"
+
+namespace frc {
+
+class Sendable;
+class ShuffleboardContainer;
+
+/**
+ * A Shuffleboard widget that handles a {@link Sendable} object such as a speed
+ * controller or sensor.
+ */
+class ComplexWidget final : public ShuffleboardWidget<ComplexWidget> {
+ public:
+  ComplexWidget(ShuffleboardContainer& parent, const wpi::Twine& title,
+                Sendable& sendable);
+
+  void EnableIfActuator() override;
+
+  void DisableIfActuator() override;
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override;
+
+ private:
+  Sendable& m_sendable;
+  SendableBuilderImpl m_builder;
+  bool m_builderInit = false;
+};
+
+}  // 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
new file mode 100644
index 0000000..22fe361
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/LayoutType.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+namespace frc {
+
+/**
+ * Represents the type of a layout in Shuffleboard. Using this is preferred over
+ * specifying raw strings, to avoid typos and having to know or look up the
+ * exact string name for a desired layout.
+ *
+ * @see BuiltInLayouts the built-in layout types
+ */
+class LayoutType {
+ public:
+  explicit LayoutType(const char* layoutName) : m_layoutName(layoutName) {}
+  ~LayoutType() = default;
+
+  /**
+   * Gets the string type of the layout as defined by that layout in
+   * Shuffleboard.
+   */
+  wpi::StringRef GetLayoutName() const;
+
+ private:
+  wpi::StringRef m_layoutName;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h
new file mode 100644
index 0000000..dacbdb4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/RecordingController.h
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableInstance.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+
+#include "frc/shuffleboard/ShuffleboardEventImportance.h"
+
+namespace frc {
+namespace detail {
+
+class RecordingController final {
+ public:
+  explicit RecordingController(nt::NetworkTableInstance ntInstance);
+  virtual ~RecordingController() = default;
+
+  void StartRecording();
+  void StopRecording();
+  void SetRecordingFileNameFormat(wpi::StringRef format);
+  void ClearRecordingFileNameFormat();
+
+  void AddEventMarker(wpi::StringRef name, wpi::StringRef description,
+                      ShuffleboardEventImportance importance);
+
+ private:
+  nt::NetworkTableEntry m_recordingControlEntry;
+  nt::NetworkTableEntry m_recordingFileNameFormatEntry;
+  std::shared_ptr<nt::NetworkTable> m_eventsTable;
+};
+
+}  // namespace detail
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h
new file mode 100644
index 0000000..291e64d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/SendableCameraWrapper.h
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <cscore_c.h>
+
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace cs {
+class VideoSource;
+}  // namespace cs
+
+namespace frc {
+
+/**
+ * A wrapper to make video sources sendable and usable from Shuffleboard.
+ */
+class SendableCameraWrapper : public SendableBase {
+ private:
+  struct private_init {};
+
+ public:
+  /**
+   * Creates a new sendable wrapper. Private constructor to avoid direct
+   * instantiation with multiple wrappers floating around for the same camera.
+   *
+   * @param source the source to wrap
+   */
+  SendableCameraWrapper(CS_Source source, const private_init&);
+
+  /**
+   * Gets a sendable wrapper object for the given video source, creating the
+   * wrapper if one does not already exist for the source.
+   *
+   * @param source the video source to wrap
+   * @return a sendable wrapper object for the video source, usable in
+   * Shuffleboard via ShuffleboardTab::Add() and ShuffleboardLayout::Add()
+   */
+  static SendableCameraWrapper& Wrap(const cs::VideoSource& source);
+  static SendableCameraWrapper& Wrap(CS_Source source);
+
+  void InitSendable(SendableBuilder& builder) override;
+
+ private:
+  std::string m_uri;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/Shuffleboard.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/Shuffleboard.h
new file mode 100644
index 0000000..e49d1c3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/Shuffleboard.h
@@ -0,0 +1,198 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+#include "frc/shuffleboard/RecordingController.h"
+#include "frc/shuffleboard/ShuffleboardEventImportance.h"
+#include "frc/shuffleboard/ShuffleboardInstance.h"
+
+namespace frc {
+
+class ShuffleboardTab;
+
+/**
+ * The Shuffleboard class provides a mechanism with which data can be added and
+ * laid out in the Shuffleboard dashboard application from a robot program. Tabs
+ * and layouts can be specified, as well as choosing which widgets to display
+ * with and setting properties of these widgets; for example, programmers can
+ * specify a specific {@code boolean} value to be displayed with a toggle button
+ * instead of the default colored box, or set custom colors for that box.
+ *
+ * For example, displaying a boolean entry with a toggle button:
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .add("My Boolean", false)
+ *   .withWidget("Toggle Button")
+ *   .getEntry();
+ * }</pre>
+ *
+ * Changing the colors of the boolean box:
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .add("My Boolean", false)
+ *   .withWidget("Boolean Box")
+ *   .withProperties(Map.of("colorWhenTrue", "green", "colorWhenFalse",
+ * "maroon")) .getEntry();
+ * }</pre>
+ *
+ * Specifying a parent layout. Note that the layout type must <i>always</i> be
+ * specified, even if the layout has already been generated by a previously
+ * defined entry.
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .getLayout("List", "Example List")
+ *   .add("My Boolean", false)
+ *   .withWidget("Toggle Button")
+ *   .getEntry();
+ * }</pre>
+ * </p>
+ *
+ * Teams are encouraged to set up shuffleboard layouts at the start of the robot
+ * program.
+ */
+class Shuffleboard final {
+ public:
+  /**
+   * The name of the base NetworkTable into which all Shuffleboard data will be
+   * added.
+   */
+  static constexpr const char* kBaseTableName = "/Shuffleboard";
+
+  /**
+   * Updates all the values in Shuffleboard. Iterative and timed robots are
+   * pre-configured to call this method in the main robot loop; teams using
+   * custom robot base classes, or subclass SampleRobot, should make sure to
+   * call this repeatedly to keep data on the dashboard up to date.
+   */
+  static void Update();
+
+  /**
+   * Gets the Shuffleboard tab with the given title, creating it if it does not
+   * already exist.
+   *
+   * @param title the title of the tab
+   * @return the tab with the given title
+   */
+  static ShuffleboardTab& GetTab(wpi::StringRef title);
+
+  /**
+   * Selects the tab in the dashboard with the given index in the range
+   * [0..n-1], where <i>n</i> is the number of tabs in the dashboard at the time
+   * this method is called.
+   *
+   * @param index the index of the tab to select
+   */
+  static void SelectTab(int index);
+
+  /**
+   * Selects the tab in the dashboard with the given title.
+   *
+   * @param title the title of the tab to select
+   */
+  static void SelectTab(wpi::StringRef title);
+
+  /**
+   * Enables user control of widgets containing actuators: speed controllers,
+   * relays, etc. This should only be used when the robot is in test mode.
+   * IterativeRobotBase and SampleRobot are both configured to call this method
+   * when entering test mode; most users should not need to use this method
+   * directly.
+   */
+  static void EnableActuatorWidgets();
+
+  /**
+   * Disables user control of widgets containing actuators. For safety reasons,
+   * actuators should only be controlled while in test mode. IterativeRobotBase
+   * and SampleRobot are both configured to call this method when exiting in
+   * test mode; most users should not need to use this method directly.
+   */
+  static void DisableActuatorWidgets();
+
+  /**
+   * Starts data recording on the dashboard. Has no effect if recording is
+   * already in progress.
+   */
+  static void StartRecording();
+
+  /**
+   * Stops data recording on the dashboard. Has no effect if no recording is in
+   * progress.
+   */
+  static void StopRecording();
+
+  /**
+   * Sets the file name format for new recording files to use. If recording is
+   * in progress when this method is called, it will continue to use the same
+   * file. New recordings will use the format.
+   *
+   * <p>To avoid recording files overwriting each other, make sure to use unique
+   * recording file names. File name formats accept templates for inserting the
+   * date and time when the recording started with the {@code ${date}} and
+   * {@code ${time}} templates, respectively. For example, the default format is
+   * {@code "recording-${time}"} and recording files created with it will have
+   * names like {@code "recording-2018.01.15.sbr"}. Users are
+   * <strong>strongly</strong> recommended to use the {@code ${time}} template
+   * to ensure unique file names.
+   * </p>
+   *
+   * @param format the format for the
+   */
+  static void SetRecordingFileNameFormat(wpi::StringRef format);
+
+  /**
+   * Clears the custom name format for recording files. New recordings will use
+   * the default format.
+   *
+   * @see #setRecordingFileNameFormat(String)
+   */
+  static void ClearRecordingFileNameFormat();
+
+  /**
+   * Notifies Shuffleboard of an event. Events can range from as trivial as a
+   * change in a command state to as critical as a total power loss or component
+   * failure. If Shuffleboard is recording, the event will also be recorded.
+   *
+   * <p>If {@code name} is {@code null} or empty, no event will be sent and an
+   * error will be printed to the driver station.
+   *
+   * @param name        the name of the event
+   * @param description a description of the event
+   * @param importance  the importance of the event
+   */
+  static void AddEventMarker(wpi::StringRef name, wpi::StringRef description,
+                             ShuffleboardEventImportance importance);
+
+  /**
+   * Notifies Shuffleboard of an event. Events can range from as trivial as a
+   * change in a command state to as critical as a total power loss or component
+   * failure. If Shuffleboard is recording, the event will also be recorded.
+   *
+   * <p>If {@code name} is {@code null} or empty, no event will be sent and an
+   * error will be printed to the driver station.
+   *
+   * @param name        the name of the event
+   * @param importance  the importance of the event
+   */
+  static void AddEventMarker(wpi::StringRef name,
+                             ShuffleboardEventImportance importance);
+
+ private:
+  static detail::ShuffleboardInstance& GetInstance();
+  static detail::RecordingController& GetRecordingController();
+
+  // TODO usage reporting
+
+  Shuffleboard() = default;
+};
+
+}  // namespace frc
+
+// Make use of references returned by member functions usable
+#include "frc/shuffleboard/ShuffleboardTab.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
new file mode 100644
index 0000000..d6b4bc4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.h
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardComponentBase.h"
+
+namespace frc {
+
+class ShuffleboardContainer;
+
+/**
+ * A generic component in Shuffleboard.
+ *
+ * @tparam Derived the self type
+ */
+template <typename Derived>
+class ShuffleboardComponent : public ShuffleboardComponentBase {
+ public:
+  ShuffleboardComponent(ShuffleboardContainer& parent, const wpi::Twine& title,
+                        const wpi::Twine& type = "");
+
+  virtual ~ShuffleboardComponent() = default;
+
+  /**
+   * Sets custom properties for this component. Property names are
+   * case-sensitive and whitespace-insensitive (capitalization and spaces do not
+   * matter).
+   *
+   * @param properties the properties for this component
+   * @return this component
+   */
+  Derived& WithProperties(
+      const wpi::StringMap<std::shared_ptr<nt::Value>>& properties);
+
+  /**
+   * Sets the position of this component in the tab. This has no effect if this
+   * component is inside a layout.
+   *
+   * If the position of a single component is set, it is recommended to set the
+   * positions of <i>all</i> components inside a tab to prevent Shuffleboard
+   * from automatically placing another component there before the one with the
+   * specific position is sent.
+   *
+   * @param columnIndex the column in the tab to place this component
+   * @param rowIndex    the row in the tab to place this component
+   * @return this component
+   */
+  Derived& WithPosition(int columnIndex, int rowIndex);
+
+  /**
+   * Sets the size of this component in the tab. This has no effect if this
+   * component is inside a layout.
+   *
+   * @param width  how many columns wide the component should be
+   * @param height how many rows high the component should be
+   * @return this component
+   */
+  Derived& WithSize(int width, int height);
+};
+
+}  // namespace frc
+
+#include "frc/shuffleboard/ShuffleboardComponent.inc"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc
new file mode 100644
index 0000000..f75fb0d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponent.inc
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+namespace frc {
+
+template <typename Derived>
+ShuffleboardComponent<Derived>::ShuffleboardComponent(
+    ShuffleboardContainer& parent, const wpi::Twine& title,
+    const wpi::Twine& type)
+    : ShuffleboardValue(title),
+      ShuffleboardComponentBase(parent, title, type) {}
+
+template <typename Derived>
+Derived& ShuffleboardComponent<Derived>::WithProperties(
+    const wpi::StringMap<std::shared_ptr<nt::Value>>& properties) {
+  m_properties = properties;
+  m_metadataDirty = true;
+  return *static_cast<Derived*>(this);
+}
+
+template <typename Derived>
+Derived& ShuffleboardComponent<Derived>::WithPosition(int columnIndex,
+                                                      int rowIndex) {
+  m_column = columnIndex;
+  m_row = rowIndex;
+  m_metadataDirty = true;
+  return *static_cast<Derived*>(this);
+}
+
+template <typename Derived>
+Derived& ShuffleboardComponent<Derived>::WithSize(int width, int height) {
+  m_width = width;
+  m_height = height;
+  m_metadataDirty = true;
+  return *static_cast<Derived*>(this);
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h
new file mode 100644
index 0000000..c63e517
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardComponentBase.h
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardValue.h"
+
+namespace frc {
+
+class ShuffleboardContainer;
+
+/**
+ * A shim class to allow storing ShuffleboardComponents in arrays.
+ */
+class ShuffleboardComponentBase : public virtual ShuffleboardValue {
+ public:
+  ShuffleboardComponentBase(ShuffleboardContainer& parent,
+                            const wpi::Twine& title,
+                            const wpi::Twine& type = "");
+
+  virtual ~ShuffleboardComponentBase() = default;
+
+  void SetType(const wpi::Twine& type);
+
+  void BuildMetadata(std::shared_ptr<nt::NetworkTable> metaTable);
+
+  ShuffleboardContainer& GetParent();
+
+  const std::string& GetType() const;
+
+ protected:
+  wpi::StringMap<std::shared_ptr<nt::Value>> m_properties;
+  bool m_metadataDirty = true;
+  int m_column = -1;
+  int m_row = -1;
+  int m_width = -1;
+  int m_height = -1;
+
+ private:
+  ShuffleboardContainer& m_parent;
+  std::string m_type;
+
+  /**
+   * Gets the custom properties for this component. May be null.
+   */
+  const wpi::StringMap<std::shared_ptr<nt::Value>>& GetProperties() const;
+};
+
+}  // 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
new file mode 100644
index 0000000..e53bcfc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardContainer.h
@@ -0,0 +1,398 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallSet.h>
+#include <wpi/StringMap.h>
+#include <wpi/Twine.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/WPIErrors.h"
+#include "frc/shuffleboard/LayoutType.h"
+#include "frc/shuffleboard/ShuffleboardComponentBase.h"
+#include "frc/shuffleboard/ShuffleboardValue.h"
+
+namespace cs {
+class VideoSource;
+}  // namespace cs
+
+namespace frc {
+
+class ComplexWidget;
+class Sendable;
+class ShuffleboardLayout;
+class SimpleWidget;
+
+/**
+ * Common interface for objects that can contain shuffleboard components.
+ */
+class ShuffleboardContainer : public virtual ShuffleboardValue,
+                              public ErrorBase {
+ public:
+  explicit ShuffleboardContainer(const wpi::Twine& title);
+
+  ShuffleboardContainer(ShuffleboardContainer&& rhs) = default;
+
+  virtual ~ShuffleboardContainer() = default;
+
+  /**
+   * Gets the components that are direct children of this container.
+   */
+  const std::vector<std::unique_ptr<ShuffleboardComponentBase>>& GetComponents()
+      const;
+
+  /**
+   * 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);
+
+  /**
+   * Gets the layout with the given type and title, creating it if it does not
+   * already exist at the time this method is called. Note: this method should
+   * only be used to use a layout type that is not already built into
+   * Shuffleboard. To use a layout built into Shuffleboard, use
+   * {@link #GetLayout(String, LayoutType)} and the layouts in {@link
+   * BuiltInLayouts}.
+   *
+   * @param title the title of the layout
+   * @param type  the type of the layout, eg "List Layout" or "Grid Layout"
+   * @return the layout
+   * @see #GetLayout(String, LayoutType)
+   */
+  ShuffleboardLayout& GetLayout(const wpi::Twine& title,
+                                const wpi::Twine& type);
+
+  /**
+   * Gets the already-defined layout in this container with the given title.
+   *
+   * <pre>{@code
+   * Shuffleboard::GetTab("Example Tab")->getLayout("My Layout",
+   * &BuiltInLayouts.kList);
+   *
+   * // Later...
+   * Shuffleboard::GetTab("Example Tab")->GetLayout("My Layout");
+   * }</pre>
+   *
+   * @param title the title of the layout to get
+   * @return the layout with the given title
+   * @throws if no layout has yet been defined with the given title
+   */
+  ShuffleboardLayout& GetLayout(const wpi::Twine& title);
+
+  /**
+   * Adds a widget to this container to display the given sendable.
+   *
+   * @param title    the title of the widget
+   * @param sendable the sendable to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   * container with the given title
+   */
+  ComplexWidget& Add(const wpi::Twine& title, Sendable& sendable);
+
+  /**
+   * Adds a widget to this container to display the given video stream.
+   *
+   * @param title    the title of the widget
+   * @param video    the video stream to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   * container with the given title
+   */
+  ComplexWidget& Add(const wpi::Twine& title, const cs::VideoSource& video);
+
+  /**
+   * Adds a widget to this container to display the given sendable.
+   *
+   * @param sendable the sendable to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   * container with the given title, or if the sendable's name has not been
+   * specified
+   */
+  ComplexWidget& Add(Sendable& sendable);
+
+  /**
+   * Adds a widget to this container to display the given video stream.
+   *
+   * @param video the video to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   * container with the same title as the video source
+   */
+  ComplexWidget& Add(const cs::VideoSource& video);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title,
+                    std::shared_ptr<nt::Value> defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, bool defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, double defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, int defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, const wpi::Twine& defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, const char* defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title, wpi::ArrayRef<bool> defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title,
+                    wpi::ArrayRef<double> defaultValue);
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title the title of the widget
+   * @param defaultValue  the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this
+   *         container with the given title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& Add(const wpi::Twine& title,
+                    wpi::ArrayRef<std::string> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              std::shared_ptr<nt::Value> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title, bool defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title, double defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title, int defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              const wpi::Twine& defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              wpi::ArrayRef<bool> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              wpi::ArrayRef<double> defaultValue);
+
+  /**
+   * Adds a widget to this container to display a simple piece of data.
+   *
+   * Unlike {@link #add(String, Object)}, the value in the widget will be saved
+   * on the robot and will be used when the robot program next starts rather
+   * than {@code defaultValue}.
+   *
+   * @param title the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget& AddPersistent(const wpi::Twine& title,
+                              wpi::ArrayRef<std::string> defaultValue);
+
+  void EnableIfActuator() override;
+
+  void DisableIfActuator() override;
+
+ protected:
+  bool m_isLayout = false;
+
+ private:
+  wpi::SmallSet<std::string, 32> m_usedTitles;
+  std::vector<std::unique_ptr<ShuffleboardComponentBase>> m_components;
+  wpi::StringMap<ShuffleboardLayout*> m_layouts;
+
+  /**
+   * Adds title to internal set if it hasn't already.
+   *
+   * @return True if title isn't in use; false otherwise.
+   */
+  void CheckTitle(const wpi::Twine& title);
+
+  friend class SimpleWidget;
+};
+
+}  // namespace frc
+
+// Make use of references returned by member functions usable
+#include "frc/shuffleboard/ComplexWidget.h"
+#include "frc/shuffleboard/ShuffleboardLayout.h"
+#include "frc/shuffleboard/SimpleWidget.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h
new file mode 100644
index 0000000..ccbc802
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardEventImportance.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+namespace frc {
+
+// Maintainer note: this enum is mirrored in WPILibJ and in Shuffleboard
+// Modifying the enum or enum strings requires a corresponding change to the
+// Java enum and the enum in Shuffleboard
+
+enum ShuffleboardEventImportance { kTrivial, kLow, kNormal, kHigh, kCritical };
+
+inline wpi::StringRef ShuffleboardEventImportanceName(
+    ShuffleboardEventImportance importance) {
+  switch (importance) {
+    case kTrivial:
+      return "TRIVIAL";
+    case kLow:
+      return "LOW";
+    case kNormal:
+      return "NORMAL";
+    case kHigh:
+      return "HIGH";
+    case kCritical:
+      return "CRITICAL";
+    default:
+      return "NORMAL";
+  }
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardInstance.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardInstance.h
new file mode 100644
index 0000000..b202160
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardInstance.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include "frc/shuffleboard/ShuffleboardRoot.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+
+namespace frc {
+namespace detail {
+
+class ShuffleboardInstance final : public ShuffleboardRoot {
+ public:
+  explicit ShuffleboardInstance(nt::NetworkTableInstance ntInstance);
+  virtual ~ShuffleboardInstance();
+
+  frc::ShuffleboardTab& GetTab(wpi::StringRef title) override;
+
+  void Update() override;
+
+  void EnableActuatorWidgets() override;
+
+  void DisableActuatorWidgets() override;
+
+  void SelectTab(int index) override;
+
+  void SelectTab(wpi::StringRef) override;
+
+ private:
+  struct Impl;
+  std::unique_ptr<Impl> m_impl;
+};
+
+}  // namespace detail
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h
new file mode 100644
index 0000000..0b5d459
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardLayout.h
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardComponent.h"
+#include "frc/shuffleboard/ShuffleboardContainer.h"
+#include "frc/smartdashboard/Sendable.h"
+
+namespace frc {
+
+/**
+ * A layout in a Shuffleboard tab. Layouts can contain widgets and other
+ * layouts.
+ */
+class ShuffleboardLayout : public ShuffleboardComponent<ShuffleboardLayout>,
+                           public ShuffleboardContainer {
+ public:
+  ShuffleboardLayout(ShuffleboardContainer& parent, const wpi::Twine& name,
+                     const wpi::Twine& type);
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardRoot.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardRoot.h
new file mode 100644
index 0000000..0c50545
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardRoot.h
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+class ShuffleboardTab;
+
+/**
+ * The root of the data placed in Shuffleboard. It contains the tabs, but no
+ * data is placed directly in the root.
+ *
+ * This class is package-private to minimize API surface area.
+ */
+class ShuffleboardRoot {
+ public:
+  /**
+   * Gets the tab with the given title, creating it if it does not already
+   * exist.
+   *
+   * @param title the title of the tab
+   * @return the tab with the given title
+   */
+  virtual ShuffleboardTab& GetTab(wpi::StringRef title) = 0;
+
+  /**
+   * Updates all tabs.
+   */
+  virtual void Update() = 0;
+
+  /**
+   * Enables all widgets in Shuffleboard that offer user control over actuators.
+   */
+  virtual void EnableActuatorWidgets() = 0;
+
+  /**
+   * Disables all widgets in Shuffleboard that offer user control over
+   * actuators.
+   */
+  virtual void DisableActuatorWidgets() = 0;
+
+  /**
+   * Selects the tab in the dashboard with the given index in the range
+   * [0..n-1], where <i>n</i> is the number of tabs in the dashboard at the time
+   * this method is called.
+   *
+   * @param index the index of the tab to select
+   */
+  virtual void SelectTab(int index) = 0;
+
+  /**
+   * Selects the tab in the dashboard with the given title.
+   *
+   * @param title the title of the tab to select
+   */
+  virtual void SelectTab(wpi::StringRef title) = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h
new file mode 100644
index 0000000..16e6f92
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardTab.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/StringRef.h>
+
+#include "frc/shuffleboard/ShuffleboardContainer.h"
+#include "frc/smartdashboard/Sendable.h"
+
+namespace frc {
+
+class ShuffleboardRoot;
+
+/**
+ * Represents a tab in the Shuffleboard dashboard. Widgets can be added to the
+ * tab with {@link #add(Sendable)}, {@link #add(String, Object)}, and
+ * {@link #add(String, Sendable)}. Widgets can also be added to layouts with
+ * {@link #getLayout(String, String)}; layouts can be nested arbitrarily deep
+ * (note that too many levels may make deeper components unusable).
+ */
+class ShuffleboardTab final : public ShuffleboardContainer {
+ public:
+  ShuffleboardTab(ShuffleboardRoot& root, wpi::StringRef title);
+
+  ShuffleboardRoot& GetRoot();
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override;
+
+ private:
+  ShuffleboardRoot& m_root;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardValue.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardValue.h
new file mode 100644
index 0000000..4a88cc1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardValue.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTable.h>
+#include <wpi/SmallVector.h>
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+class ShuffleboardValue {
+ public:
+  explicit ShuffleboardValue(const wpi::Twine& title) {
+    wpi::SmallVector<char, 16> storage;
+    m_title = title.toStringRef(storage);
+  }
+
+  virtual ~ShuffleboardValue() = default;
+
+  /**
+   * Gets the title of this Shuffleboard value.
+   */
+  wpi::StringRef GetTitle() const { return m_title; }
+
+  /**
+   * Builds the entries for this value.
+   *
+   * @param parentTable The table containing all the data for the parent. Values
+   *                    that require a complex entry or table structure should
+   *                    call {@code parentTable.getSubtable(getTitle())} to get
+   *                    the table to put data into. Values that only use a
+   *                    single entry should call
+   *                    {@code parentTable.getEntry(getTitle())} to get that
+   *                    entry.
+   * @param metaTable   The table containing all the metadata for this value and
+   *                    its sub-values
+   */
+  virtual void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                         std::shared_ptr<nt::NetworkTable> metaTable) = 0;
+
+  /**
+   * Enables user control of this widget in the Shuffleboard application.
+   *
+   * This method is package-private to prevent users from enabling control
+   * themselves. Has no effect if the sendable is not marked as an actuator with
+   * {@link SendableBuilder#setActuator}.
+   */
+  virtual void EnableIfActuator() {}
+
+  /**
+   * Disables user control of this widget in the Shuffleboard application.
+   *
+   * This method is package-private to prevent users from enabling control
+   * themselves. Has no effect if the sendable is not marked as an actuator with
+   * {@link SendableBuilder#setActuator}.
+   */
+  virtual void DisableIfActuator() {}
+
+ private:
+  std::string m_title;
+};
+
+}  // namespace frc
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
new file mode 100644
index 0000000..2e67160
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/ShuffleboardWidget.h
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardComponent.h"
+#include "frc/shuffleboard/WidgetType.h"
+
+namespace frc {
+
+class ShuffleboardContainer;
+
+/**
+ * Abstract superclass for widgets.
+ *
+ * <p>This class is package-private to minimize API surface area.
+ *
+ * @tparam Derived the self type
+ */
+template <typename Derived>
+class ShuffleboardWidget
+    : public ShuffleboardComponent<ShuffleboardWidget<Derived>> {
+ public:
+  ShuffleboardWidget(ShuffleboardContainer& parent, const wpi::Twine& title)
+      : ShuffleboardValue(title),
+        ShuffleboardComponent<ShuffleboardWidget<Derived>>(parent, title) {}
+
+  /**
+   * 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
+   * @see BuiltInWidgets
+   */
+  Derived& withWidget(const WidgetType& widgetType) {
+    return WithWidget(widgetType.GetWidgetName());
+  }
+
+  /**
+   * Sets the type of widget used to display the data. If not set, the default
+   * widget type will be used. This method should only be used to use a widget
+   * that does not come built into Shuffleboard (i.e. one that comes with a
+   * custom or thrid-party plugin). To use a widget that is built into
+   * Shuffleboard, use {@link #withWidget(WidgetType)} and {@link
+   * BuiltInWidgets}.
+   *
+   * @param widgetType the type of the widget used to display the data
+   * @return this widget object
+   */
+  Derived& WithWidget(const wpi::Twine& widgetType) {
+    this->SetType(widgetType);
+    return *static_cast<Derived*>(this);
+  }
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h
new file mode 100644
index 0000000..973f8cb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <wpi/Twine.h>
+
+#include "frc/shuffleboard/ShuffleboardWidget.h"
+
+namespace frc {
+
+class ShuffleboardContainer;
+
+/**
+ * A Shuffleboard widget that handles a single data point such as a number or
+ * string.
+ */
+class SimpleWidget final : public ShuffleboardWidget<SimpleWidget> {
+ public:
+  SimpleWidget(ShuffleboardContainer& parent, const wpi::Twine& title);
+
+  /**
+   * Gets the NetworkTable entry that contains the data for this widget.
+   */
+  nt::NetworkTableEntry GetEntry();
+
+  void BuildInto(std::shared_ptr<nt::NetworkTable> parentTable,
+                 std::shared_ptr<nt::NetworkTable> metaTable) override;
+
+ private:
+  nt::NetworkTableEntry m_entry;
+
+  void ForceGenerate();
+};
+
+}  // namespace frc
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
new file mode 100644
index 0000000..f96e9b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/shuffleboard/WidgetType.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/Twine.h>
+
+namespace frc {
+
+/**
+ * Represents the type of a widget in Shuffleboard. Using this is preferred over
+ * specifying raw strings, to avoid typos and having to know or look up the
+ * exact string name for a desired widget.
+ *
+ * @see BuiltInWidgets the built-in widget types
+ */
+class WidgetType {
+ public:
+  explicit WidgetType(const char* widgetName) : m_widgetName(widgetName) {}
+  ~WidgetType() = default;
+
+  /**
+   * Gets the string type of the widget as defined by that widget in
+   * Shuffleboard.
+   */
+  wpi::StringRef GetWidgetName() const;
+
+ private:
+  wpi::StringRef m_widgetName;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/NamedSendable.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/NamedSendable.h
new file mode 100644
index 0000000..604d2e0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/NamedSendable.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2012-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <wpi/deprecated.h>
+
+#include "frc/smartdashboard/Sendable.h"
+
+namespace frc {
+
+/**
+ * The interface for sendable objects that gives the sendable a default name in
+ * the Smart Dashboard.
+ * @deprecated Use Sendable directly instead
+ */
+class NamedSendable : public Sendable {
+ public:
+  WPI_DEPRECATED("use Sendable directly instead")
+  NamedSendable() = default;
+
+  void SetName(const wpi::Twine& name) override;
+  std::string GetSubsystem() const override;
+  void SetSubsystem(const wpi::Twine& subsystem) override;
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h
new file mode 100644
index 0000000..383c169
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/Sendable.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <wpi/Twine.h>
+
+namespace frc {
+
+class SendableBuilder;
+
+class Sendable {
+ public:
+  Sendable() = default;
+  virtual ~Sendable() = default;
+
+  Sendable(Sendable&&) = default;
+  Sendable& operator=(Sendable&&) = default;
+
+  /**
+   * Gets the name of this Sendable object.
+   *
+   * @return Name
+   */
+  virtual std::string GetName() const = 0;
+
+  /**
+   * Sets the name of this Sendable object.
+   *
+   * @param name name
+   */
+  virtual void SetName(const wpi::Twine& name) = 0;
+
+  /**
+   * Sets both the subsystem name and device name of this Sendable object.
+   *
+   * @param subsystem subsystem name
+   * @param name device name
+   */
+  void SetName(const wpi::Twine& subsystem, const wpi::Twine& name) {
+    SetSubsystem(subsystem);
+    SetName(name);
+  }
+
+  /**
+   * Gets the subsystem name of this Sendable object.
+   *
+   * @return Subsystem name
+   */
+  virtual std::string GetSubsystem() const = 0;
+
+  /**
+   * Sets the subsystem name of this Sendable object.
+   *
+   * @param subsystem subsystem name
+   */
+  virtual void SetSubsystem(const wpi::Twine& subsystem) = 0;
+
+  /**
+   * Initializes this Sendable object.
+   *
+   * @param builder sendable builder
+   */
+  virtual void InitSendable(SendableBuilder& builder) = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h
new file mode 100644
index 0000000..6d2fbbe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBase.h
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+
+#include <wpi/mutex.h>
+
+#include "frc/smartdashboard/Sendable.h"
+
+namespace frc {
+
+class SendableBase : public Sendable {
+ public:
+  /**
+   * Creates an instance of the sensor base.
+   *
+   * @param addLiveWindow if true, add this Sendable to LiveWindow
+   */
+  explicit SendableBase(bool addLiveWindow = true);
+
+  ~SendableBase() override;
+
+  SendableBase(SendableBase&& rhs);
+  SendableBase& operator=(SendableBase&& rhs);
+
+  using Sendable::SetName;
+
+  std::string GetName() const final;
+  void SetName(const wpi::Twine& name) final;
+  std::string GetSubsystem() const final;
+  void SetSubsystem(const wpi::Twine& subsystem) final;
+
+ protected:
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  void AddChild(std::shared_ptr<Sendable> child);
+
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  void AddChild(void* child);
+
+  /**
+   * Sets the name of the sensor with a channel number.
+   *
+   * @param moduleType A string that defines the module name in the label for
+   *                   the value
+   * @param channel    The channel number the device is plugged into
+   */
+  void SetName(const wpi::Twine& moduleType, int channel);
+
+  /**
+   * Sets the name of the sensor with a module and channel number.
+   *
+   * @param moduleType   A string that defines the module name in the label for
+   *                     the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually
+   * PWM)
+   */
+  void SetName(const wpi::Twine& moduleType, int moduleNumber, int channel);
+
+ private:
+  mutable wpi::mutex m_mutex;
+  std::string m_name;
+  std::string m_subsystem = "Ungrouped";
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h
new file mode 100644
index 0000000..3f5f892
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilder.h
@@ -0,0 +1,222 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+
+namespace frc {
+
+class SendableBuilder {
+ public:
+  virtual ~SendableBuilder() = default;
+
+  /**
+   * Set the string representation of the named data type that will be used
+   * by the smart dashboard for this sendable.
+   *
+   * @param type    data type
+   */
+  virtual void SetSmartDashboardType(const wpi::Twine& type) = 0;
+
+  /**
+   * Set a flag indicating if this sendable should be treated as an actuator.
+   * By default this flag is false.
+   *
+   * @param value   true if actuator, false if not
+   */
+  virtual void SetActuator(bool value) = 0;
+
+  /**
+   * Set the function that should be called to set the Sendable into a safe
+   * state.  This is called when entering and exiting Live Window mode.
+   *
+   * @param func    function
+   */
+  virtual void SetSafeState(std::function<void()> func) = 0;
+
+  /**
+   * Set the function that should be called to update the network table
+   * for things other than properties.  Note this function is not passed
+   * the network table object; instead it should use the entry handles
+   * returned by GetEntry().
+   *
+   * @param func    function
+   */
+  virtual void SetUpdateTable(std::function<void()> func) = 0;
+
+  /**
+   * Add a property without getters or setters.  This can be used to get
+   * entry handles for the function called by SetUpdateTable().
+   *
+   * @param key   property name
+   * @return Network table entry
+   */
+  virtual nt::NetworkTableEntry GetEntry(const wpi::Twine& key) = 0;
+
+  /**
+   * Add a boolean property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddBooleanProperty(const wpi::Twine& key,
+                                  std::function<bool()> getter,
+                                  std::function<void(bool)> setter) = 0;
+
+  /**
+   * Add a double property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddDoubleProperty(const wpi::Twine& key,
+                                 std::function<double()> getter,
+                                 std::function<void(double)> setter) = 0;
+
+  /**
+   * Add a string property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddStringProperty(
+      const wpi::Twine& key, std::function<std::string()> getter,
+      std::function<void(wpi::StringRef)> setter) = 0;
+
+  /**
+   * Add a boolean array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddBooleanArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<int>()> getter,
+      std::function<void(wpi::ArrayRef<int>)> setter) = 0;
+
+  /**
+   * Add a double array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddDoubleArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<double>()> getter,
+      std::function<void(wpi::ArrayRef<double>)> setter) = 0;
+
+  /**
+   * Add a string array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddStringArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<std::string>()> getter,
+      std::function<void(wpi::ArrayRef<std::string>)> setter) = 0;
+
+  /**
+   * Add a raw property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddRawProperty(const wpi::Twine& key,
+                              std::function<std::string()> getter,
+                              std::function<void(wpi::StringRef)> setter) = 0;
+
+  /**
+   * Add a NetworkTableValue property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddValueProperty(
+      const wpi::Twine& key, std::function<std::shared_ptr<nt::Value>()> getter,
+      std::function<void(std::shared_ptr<nt::Value>)> setter) = 0;
+
+  /**
+   * Add a string property (SmallString form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallStringProperty(
+      const wpi::Twine& key,
+      std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+      std::function<void(wpi::StringRef)> setter) = 0;
+
+  /**
+   * Add a boolean array property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallBooleanArrayProperty(
+      const wpi::Twine& key,
+      std::function<wpi::ArrayRef<int>(wpi::SmallVectorImpl<int>& buf)> getter,
+      std::function<void(wpi::ArrayRef<int>)> setter) = 0;
+
+  /**
+   * Add a double array property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallDoubleArrayProperty(
+      const wpi::Twine& key,
+      std::function<wpi::ArrayRef<double>(wpi::SmallVectorImpl<double>& buf)>
+          getter,
+      std::function<void(wpi::ArrayRef<double>)> setter) = 0;
+
+  /**
+   * Add a string array property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallStringArrayProperty(
+      const wpi::Twine& key,
+      std::function<
+          wpi::ArrayRef<std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+          getter,
+      std::function<void(wpi::ArrayRef<std::string>)> setter) = 0;
+
+  /**
+   * Add a raw property (SmallVector form).
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  virtual void AddSmallRawProperty(
+      const wpi::Twine& key,
+      std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+      std::function<void(wpi::StringRef)> setter) = 0;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
new file mode 100644
index 0000000..e10f085
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableBuilderImpl.h
@@ -0,0 +1,200 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <networktables/NetworkTable.h>
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableValue.h>
+#include <wpi/ArrayRef.h>
+#include <wpi/SmallVector.h>
+#include <wpi/Twine.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+
+namespace frc {
+
+class SendableBuilderImpl : public SendableBuilder {
+ public:
+  SendableBuilderImpl() = default;
+  ~SendableBuilderImpl() override = default;
+
+  SendableBuilderImpl(SendableBuilderImpl&&) = default;
+  SendableBuilderImpl& operator=(SendableBuilderImpl&&) = default;
+
+  /**
+   * Set the network table.  Must be called prior to any Add* functions being
+   * called.
+   * @param table Network table
+   */
+  void SetTable(std::shared_ptr<nt::NetworkTable> table);
+
+  /**
+   * Get the network table.
+   * @return The network table
+   */
+  std::shared_ptr<nt::NetworkTable> GetTable();
+
+  /**
+   * Return whether this sendable should be treated as an actuator.
+   * @return True if actuator, false if not.
+   */
+  bool IsActuator() const;
+
+  /**
+   * Update the network table values by calling the getters for all properties.
+   */
+  void UpdateTable();
+
+  /**
+   * Hook setters for all properties.
+   */
+  void StartListeners();
+
+  /**
+   * Unhook setters for all properties.
+   */
+  void StopListeners();
+
+  /**
+   * Start LiveWindow mode by hooking the setters for all properties.  Also
+   * calls the SafeState function if one was provided.
+   */
+  void StartLiveWindowMode();
+
+  /**
+   * Stop LiveWindow mode by unhooking the setters for all properties.  Also
+   * calls the SafeState function if one was provided.
+   */
+  void StopLiveWindowMode();
+
+  void SetSmartDashboardType(const wpi::Twine& type) override;
+  void SetActuator(bool value) override;
+  void SetSafeState(std::function<void()> func) override;
+  void SetUpdateTable(std::function<void()> func) override;
+  nt::NetworkTableEntry GetEntry(const wpi::Twine& key) override;
+
+  void AddBooleanProperty(const wpi::Twine& key, std::function<bool()> getter,
+                          std::function<void(bool)> setter) override;
+
+  void AddDoubleProperty(const wpi::Twine& key, std::function<double()> getter,
+                         std::function<void(double)> setter) override;
+
+  void AddStringProperty(const wpi::Twine& key,
+                         std::function<std::string()> getter,
+                         std::function<void(wpi::StringRef)> setter) override;
+
+  void AddBooleanArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<int>()> getter,
+      std::function<void(wpi::ArrayRef<int>)> setter) override;
+
+  void AddDoubleArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<double>()> getter,
+      std::function<void(wpi::ArrayRef<double>)> setter) override;
+
+  void AddStringArrayProperty(
+      const wpi::Twine& key, std::function<std::vector<std::string>()> getter,
+      std::function<void(wpi::ArrayRef<std::string>)> setter) override;
+
+  void AddRawProperty(const wpi::Twine& key,
+                      std::function<std::string()> getter,
+                      std::function<void(wpi::StringRef)> setter) override;
+
+  void AddValueProperty(
+      const wpi::Twine& key, std::function<std::shared_ptr<nt::Value>()> getter,
+      std::function<void(std::shared_ptr<nt::Value>)> setter) override;
+
+  void AddSmallStringProperty(
+      const wpi::Twine& key,
+      std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+      std::function<void(wpi::StringRef)> setter) override;
+
+  void AddSmallBooleanArrayProperty(
+      const wpi::Twine& key,
+      std::function<wpi::ArrayRef<int>(wpi::SmallVectorImpl<int>& buf)> getter,
+      std::function<void(wpi::ArrayRef<int>)> setter) override;
+
+  void AddSmallDoubleArrayProperty(
+      const wpi::Twine& key,
+      std::function<wpi::ArrayRef<double>(wpi::SmallVectorImpl<double>& buf)>
+          getter,
+      std::function<void(wpi::ArrayRef<double>)> setter) override;
+
+  void AddSmallStringArrayProperty(
+      const wpi::Twine& key,
+      std::function<
+          wpi::ArrayRef<std::string>(wpi::SmallVectorImpl<std::string>& buf)>
+          getter,
+      std::function<void(wpi::ArrayRef<std::string>)> setter) override;
+
+  void AddSmallRawProperty(
+      const wpi::Twine& key,
+      std::function<wpi::StringRef(wpi::SmallVectorImpl<char>& buf)> getter,
+      std::function<void(wpi::StringRef)> setter) override;
+
+ private:
+  struct Property {
+    Property(nt::NetworkTable& table, const wpi::Twine& key)
+        : entry(table.GetEntry(key)) {}
+
+    Property(const Property&) = delete;
+    Property& operator=(const Property&) = delete;
+
+    Property(Property&& other) noexcept
+        : entry(other.entry),
+          listener(other.listener),
+          update(std::move(other.update)),
+          createListener(std::move(other.createListener)) {
+      other.entry = nt::NetworkTableEntry();
+      other.listener = 0;
+    }
+
+    Property& operator=(Property&& other) noexcept {
+      entry = other.entry;
+      listener = other.listener;
+      other.entry = nt::NetworkTableEntry();
+      other.listener = 0;
+      update = std::move(other.update);
+      createListener = std::move(other.createListener);
+      return *this;
+    }
+
+    ~Property() { StopListener(); }
+
+    void StartListener() {
+      if (entry && listener == 0 && createListener)
+        listener = createListener(entry);
+    }
+
+    void StopListener() {
+      if (entry && listener != 0) {
+        entry.RemoveListener(listener);
+        listener = 0;
+      }
+    }
+
+    nt::NetworkTableEntry entry;
+    NT_EntryListener listener = 0;
+    std::function<void(nt::NetworkTableEntry entry, uint64_t time)> update;
+    std::function<NT_EntryListener(nt::NetworkTableEntry entry)> createListener;
+  };
+
+  std::vector<Property> m_properties;
+  std::function<void()> m_safeState;
+  std::function<void()> m_updateTable;
+  std::shared_ptr<nt::NetworkTable> m_table;
+  nt::NetworkTableEntry m_controllableEntry;
+  bool m_actuator = false;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h
new file mode 100644
index 0000000..6cf3c47
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+
+#include <wpi/StringMap.h>
+#include <wpi/StringRef.h>
+#include <wpi/deprecated.h>
+
+#include "frc/smartdashboard/SendableBuilder.h"
+#include "frc/smartdashboard/SendableChooserBase.h"
+
+namespace frc {
+
+/**
+ * The SendableChooser class is a useful tool for presenting a selection of
+ * options to the SmartDashboard.
+ *
+ * For instance, you may wish to be able to select between multiple autonomous
+ * modes. You can do this by putting every possible Command you want to run as
+ * an autonomous into a SendableChooser and then put it into the SmartDashboard
+ * to have a list of options appear on the laptop. Once autonomous starts,
+ * simply ask the SendableChooser what the selected value is.
+ *
+ * @tparam T The type of values to be stored
+ * @see SmartDashboard
+ */
+template <class T>
+class SendableChooser : public SendableChooserBase {
+  wpi::StringMap<T> m_choices;
+
+  template <class U>
+  static U _unwrap_smart_ptr(const U& value);
+
+  template <class U>
+  static U* _unwrap_smart_ptr(const std::unique_ptr<U>& value);
+
+  template <class U>
+  static std::weak_ptr<U> _unwrap_smart_ptr(const std::shared_ptr<U>& value);
+
+ public:
+  ~SendableChooser() override = default;
+
+  void AddOption(wpi::StringRef name, T object);
+  void SetDefaultOption(wpi::StringRef name, T object);
+
+  WPI_DEPRECATED("use AddOption() instead")
+  void AddObject(wpi::StringRef name, T object) { AddOption(name, object); }
+
+  WPI_DEPRECATED("use SetDefaultOption() instead")
+  void AddDefault(wpi::StringRef name, T object) {
+    SetDefaultOption(name, object);
+  }
+
+  auto GetSelected() -> decltype(_unwrap_smart_ptr(m_choices[""]));
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
+
+#include "frc/smartdashboard/SendableChooser.inc"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc
new file mode 100644
index 0000000..42b4a65
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.inc
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <algorithm>
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include <wpi/StringRef.h>
+
+namespace frc {
+
+/**
+ * Adds the given object to the list of options.
+ *
+ * On the SmartDashboard on the desktop, the object will appear as the given
+ * name.
+ *
+ * @param name   the name of the option
+ * @param object the option
+ */
+template <class T>
+void SendableChooser<T>::AddOption(wpi::StringRef name, T object) {
+  m_choices[name] = std::move(object);
+}
+
+/**
+ * Add the given object to the list of options and marks it as the default.
+ *
+ * Functionally, this is very close to AddOption() except that it will use this
+ * as the default option if none other is explicitly selected.
+ *
+ * @param name   the name of the option
+ * @param object the option
+ */
+template <class T>
+void SendableChooser<T>::SetDefaultOption(wpi::StringRef name, T object) {
+  m_defaultChoice = name;
+  AddOption(name, std::move(object));
+}
+
+/**
+ * Returns a copy of the selected option (a raw pointer U* if T =
+ * std::unique_ptr<U> or a std::weak_ptr<U> if T = std::shared_ptr<U>).
+ *
+ * If there is none selected, it will return the default. If there is none
+ * selected and no default, then it will return a value-initialized instance.
+ * For integer types, this is 0. For container types like std::string, this is
+ * an empty string.
+ *
+ * @return The option selected
+ */
+template <class T>
+auto SendableChooser<T>::GetSelected()
+    -> decltype(_unwrap_smart_ptr(m_choices[""])) {
+  std::string selected = m_defaultChoice;
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    if (m_haveSelected) selected = m_selected;
+  }
+  if (selected.empty()) {
+    return decltype(_unwrap_smart_ptr(m_choices[""])){};
+  } else {
+    return _unwrap_smart_ptr(m_choices[selected]);
+  }
+}
+
+template <class T>
+void SendableChooser<T>::InitSendable(SendableBuilder& builder) {
+  builder.SetSmartDashboardType("String Chooser");
+  builder.GetEntry(kInstance).SetDouble(m_instance);
+  builder.AddStringArrayProperty(kOptions,
+                                 [=]() {
+                                   std::vector<std::string> keys;
+                                   for (const auto& choice : m_choices) {
+                                     keys.push_back(choice.first());
+                                   }
+
+                                   // Unlike std::map, wpi::StringMap elements
+                                   // are not sorted
+                                   std::sort(keys.begin(), keys.end());
+
+                                   return keys;
+                                 },
+                                 nullptr);
+  builder.AddSmallStringProperty(
+      kDefault,
+      [=](wpi::SmallVectorImpl<char>&) -> wpi::StringRef {
+        return m_defaultChoice;
+      },
+      nullptr);
+  builder.AddSmallStringProperty(
+      kActive,
+      [=](wpi::SmallVectorImpl<char>& buf) -> wpi::StringRef {
+        std::lock_guard<wpi::mutex> lock(m_mutex);
+        if (m_haveSelected) {
+          buf.assign(m_selected.begin(), m_selected.end());
+          return wpi::StringRef(buf.data(), buf.size());
+        } else {
+          return m_defaultChoice;
+        }
+      },
+      nullptr);
+  {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_activeEntries.emplace_back(builder.GetEntry(kActive));
+  }
+  builder.AddStringProperty(kSelected, nullptr, [=](wpi::StringRef val) {
+    std::lock_guard<wpi::mutex> lock(m_mutex);
+    m_haveSelected = true;
+    m_selected = val;
+    for (auto& entry : m_activeEntries) entry.SetString(val);
+  });
+}
+
+template <class T>
+template <class U>
+U SendableChooser<T>::_unwrap_smart_ptr(const U& value) {
+  return value;
+}
+
+template <class T>
+template <class U>
+U* SendableChooser<T>::_unwrap_smart_ptr(const std::unique_ptr<U>& value) {
+  return value.get();
+}
+
+template <class T>
+template <class U>
+std::weak_ptr<U> SendableChooser<T>::_unwrap_smart_ptr(
+    const std::shared_ptr<U>& value) {
+  return value;
+}
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h
new file mode 100644
index 0000000..ae7908e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooserBase.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <string>
+
+#include <networktables/NetworkTableEntry.h>
+#include <wpi/SmallVector.h>
+#include <wpi/mutex.h>
+
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+/**
+ * This class is a non-template base class for SendableChooser.
+ *
+ * It contains static, non-templated variables to avoid their duplication in the
+ * template class.
+ */
+class SendableChooserBase : public SendableBase {
+ public:
+  SendableChooserBase();
+  ~SendableChooserBase() override = default;
+
+  SendableChooserBase(SendableChooserBase&&) = default;
+  SendableChooserBase& operator=(SendableChooserBase&&) = default;
+
+ protected:
+  static constexpr const char* kDefault = "default";
+  static constexpr const char* kOptions = "options";
+  static constexpr const char* kSelected = "selected";
+  static constexpr const char* kActive = "active";
+  static constexpr const char* kInstance = ".instance";
+
+  std::string m_defaultChoice;
+  std::string m_selected;
+  bool m_haveSelected = false;
+  wpi::SmallVector<nt::NetworkTableEntry, 2> m_activeEntries;
+  wpi::mutex m_mutex;
+  int m_instance;
+  static std::atomic_int s_instances;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h
new file mode 100644
index 0000000..903fb8b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/frc/smartdashboard/SmartDashboard.h
@@ -0,0 +1,413 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2011-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <memory>
+#include <string>
+#include <vector>
+
+#include <networktables/NetworkTableValue.h>
+
+#include "frc/ErrorBase.h"
+#include "frc/smartdashboard/SendableBase.h"
+
+namespace frc {
+
+class Sendable;
+
+class SmartDashboard : public ErrorBase, public SendableBase {
+ public:
+  static void init();
+
+  /**
+   * Determines whether the given key is in this table.
+   *
+   * @param key the key to search for
+   * @return true if the table as a value assigned to the given key
+   */
+  static bool ContainsKey(wpi::StringRef key);
+
+  /**
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return keys currently in the table
+   */
+  static std::vector<std::string> GetKeys(int types = 0);
+
+  /**
+   * Makes a key's value persistent through program restarts.
+   *
+   * @param key the key to make persistent
+   */
+  static void SetPersistent(wpi::StringRef key);
+
+  /**
+   * Stop making a key's value persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  static void ClearPersistent(wpi::StringRef key);
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  static bool IsPersistent(wpi::StringRef key);
+
+  /**
+   * Sets flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to set (bitmask)
+   */
+  static void SetFlags(wpi::StringRef key, unsigned int flags);
+
+  /**
+   * Clears flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to clear (bitmask)
+   */
+  static void ClearFlags(wpi::StringRef key, unsigned int flags);
+
+  /**
+   * Returns the flags for the specified key.
+   *
+   * @param key the key name
+   * @return the flags, or 0 if the key is not defined
+   */
+  static unsigned int GetFlags(wpi::StringRef key);
+
+  /**
+   * Deletes the specified key in this table.
+   *
+   * @param key the key name
+   */
+  static void Delete(wpi::StringRef key);
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   */
+  static void PutData(wpi::StringRef key, Sendable* data);
+
+  /**
+   * Maps the specified key (where the key is the name of the Sendable)
+   * to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * @param value the value
+   */
+  static void PutData(Sendable* value);
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * @param keyName the key
+   * @return the value
+   */
+  static Sendable* GetData(wpi::StringRef keyName);
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   * @return        False if the table key already exists with a different type
+   */
+  static bool PutBoolean(wpi::StringRef keyName, bool value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultBoolean(wpi::StringRef key, bool defaultValue);
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * If the key is not found, returns the default value.
+   *
+   * @param keyName the key
+   * @return the value
+   */
+  static bool GetBoolean(wpi::StringRef keyName, bool defaultValue);
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   * @return        False if the table key already exists with a different type
+   */
+  static bool PutNumber(wpi::StringRef keyName, double value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key          The key.
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultNumber(wpi::StringRef key, double defaultValue);
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * If the key is not found, returns the default value.
+   *
+   * @param keyName the key
+   * @return the value
+   */
+  static double GetNumber(wpi::StringRef keyName, double defaultValue);
+
+  /**
+   * Maps the specified key to the specified value in this table.
+   *
+   * The value can be retrieved by calling the get method with a key that is
+   * equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   * @return        False if the table key already exists with a different type
+   */
+  static bool PutString(wpi::StringRef keyName, wpi::StringRef value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultString(wpi::StringRef key, wpi::StringRef defaultValue);
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * If the key is not found, returns the default value.
+   *
+   * @param keyName the key
+   * @return the value
+   */
+  static std::string GetString(wpi::StringRef keyName,
+                               wpi::StringRef defaultValue);
+
+  /**
+   * Put a boolean array in the table.
+   *
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   *
+   * @note The array must be of int's rather than of bool's because
+   *       std::vector<bool> is special-cased in C++. 0 is false, any
+   *       non-zero value is true.
+   */
+  static bool PutBooleanArray(wpi::StringRef key, wpi::ArrayRef<int> value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue the default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultBooleanArray(wpi::StringRef key,
+                                     wpi::ArrayRef<int> defaultValue);
+
+  /**
+   * Returns the boolean array the key maps to.
+   *
+   * If the key does not exist or is of different type, it will return the
+   * default value.
+   *
+   * @param key          The key to look up.
+   * @param defaultValue The value to be returned if no value is found.
+   * @return the value associated with the given key or the given default value
+   *         if there is no value associated with the key
+   *
+   * @note This makes a copy of the array. If the overhead of this is a concern,
+   *       use GetValue() instead.
+   *
+   * @note The returned array is std::vector<int> instead of std::vector<bool>
+   *       because std::vector<bool> is special-cased in C++. 0 is false, any
+   *       non-zero value is true.
+   */
+  static std::vector<int> GetBooleanArray(wpi::StringRef key,
+                                          wpi::ArrayRef<int> defaultValue);
+
+  /**
+   * Put a number array in the table.
+   *
+   * @param key   The key to be assigned to.
+   * @param value The value that will be assigned.
+   * @return False if the table key already exists with a different type
+   */
+  static bool PutNumberArray(wpi::StringRef key, wpi::ArrayRef<double> value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key          The key.
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultNumberArray(wpi::StringRef key,
+                                    wpi::ArrayRef<double> defaultValue);
+
+  /**
+   * Returns the number array the key maps to.
+   *
+   * If the key does not exist or is of different type, it will return the
+   * default value.
+   *
+   * @param key The key to look up.
+   * @param defaultValue The value to be returned if no value is found.
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array. If the overhead of this is a concern,
+   *       use GetValue() instead.
+   */
+  static std::vector<double> GetNumberArray(wpi::StringRef key,
+                                            wpi::ArrayRef<double> defaultValue);
+
+  /**
+   * Put a string array in the table.
+   *
+   * @param key   The key to be assigned to.
+   * @param value The value that will be assigned.
+   * @return False if the table key already exists with a different type
+   */
+  static bool PutStringArray(wpi::StringRef key,
+                             wpi::ArrayRef<std::string> value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key          The key.
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultStringArray(wpi::StringRef key,
+                                    wpi::ArrayRef<std::string> defaultValue);
+
+  /**
+   * Returns the string array the key maps to.
+   *
+   * If the key does not exist or is of different type, it will return the
+   * default value.
+   *
+   * @param key          The key to look up.
+   * @param defaultValue The value to be returned if no value is found.
+   * @return the value associated with the given key or the given default value
+   * if there is no value associated with the key
+   *
+   * @note This makes a copy of the array. If the overhead of this is a concern,
+   *       use GetValue() instead.
+   */
+  static std::vector<std::string> GetStringArray(
+      wpi::StringRef key, wpi::ArrayRef<std::string> defaultValue);
+
+  /**
+   * Put a raw value (byte array) in the table.
+   *
+   * @param key   The key to be assigned to.
+   * @param value The value that will be assigned.
+   * @return False if the table key already exists with a different type
+   */
+  static bool PutRaw(wpi::StringRef key, wpi::StringRef value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key          The key.
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultRaw(wpi::StringRef key, wpi::StringRef defaultValue);
+
+  /**
+   * Returns the raw value (byte array) the key maps to.
+   *
+   * If the key does not exist or is of different type, it will return the
+   * default value.
+   *
+   * @param key          The key to look up.
+   * @param defaultValue The value to be returned if no value is found.
+   * @return the value associated with the given key or the given default value
+   *         if there is no value associated with the key
+   *
+   * @note This makes a copy of the raw contents. If the overhead of this is a
+   *       concern, use GetValue() instead.
+   */
+  static std::string GetRaw(wpi::StringRef key, wpi::StringRef defaultValue);
+
+  /**
+   * Maps the specified key to the specified complex value (such as an array) in
+   * this table.
+   *
+   * The value can be retrieved by calling the RetrieveValue method with a key
+   * that is equal to the original key.
+   *
+   * @param keyName the key
+   * @param value   the value
+   * @return        False if the table key already exists with a different type
+   */
+  static bool PutValue(wpi::StringRef keyName,
+                       std::shared_ptr<nt::Value> value);
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   *
+   * @param key the key
+   * @param defaultValue The default value to set if key doesn't exist.
+   * @returns False if the table key exists with a different type
+   */
+  static bool SetDefaultValue(wpi::StringRef key,
+                              std::shared_ptr<nt::Value> defaultValue);
+
+  /**
+   * Retrieves the complex value (such as an array) in this table into the
+   * complex data object.
+   *
+   * @param keyName the key
+   * @param value   the object to retrieve the value into
+   */
+  static std::shared_ptr<nt::Value> GetValue(wpi::StringRef keyName);
+
+  /**
+   * Puts all sendable data to the dashboard.
+   */
+  static void UpdateValues();
+
+ private:
+  virtual ~SmartDashboard() = default;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Accelerometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Accelerometer.h
new file mode 100644
index 0000000..74b3c38
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Accelerometer.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: interfaces/Accelerometer.h is deprecated; include frc/interfaces/Accelerometer.h instead"
+#else
+#warning "interfaces/Accelerometer.h is deprecated; include frc/interfaces/Accelerometer.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/interfaces/Accelerometer.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Gyro.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Gyro.h
new file mode 100644
index 0000000..f88ec5d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Gyro.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: interfaces/Gyro.h is deprecated; include frc/interfaces/Gyro.h instead"
+#else
+#warning "interfaces/Gyro.h is deprecated; include frc/interfaces/Gyro.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/interfaces/Gyro.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Potentiometer.h b/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Potentiometer.h
new file mode 100644
index 0000000..d73d3db
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/main/native/include/interfaces/Potentiometer.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: interfaces/Potentiometer.h is deprecated; include frc/interfaces/Potentiometer.h instead"
+#else
+#warning "interfaces/Potentiometer.h is deprecated; include frc/interfaces/Potentiometer.h instead"
+#endif
+
+// clang-format on
+
+#include "frc/interfaces/Potentiometer.h"
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/c/test.c b/third_party/allwpilib_2019/wpilibc/src/test/native/c/test.c
new file mode 100644
index 0000000..105e289
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/c/test.c
@@ -0,0 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <cscore.h>
+#include <hal/HAL.h>
+#include <ntcore.h>
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/CircularBufferTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/CircularBufferTest.cpp
new file mode 100644
index 0000000..ada4f9a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/CircularBufferTest.cpp
@@ -0,0 +1,211 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/circular_buffer.h"  // NOLINT(build/include_order)
+
+#include <array>
+
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const std::array<double, 10> values = {
+    {751.848, 766.366, 342.657, 234.252, 716.126, 132.344, 445.697, 22.727,
+     421.125, 799.913}};
+
+static const std::array<double, 8> pushFrontOut = {
+    {799.913, 421.125, 22.727, 445.697, 132.344, 716.126, 234.252, 342.657}};
+
+static const std::array<double, 8> pushBackOut = {
+    {342.657, 234.252, 716.126, 132.344, 445.697, 22.727, 421.125, 799.913}};
+
+TEST(CircularBufferTest, PushFrontTest) {
+  circular_buffer<double> queue(8);
+
+  for (auto& value : values) {
+    queue.push_front(value);
+  }
+
+  for (size_t i = 0; i < pushFrontOut.size(); i++) {
+    EXPECT_EQ(pushFrontOut[i], queue[i]);
+  }
+}
+
+TEST(CircularBufferTest, PushBackTest) {
+  circular_buffer<double> queue(8);
+
+  for (auto& value : values) {
+    queue.push_back(value);
+  }
+
+  for (size_t i = 0; i < pushBackOut.size(); i++) {
+    EXPECT_EQ(pushBackOut[i], queue[i]);
+  }
+}
+
+TEST(CircularBufferTest, PushPopTest) {
+  circular_buffer<double> queue(3);
+
+  // Insert three elements into the buffer
+  queue.push_back(1.0);
+  queue.push_back(2.0);
+  queue.push_back(3.0);
+
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+  EXPECT_EQ(3.0, queue[2]);
+
+  /*
+   * The buffer is full now, so pushing subsequent elements will overwrite the
+   * front-most elements.
+   */
+
+  queue.push_back(4.0);  // Overwrite 1 with 4
+
+  // The buffer now contains 2, 3 and 4
+  EXPECT_EQ(2.0, queue[0]);
+  EXPECT_EQ(3.0, queue[1]);
+  EXPECT_EQ(4.0, queue[2]);
+
+  queue.push_back(5.0);  // Overwrite 2 with 5
+
+  // The buffer now contains 3, 4 and 5
+  EXPECT_EQ(3.0, queue[0]);
+  EXPECT_EQ(4.0, queue[1]);
+  EXPECT_EQ(5.0, queue[2]);
+
+  EXPECT_EQ(5.0, queue.pop_back());  // 5 is removed
+
+  // The buffer now contains 3 and 4
+  EXPECT_EQ(3.0, queue[0]);
+  EXPECT_EQ(4.0, queue[1]);
+
+  EXPECT_EQ(3.0, queue.pop_front());  // 3 is removed
+
+  // Leaving only one element with value == 4
+  EXPECT_EQ(4.0, queue[0]);
+}
+
+TEST(CircularBufferTest, ResetTest) {
+  circular_buffer<double> queue(5);
+
+  for (size_t i = 1; i < 6; i++) {
+    queue.push_back(i);
+  }
+
+  queue.reset();
+
+  for (size_t i = 0; i < 5; i++) {
+    EXPECT_EQ(0.0, queue[i]);
+  }
+}
+
+TEST(CircularBufferTest, ResizeTest) {
+  circular_buffer<double> queue(5);
+
+  /* Buffer contains {1, 2, 3, _, _}
+   *                  ^ front
+   */
+  queue.push_back(1.0);
+  queue.push_back(2.0);
+  queue.push_back(3.0);
+
+  queue.resize(2);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.resize(5);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.reset();
+
+  /* Buffer contains {_, 1, 2, 3, _}
+   *                     ^ front
+   */
+  queue.push_back(0.0);
+  queue.push_back(1.0);
+  queue.push_back(2.0);
+  queue.push_back(3.0);
+  queue.pop_front();
+
+  queue.resize(2);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.resize(5);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.reset();
+
+  /* Buffer contains {_, _, 1, 2, 3}
+   *                        ^ front
+   */
+  queue.push_back(0.0);
+  queue.push_back(0.0);
+  queue.push_back(1.0);
+  queue.push_back(2.0);
+  queue.push_back(3.0);
+  queue.pop_front();
+  queue.pop_front();
+
+  queue.resize(2);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.resize(5);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.reset();
+
+  /* Buffer contains {3, _, _, 1, 2}
+   *                           ^ front
+   */
+  queue.push_back(3.0);
+  queue.push_front(2.0);
+  queue.push_front(1.0);
+
+  queue.resize(2);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.resize(5);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.reset();
+
+  /* Buffer contains {2, 3, _, _, 1}
+   *                              ^ front
+   */
+  queue.push_back(2.0);
+  queue.push_back(3.0);
+  queue.push_front(1.0);
+
+  queue.resize(2);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  queue.resize(5);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+
+  // Test push_back() after resize
+  queue.push_back(3.0);
+  EXPECT_EQ(1.0, queue[0]);
+  EXPECT_EQ(2.0, queue[1]);
+  EXPECT_EQ(3.0, queue[2]);
+
+  // Test push_front() after resize
+  queue.push_front(4.0);
+  EXPECT_EQ(4.0, queue[0]);
+  EXPECT_EQ(1.0, queue[1]);
+  EXPECT_EQ(2.0, queue[2]);
+  EXPECT_EQ(3.0, queue[3]);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/FilterNoiseTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/FilterNoiseTest.cpp
new file mode 100644
index 0000000..ea14f32
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/FilterNoiseTest.cpp
@@ -0,0 +1,137 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/filters/LinearDigitalFilter.h"  // NOLINT(build/include_order)
+
+#include <cmath>
+#include <functional>
+#include <memory>
+#include <random>
+#include <thread>
+
+#include "frc/Base.h"
+#include "gtest/gtest.h"
+
+/* Filter constants */
+static constexpr double kFilterStep = 0.005;
+static constexpr double kFilterTime = 2.0;
+static constexpr double kSinglePoleIIRTimeConstant = 0.015915;
+static constexpr double kSinglePoleIIRExpectedOutput = -3.2172003;
+static constexpr double kHighPassTimeConstant = 0.006631;
+static constexpr double kHighPassExpectedOutput = 10.074717;
+static constexpr int32_t kMovAvgTaps = 6;
+static constexpr double kMovAvgExpectedOutput = -10.191644;
+static constexpr double kPi = 3.14159265358979323846;
+
+using namespace frc;
+
+enum FilterNoiseTestType { TEST_SINGLE_POLE_IIR, TEST_MOVAVG };
+
+std::ostream& operator<<(std::ostream& os, const FilterNoiseTestType& type) {
+  switch (type) {
+    case TEST_SINGLE_POLE_IIR:
+      os << "LinearDigitalFilter SinglePoleIIR";
+      break;
+    case TEST_MOVAVG:
+      os << "LinearDigitalFilter MovingAverage";
+      break;
+  }
+
+  return os;
+}
+
+constexpr double kStdDev = 10.0;
+
+/**
+ * Adds Gaussian white noise to a function returning data. The noise will have
+ * the standard deviation provided in the constructor.
+ */
+class NoiseGenerator : public PIDSource {
+ public:
+  NoiseGenerator(double (*dataFunc)(double), double stdDev)
+      : m_distr(0.0, stdDev) {
+    m_dataFunc = dataFunc;
+  }
+
+  void SetPIDSourceType(PIDSourceType pidSource) override {}
+
+  double Get() { return m_dataFunc(m_count) + m_noise; }
+
+  double PIDGet() override {
+    m_noise = m_distr(m_gen);
+    m_count += kFilterStep;
+    return m_dataFunc(m_count) + m_noise;
+  }
+
+  void Reset() { m_count = -kFilterStep; }
+
+ private:
+  std::function<double(double)> m_dataFunc;
+  double m_noise = 0.0;
+
+  // Make sure first call to PIDGet() uses m_count == 0
+  double m_count = -kFilterStep;
+
+  std::random_device m_rd;
+  std::mt19937 m_gen{m_rd()};
+  std::normal_distribution<double> m_distr;
+};
+
+/**
+ * A fixture that includes a noise generator wrapped in a filter
+ */
+class FilterNoiseTest : public testing::TestWithParam<FilterNoiseTestType> {
+ protected:
+  std::unique_ptr<PIDSource> m_filter;
+  std::shared_ptr<NoiseGenerator> m_noise;
+
+  static double GetData(double t) { return 100.0 * std::sin(2.0 * kPi * t); }
+
+  void SetUp() override {
+    m_noise = std::make_shared<NoiseGenerator>(GetData, kStdDev);
+
+    switch (GetParam()) {
+      case TEST_SINGLE_POLE_IIR: {
+        m_filter = std::make_unique<LinearDigitalFilter>(
+            LinearDigitalFilter::SinglePoleIIR(
+                m_noise, kSinglePoleIIRTimeConstant, kFilterStep));
+        break;
+      }
+
+      case TEST_MOVAVG: {
+        m_filter = std::make_unique<LinearDigitalFilter>(
+            LinearDigitalFilter::MovingAverage(m_noise, kMovAvgTaps));
+        break;
+      }
+    }
+  }
+};
+
+/**
+ * Test if the filter reduces the noise produced by a signal generator
+ */
+TEST_P(FilterNoiseTest, NoiseReduce) {
+  double theoryData = 0.0;
+  double noiseGenError = 0.0;
+  double filterError = 0.0;
+
+  m_noise->Reset();
+  for (double t = 0; t < kFilterTime; t += kFilterStep) {
+    theoryData = GetData(t);
+    filterError += std::abs(m_filter->PIDGet() - theoryData);
+    noiseGenError += std::abs(m_noise->Get() - theoryData);
+  }
+
+  RecordProperty("FilterError", filterError);
+
+  // The filter should have produced values closer to the theory
+  EXPECT_GT(noiseGenError, filterError)
+      << "Filter should have reduced noise accumulation but failed";
+}
+
+INSTANTIATE_TEST_CASE_P(Test, FilterNoiseTest,
+                        testing::Values(TEST_SINGLE_POLE_IIR, TEST_MOVAVG), );
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/FilterOutputTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/FilterOutputTest.cpp
new file mode 100644
index 0000000..ec71760
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/FilterOutputTest.cpp
@@ -0,0 +1,157 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/filters/LinearDigitalFilter.h"  // NOLINT(build/include_order)
+
+#include <cmath>
+#include <functional>
+#include <memory>
+#include <random>
+#include <thread>
+
+#include "frc/Base.h"
+#include "gtest/gtest.h"
+
+/* Filter constants */
+static constexpr double kFilterStep = 0.005;
+static constexpr double kFilterTime = 2.0;
+static constexpr double kSinglePoleIIRTimeConstant = 0.015915;
+static constexpr double kSinglePoleIIRExpectedOutput = -3.2172003;
+static constexpr double kHighPassTimeConstant = 0.006631;
+static constexpr double kHighPassExpectedOutput = 10.074717;
+static constexpr int32_t kMovAvgTaps = 6;
+static constexpr double kMovAvgExpectedOutput = -10.191644;
+static constexpr double kPi = 3.14159265358979323846;
+
+using namespace frc;
+
+enum FilterOutputTestType {
+  TEST_SINGLE_POLE_IIR,
+  TEST_HIGH_PASS,
+  TEST_MOVAVG,
+  TEST_PULSE
+};
+
+std::ostream& operator<<(std::ostream& os, const FilterOutputTestType& type) {
+  switch (type) {
+    case TEST_SINGLE_POLE_IIR:
+      os << "LinearDigitalFilter SinglePoleIIR";
+      break;
+    case TEST_HIGH_PASS:
+      os << "LinearDigitalFilter HighPass";
+      break;
+    case TEST_MOVAVG:
+      os << "LinearDigitalFilter MovingAverage";
+      break;
+    case TEST_PULSE:
+      os << "LinearDigitalFilter Pulse";
+      break;
+  }
+
+  return os;
+}
+
+class DataWrapper : public PIDSource {
+ public:
+  explicit DataWrapper(double (*dataFunc)(double)) { m_dataFunc = dataFunc; }
+
+  virtual void SetPIDSourceType(PIDSourceType pidSource) {}
+
+  virtual double PIDGet() {
+    m_count += kFilterStep;
+    return m_dataFunc(m_count);
+  }
+
+  void Reset() { m_count = -kFilterStep; }
+
+ private:
+  std::function<double(double)> m_dataFunc;
+
+  // Make sure first call to PIDGet() uses m_count == 0
+  double m_count = -kFilterStep;
+};
+
+/**
+ * A fixture that includes a consistent data source wrapped in a filter
+ */
+class FilterOutputTest : public testing::TestWithParam<FilterOutputTestType> {
+ protected:
+  std::unique_ptr<PIDSource> m_filter;
+  std::shared_ptr<DataWrapper> m_data;
+  double m_expectedOutput = 0.0;
+
+  static double GetData(double t) {
+    return 100.0 * std::sin(2.0 * kPi * t) + 20.0 * std::cos(50.0 * kPi * t);
+  }
+
+  static double GetPulseData(double t) {
+    if (std::abs(t - 1.0) < 0.001) {
+      return 1.0;
+    } else {
+      return 0.0;
+    }
+  }
+
+  void SetUp() override {
+    switch (GetParam()) {
+      case TEST_SINGLE_POLE_IIR: {
+        m_data = std::make_shared<DataWrapper>(GetData);
+        m_filter = std::make_unique<LinearDigitalFilter>(
+            LinearDigitalFilter::SinglePoleIIR(
+                m_data, kSinglePoleIIRTimeConstant, kFilterStep));
+        m_expectedOutput = kSinglePoleIIRExpectedOutput;
+        break;
+      }
+
+      case TEST_HIGH_PASS: {
+        m_data = std::make_shared<DataWrapper>(GetData);
+        m_filter =
+            std::make_unique<LinearDigitalFilter>(LinearDigitalFilter::HighPass(
+                m_data, kHighPassTimeConstant, kFilterStep));
+        m_expectedOutput = kHighPassExpectedOutput;
+        break;
+      }
+
+      case TEST_MOVAVG: {
+        m_data = std::make_shared<DataWrapper>(GetData);
+        m_filter = std::make_unique<LinearDigitalFilter>(
+            LinearDigitalFilter::MovingAverage(m_data, kMovAvgTaps));
+        m_expectedOutput = kMovAvgExpectedOutput;
+        break;
+      }
+
+      case TEST_PULSE: {
+        m_data = std::make_shared<DataWrapper>(GetPulseData);
+        m_filter = std::make_unique<LinearDigitalFilter>(
+            LinearDigitalFilter::MovingAverage(m_data, kMovAvgTaps));
+        m_expectedOutput = 0.0;
+        break;
+      }
+    }
+  }
+};
+
+/**
+ * Test if the linear digital filters produce consistent output
+ */
+TEST_P(FilterOutputTest, FilterOutput) {
+  m_data->Reset();
+
+  double filterOutput = 0.0;
+  for (double t = 0.0; t < kFilterTime; t += kFilterStep) {
+    filterOutput = m_filter->PIDGet();
+  }
+
+  RecordProperty("FilterOutput", filterOutput);
+
+  EXPECT_FLOAT_EQ(m_expectedOutput, filterOutput)
+      << "Filter output didn't match expected value";
+}
+
+INSTANTIATE_TEST_CASE_P(Test, FilterOutputTest,
+                        testing::Values(TEST_SINGLE_POLE_IIR, TEST_HIGH_PASS,
+                                        TEST_MOVAVG, TEST_PULSE), );
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/MockSpeedController.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/MockSpeedController.cpp
new file mode 100644
index 0000000..875fec1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/MockSpeedController.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "MockSpeedController.h"
+
+using namespace frc;
+
+void MockSpeedController::Set(double speed) {
+  m_speed = m_isInverted ? -speed : speed;
+}
+
+double MockSpeedController::Get() const { return m_speed; }
+
+void MockSpeedController::SetInverted(bool isInverted) {
+  m_isInverted = isInverted;
+}
+
+bool MockSpeedController::GetInverted() const { return m_isInverted; }
+
+void MockSpeedController::Disable() { m_speed = 0; }
+
+void MockSpeedController::StopMotor() { Disable(); }
+
+void MockSpeedController::PIDWrite(double output) { Set(output); }
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/RobotDriveTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/RobotDriveTest.cpp
new file mode 100644
index 0000000..464a707
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/RobotDriveTest.cpp
@@ -0,0 +1,190 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "MockSpeedController.h"
+#include "frc/RobotDrive.h"
+#include "frc/drive/DifferentialDrive.h"
+#include "frc/drive/MecanumDrive.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class RobotDriveTest : public testing::Test {
+ protected:
+  MockSpeedController m_rdFrontLeft;
+  MockSpeedController m_rdRearLeft;
+  MockSpeedController m_rdFrontRight;
+  MockSpeedController m_rdRearRight;
+  MockSpeedController m_frontLeft;
+  MockSpeedController m_rearLeft;
+  MockSpeedController m_frontRight;
+  MockSpeedController m_rearRight;
+  frc::RobotDrive m_robotDrive{m_rdFrontLeft, m_rdRearLeft, m_rdFrontRight,
+                               m_rdRearRight};
+  frc::DifferentialDrive m_differentialDrive{m_frontLeft, m_frontRight};
+  frc::MecanumDrive m_mecanumDrive{m_frontLeft, m_rearLeft, m_frontRight,
+                                   m_rearRight};
+
+  double m_testJoystickValues[9] = {-1.0, -0.9, -0.5, -0.01, 0.0,
+                                    0.01, 0.5,  0.9,  1.0};
+  double m_testGyroValues[19] = {0,    45,   90,   135,  180, 225,  270,
+                                 305,  360,  540,  -45,  -90, -135, -180,
+                                 -225, -270, -305, -360, -540};
+};
+
+TEST_F(RobotDriveTest, TankDrive) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  double leftJoystick, rightJoystick;
+  m_differentialDrive.SetDeadband(0.0);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      leftJoystick = m_testJoystickValues[i];
+      rightJoystick = m_testJoystickValues[j];
+      m_robotDrive.TankDrive(leftJoystick, rightJoystick, false);
+      m_differentialDrive.TankDrive(leftJoystick, rightJoystick, false);
+      ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01);
+      ASSERT_NEAR(m_rdFrontRight.Get(), m_frontRight.Get(), 0.01);
+    }
+  }
+}
+
+TEST_F(RobotDriveTest, TankDriveSquared) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  double leftJoystick, rightJoystick;
+  m_differentialDrive.SetDeadband(0.0);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      leftJoystick = m_testJoystickValues[i];
+      rightJoystick = m_testJoystickValues[j];
+      m_robotDrive.TankDrive(leftJoystick, rightJoystick, true);
+      m_differentialDrive.TankDrive(leftJoystick, rightJoystick, true);
+      ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01);
+      ASSERT_NEAR(m_rdFrontRight.Get(), m_frontRight.Get(), 0.01);
+    }
+  }
+}
+
+TEST_F(RobotDriveTest, ArcadeDriveSquared) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  double moveJoystick, rotateJoystick;
+  m_differentialDrive.SetDeadband(0.0);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      moveJoystick = m_testJoystickValues[i];
+      rotateJoystick = m_testJoystickValues[j];
+      m_robotDrive.ArcadeDrive(moveJoystick, rotateJoystick, true);
+      m_differentialDrive.ArcadeDrive(moveJoystick, -rotateJoystick, true);
+      ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01);
+      ASSERT_NEAR(m_rdFrontRight.Get(), m_frontRight.Get(), 0.01);
+    }
+  }
+}
+
+TEST_F(RobotDriveTest, ArcadeDrive) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  double moveJoystick, rotateJoystick;
+  m_differentialDrive.SetDeadband(0.0);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      moveJoystick = m_testJoystickValues[i];
+      rotateJoystick = m_testJoystickValues[j];
+      m_robotDrive.ArcadeDrive(moveJoystick, rotateJoystick, false);
+      m_differentialDrive.ArcadeDrive(moveJoystick, -rotateJoystick, false);
+      ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01);
+      ASSERT_NEAR(m_rdFrontRight.Get(), m_frontRight.Get(), 0.01);
+    }
+  }
+}
+
+TEST_F(RobotDriveTest, MecanumCartesian) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  int gyroSize = sizeof(m_testGyroValues) / sizeof(double);
+  double xJoystick, yJoystick, rotateJoystick, gyroValue;
+  m_mecanumDrive.SetDeadband(0.0);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < joystickSize; j++) {
+      for (int k = 0; k < joystickSize; k++) {
+        for (int l = 0; l < gyroSize; l++) {
+          xJoystick = m_testJoystickValues[i];
+          yJoystick = m_testJoystickValues[j];
+          rotateJoystick = m_testJoystickValues[k];
+          gyroValue = m_testGyroValues[l];
+          m_robotDrive.MecanumDrive_Cartesian(xJoystick, yJoystick,
+                                              rotateJoystick, gyroValue);
+          m_mecanumDrive.DriveCartesian(xJoystick, -yJoystick, rotateJoystick,
+                                        -gyroValue);
+          ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01)
+              << "X: " << xJoystick << " Y: " << yJoystick
+              << " Rotate: " << rotateJoystick << " Gyro: " << gyroValue;
+          ASSERT_NEAR(m_rdFrontRight.Get(), -m_frontRight.Get(), 0.01)
+              << "X: " << xJoystick << " Y: " << yJoystick
+              << " Rotate: " << rotateJoystick << " Gyro: " << gyroValue;
+          ASSERT_NEAR(m_rdRearLeft.Get(), m_rearLeft.Get(), 0.01)
+              << "X: " << xJoystick << " Y: " << yJoystick
+              << " Rotate: " << rotateJoystick << " Gyro: " << gyroValue;
+          ASSERT_NEAR(m_rdRearRight.Get(), -m_rearRight.Get(), 0.01)
+              << "X: " << xJoystick << " Y: " << yJoystick
+              << " Rotate: " << rotateJoystick << " Gyro: " << gyroValue;
+        }
+      }
+    }
+  }
+}
+
+TEST_F(RobotDriveTest, MecanumPolar) {
+  int joystickSize = sizeof(m_testJoystickValues) / sizeof(double);
+  int gyroSize = sizeof(m_testGyroValues) / sizeof(double);
+  double magnitudeJoystick, directionJoystick, rotateJoystick;
+  m_mecanumDrive.SetDeadband(0.0);
+  m_mecanumDrive.SetSafetyEnabled(false);
+  m_differentialDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetSafetyEnabled(false);
+  for (int i = 0; i < joystickSize; i++) {
+    for (int j = 0; j < gyroSize; j++) {
+      for (int k = 0; k < joystickSize; k++) {
+        magnitudeJoystick = m_testJoystickValues[i];
+        directionJoystick = m_testGyroValues[j];
+        rotateJoystick = m_testJoystickValues[k];
+        m_robotDrive.MecanumDrive_Polar(magnitudeJoystick, directionJoystick,
+                                        rotateJoystick);
+        m_mecanumDrive.DrivePolar(magnitudeJoystick, directionJoystick,
+                                  rotateJoystick);
+        ASSERT_NEAR(m_rdFrontLeft.Get(), m_frontLeft.Get(), 0.01)
+            << "Magnitude: " << magnitudeJoystick
+            << " Direction: " << directionJoystick
+            << " Rotate: " << rotateJoystick;
+        ASSERT_NEAR(m_rdFrontRight.Get(), -m_frontRight.Get(), 0.01)
+            << "Magnitude: " << magnitudeJoystick
+            << " Direction: " << directionJoystick
+            << " Rotate: " << rotateJoystick;
+        ASSERT_NEAR(m_rdRearLeft.Get(), m_rearLeft.Get(), 0.01)
+            << "Magnitude: " << magnitudeJoystick
+            << " Direction: " << directionJoystick
+            << " Rotate: " << rotateJoystick;
+        ASSERT_NEAR(m_rdRearRight.Get(), -m_rearRight.Get(), 0.01)
+            << "Magnitude: " << magnitudeJoystick
+            << " Direction: " << directionJoystick
+            << " Rotate: " << rotateJoystick;
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp
new file mode 100644
index 0000000..a6f5028
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/SpeedControllerGroupTest.cpp
@@ -0,0 +1,136 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/SpeedControllerGroup.h"  // NOLINT(build/include_order)
+
+#include <memory>
+#include <vector>
+
+#include "MockSpeedController.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+enum SpeedControllerGroupTestType { TEST_ONE, TEST_TWO, TEST_THREE };
+
+std::ostream& operator<<(std::ostream& os,
+                         const SpeedControllerGroupTestType& type) {
+  switch (type) {
+    case TEST_ONE:
+      os << "SpeedControllerGroup with one speed controller";
+      break;
+    case TEST_TWO:
+      os << "SpeedControllerGroup with two speed controllers";
+      break;
+    case TEST_THREE:
+      os << "SpeedControllerGroup with three speed controllers";
+      break;
+  }
+
+  return os;
+}
+
+/**
+ * A fixture used for SpeedControllerGroup testing.
+ */
+class SpeedControllerGroupTest
+    : public testing::TestWithParam<SpeedControllerGroupTestType> {
+ protected:
+  std::vector<MockSpeedController> m_speedControllers;
+  std::unique_ptr<SpeedControllerGroup> m_group;
+
+  void SetUp() override {
+    switch (GetParam()) {
+      case TEST_ONE: {
+        m_speedControllers.emplace_back();
+        m_group = std::make_unique<SpeedControllerGroup>(m_speedControllers[0]);
+        break;
+      }
+
+      case TEST_TWO: {
+        m_speedControllers.emplace_back();
+        m_speedControllers.emplace_back();
+        m_group = std::make_unique<SpeedControllerGroup>(m_speedControllers[0],
+                                                         m_speedControllers[1]);
+        break;
+      }
+
+      case TEST_THREE: {
+        m_speedControllers.emplace_back();
+        m_speedControllers.emplace_back();
+        m_speedControllers.emplace_back();
+        m_group = std::make_unique<SpeedControllerGroup>(m_speedControllers[0],
+                                                         m_speedControllers[1],
+                                                         m_speedControllers[2]);
+        break;
+      }
+    }
+  }
+};
+
+TEST_P(SpeedControllerGroupTest, Set) {
+  m_group->Set(1.0);
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), 1.0);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, GetInverted) {
+  m_group->SetInverted(true);
+
+  EXPECT_TRUE(m_group->GetInverted());
+}
+
+TEST_P(SpeedControllerGroupTest, SetInvertedDoesNotModifySpeedControllers) {
+  for (auto& speedController : m_speedControllers) {
+    speedController.SetInverted(false);
+  }
+  m_group->SetInverted(true);
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_EQ(speedController.GetInverted(), false);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, SetInvertedDoesInvert) {
+  m_group->SetInverted(true);
+  m_group->Set(1.0);
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), -1.0);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, Disable) {
+  m_group->Set(1.0);
+  m_group->Disable();
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), 0.0);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, StopMotor) {
+  m_group->Set(1.0);
+  m_group->StopMotor();
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), 0.0);
+  }
+}
+
+TEST_P(SpeedControllerGroupTest, PIDWrite) {
+  m_group->PIDWrite(1.0);
+
+  for (auto& speedController : m_speedControllers) {
+    EXPECT_FLOAT_EQ(speedController.Get(), 1.0);
+  }
+}
+
+INSTANTIATE_TEST_CASE_P(Test, SpeedControllerGroupTest,
+                        testing::Values(TEST_ONE, TEST_TWO, TEST_THREE), );
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
new file mode 100644
index 0000000..141c72e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/WatchdogTest.cpp
@@ -0,0 +1,142 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Watchdog.h"  // NOLINT(build/include_order)
+
+#include <stdint.h>
+
+#include <thread>
+
+#include <wpi/raw_ostream.h>
+
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+TEST(WatchdogTest, EnableDisable) {
+  uint32_t watchdogCounter = 0;
+
+  Watchdog watchdog(0.4, [&] { watchdogCounter++; });
+
+  wpi::outs() << "Run 1\n";
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.Disable();
+
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+
+  wpi::outs() << "Run 2\n";
+  watchdogCounter = 0;
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(600));
+  watchdog.Disable();
+
+  EXPECT_EQ(1u, watchdogCounter)
+      << "Watchdog either didn't trigger or triggered more than once";
+
+  wpi::outs() << "Run 3\n";
+  watchdogCounter = 0;
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(1000));
+  watchdog.Disable();
+
+  EXPECT_EQ(1u, watchdogCounter)
+      << "Watchdog either didn't trigger or triggered more than once";
+}
+
+TEST(WatchdogTest, Reset) {
+  uint32_t watchdogCounter = 0;
+
+  Watchdog watchdog(0.4, [&] { watchdogCounter++; });
+
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.Reset();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.Disable();
+
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+}
+
+TEST(WatchdogTest, SetTimeout) {
+  uint32_t watchdogCounter = 0;
+
+  Watchdog watchdog(1.0, [&] { watchdogCounter++; });
+
+  watchdog.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.SetTimeout(0.2);
+
+  EXPECT_EQ(0.2, watchdog.GetTimeout());
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+
+  std::this_thread::sleep_for(std::chrono::milliseconds(300));
+  watchdog.Disable();
+
+  EXPECT_EQ(1u, watchdogCounter)
+      << "Watchdog either didn't trigger or triggered more than once";
+}
+
+TEST(WatchdogTest, IsExpired) {
+  Watchdog watchdog(0.2, [] {});
+  watchdog.Enable();
+
+  EXPECT_FALSE(watchdog.IsExpired());
+  std::this_thread::sleep_for(std::chrono::milliseconds(300));
+  EXPECT_TRUE(watchdog.IsExpired());
+}
+
+TEST(WatchdogTest, Epochs) {
+  uint32_t watchdogCounter = 0;
+
+  Watchdog watchdog(0.4, [&] { watchdogCounter++; });
+
+  wpi::outs() << "Run 1\n";
+  watchdog.Enable();
+  watchdog.AddEpoch("Epoch 1");
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+  watchdog.AddEpoch("Epoch 2");
+  std::this_thread::sleep_for(std::chrono::milliseconds(100));
+  watchdog.AddEpoch("Epoch 3");
+  watchdog.Disable();
+
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+
+  wpi::outs() << "Run 2\n";
+  watchdog.Enable();
+  watchdog.AddEpoch("Epoch 1");
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.Reset();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  watchdog.AddEpoch("Epoch 2");
+  watchdog.Disable();
+
+  EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
+}
+
+TEST(WatchdogTest, MultiWatchdog) {
+  uint32_t watchdogCounter1 = 0;
+  uint32_t watchdogCounter2 = 0;
+
+  Watchdog watchdog1(0.2, [&] { watchdogCounter1++; });
+  Watchdog watchdog2(0.6, [&] { watchdogCounter2++; });
+
+  watchdog2.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(200));
+  EXPECT_EQ(0u, watchdogCounter1) << "Watchdog triggered early";
+  EXPECT_EQ(0u, watchdogCounter2) << "Watchdog triggered early";
+
+  // Sleep enough such that only the watchdog enabled later times out first
+  watchdog1.Enable();
+  std::this_thread::sleep_for(std::chrono::milliseconds(300));
+  watchdog1.Disable();
+  watchdog2.Disable();
+
+  EXPECT_EQ(1u, watchdogCounter1)
+      << "Watchdog either didn't trigger or triggered more than once";
+  EXPECT_EQ(0u, watchdogCounter2) << "Watchdog triggered early";
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..0e00efa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/main.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 <hal/HAL.h>
+
+#include "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  HAL_Initialize(500, 0);
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp
new file mode 100644
index 0000000..3c9e411
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/MockActuatorSendable.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "shuffleboard/MockActuatorSendable.h"
+
+using namespace frc;
+
+MockActuatorSendable::MockActuatorSendable(wpi::StringRef name)
+    : SendableBase(false) {
+  SetName(name);
+}
+
+void MockActuatorSendable::InitSendable(SendableBuilder& builder) {
+  builder.SetActuator(true);
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
new file mode 100644
index 0000000..ae21526
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardInstance.h"  // NOLINT(build/include_order)
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+
+#include "frc/shuffleboard/ShuffleboardInstance.h"
+#include "gtest/gtest.h"
+#include "shuffleboard/MockActuatorSendable.h"
+
+using namespace frc;
+
+class ShuffleboardInstanceTest : public testing::Test {
+  void SetUp() override {
+    m_ntInstance = nt::NetworkTableInstance::Create();
+    m_shuffleboardInstance =
+        std::make_unique<detail::ShuffleboardInstance>(m_ntInstance);
+  }
+
+ protected:
+  nt::NetworkTableInstance m_ntInstance;
+  std::unique_ptr<detail::ShuffleboardInstance> m_shuffleboardInstance;
+};
+
+TEST_F(ShuffleboardInstanceTest, PathFluent) {
+  auto entry = m_shuffleboardInstance->GetTab("Tab Title")
+                   .GetLayout("List Layout", "List")
+                   .Add("Data", "string")
+                   .WithWidget("Text View")
+                   .GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab Title/List Layout/Data", entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedLayoutsFluent) {
+  auto entry = m_shuffleboardInstance->GetTab("Tab")
+                   .GetLayout("First", "List")
+                   .GetLayout("Second", "List")
+                   .GetLayout("Third", "List")
+                   .GetLayout("Fourth", "List")
+                   .Add("Value", "string")
+                   .GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
+            entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedLayoutsOop) {
+  ShuffleboardTab& tab = m_shuffleboardInstance->GetTab("Tab");
+  ShuffleboardLayout& first = tab.GetLayout("First", "List");
+  ShuffleboardLayout& second = first.GetLayout("Second", "List");
+  ShuffleboardLayout& third = second.GetLayout("Third", "List");
+  ShuffleboardLayout& fourth = third.GetLayout("Fourth", "List");
+  SimpleWidget& widget = fourth.Add("Value", "string");
+  auto entry = widget.GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
+            entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, LayoutTypeIsSet) {
+  std::string layoutType = "Type";
+  m_shuffleboardInstance->GetTab("Tab").GetLayout("Title", layoutType);
+  m_shuffleboardInstance->Update();
+  nt::NetworkTableEntry entry = m_ntInstance.GetEntry(
+      "/Shuffleboard/.metadata/Tab/Title/PreferredComponent");
+  EXPECT_EQ(layoutType, entry.GetString("Not Set")) << "Layout type not set";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedActuatorWidgetsAreDisabled) {
+  MockActuatorSendable sendable("Actuator");
+  m_shuffleboardInstance->GetTab("Tab")
+      .GetLayout("Title", "Type")
+      .Add(sendable);
+  auto controllableEntry =
+      m_ntInstance.GetEntry("/Shuffleboard/Tab/Title/Actuator/.controllable");
+  m_shuffleboardInstance->Update();
+
+  // Note: we use the unsafe `GetBoolean()` method because if the value is NOT
+  // a boolean, or if it is not present, then something has clearly gone very,
+  // very wrong
+  bool controllable = controllableEntry.GetValue()->GetBoolean();
+  // Sanity check
+  EXPECT_TRUE(controllable)
+      << "The nested actuator widget should be enabled by default";
+  m_shuffleboardInstance->DisableActuatorWidgets();
+  controllable = controllableEntry.GetValue()->GetBoolean();
+  EXPECT_FALSE(controllable)
+      << "The nested actuator widget should have been disabled";
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp
new file mode 100644
index 0000000..23f3e3a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTabTest.cpp
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardInstance.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class ShuffleboardTabTest : 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(ShuffleboardTabTest, AddDouble) {
+  auto entry = m_tab->Add("Double", 1.0).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/Double", entry.GetName());
+  EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
+}
+
+TEST_F(ShuffleboardTabTest, AddInteger) {
+  auto entry = m_tab->Add("Int", 1).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/Int", entry.GetName());
+  EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
+}
+
+TEST_F(ShuffleboardTabTest, AddBoolean) {
+  auto entry = m_tab->Add("Bool", false).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/Bool", entry.GetName());
+  EXPECT_FALSE(entry.GetValue()->GetBoolean());
+}
+
+TEST_F(ShuffleboardTabTest, AddString) {
+  auto entry = m_tab->Add("String", "foobar").GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/String", entry.GetName());
+  EXPECT_EQ("foobar", entry.GetValue()->GetString());
+}
+
+TEST_F(ShuffleboardTabTest, AddNamedSendableWithProperties) {
+  InstantCommand sendable("Command");
+  std::string widgetType = "Command Widget";
+  wpi::StringMap<std::shared_ptr<nt::Value>> map;
+  map.try_emplace("foo", nt::Value::MakeDouble(1234));
+  map.try_emplace("bar", nt::Value::MakeString("baz"));
+  m_tab->Add(sendable).WithWidget(widgetType).WithProperties(map);
+
+  m_instance->Update();
+  std::string meta = "/Shuffleboard/.metadata/Tab/Command";
+
+  EXPECT_EQ(1234, m_ntInstance.GetEntry(meta + "/Properties/foo").GetDouble(-1))
+      << "Property 'foo' not set correctly";
+  EXPECT_EQ("baz",
+            m_ntInstance.GetEntry(meta + "/Properties/bar").GetString(""))
+      << "Property 'bar' not set correctly";
+  EXPECT_EQ(widgetType,
+            m_ntInstance.GetEntry(meta + "/PreferredComponent").GetString(""))
+      << "Preferred component not set correctly";
+}
+
+TEST_F(ShuffleboardTabTest, AddNumberArray) {
+  std::array<double, 3> expect = {{1.0, 2.0, 3.0}};
+  auto entry = m_tab->Add("DoubleArray", expect).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/DoubleArray", entry.GetName());
+
+  auto actual = entry.GetValue()->GetDoubleArray();
+  EXPECT_EQ(expect.size(), actual.size());
+  for (size_t i = 0; i < expect.size(); i++) {
+    EXPECT_FLOAT_EQ(expect[i], actual[i]);
+  }
+}
+
+TEST_F(ShuffleboardTabTest, AddBooleanArray) {
+  std::array<bool, 2> expect = {{true, false}};
+  auto entry = m_tab->Add("BoolArray", expect).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/BoolArray", entry.GetName());
+
+  auto actual = entry.GetValue()->GetBooleanArray();
+  EXPECT_EQ(expect.size(), actual.size());
+  for (size_t i = 0; i < expect.size(); i++) {
+    EXPECT_EQ(expect[i], actual[i]);
+  }
+}
+
+TEST_F(ShuffleboardTabTest, AddStringArray) {
+  std::array<std::string, 2> expect = {{"foo", "bar"}};
+  auto entry = m_tab->Add("StringArray", expect).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/StringArray", entry.GetName());
+
+  auto actual = entry.GetValue()->GetStringArray();
+  EXPECT_EQ(expect.size(), actual.size());
+  for (size_t i = 0; i < expect.size(); i++) {
+    EXPECT_EQ(expect[i], actual[i]);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTest.cpp b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTest.cpp
new file mode 100644
index 0000000..d39d59d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardTest.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Shuffleboard.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class ShuffleboardTest : public testing::Test {};
+
+TEST_F(ShuffleboardTest, TabObjectsCached) {
+  ShuffleboardTab& tab1 = Shuffleboard::GetTab("testTabObjectsCached");
+  ShuffleboardTab& tab2 = Shuffleboard::GetTab("testTabObjectsCached");
+  EXPECT_EQ(&tab1, &tab2) << "Tab objects were not cached";
+}
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/include/MockSpeedController.h b/third_party/allwpilib_2019/wpilibc/src/test/native/include/MockSpeedController.h
new file mode 100644
index 0000000..e0c788f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/include/MockSpeedController.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/SpeedController.h"
+
+namespace frc {
+
+class MockSpeedController : public SpeedController {
+ public:
+  void Set(double speed) override;
+  double Get() const override;
+  void SetInverted(bool isInverted) override;
+  bool GetInverted() const override;
+  void Disable() override;
+  void StopMotor() override;
+
+  void PIDWrite(double output) override;
+
+ private:
+  double m_speed = 0.0;
+  bool m_isInverted = false;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h b/third_party/allwpilib_2019/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h
new file mode 100644
index 0000000..f56215c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/src/test/native/include/shuffleboard/MockActuatorSendable.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+#include "frc/smartdashboard/SendableBase.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+namespace frc {
+
+/**
+ * A mock sendable that marks itself as an actuator.
+ */
+class MockActuatorSendable : public SendableBase {
+ public:
+  explicit MockActuatorSendable(wpi::StringRef name);
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibc/wpilibc-config.cmake b/third_party/allwpilib_2019/wpilibc/wpilibc-config.cmake
new file mode 100644
index 0000000..86f077c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibc/wpilibc-config.cmake
@@ -0,0 +1,10 @@
+include(CMakeFindDependencyMacro)
+find_dependency(wpiutil)
+find_dependency(ntcore)
+find_dependency(cscore)
+find_dependency(cameraserver)
+find_dependency(hal)
+find_dependency(OpenCV)
+
+get_filename_component(SELF_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)
+include(${SELF_DIR}/wpilibc.cmake)
diff --git a/third_party/allwpilib_2019/wpilibcExamples/.styleguide b/third_party/allwpilib_2019/wpilibcExamples/.styleguide
new file mode 100644
index 0000000..d39dee7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/.styleguide
@@ -0,0 +1,22 @@
+cppHeaderFileInclude {
+  \.h$
+  \.hpp$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+includeOtherLibs {
+  ^HAL/
+  ^cameraserver/
+  ^cscore
+  ^frc/
+  ^networktables/
+  ^ntcore
+  ^opencv2/
+  ^support/
+  ^vision/
+  ^wpi/
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/build.gradle b/third_party/allwpilib_2019/wpilibcExamples/build.gradle
new file mode 100644
index 0000000..3c87203
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/build.gradle
@@ -0,0 +1,233 @@
+import org.gradle.language.base.internal.ProjectLayout
+
+apply plugin: 'cpp'
+apply plugin: 'c'
+apply plugin: 'visual-studio'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: ExtraTasks
+
+apply from: '../shared/config.gradle'
+
+ext.examplesMap = [:]
+ext.templatesMap = [:]
+
+File examplesTree = file("$projectDir/src/main/cpp/examples")
+examplesTree.list(new FilenameFilter() {
+    @Override
+    public boolean accept(File current, String name) {
+        return new File(current, name).isDirectory();
+    }
+}).each {
+    examplesMap.put(it, [])
+}
+File templatesTree = file("$projectDir/src/main/cpp/templates")
+templatesTree.list(new FilenameFilter() {
+    @Override
+    public boolean accept(File current, String name) {
+        return new File(current, name).isDirectory();
+    }
+}).each {
+    templatesMap.put(it, [])
+}
+
+
+ext {
+    sharedCvConfigs = examplesMap + templatesMap + [commands: []]
+    staticCvConfigs = [:]
+    useJava = false
+    useCpp = true
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+ext {
+    chipObjectComponents = ['commands']
+    netCommComponents = ['commands']
+    examplesMap.each { key, value ->
+        chipObjectComponents << key.toString()
+        netCommComponents << key.toString()
+    }
+    templatesMap.each { key, value ->
+        chipObjectComponents << key.toString()
+        netCommComponents << key.toString()
+    }
+}
+
+apply from: "${rootDir}/shared/nilibraries.gradle"
+
+model {
+    components {
+        commands(NativeLibrarySpec) {
+            binaries.all { binary ->
+                if (binary in StaticLibraryBinarySpec) {
+                    binary.buildable = false
+                    return
+                }
+                lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                project(':hal').addHalDependency(binary, 'shared')
+                lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+            }
+            sources {
+                cpp {
+                    source {
+                        srcDirs = ['src/main/cpp/commands']
+                        include '**/*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/cpp/commands'
+                        include '**/*.h'
+                    }
+                }
+            }
+        }
+
+        examplesMap.each { key, value ->
+            "${key}"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                binaries.all { binary ->
+                    lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                    project(':hal').addHalDependency(binary, 'shared')
+                    lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    if (binary.targetPlatform.architecture.name != 'athena') {
+                        lib project: ':simulation:halsim_lowfi', library: 'halsim_lowfi', linkage: 'shared'
+                        lib project: ':simulation:halsim_adx_gyro_accelerometer', library: 'halsim_adx_gyro_accelerometer', linkage: 'shared'
+                        lib project: ':simulation:halsim_print', library: 'halsim_print', linkage: 'shared'
+                        lib project: ':simulation:halsim_ds_nt', library: 'halsim_ds_nt', linkage: 'shared'
+                    }
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'src/main/cpp/examples/' + "${key}" + "/cpp"
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/cpp/examples/' + "${key}" + "/include"
+                            include '**/*.h'
+                        }
+                    }
+                }
+                sources {
+                    c {
+                        source {
+                            srcDirs 'src/main/cpp/examples/' + "${key}" + "/c"
+                            include '**/*.c'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/cpp/examples/' + "${key}" + "/include"
+                            include '**/*.h'
+                        }
+                    }
+                }
+            }
+        }
+        templatesMap.each { key, value ->
+            "${key}"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                binaries.all { binary ->
+                    lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                    project(':hal').addHalDependency(binary, 'shared')
+                    lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    binary.tasks.withType(CppCompile) {
+                        if (!(binary.toolChain in VisualCpp)) {
+                            cppCompiler.args "-Wno-error=deprecated-declarations"
+                        }
+                    }
+                    if (binary.targetPlatform.architecture.name != 'athena') {
+                        lib project: ':simulation:halsim_lowfi', library: 'halsim_lowfi', linkage: 'shared'
+                        lib project: ':simulation:halsim_adx_gyro_accelerometer', library: 'halsim_adx_gyro_accelerometer', linkage: 'shared'
+                        lib project: ':simulation:halsim_print', library: 'halsim_print', linkage: 'shared'
+                        lib project: ':simulation:halsim_ds_nt', library: 'halsim_ds_nt', linkage: 'shared'
+                    }
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'src/main/cpp/templates/' + "${key}" + "/cpp"
+                            include '**/*.cpp'
+                        }
+                        exportedHeaders {
+                            srcDirs 'src/main/cpp/templates/' + "${key}" + "/include"
+                            include '**/*.h'
+                        }
+                    }
+                }
+            }
+        }
+    }
+    tasks {
+        def b = $.binaries
+        b.each { binary->
+            if (binary in NativeExecutableBinarySpec) {
+                def installDir = binary.tasks.install.installDirectory.get().toString() + File.separatorChar
+                def runFile = binary.tasks.install.runScriptFile.get().asFile.toString()
+
+                binary.tasks.install.doLast {
+                    if (binary.targetPlatform.operatingSystem.isWindows()) {
+                        // Windows batch scripts
+                        def fileName = binary.component.name + 'LowFi.bat'
+                        def file = new File(installDir + fileName)
+                        file.withWriter { out ->
+                            out.println '@ECHO OFF'
+                            out.print 'SET HALSIM_EXTENSIONS='
+                            out.print '"' + new File(installDir + 'lib\\halsim_lowfi.dll').toString() + '";'
+                            out.println '"' + new File(installDir + 'lib\\halsim_ds_nt.dll').toString() + '"'
+                            out.println runFile + ' %*'
+                        }
+
+                        fileName = binary.component.name + 'LowFiRealDS.bat'
+                        file = new File(installDir + fileName)
+                        file.withWriter { out ->
+                            out.println '@ECHO OFF'
+                            out.print 'SET HALSIM_EXTENSIONS='
+                            out.print '"' + new File(installDir + 'lib\\halsim_lowfi.dll').toString() + '";'
+                            out.println '"' + new File(installDir + 'lib\\halsim_ds_socket.dll').toString() + '"'
+                            out.println runFile + ' %*'
+                        }
+                    } else {
+                        def fileName = binary.component.name + 'LowFi.sh'
+                        def file = new File(installDir + fileName)
+
+                        file.withWriter { out ->
+                            out.print 'export HALSIM_EXTENSIONS='
+                            out.print '"' + new File(installDir + '/lib/libhalsim_lowfi.so').toString() + '";'
+                            out.println '"' + new File(installDir + '/lib/libhalsim_ds_nt.so').toString() + '"'
+                            out.println runFile + ' "$@"'
+                        }
+
+                        fileName = binary.component.name + 'LowFiRealDS.sh'
+                        file = new File(installDir + fileName)
+                        file.withWriter { out ->
+                            out.print 'export HALSIM_EXTENSIONS='
+                            out.print '"' + new File(installDir + '/lib/libhalsim_lowfi.so').toString() + '":'
+                            out.println '"' + new File(installDir + '/lib/libhalsim_ds_socket.so').toString() + '"'
+                            out.println runFile + ' "$@"'
+                        }
+                    }
+                }
+
+            }
+        }
+    }
+}
+apply from: 'publish.gradle'
+
+ext {
+    templateDirectory = new File("$projectDir/src/main/cpp/templates/")
+    templateFile = new File("$projectDir/src/main/cpp/templates/templates.json")
+    exampleDirectory = new File("$projectDir/src/main/cpp/examples/")
+    exampleFile = new File("$projectDir/src/main/cpp/examples/examples.json")
+    commandDirectory = new File("$projectDir/src/main/cpp/commands/")
+    commandFile = new File("$projectDir/src/main/cpp/commands/commands.json")
+}
+
+apply from: "${rootDir}/shared/examplecheck.gradle"
diff --git a/third_party/allwpilib_2019/wpilibcExamples/publish.gradle b/third_party/allwpilib_2019/wpilibcExamples/publish.gradle
new file mode 100644
index 0000000..ec645ae
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/publish.gradle
@@ -0,0 +1,94 @@
+apply plugin: 'maven-publish'
+
+def pubVersion
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseExamplesArtifactId = 'examples'
+def baseTemplatesArtifactId = 'templates'
+def baseCommandsArtifactId = 'commands'
+def artifactGroupId = 'edu.wpi.first.wpilibc'
+
+def examplesZipBaseName = '_GROUP_edu_wpi_first_wpilibc_ID_examples_CLS'
+def templatesZipBaseName = '_GROUP_edu_wpi_first_wpilibc_ID_templates_CLS'
+def commandsZipBaseName = '_GROUP_edu_wpi_first_wpilibc_ID_commands_CLS'
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task cppExamplesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = examplesZipBaseName
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/cpp/examples') {
+        into 'examples'
+    }
+}
+
+task cppTemplatesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = templatesZipBaseName
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/cpp/templates') {
+        into 'templates'
+    }
+}
+
+task cppCommandsZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = commandsZipBaseName
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/cpp/commands') {
+        into 'commands'
+    }
+}
+
+build.dependsOn cppTemplatesZip
+build.dependsOn cppExamplesZip
+build.dependsOn cppCommandsZip
+
+addTaskToCopyAllOutputs(cppTemplatesZip)
+addTaskToCopyAllOutputs(cppExamplesZip)
+addTaskToCopyAllOutputs(cppCommandsZip)
+
+publishing {
+    publications {
+        examples(MavenPublication) {
+            artifact cppExamplesZip
+
+            artifactId = baseExamplesArtifactId
+            groupId artifactGroupId
+            version pubVersion
+        }
+
+        templates(MavenPublication) {
+            artifact cppTemplatesZip
+
+            artifactId = baseTemplatesArtifactId
+            groupId artifactGroupId
+            version pubVersion
+        }
+
+        commands(MavenPublication) {
+            artifact cppCommandsZip
+
+            artifactId = baseCommandsArtifactId
+            groupId artifactGroupId
+            version pubVersion
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp
new file mode 100644
index 0000000..07c233e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.cpp
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ReplaceMeCommand.h"
+
+ReplaceMeCommand::ReplaceMeCommand() {
+  // Use Requires() here to declare subsystem dependencies
+  // eg. Requires(Robot::chassis.get());
+}
+
+// Called just before this Command runs the first time
+void ReplaceMeCommand::Initialize() {}
+
+// Called repeatedly when this Command is scheduled to run
+void ReplaceMeCommand::Execute() {}
+
+// Make this return true when this Command no longer needs to run execute()
+bool ReplaceMeCommand::IsFinished() { return false; }
+
+// Called once after isFinished returns true
+void ReplaceMeCommand::End() {}
+
+// Called when another command which requires one or more of the same
+// subsystems is scheduled to run
+void ReplaceMeCommand::Interrupted() {}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h
new file mode 100644
index 0000000..49a3139
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/command/ReplaceMeCommand.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+class ReplaceMeCommand : public frc::Command {
+ public:
+  ReplaceMeCommand();
+  void Initialize() override;
+  void Execute() override;
+  bool IsFinished() override;
+  void End() override;
+  void Interrupted() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp
new file mode 100644
index 0000000..1a431f4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ReplaceMeCommandGroup.h"
+
+ReplaceMeCommandGroup::ReplaceMeCommandGroup() {
+  // Add Commands here:
+  // e.g. AddSequential(new Command1());
+  //      AddSequential(new Command2());
+  // these will run in order.
+
+  // To run multiple commands at the same time,
+  // use AddParallel()
+  // e.g. AddParallel(new Command1());
+  //      AddSequential(new Command2());
+  // Command1 and Command2 will run in parallel.
+
+  // A command group will require all of the subsystems that each member
+  // would require.
+  // e.g. if Command1 requires chassis, and Command2 requires arm,
+  // a CommandGroup containing them would require both the chassis and the
+  // arm.
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h
new file mode 100644
index 0000000..a58f586
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commandgroup/ReplaceMeCommandGroup.h
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+class ReplaceMeCommandGroup : public frc::CommandGroup {
+ public:
+  ReplaceMeCommandGroup();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commands.json b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commands.json
new file mode 100644
index 0000000..bb8cbb6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/commands.json
@@ -0,0 +1,123 @@
+[
+  {
+    "name": "Empty Class",
+    "description": "Create an empty command",
+    "tags": [
+      "class"
+    ],
+    "foldername": "emptyclass",
+    "headers": [
+      "ReplaceMeEmptyClass.h"
+    ],
+    "source": [
+      "ReplaceMeEmptyClass.cpp"
+    ],
+    "replacename": "ReplaceMeEmptyClass"
+  },
+  {
+    "name": "Command",
+    "description": "Create a base command",
+    "tags": [
+      "command"
+    ],
+    "foldername": "command",
+    "headers": [
+      "ReplaceMeCommand.h"
+    ],
+    "source": [
+      "ReplaceMeCommand.cpp"
+    ],
+    "replacename": "ReplaceMeCommand"
+  },
+  {
+    "name": "Command Group",
+    "description": "Create a command group",
+    "tags": [
+      "commandgroup"
+    ],
+    "foldername": "commandgroup",
+    "headers": [
+      "ReplaceMeCommandGroup.h"
+    ],
+    "source": [
+      "ReplaceMeCommandGroup.cpp"
+    ],
+    "replacename": "ReplaceMeCommandGroup"
+  },
+  {
+    "name": "Instant Command",
+    "description": "A command that runs immediately",
+    "tags": [
+      "instantcommand"
+    ],
+    "foldername": "instant",
+    "headers": [
+      "ReplaceMeInstantCommand.h"
+    ],
+    "source": [
+      "ReplaceMeInstantCommand.cpp"
+    ],
+    "replacename": "ReplaceMeInstantCommand"
+  },
+  {
+    "name": "Subsystem",
+    "description": "A subsystem",
+    "tags": [
+      "subsystem"
+    ],
+    "foldername": "subsystem",
+    "headers": [
+      "ReplaceMeSubsystem.h"
+    ],
+    "source": [
+      "ReplaceMeSubsystem.cpp"
+    ],
+    "replacename": "ReplaceMeSubsystem"
+  },
+  {
+    "name": "PID Subsystem",
+    "description": "A subsystem that runs a PID loop",
+    "tags": [
+      "pidsubsystem",
+      "pid"
+    ],
+    "foldername": "pidsubsystem",
+    "headers": [
+      "ReplaceMePIDSubsystem.h"
+    ],
+    "source": [
+      "ReplaceMePIDSubsystem.cpp"
+    ],
+    "replacename": "ReplaceMePIDSubsystem"
+  },
+  {
+    "name": "Timed Command",
+    "description": "A command that runs for a specified time",
+    "tags": [
+      "timedcommand"
+    ],
+    "foldername": "timed",
+    "headers": [
+      "ReplaceMeTimedCommand.h"
+    ],
+    "source": [
+      "ReplaceMeTimedCommand.cpp"
+    ],
+    "replacename": "ReplaceMeTimedCommand"
+  },
+  {
+    "name": "Trigger",
+    "description": "A command that runs off of a trigger",
+    "tags": [
+      "trigger"
+    ],
+    "foldername": "trigger",
+    "headers": [
+      "ReplaceMeTrigger.h"
+    ],
+    "source": [
+      "ReplaceMeTrigger.cpp"
+    ],
+    "replacename": "ReplaceMeTrigger"
+  }
+]
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/emptyclass/ReplaceMeEmptyClass.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/emptyclass/ReplaceMeEmptyClass.cpp
new file mode 100644
index 0000000..4ff8ad8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/emptyclass/ReplaceMeEmptyClass.cpp
@@ -0,0 +1,10 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "ReplaceMeEmptyClass.h"
+
+ReplaceMeEmptyClass::ReplaceMeEmptyClass() {}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/emptyclass/ReplaceMeEmptyClass.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/emptyclass/ReplaceMeEmptyClass.h
new file mode 100644
index 0000000..131edab
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/emptyclass/ReplaceMeEmptyClass.h
@@ -0,0 +1,13 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+class ReplaceMeEmptyClass {
+ public:
+  ReplaceMeEmptyClass();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp
new file mode 100644
index 0000000..c130e09
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.cpp
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ReplaceMeInstantCommand.h"
+
+ReplaceMeInstantCommand::ReplaceMeInstantCommand() {
+  // Use Requires() here to declare subsystem dependencies
+  // eg. Requires(Robot::chassis.get());
+}
+
+// Called once when the command executes
+void ReplaceMeInstantCommand::Initialize() {}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h
new file mode 100644
index 0000000..b50b617
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/instant/ReplaceMeInstantCommand.h
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/InstantCommand.h>
+
+class ReplaceMeInstantCommand : public frc::InstantCommand {
+ public:
+  ReplaceMeInstantCommand();
+  void Initialize() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp
new file mode 100644
index 0000000..f446f8e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ReplaceMePIDSubsystem.h"
+
+#include <frc/livewindow/LiveWindow.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+ReplaceMePIDSubsystem::ReplaceMePIDSubsystem()
+    : PIDSubsystem("ReplaceMePIDSubsystem", 1.0, 0.0, 0.0) {
+  // Use these to get going:
+  // SetSetpoint() -  Sets where the PID controller should move the system
+  //                  to
+  // Enable() - Enables the PID controller.
+}
+
+double ReplaceMePIDSubsystem::ReturnPIDInput() {
+  // Return your input value for the PID loop
+  // e.g. a sensor, like a potentiometer:
+  // yourPot->SetAverageVoltage() / kYourMaxVoltage;
+  return 0;
+}
+
+void ReplaceMePIDSubsystem::UsePIDOutput(double output) {
+  // Use output to drive your system, like a motor
+  // e.g. yourMotor->Set(output);
+}
+
+void ReplaceMePIDSubsystem::InitDefaultCommand() {
+  // Set the default command for a subsystem here.
+  // SetDefaultCommand(new MySpecialCommand());
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h
new file mode 100644
index 0000000..2ab3d92
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/pidsubsystem/ReplaceMePIDSubsystem.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/PIDSubsystem.h>
+
+class ReplaceMePIDSubsystem : public frc::PIDSubsystem {
+ public:
+  ReplaceMePIDSubsystem();
+  double ReturnPIDInput() override;
+  void UsePIDOutput(double output) override;
+  void InitDefaultCommand() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp
new file mode 100644
index 0000000..8ca89d3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ReplaceMeSubsystem.h"
+
+ReplaceMeSubsystem::ReplaceMeSubsystem() : Subsystem("ExampleSubsystem") {}
+
+void ReplaceMeSubsystem::InitDefaultCommand() {
+  // Set the default command for a subsystem here.
+  // SetDefaultCommand(new MySpecialCommand());
+}
+
+// Put methods for controlling this subsystem
+// here. Call these from Commands.
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h
new file mode 100644
index 0000000..de84a48
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/subsystem/ReplaceMeSubsystem.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Subsystem.h>
+
+class ReplaceMeSubsystem : public frc::Subsystem {
+ private:
+  // It's desirable that everything possible under private except
+  // for methods that implement subsystem capabilities
+
+ public:
+  ReplaceMeSubsystem();
+  void InitDefaultCommand() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp
new file mode 100644
index 0000000..2076e5b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ReplaceMeTimedCommand.h"
+
+ReplaceMeTimedCommand::ReplaceMeTimedCommand(double timeout)
+    : TimedCommand(timeout) {
+  // Use Requires() here to declare subsystem dependencies
+  // eg. Requires(Robot::chassis.get());
+}
+
+// Called just before this Command runs the first time
+void ReplaceMeTimedCommand::Initialize() {}
+
+// Called repeatedly when this Command is scheduled to run
+void ReplaceMeTimedCommand::Execute() {}
+
+// Called once after command times out
+void ReplaceMeTimedCommand::End() {}
+
+// Called when another command which requires one or more of the same
+// subsystems is scheduled to run
+void ReplaceMeTimedCommand::Interrupted() {}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h
new file mode 100644
index 0000000..bf55e45
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/timed/ReplaceMeTimedCommand.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/TimedCommand.h>
+
+class ReplaceMeTimedCommand : public frc::TimedCommand {
+ public:
+  explicit ReplaceMeTimedCommand(double timeout);
+  void Initialize() override;
+  void Execute() override;
+  void End() override;
+  void Interrupted() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp
new file mode 100644
index 0000000..4759e0e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.cpp
@@ -0,0 +1,12 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "ReplaceMeTrigger.h"
+
+ReplaceMeTrigger::ReplaceMeTrigger() {}
+
+bool ReplaceMeTrigger::Get() { return false; }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h
new file mode 100644
index 0000000..9da7ef8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/commands/trigger/ReplaceMeTrigger.h
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/buttons/Trigger.h>
+
+class ReplaceMeTrigger : public frc::Trigger {
+ public:
+  ReplaceMeTrigger();
+  bool Get() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
new file mode 100644
index 0000000..3361754
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/drive/DifferentialDrive.h>
+
+/**
+ * This is a demo program showing the use of the DifferentialDrive class.
+ * Runs the motors with arcade steering.
+ */
+class Robot : public frc::TimedRobot {
+  frc::PWMVictorSPX m_leftMotor{0};
+  frc::PWMVictorSPX m_rightMotor{1};
+  frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
+  frc::Joystick m_stick{0};
+
+ public:
+  void TeleopPeriodic() {
+    // Drive with arcade style
+    m_robotDrive.ArcadeDrive(m_stick.GetY(), m_stick.GetX());
+  }
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/AxisCameraSample/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/AxisCameraSample/cpp/Robot.cpp
new file mode 100644
index 0000000..2811cf1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/AxisCameraSample/cpp/Robot.cpp
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <cameraserver/CameraServer.h>
+#include <frc/TimedRobot.h>
+#include <opencv2/core/core.hpp>
+#include <opencv2/core/types.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+
+/**
+ * This is a demo program showing the use of OpenCV to do vision processing. The
+ * image is acquired from the Axis camera, then a rectangle is put on the image
+ * and sent to the dashboard. OpenCV has many methods for different types of
+ * processing.
+ */
+class Robot : public frc::TimedRobot {
+ private:
+  static void VisionThread() {
+    // Get the Axis camera from CameraServer
+    cs::AxisCamera camera =
+        frc::CameraServer::GetInstance()->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();
+    // Setup a CvSource. This will send images back to the Dashboard
+    cs::CvSource outputStream =
+        frc::CameraServer::GetInstance()->PutVideo("Rectangle", 640, 480);
+
+    // Mats are very memory expensive. Lets reuse this Mat.
+    cv::Mat mat;
+
+    while (true) {
+      // Tell the CvSink to grab a frame from the camera and put it in the
+      // source mat. If there is an error notify the output.
+      if (cvSink.GrabFrame(mat) == 0) {
+        // Send the output the error.
+        outputStream.NotifyError(cvSink.GetError());
+        // skip the rest of the current iteration
+        continue;
+      }
+      // Put a rectangle on the image
+      rectangle(mat, cv::Point(100, 100), cv::Point(400, 400),
+                cv::Scalar(255, 255, 255), 5);
+      // Give the output stream a new image to display
+      outputStream.PutFrame(mat);
+    }
+  }
+
+  void RobotInit() override {
+    // We need to run our vision program in a separate thread. If not, our robot
+    // program will not run.
+    std::thread visionThread(VisionThread);
+    visionThread.detach();
+  }
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp
new file mode 100644
index 0000000..76493b5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/PowerDistributionPanel.h>
+#include <frc/TimedRobot.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+/**
+ * This is a sample program showing how to retrieve information from the Power
+ * Distribution Panel via CAN. The information will be displayed under variables
+ * through the SmartDashboard.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void TeleopPeriodic() override {
+    /* Get the current going through channel 7, in Amperes. The PDP returns the
+     * current in increments of 0.125A. At low currents the current readings
+     * tend to be less accurate.
+     */
+    frc::SmartDashboard::PutNumber("Current Channel 7", m_pdp.GetCurrent(7));
+
+    /* Get the voltage going into the PDP, in Volts. The PDP returns the voltage
+     * in increments of 0.05 Volts.
+     */
+    frc::SmartDashboard::PutNumber("Voltage", m_pdp.GetVoltage());
+
+    // Retrieves the temperature of the PDP, in degrees Celsius.
+    frc::SmartDashboard::PutNumber("Temperature", m_pdp.GetTemperature());
+  }
+
+ private:
+  // Object for dealing with the Power Distribution Panel (PDP).
+  frc::PowerDistributionPanel m_pdp;
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp
new file mode 100644
index 0000000..1dbbfa5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/Encoder.h>
+#include <frc/TimedRobot.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+/**
+ * Sample program displaying the value of a quadrature encoder on the
+ * SmartDashboard.
+ *
+ * Quadrature Encoders are digital sensors which can detect the amount the
+ * encoder has rotated since starting as well as the direction in which the
+ * encoder shaft is rotating. However, encoders can not tell you the absolute
+ * position of the encoder shaft (ie, it considers where it starts to be the
+ * zero position, no matter where it starts), and so can only tell you how much
+ * the encoder has rotated since starting.
+ *
+ * Depending on the precision of an encoder, it will have fewer or greater ticks
+ * per revolution; the number of ticks per revolution will affect the conversion
+ * between ticks and distance, as specified by DistancePerPulse.
+ *
+ * One of the most common uses of encoders is in the drivetrain, so that the
+ * distance that the robot drives can be precisely controlled during the
+ * autonomous mode.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  Robot() {
+    /* Defines the number of samples to average when determining the rate.
+     * On a quadrature encoder, values range from 1-255; larger values result in
+     * smoother but potentially less accurate rates than lower values.
+     */
+    m_encoder.SetSamplesToAverage(5);
+
+    /* Defines how far the mechanism attached to the encoder moves per pulse. In
+     * this case, we assume that a 360 count encoder is directly attached to a 3
+     * inch diameter (1.5inch radius) wheel, and that we want to measure
+     * distance in inches.
+     */
+    m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * 3.1415 * 1.5);
+
+    /* Defines the lowest rate at which the encoder will not be considered
+     * stopped, for the purposes of the GetStopped() method. Units are in
+     * distance / second, where distance refers to the units of distance that
+     * you are using, in this case inches.
+     */
+    m_encoder.SetMinRate(1.0);
+  }
+
+  void TeleopPeriodic() override {
+    // Retrieve the net displacement of the Encoder since the last Reset.
+    frc::SmartDashboard::PutNumber("Encoder Distance", m_encoder.GetDistance());
+
+    // Retrieve the current rate of the encoder.
+    frc::SmartDashboard::PutNumber("Encoder Rate", m_encoder.GetRate());
+  }
+
+ private:
+  /**
+   * The Encoder object is constructed with 4 parameters, the last two being
+   * optional.
+   *
+   * The first two parameters (1, 2 in this case) refer to the ports on the
+   * roboRIO which the encoder uses. Because a quadrature encoder has two signal
+   * wires, the signal from two DIO ports on the roboRIO are used.
+   *
+   * The third (optional) parameter is a boolean which defaults to false. If you
+   * set this parameter to true, the direction of the encoder will  be reversed,
+   * in case it makes more sense mechanically.
+   *
+   * The final (optional) parameter specifies encoding rate (k1X, k2X, or k4X)
+   * and defaults to k4X. Faster (k4X) encoding gives greater positional
+   * precision but more noise in the rate.
+   */
+  frc::Encoder m_encoder{1, 2, false, frc::Encoder::k4X};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/OI.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/OI.cpp
new file mode 100644
index 0000000..bd0e922
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/OI.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "OI.h"
+
+#include <frc/smartdashboard/SmartDashboard.h>
+
+#include "commands/Autonomous.h"
+#include "commands/CloseClaw.h"
+#include "commands/OpenClaw.h"
+#include "commands/Pickup.h"
+#include "commands/Place.h"
+#include "commands/PrepareToPickup.h"
+#include "commands/SetElevatorSetpoint.h"
+
+OI::OI() {
+  frc::SmartDashboard::PutData("Open Claw", new OpenClaw());
+  frc::SmartDashboard::PutData("Close Claw", new CloseClaw());
+
+  // Connect the buttons to commands
+  m_dUp.WhenPressed(new SetElevatorSetpoint(0.2));
+  m_dDown.WhenPressed(new SetElevatorSetpoint(-0.2));
+  m_dRight.WhenPressed(new CloseClaw());
+  m_dLeft.WhenPressed(new OpenClaw());
+
+  m_r1.WhenPressed(new PrepareToPickup());
+  m_r2.WhenPressed(new Pickup());
+  m_l1.WhenPressed(new Place());
+  m_l2.WhenPressed(new Autonomous());
+}
+
+frc::Joystick& OI::GetJoystick() { return m_joy; }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp
new file mode 100644
index 0000000..ca2f9d6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/Robot.cpp
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "Robot.h"
+
+#include <iostream>
+
+DriveTrain Robot::drivetrain;
+Elevator Robot::elevator;
+Wrist Robot::wrist;
+Claw Robot::claw;
+OI Robot::oi;
+
+void Robot::RobotInit() {
+  // Show what command your subsystem is running on the SmartDashboard
+  frc::SmartDashboard::PutData(&drivetrain);
+  frc::SmartDashboard::PutData(&elevator);
+  frc::SmartDashboard::PutData(&wrist);
+  frc::SmartDashboard::PutData(&claw);
+}
+
+void Robot::AutonomousInit() {
+  m_autonomousCommand.Start();
+  std::cout << "Starting Auto" << std::endl;
+}
+
+void Robot::AutonomousPeriodic() { frc::Scheduler::GetInstance()->Run(); }
+
+void Robot::TeleopInit() {
+  // This makes sure that the autonomous stops running when teleop starts
+  // running. If you want the autonomous to continue until interrupted by
+  // another command, remove this line or comment it out.
+  m_autonomousCommand.Cancel();
+  std::cout << "Starting Teleop" << std::endl;
+}
+
+void Robot::TeleopPeriodic() { frc::Scheduler::GetInstance()->Run(); }
+
+void Robot::TestPeriodic() {}
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Autonomous.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Autonomous.cpp
new file mode 100644
index 0000000..30ce002
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Autonomous.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/Autonomous.h"
+
+#include "commands/CloseClaw.h"
+#include "commands/DriveStraight.h"
+#include "commands/Pickup.h"
+#include "commands/Place.h"
+#include "commands/PrepareToPickup.h"
+#include "commands/SetDistanceToBox.h"
+#include "commands/SetWristSetpoint.h"
+
+Autonomous::Autonomous() : frc::CommandGroup("Autonomous") {
+  AddSequential(new PrepareToPickup());
+  AddSequential(new Pickup());
+  AddSequential(new SetDistanceToBox(0.10));
+  // AddSequential(new DriveStraight(4));  // Use Encoders if ultrasonic
+  // is broken
+  AddSequential(new Place());
+  AddSequential(new SetDistanceToBox(0.60));
+  // AddSequential(new DriveStraight(-2));  // Use Encoders if ultrasonic
+  // is broken
+  AddParallel(new SetWristSetpoint(-45));
+  AddSequential(new CloseClaw());
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/CloseClaw.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/CloseClaw.cpp
new file mode 100644
index 0000000..e1a2f6e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/CloseClaw.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/CloseClaw.h"
+
+#include "Robot.h"
+
+CloseClaw::CloseClaw() : frc::Command("CloseClaw") { Requires(&Robot::claw); }
+
+// Called just before this Command runs the first time
+void CloseClaw::Initialize() { Robot::claw.Close(); }
+
+// Make this return true when this Command no longer needs to run execute()
+bool CloseClaw::IsFinished() { return Robot::claw.IsGripping(); }
+
+// Called once after isFinished returns true
+void CloseClaw::End() {
+// NOTE: Doesn't stop in simulation due to lower friction causing the can to
+// fall out
+// + there is no need to worry about stalling the motor or crushing the can.
+#ifndef SIMULATION
+  Robot::claw.Stop();
+#endif
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp
new file mode 100644
index 0000000..dfd1744
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/DriveStraight.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/DriveStraight.h"
+
+#include "Robot.h"
+
+DriveStraight::DriveStraight(double distance) {
+  Requires(&Robot::drivetrain);
+  m_pid.SetAbsoluteTolerance(0.01);
+  m_pid.SetSetpoint(distance);
+}
+
+// Called just before this Command runs the first time
+void DriveStraight::Initialize() {
+  // Get everything in a safe starting state.
+  Robot::drivetrain.Reset();
+  m_pid.Reset();
+  m_pid.Enable();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool DriveStraight::IsFinished() { return m_pid.OnTarget(); }
+
+// Called once after isFinished returns true
+void DriveStraight::End() {
+  // Stop PID and the wheels
+  m_pid.Disable();
+  Robot::drivetrain.Drive(0, 0);
+}
+
+double DriveStraight::DriveStraightPIDSource::PIDGet() {
+  return Robot::drivetrain.GetDistance();
+}
+
+void DriveStraight::DriveStraightPIDOutput::PIDWrite(double d) {
+  Robot::drivetrain.Drive(d, d);
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/OpenClaw.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/OpenClaw.cpp
new file mode 100644
index 0000000..175f3c1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/OpenClaw.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/OpenClaw.h"
+
+#include "Robot.h"
+
+OpenClaw::OpenClaw() : frc::Command("OpenClaw") {
+  Requires(&Robot::claw);
+  SetTimeout(1);
+}
+
+// Called just before this Command runs the first time
+void OpenClaw::Initialize() { Robot::claw.Open(); }
+
+// Make this return true when this Command no longer needs to run execute()
+bool OpenClaw::IsFinished() { return IsTimedOut(); }
+
+// Called once after isFinished returns true
+void OpenClaw::End() { Robot::claw.Stop(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Pickup.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Pickup.cpp
new file mode 100644
index 0000000..b5d8dd1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Pickup.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/Pickup.h"
+
+#include "commands/CloseClaw.h"
+#include "commands/SetElevatorSetpoint.h"
+#include "commands/SetWristSetpoint.h"
+
+Pickup::Pickup() : frc::CommandGroup("Pickup") {
+  AddSequential(new CloseClaw());
+  AddParallel(new SetWristSetpoint(-45));
+  AddSequential(new SetElevatorSetpoint(0.25));
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Place.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Place.cpp
new file mode 100644
index 0000000..cf31d3c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/Place.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/Place.h"
+
+#include "commands/OpenClaw.h"
+#include "commands/SetElevatorSetpoint.h"
+#include "commands/SetWristSetpoint.h"
+
+Place::Place() : frc::CommandGroup("Place") {
+  AddSequential(new SetElevatorSetpoint(0.25));
+  AddSequential(new SetWristSetpoint(0));
+  AddSequential(new OpenClaw());
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/PrepareToPickup.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/PrepareToPickup.cpp
new file mode 100644
index 0000000..af8f0c7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/PrepareToPickup.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/PrepareToPickup.h"
+
+#include "commands/OpenClaw.h"
+#include "commands/SetElevatorSetpoint.h"
+#include "commands/SetWristSetpoint.h"
+
+PrepareToPickup::PrepareToPickup() : frc::CommandGroup("PrepareToPickup") {
+  AddParallel(new OpenClaw());
+  AddParallel(new SetWristSetpoint(0));
+  AddSequential(new SetElevatorSetpoint(0));
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp
new file mode 100644
index 0000000..a0921e8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetDistanceToBox.cpp
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/SetDistanceToBox.h"
+
+#include <frc/PIDController.h>
+
+#include "Robot.h"
+
+SetDistanceToBox::SetDistanceToBox(double distance) {
+  Requires(&Robot::drivetrain);
+  m_pid.SetAbsoluteTolerance(0.01);
+  m_pid.SetSetpoint(distance);
+}
+
+// Called just before this Command runs the first time
+void SetDistanceToBox::Initialize() {
+  // Get everything in a safe starting state.
+  Robot::drivetrain.Reset();
+  m_pid.Reset();
+  m_pid.Enable();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool SetDistanceToBox::IsFinished() { return m_pid.OnTarget(); }
+
+// Called once after isFinished returns true
+void SetDistanceToBox::End() {
+  // Stop PID and the wheels
+  m_pid.Disable();
+  Robot::drivetrain.Drive(0, 0);
+}
+
+double SetDistanceToBox::SetDistanceToBoxPIDSource::PIDGet() {
+  return Robot::drivetrain.GetDistanceToObstacle();
+}
+
+void SetDistanceToBox::SetDistanceToBoxPIDOutput::PIDWrite(double d) {
+  Robot::drivetrain.Drive(d, d);
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetElevatorSetpoint.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetElevatorSetpoint.cpp
new file mode 100644
index 0000000..afe85e5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetElevatorSetpoint.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/SetElevatorSetpoint.h"
+
+#include <cmath>
+
+#include "Robot.h"
+
+SetElevatorSetpoint::SetElevatorSetpoint(double setpoint)
+    : frc::Command("SetElevatorSetpoint") {
+  m_setpoint = setpoint;
+  Requires(&Robot::elevator);
+}
+
+// Called just before this Command runs the first time
+void SetElevatorSetpoint::Initialize() {
+  Robot::elevator.SetSetpoint(m_setpoint);
+  Robot::elevator.Enable();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool SetElevatorSetpoint::IsFinished() { return Robot::elevator.OnTarget(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetWristSetpoint.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetWristSetpoint.cpp
new file mode 100644
index 0000000..e9dc2af
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/SetWristSetpoint.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/SetWristSetpoint.h"
+
+#include "Robot.h"
+
+SetWristSetpoint::SetWristSetpoint(double setpoint)
+    : frc::Command("SetWristSetpoint") {
+  m_setpoint = setpoint;
+  Requires(&Robot::wrist);
+}
+
+// Called just before this Command runs the first time
+void SetWristSetpoint::Initialize() {
+  Robot::wrist.SetSetpoint(m_setpoint);
+  Robot::wrist.Enable();
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool SetWristSetpoint::IsFinished() { return Robot::wrist.OnTarget(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/TankDriveWithJoystick.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/TankDriveWithJoystick.cpp
new file mode 100644
index 0000000..a1be9a3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/commands/TankDriveWithJoystick.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/TankDriveWithJoystick.h"
+
+#include "Robot.h"
+
+TankDriveWithJoystick::TankDriveWithJoystick()
+    : frc::Command("TankDriveWithJoystick") {
+  Requires(&Robot::drivetrain);
+}
+
+// Called repeatedly when this Command is scheduled to run
+void TankDriveWithJoystick::Execute() {
+  auto& joystick = Robot::oi.GetJoystick();
+  Robot::drivetrain.Drive(-joystick.GetY(), -joystick.GetRawAxis(4));
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool TankDriveWithJoystick::IsFinished() { return false; }
+
+// Called once after isFinished returns true
+void TankDriveWithJoystick::End() { Robot::drivetrain.Drive(0, 0); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Claw.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Claw.cpp
new file mode 100644
index 0000000..8bad17f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Claw.cpp
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/Claw.h"
+
+Claw::Claw() : frc::Subsystem("Claw") {
+  // Let's show everything on the LiveWindow
+  AddChild("Motor", m_motor);
+}
+
+void Claw::InitDefaultCommand() {}
+
+void Claw::Open() { m_motor.Set(-1); }
+
+void Claw::Close() { m_motor.Set(1); }
+
+void Claw::Stop() { m_motor.Set(0); }
+
+bool Claw::IsGripping() { return m_contact.Get(); }
+
+void Claw::Log() {}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/DriveTrain.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/DriveTrain.cpp
new file mode 100644
index 0000000..4110485
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/DriveTrain.cpp
@@ -0,0 +1,75 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/DriveTrain.h"
+
+#include <frc/Joystick.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+#include "commands/TankDriveWithJoystick.h"
+
+DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") {
+// Encoders may measure differently in the real world and in
+// simulation. In this example the robot moves 0.042 barleycorns
+// per tick in the real world, but the simulated encoders
+// simulate 360 tick encoders. This if statement allows for the
+// real robot to handle this difference in devices.
+#ifndef SIMULATION
+  m_leftEncoder.SetDistancePerPulse(0.042);
+  m_rightEncoder.SetDistancePerPulse(0.042);
+#else
+  // Circumference in ft = 4in/12(in/ft)*PI
+  m_leftEncoder.SetDistancePerPulse(static_cast<double>(4.0 / 12.0 * M_PI) /
+                                    360.0);
+  m_rightEncoder.SetDistancePerPulse(static_cast<double>(4.0 / 12.0 * M_PI) /
+                                     360.0);
+#endif
+
+  // Let's show everything on the LiveWindow
+  // AddChild("Front_Left Motor", m_frontLeft);
+  // AddChild("Rear Left Motor", m_rearLeft);
+  // AddChild("Front Right Motor", m_frontRight);
+  // AddChild("Rear Right Motor", m_rearRight);
+  AddChild("Left Encoder", m_leftEncoder);
+  AddChild("Right Encoder", m_rightEncoder);
+  AddChild("Rangefinder", m_rangefinder);
+  AddChild("Gyro", m_gyro);
+}
+
+void DriveTrain::InitDefaultCommand() {
+  SetDefaultCommand(new TankDriveWithJoystick());
+}
+
+void DriveTrain::Log() {
+  frc::SmartDashboard::PutNumber("Left Distance", m_leftEncoder.GetDistance());
+  frc::SmartDashboard::PutNumber("Right Distance",
+                                 m_rightEncoder.GetDistance());
+  frc::SmartDashboard::PutNumber("Left Speed", m_leftEncoder.GetRate());
+  frc::SmartDashboard::PutNumber("Right Speed", m_rightEncoder.GetRate());
+  frc::SmartDashboard::PutNumber("Gyro", m_gyro.GetAngle());
+}
+
+void DriveTrain::Drive(double left, double right) {
+  m_robotDrive.TankDrive(left, right);
+}
+
+double DriveTrain::GetHeading() { return m_gyro.GetAngle(); }
+
+void DriveTrain::Reset() {
+  m_gyro.Reset();
+  m_leftEncoder.Reset();
+  m_rightEncoder.Reset();
+}
+
+double DriveTrain::GetDistance() {
+  return (m_leftEncoder.GetDistance() + m_rightEncoder.GetDistance()) / 2.0;
+}
+
+double DriveTrain::GetDistanceToObstacle() {
+  // Really meters in simulation since it's a rangefinder...
+  return m_rangefinder.GetAverageVoltage();
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Elevator.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Elevator.cpp
new file mode 100644
index 0000000..5318481
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Elevator.cpp
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/Elevator.h"
+
+#include <frc/livewindow/LiveWindow.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+Elevator::Elevator() : frc::PIDSubsystem("Elevator", kP_real, kI_real, 0.0) {
+#ifdef SIMULATION  // Check for simulation and update PID values
+  GetPIDController()->SetPID(kP_simulation, kI_simulation, 0, 0);
+#endif
+  SetAbsoluteTolerance(0.005);
+
+  // Let's show everything on the LiveWindow
+  AddChild("Motor", m_motor);
+  AddChild("Pot", &m_pot);
+}
+
+void Elevator::InitDefaultCommand() {}
+
+void Elevator::Log() {
+  // frc::SmartDashboard::PutData("Wrist Pot", &m_pot);
+}
+
+double Elevator::ReturnPIDInput() { return m_pot.Get(); }
+
+void Elevator::UsePIDOutput(double d) { m_motor.Set(d); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp
new file mode 100644
index 0000000..9bab812
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/cpp/subsystems/Wrist.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/Wrist.h"
+
+#include <frc/smartdashboard/SmartDashboard.h>
+
+Wrist::Wrist() : frc::PIDSubsystem("Wrist", kP_real, 0.0, 0.0) {
+#ifdef SIMULATION  // Check for simulation and update PID values
+  GetPIDController()->SetPID(kP_simulation, 0, 0, 0);
+#endif
+  SetAbsoluteTolerance(2.5);
+
+  // Let's show everything on the LiveWindow
+  AddChild("Motor", m_motor);
+  AddChild("Pot", m_pot);
+}
+
+void Wrist::InitDefaultCommand() {}
+
+void Wrist::Log() {
+  // frc::SmartDashboard::PutData("Wrist Angle", &m_pot);
+}
+
+double Wrist::ReturnPIDInput() { return m_pot.Get(); }
+
+void Wrist::UsePIDOutput(double d) { m_motor.Set(d); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/OI.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/OI.h
new file mode 100644
index 0000000..77e50b9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/OI.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/Joystick.h>
+#include <frc/buttons/JoystickButton.h>
+
+class OI {
+ public:
+  OI();
+  frc::Joystick& GetJoystick();
+
+ private:
+  frc::Joystick m_joy{0};
+
+  // Create some buttons
+  frc::JoystickButton m_dUp{&m_joy, 5};
+  frc::JoystickButton m_dRight{&m_joy, 6};
+  frc::JoystickButton m_dDown{&m_joy, 7};
+  frc::JoystickButton m_dLeft{&m_joy, 8};
+  frc::JoystickButton m_l2{&m_joy, 9};
+  frc::JoystickButton m_r2{&m_joy, 10};
+  frc::JoystickButton m_l1{&m_joy, 11};
+  frc::JoystickButton m_r1{&m_joy, 12};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/Robot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/Robot.h
new file mode 100644
index 0000000..015bbc0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/Robot.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/TimedRobot.h>
+#include <frc/commands/Command.h>
+#include <frc/commands/Scheduler.h>
+#include <frc/livewindow/LiveWindow.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+#include "OI.h"
+#include "commands/Autonomous.h"
+#include "subsystems/Claw.h"
+#include "subsystems/DriveTrain.h"
+#include "subsystems/Elevator.h"
+#include "subsystems/Wrist.h"
+
+class Robot : public frc::TimedRobot {
+ public:
+  static DriveTrain drivetrain;
+  static Elevator elevator;
+  static Wrist wrist;
+  static Claw claw;
+  static OI oi;
+
+ private:
+  Autonomous m_autonomousCommand;
+  frc::LiveWindow& m_lw = *frc::LiveWindow::GetInstance();
+
+  void RobotInit() override;
+  void AutonomousInit() override;
+  void AutonomousPeriodic() override;
+  void TeleopInit() override;
+  void TeleopPeriodic() override;
+  void TestPeriodic() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Autonomous.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Autonomous.h
new file mode 100644
index 0000000..e90098e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Autonomous.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+/**
+ * The main autonomous command to pickup and deliver the soda to the box.
+ */
+class Autonomous : public frc::CommandGroup {
+ public:
+  Autonomous();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h
new file mode 100644
index 0000000..bda8a5f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Opens the claw for one second. Real robots should use sensors, stalling
+ * motors is BAD!
+ */
+class CloseClaw : public frc::Command {
+ public:
+  CloseClaw();
+  void Initialize() override;
+  bool IsFinished() override;
+  void End() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/DriveStraight.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/DriveStraight.h
new file mode 100644
index 0000000..f03e46c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/DriveStraight.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/PIDController.h>
+#include <frc/PIDOutput.h>
+#include <frc/PIDSource.h>
+#include <frc/commands/Command.h>
+
+/**
+ * Drive the given distance straight (negative values go backwards).
+ * Uses a local PID controller to run a simple PID loop that is only
+ * enabled while this command is running. The input is the averaged
+ * values of the left and right encoders.
+ */
+class DriveStraight : public frc::Command {
+ public:
+  explicit DriveStraight(double distance);
+  void Initialize() override;
+  bool IsFinished() override;
+  void End() override;
+
+  class DriveStraightPIDSource : public frc::PIDSource {
+   public:
+    virtual ~DriveStraightPIDSource() = default;
+    double PIDGet() override;
+  };
+
+  class DriveStraightPIDOutput : public frc::PIDOutput {
+   public:
+    virtual ~DriveStraightPIDOutput() = default;
+    void PIDWrite(double d) override;
+  };
+
+ private:
+  DriveStraightPIDSource m_source;
+  DriveStraightPIDOutput m_output;
+  frc::PIDController m_pid{4, 0, 0, &m_source, &m_output};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/OpenClaw.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/OpenClaw.h
new file mode 100644
index 0000000..c2a7cfb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/OpenClaw.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Opens the claw for one second. Real robots should use sensors, stalling
+ * motors is BAD!
+ */
+class OpenClaw : public frc::Command {
+ public:
+  OpenClaw();
+  void Initialize() override;
+  bool IsFinished() override;
+  void End() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Pickup.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Pickup.h
new file mode 100644
index 0000000..ed68990
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Pickup.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+/**
+ * Pickup a soda can (if one is between the open claws) and
+ * get it in a safe state to drive around.
+ */
+class Pickup : public frc::CommandGroup {
+ public:
+  Pickup();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Place.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Place.h
new file mode 100644
index 0000000..7695393
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/Place.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+/**
+ * Place a held soda can onto the platform.
+ */
+class Place : public frc::CommandGroup {
+ public:
+  Place();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/PrepareToPickup.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/PrepareToPickup.h
new file mode 100644
index 0000000..c58035d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/PrepareToPickup.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+/**
+ * Make sure the robot is in a state to pickup soda cans.
+ */
+class PrepareToPickup : public frc::CommandGroup {
+ public:
+  PrepareToPickup();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetDistanceToBox.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetDistanceToBox.h
new file mode 100644
index 0000000..884a09b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetDistanceToBox.h
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/PIDController.h>
+#include <frc/PIDOutput.h>
+#include <frc/PIDSource.h>
+#include <frc/commands/Command.h>
+
+/**
+ * Drive until the robot is the given distance away from the box. Uses a local
+ * PID controller to run a simple PID loop that is only enabled while this
+ * command is running. The input is the averaged values of the left and right
+ * encoders.
+ */
+class SetDistanceToBox : public frc::Command {
+ public:
+  explicit SetDistanceToBox(double distance);
+  void Initialize() override;
+  bool IsFinished() override;
+  void End() override;
+
+  class SetDistanceToBoxPIDSource : public frc::PIDSource {
+   public:
+    virtual ~SetDistanceToBoxPIDSource() = default;
+    double PIDGet() override;
+  };
+
+  class SetDistanceToBoxPIDOutput : public frc::PIDOutput {
+   public:
+    virtual ~SetDistanceToBoxPIDOutput() = default;
+    void PIDWrite(double d) override;
+  };
+
+ private:
+  SetDistanceToBoxPIDSource m_source;
+  SetDistanceToBoxPIDOutput m_output;
+  frc::PIDController m_pid{-2, 0, 0, &m_source, &m_output};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h
new file mode 100644
index 0000000..388ac0e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Move the elevator to a given location. This command finishes when it is
+ * within
+ * the tolerance, but leaves the PID loop running to maintain the position.
+ * Other
+ * commands using the elevator should make sure they disable PID!
+ */
+class SetElevatorSetpoint : public frc::Command {
+ public:
+  explicit SetElevatorSetpoint(double setpoint);
+  void Initialize() override;
+  bool IsFinished() override;
+
+ private:
+  double m_setpoint;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h
new file mode 100644
index 0000000..effb173
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Move the wrist to a given angle. This command finishes when it is within
+ * the tolerance, but leaves the PID loop running to maintain the position.
+ * Other commands using the wrist should make sure they disable PID!
+ */
+class SetWristSetpoint : public frc::Command {
+ public:
+  explicit SetWristSetpoint(double setpoint);
+  void Initialize() override;
+  bool IsFinished() override;
+
+ private:
+  double m_setpoint;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDriveWithJoystick.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDriveWithJoystick.h
new file mode 100644
index 0000000..9337025
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDriveWithJoystick.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Have the robot drive tank style using the PS3 Joystick until interrupted.
+ */
+class TankDriveWithJoystick : public frc::Command {
+ public:
+  TankDriveWithJoystick();
+  void Execute() override;
+  bool IsFinished() override;
+  void End() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h
new file mode 100644
index 0000000..96a436a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/DigitalInput.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/commands/Subsystem.h>
+
+/**
+ * The claw subsystem is a simple system with a motor for opening and closing.
+ * If using stronger motors, you should probably use a sensor so that the
+ * motors don't stall.
+ */
+class Claw : public frc::Subsystem {
+ public:
+  Claw();
+
+  void InitDefaultCommand() override;
+
+  /**
+   * Set the claw motor to move in the open direction.
+   */
+  void Open();
+
+  /**
+   * Set the claw motor to move in the close direction.
+   */
+  void Close();
+
+  /**
+   * Stops the claw motor from moving.
+   */
+  void Stop();
+
+  /**
+   * Return true when the robot is grabbing an object hard enough
+   * to trigger the limit switch.
+   */
+  bool IsGripping();
+
+  void Log();
+
+ private:
+  frc::PWMVictorSPX m_motor{7};
+  frc::DigitalInput m_contact{5};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/DriveTrain.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/DriveTrain.h
new file mode 100644
index 0000000..dce4d9c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/DriveTrain.h
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/AnalogGyro.h>
+#include <frc/AnalogInput.h>
+#include <frc/Encoder.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/SpeedControllerGroup.h>
+#include <frc/commands/Subsystem.h>
+#include <frc/drive/DifferentialDrive.h>
+
+namespace frc {
+class Joystick;
+}  // namespace frc
+
+/**
+ * The DriveTrain subsystem incorporates the sensors and actuators attached to
+ * the robots chassis. These include four drive motors, a left and right encoder
+ * and a gyro.
+ */
+class DriveTrain : public frc::Subsystem {
+ public:
+  DriveTrain();
+
+  /**
+   * When no other command is running let the operator drive around
+   * using the PS3 joystick.
+   */
+  void InitDefaultCommand() override;
+
+  /**
+   * The log method puts interesting information to the SmartDashboard.
+   */
+  void Log();
+
+  /**
+   * Tank style driving for the DriveTrain.
+   * @param left Speed in range [-1,1]
+   * @param right Speed in range [-1,1]
+   */
+  void Drive(double left, double right);
+
+  /**
+   * @return The robots heading in degrees.
+   */
+  double GetHeading();
+
+  /**
+   * Reset the robots sensors to the zero states.
+   */
+  void Reset();
+
+  /**
+   * @return The distance driven (average of left and right encoders).
+   */
+  double GetDistance();
+
+  /**
+   * @return The distance to the obstacle detected by the rangefinder.
+   */
+  double GetDistanceToObstacle();
+
+ private:
+  frc::PWMVictorSPX m_frontLeft{1};
+  frc::PWMVictorSPX m_rearLeft{2};
+  frc::SpeedControllerGroup m_left{m_frontLeft, m_rearLeft};
+
+  frc::PWMVictorSPX m_frontRight{3};
+  frc::PWMVictorSPX m_rearRight{4};
+  frc::SpeedControllerGroup m_right{m_frontRight, m_rearRight};
+
+  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+
+  frc::Encoder m_leftEncoder{1, 2};
+  frc::Encoder m_rightEncoder{3, 4};
+  frc::AnalogInput m_rangefinder{6};
+  frc::AnalogGyro m_gyro{1};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Elevator.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Elevator.h
new file mode 100644
index 0000000..53f6057
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Elevator.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/AnalogPotentiometer.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/commands/PIDSubsystem.h>
+
+/**
+ * The elevator subsystem uses PID to go to a given height. Unfortunately, in
+ * it's current
+ * state PID values for simulation are different than in the real world do to
+ * minor differences.
+ */
+class Elevator : public frc::PIDSubsystem {
+ public:
+  Elevator();
+
+  void InitDefaultCommand() override;
+
+  /**
+   * The log method puts interesting information to the SmartDashboard.
+   */
+  void Log();
+
+  /**
+   * Use the potentiometer as the PID sensor. This method is automatically
+   * called by the subsystem.
+   */
+  double ReturnPIDInput() override;
+
+  /**
+   * Use the motor as the PID output. This method is automatically called
+   * by
+   * the subsystem.
+   */
+  void UsePIDOutput(double d) override;
+
+ private:
+  frc::PWMVictorSPX m_motor{5};
+
+// Conversion value of potentiometer varies between the real world and
+// simulation
+#ifndef SIMULATION
+  frc::AnalogPotentiometer m_pot{2, -2.0 / 5};
+#else
+  frc::AnalogPotentiometer m_pot{2};  // Defaults to meters
+#endif
+
+  static constexpr double kP_real = 4;
+  static constexpr double kI_real = 0.07;
+  static constexpr double kP_simulation = 18;
+  static constexpr double kI_simulation = 0.2;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h
new file mode 100644
index 0000000..26fc74b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Wrist.h
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/AnalogPotentiometer.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/commands/PIDSubsystem.h>
+
+/**
+ * The wrist subsystem is like the elevator, but with a rotational joint instead
+ * of a linear joint.
+ */
+class Wrist : public frc::PIDSubsystem {
+ public:
+  Wrist();
+
+  void InitDefaultCommand() override;
+
+  /**
+   * The log method puts interesting information to the SmartDashboard.
+   */
+  void Log();
+
+  /**
+   * Use the potentiometer as the PID sensor. This method is automatically
+   * called by the subsystem.
+   */
+  double ReturnPIDInput() override;
+
+  /**
+   * Use the motor as the PID output. This method is automatically called
+   * by
+   * the subsystem.
+   */
+  void UsePIDOutput(double d) override;
+
+ private:
+  frc::PWMVictorSPX m_motor{6};
+
+// Conversion value of potentiometer varies between the real world and
+// simulation
+#ifndef SIMULATION
+  frc::AnalogPotentiometer m_pot{3, -270.0 / 5};
+#else
+  frc::AnalogPotentiometer m_pot{3};  // Defaults to degrees
+#endif
+
+  static constexpr double kP_real = 1;
+  static constexpr double kP_simulation = 0.05;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
new file mode 100644
index 0000000..f43cb57
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/Timer.h>
+#include <frc/drive/DifferentialDrive.h>
+#include <frc/livewindow/LiveWindow.h>
+
+class Robot : public frc::TimedRobot {
+ public:
+  Robot() {
+    m_robotDrive.SetExpiration(0.1);
+    m_timer.Start();
+  }
+
+  void AutonomousInit() override {
+    m_timer.Reset();
+    m_timer.Start();
+  }
+
+  void AutonomousPeriodic() override {
+    // Drive for 2 seconds
+    if (m_timer.Get() < 2.0) {
+      // Drive forwards half speed
+      m_robotDrive.ArcadeDrive(-0.5, 0.0);
+    } else {
+      // Stop robot
+      m_robotDrive.ArcadeDrive(0.0, 0.0);
+    }
+  }
+
+  void TeleopInit() override {}
+
+  void TeleopPeriodic() override {
+    // Drive with arcade style (use right stick)
+    m_robotDrive.ArcadeDrive(m_stick.GetY(), m_stick.GetX());
+  }
+
+  void TestPeriodic() override {}
+
+ private:
+  // Robot drive system
+  frc::PWMVictorSPX m_left{0};
+  frc::PWMVictorSPX m_right{1};
+  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+
+  frc::Joystick m_stick{0};
+  frc::LiveWindow& m_lw = *frc::LiveWindow::GetInstance();
+  frc::Timer m_timer;
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
new file mode 100644
index 0000000..b0c70d2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <cmath>
+
+#include <frc/AnalogGyro.h>
+#include <frc/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/drive/DifferentialDrive.h>
+
+/**
+ * This is a sample program to demonstrate how to use a gyro sensor to make a
+ * robot drive straight. This program uses a joystick to drive forwards and
+ * backwards while the gyro is used for direction keeping.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override { m_gyro.SetSensitivity(kVoltsPerDegreePerSecond); }
+
+  /**
+   * The motor speed is set from the joystick while the DifferentialDrive
+   * turning value is assigned from the error between the setpoint and the gyro
+   * angle.
+   */
+  void TeleopPeriodic() override {
+    double turningValue = (kAngleSetpoint - m_gyro.GetAngle()) * kP;
+    // Invert the direction of the turn if we are going backwards
+    turningValue = std::copysign(turningValue, m_joystick.GetY());
+    m_robotDrive.ArcadeDrive(m_joystick.GetY(), turningValue);
+  }
+
+ private:
+  static constexpr double kAngleSetpoint = 0.0;
+  static constexpr double kP = 0.005;  // Proportional turning constant
+
+  // Gyro calibration constant, may need to be adjusted. Gyro value of 360 is
+  // set to correspond to one full revolution.
+  static constexpr double kVoltsPerDegreePerSecond = 0.0128;
+
+  static constexpr int kLeftMotorPort = 0;
+  static constexpr int kRightMotorPort = 1;
+  static constexpr int kGyroPort = 0;
+  static constexpr int kJoystickPort = 0;
+
+  frc::PWMVictorSPX m_left{kLeftMotorPort};
+  frc::PWMVictorSPX m_right{kRightMotorPort};
+  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+
+  frc::AnalogGyro m_gyro{kGyroPort};
+  frc::Joystick m_joystick{kJoystickPort};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
new file mode 100644
index 0000000..738ff32
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/AnalogGyro.h>
+#include <frc/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/drive/MecanumDrive.h>
+
+/**
+ * This is a sample program that uses mecanum drive with a gyro sensor to
+ * maintian rotation vectorsin relation to the starting orientation of the robot
+ * (field-oriented controls).
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override {
+    // Invert the left side motors. You may need to change or remove this to
+    // match your robot.
+    m_frontLeft.SetInverted(true);
+    m_rearLeft.SetInverted(true);
+
+    m_gyro.SetSensitivity(kVoltsPerDegreePerSecond);
+  }
+
+  /**
+   * Mecanum drive is used with the gyro angle as an input.
+   */
+  void TeleopPeriodic() override {
+    m_robotDrive.DriveCartesian(m_joystick.GetX(), m_joystick.GetY(),
+                                m_joystick.GetZ(), m_gyro.GetAngle());
+  }
+
+ private:
+  // Gyro calibration constant, may need to be adjusted. Gyro value of 360 is
+  // set to correspond to one full revolution.
+  static constexpr double kVoltsPerDegreePerSecond = 0.0128;
+
+  static constexpr int kFrontLeftMotorPort = 0;
+  static constexpr int kRearLeftMotorPort = 1;
+  static constexpr int kFrontRightMotorPort = 2;
+  static constexpr int kRearRightMotorPort = 3;
+  static constexpr int kGyroPort = 0;
+  static constexpr int kJoystickPort = 0;
+
+  frc::PWMVictorSPX m_frontLeft{kFrontLeftMotorPort};
+  frc::PWMVictorSPX m_rearLeft{kRearLeftMotorPort};
+  frc::PWMVictorSPX m_frontRight{kFrontRightMotorPort};
+  frc::PWMVictorSPX m_rearRight{kRearRightMotorPort};
+  frc::MecanumDrive m_robotDrive{m_frontLeft, m_rearLeft, m_frontRight,
+                                 m_rearRight};
+
+  frc::AnalogGyro m_gyro{kGyroPort};
+  frc::Joystick m_joystick{kJoystickPort};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c
new file mode 100644
index 0000000..dedb0f2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/HAL/c/Robot.c
@@ -0,0 +1,123 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+This example shows how to use the HAL directly, and what is needed to run a
+basic program. The sample is compiled in C, however the functionality works from
+C++ as well.
+
+The HAL is considered a stable but changeable API. The API is stable during a
+season, and is safe to use for events. However, between seasons there might be
+changes to the API. This is an advanced sample, and should only be used by users
+that want even more control over what code runs on their robot.
+*/
+
+#include <stdio.h>
+
+#include "hal/HAL.h"
+
+enum DriverStationMode {
+  DisabledMode,
+  TeleopMode,
+  TestMode,
+  AutoMode,
+};
+
+enum DriverStationMode getDSMode(void) {
+  // Get Robot State
+  HAL_ControlWord word;
+  HAL_GetControlWord(&word);
+
+  // We send the observes, otherwise the DS disables
+  if (!word.enabled) {
+    HAL_ObserveUserProgramDisabled();
+    return DisabledMode;
+  } else {
+    if (word.autonomous) {
+      HAL_ObserveUserProgramAutonomous();
+      return AutoMode;
+    } else if (word.test) {
+      HAL_ObserveUserProgramTest();
+      return TestMode;
+    } else {
+      HAL_ObserveUserProgramTeleop();
+      return TeleopMode;
+    }
+  }
+}
+
+int main(void) {
+  // Must initialize the HAL, 500ms timeout
+  HAL_Bool initialized = HAL_Initialize(500, 0);
+  if (!initialized) {
+    printf("Failed to initialize the HAL\n");
+    return 1;
+  }
+
+  int32_t status = 0;
+
+  // For DS to see valid robot code
+  HAL_ObserveUserProgramStarting();
+
+  // Create a Motor Controller
+  status = 0;
+  HAL_DigitalHandle pwmPort = HAL_InitializePWMPort(HAL_GetPort(2), &status);
+
+  if (status != 0) {
+    const char* message = HAL_GetErrorMessage(status);
+    printf("%s\n", message);
+    return 1;
+  }
+
+  // Set PWM config to standard servo speeds
+  HAL_SetPWMConfig(pwmPort, 2.0, 1.501, 1.5, 1.499, 1.0, &status);
+
+  // Create an Input
+  status = 0;
+  HAL_DigitalHandle dio = HAL_InitializeDIOPort(HAL_GetPort(2), 1, &status);
+
+  if (status != 0) {
+    const char* message = HAL_GetErrorMessage(status);
+    printf("%s\n", message);
+    status = 0;
+    HAL_FreePWMPort(pwmPort, &status);
+    return 1;
+  }
+
+  while (1) {
+    // Wait for DS data, with a timeout
+    HAL_Bool validData = HAL_WaitForDSDataTimeout(1.0);
+    if (!validData) {
+      // Do something here on no packet
+      continue;
+    }
+    enum DriverStationMode dsMode = getDSMode();
+    switch (dsMode) {
+      case DisabledMode:
+        break;
+      case TeleopMode:
+        status = 0;
+        if (HAL_GetDIO(dio, &status)) {
+          HAL_SetPWMSpeed(pwmPort, 1.0, &status);
+        } else {
+          HAL_SetPWMSpeed(pwmPort, 0, &status);
+        }
+        break;
+      case AutoMode:
+        break;
+      case TestMode:
+        break;
+      default:
+        break;
+    }
+  }
+
+  // Clean up resources
+  status = 0;
+  HAL_FreeDIOPort(dio);
+  HAL_FreePWMPort(pwmPort, &status);
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp
new file mode 100644
index 0000000..3deafa5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* 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/GenericHID.h>
+#include <frc/TimedRobot.h>
+#include <frc/XboxController.h>
+
+/**
+ * This is a demo program showing the use of GenericHID's rumble feature.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void AutonomousInit() override {
+    // Turn on rumble at the start of auto
+    m_hid.SetRumble(frc::GenericHID::RumbleType::kLeftRumble, 1.0);
+    m_hid.SetRumble(frc::GenericHID::RumbleType::kRightRumble, 1.0);
+  }
+
+  void DisabledInit() override {
+    // Stop the rumble when entering disabled
+    m_hid.SetRumble(frc::GenericHID::RumbleType::kLeftRumble, 0.0);
+    m_hid.SetRumble(frc::GenericHID::RumbleType::kRightRumble, 0.0);
+  }
+
+ private:
+  frc::XboxController m_hid{0};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp
new file mode 100644
index 0000000..ae2ac83
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <thread>
+
+#include <cameraserver/CameraServer.h>
+#include <frc/TimedRobot.h>
+#include <opencv2/core/core.hpp>
+#include <opencv2/core/types.hpp>
+#include <opencv2/imgproc/imgproc.hpp>
+#include <wpi/raw_ostream.h>
+
+/**
+ * This is a demo program showing the use of OpenCV to do vision processing. The
+ * image is acquired from the USB camera, then a rectangle is put on the image
+ * and sent to the dashboard. OpenCV has many methods for different types of
+ * processing.
+ */
+class Robot : public frc::TimedRobot {
+#if defined(__linux__)
+
+ private:
+  static void VisionThread() {
+    // Get the USB camera from CameraServer
+    cs::UsbCamera camera =
+        frc::CameraServer::GetInstance()->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();
+    // Setup a CvSource. This will send images back to the Dashboard
+    cs::CvSource outputStream =
+        frc::CameraServer::GetInstance()->PutVideo("Rectangle", 640, 480);
+
+    // Mats are very memory expensive. Lets reuse this Mat.
+    cv::Mat mat;
+
+    while (true) {
+      // Tell the CvSink to grab a frame from the camera and
+      // put it
+      // in the source mat.  If there is an error notify the
+      // output.
+      if (cvSink.GrabFrame(mat) == 0) {
+        // Send the output the error.
+        outputStream.NotifyError(cvSink.GetError());
+        // skip the rest of the current iteration
+        continue;
+      }
+      // Put a rectangle on the image
+      rectangle(mat, cv::Point(100, 100), cv::Point(400, 400),
+                cv::Scalar(255, 255, 255), 5);
+      // Give the output stream a new image to display
+      outputStream.PutFrame(mat);
+    }
+  }
+#endif
+
+  void RobotInit() override {
+  // We need to run our vision program in a separate thread. If not, our robot
+  // program will not run.
+#if defined(__linux__)
+    std::thread visionThread(VisionThread);
+    visionThread.detach();
+#else
+    wpi::errs() << "Vision only available on Linux.\n";
+    wpi::errs().flush();
+#endif
+  }
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
new file mode 100644
index 0000000..8b4c98c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/drive/MecanumDrive.h>
+
+/**
+ * This is a demo program showing how to use Mecanum control with the
+ * MecanumDrive class.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override {
+    // Invert the left side motors. You may need to change or remove this to
+    // match your robot.
+    m_frontLeft.SetInverted(true);
+    m_rearLeft.SetInverted(true);
+  }
+
+  void TeleopPeriodic() override {
+    /* Use the joystick X axis for lateral movement, Y axis for forward
+     * movement, and Z axis for rotation.
+     */
+    m_robotDrive.DriveCartesian(m_stick.GetX(), m_stick.GetY(), m_stick.GetZ());
+  }
+
+ private:
+  static constexpr int kFrontLeftChannel = 0;
+  static constexpr int kRearLeftChannel = 1;
+  static constexpr int kFrontRightChannel = 2;
+  static constexpr int kRearRightChannel = 3;
+
+  static constexpr int kJoystickChannel = 0;
+
+  frc::PWMVictorSPX m_frontLeft{kFrontLeftChannel};
+  frc::PWMVictorSPX m_rearLeft{kRearLeftChannel};
+  frc::PWMVictorSPX m_frontRight{kFrontRightChannel};
+  frc::PWMVictorSPX m_rearRight{kRearRightChannel};
+  frc::MecanumDrive m_robotDrive{m_frontLeft, m_rearLeft, m_frontRight,
+                                 m_rearRight};
+
+  frc::Joystick m_stick{kJoystickChannel};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp
new file mode 100644
index 0000000..2217ec1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+
+/**
+ * This sample program shows how to control a motor using a joystick. In the
+ * operator control part of the program, the joystick is read and the value is
+ * written to the motor.
+ *
+ * Joystick analog values range from -1 to 1 and speed controller inputs as
+ * range from -1 to 1 making it easy to work together.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void TeleopPeriodic() override { m_motor.Set(m_stick.GetY()); }
+
+ private:
+  frc::Joystick m_stick{0};
+  frc::PWMVictorSPX m_motor{0};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp
new file mode 100644
index 0000000..78e1e96
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/MotorControlEncoder/cpp/Robot.cpp
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/Encoder.h>
+#include <frc/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+constexpr double kPi = 3.14159265358979;
+
+/**
+ * This sample program shows how to control a motor using a joystick. In the
+ * operator control part of the program, the joystick is read and the value is
+ * written to the motor.
+ *
+ * Joystick analog values range from -1 to 1 and speed controller inputs as
+ * range from -1 to 1 making it easy to work together.
+ *
+ * In addition, the encoder value of an encoder connected to ports 0 and 1 is
+ * consistently sent to the Dashboard.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void TeleopPeriodic() override { m_motor.Set(m_stick.GetY()); }
+
+  /*
+   * The RobotPeriodic function is called every control packet no matter the
+   * robot mode.
+   */
+  void RobotPeriodic() override {
+    frc::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance());
+  }
+
+  void RobotInit() override {
+    // Use SetDistancePerPulse to set the multiplier for GetDistance
+    // This is set up assuming a 6 inch wheel with a 360 CPR encoder.
+    m_encoder.SetDistancePerPulse((kPi * 6) / 360.0);
+  }
+
+ private:
+  frc::Joystick m_stick{0};
+  frc::PWMVictorSPX m_motor{0};
+  frc::Encoder m_encoder{0, 1};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/OI.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/OI.cpp
new file mode 100644
index 0000000..c5fcb15
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/OI.cpp
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "OI.h"
+
+#include <frc/smartdashboard/SmartDashboard.h>
+
+#include "commands/Collect.h"
+#include "commands/DriveForward.h"
+#include "commands/LowGoal.h"
+#include "commands/SetCollectionSpeed.h"
+#include "commands/SetPivotSetpoint.h"
+#include "commands/Shoot.h"
+#include "subsystems/Collector.h"
+#include "subsystems/Pivot.h"
+
+OI::OI() {
+  m_r1.WhenPressed(new LowGoal());
+  m_r2.WhenPressed(new Collect());
+
+  m_l1.WhenPressed(new SetPivotSetpoint(Pivot::kShoot));
+  m_l2.WhenPressed(new SetPivotSetpoint(Pivot::kShootNear));
+
+  m_sticks.WhenActive(new Shoot());
+
+  // SmartDashboard Buttons
+  frc::SmartDashboard::PutData("Drive Forward", new DriveForward(2.25));
+  frc::SmartDashboard::PutData("Drive Backward", new DriveForward(-2.25));
+  frc::SmartDashboard::PutData("Start Rollers",
+                               new SetCollectionSpeed(Collector::kForward));
+  frc::SmartDashboard::PutData("Stop Rollers",
+                               new SetCollectionSpeed(Collector::kStop));
+  frc::SmartDashboard::PutData("Reverse Rollers",
+                               new SetCollectionSpeed(Collector::kReverse));
+}
+
+frc::Joystick& OI::GetJoystick() { return m_joystick; }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/Robot.cpp
new file mode 100644
index 0000000..9da27f3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/Robot.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "Robot.h"
+
+#include <iostream>
+
+#include <frc/commands/Scheduler.h>
+#include <frc/livewindow/LiveWindow.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+DriveTrain Robot::drivetrain;
+Pivot Robot::pivot;
+Collector Robot::collector;
+Shooter Robot::shooter;
+Pneumatics Robot::pneumatics;
+OI Robot::oi;
+
+void Robot::RobotInit() {
+  // Show what command your subsystem is running on the SmartDashboard
+  frc::SmartDashboard::PutData(&drivetrain);
+  frc::SmartDashboard::PutData(&pivot);
+  frc::SmartDashboard::PutData(&collector);
+  frc::SmartDashboard::PutData(&shooter);
+  frc::SmartDashboard::PutData(&pneumatics);
+
+  // instantiate the command used for the autonomous period
+  m_autoChooser.SetDefaultOption("Drive and Shoot", &m_driveAndShootAuto);
+  m_autoChooser.AddOption("Drive Forward", &m_driveForwardAuto);
+  frc::SmartDashboard::PutData("Auto Mode", &m_autoChooser);
+
+  pneumatics.Start();  // Pressurize the pneumatics.
+}
+
+void Robot::AutonomousInit() {
+  m_autonomousCommand = m_autoChooser.GetSelected();
+  m_autonomousCommand->Start();
+}
+
+void Robot::AutonomousPeriodic() {
+  frc::Scheduler::GetInstance()->Run();
+  Log();
+}
+
+void Robot::TeleopInit() {
+  // This makes sure that the autonomous stops running when
+  // teleop starts running. If you want the autonomous to
+  // continue until interrupted by another command, remove
+  // this line or comment it out.
+  if (m_autonomousCommand != nullptr) {
+    m_autonomousCommand->Cancel();
+  }
+  std::cout << "Starting Teleop" << std::endl;
+}
+
+void Robot::TeleopPeriodic() {
+  frc::Scheduler::GetInstance()->Run();
+  Log();
+}
+
+void Robot::TestPeriodic() {}
+
+void Robot::DisabledInit() { shooter.Unlatch(); }
+
+void Robot::DisabledPeriodic() { Log(); }
+
+/**
+ * Log interesting values to the SmartDashboard.
+ */
+void Robot::Log() {
+  Robot::pneumatics.WritePressure();
+  frc::SmartDashboard::PutNumber("Pivot Pot Value", pivot.GetAngle());
+  frc::SmartDashboard::PutNumber("Left Distance",
+                                 drivetrain.GetLeftEncoder().GetDistance());
+  frc::SmartDashboard::PutNumber("Right Distance",
+                                 drivetrain.GetRightEncoder().GetDistance());
+}
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/CheckForHotGoal.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/CheckForHotGoal.cpp
new file mode 100644
index 0000000..c5d80c0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/CheckForHotGoal.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/CheckForHotGoal.h"
+
+#include "Robot.h"
+
+CheckForHotGoal::CheckForHotGoal(double time) { SetTimeout(time); }
+
+// Make this return true when this Command no longer needs to run execute()
+bool CheckForHotGoal::IsFinished() {
+  return IsTimedOut() || Robot::shooter.GoalIsHot();
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/CloseClaw.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/CloseClaw.cpp
new file mode 100644
index 0000000..8db41f3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/CloseClaw.cpp
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/CloseClaw.h"
+
+#include "Robot.h"
+
+CloseClaw::CloseClaw() { Requires(&Robot::collector); }
+
+// Called just before this Command runs the first time
+void CloseClaw::Initialize() { Robot::collector.Close(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/Collect.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/Collect.cpp
new file mode 100644
index 0000000..b51c2df
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/Collect.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/Collect.h"
+
+#include "Robot.h"
+#include "commands/CloseClaw.h"
+#include "commands/SetCollectionSpeed.h"
+#include "commands/SetPivotSetpoint.h"
+#include "commands/WaitForBall.h"
+
+Collect::Collect() {
+  AddSequential(new SetCollectionSpeed(Collector::kForward));
+  AddParallel(new CloseClaw());
+  AddSequential(new SetPivotSetpoint(Pivot::kCollect));
+  AddSequential(new WaitForBall());
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveAndShootAutonomous.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveAndShootAutonomous.cpp
new file mode 100644
index 0000000..3486292
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveAndShootAutonomous.cpp
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/DriveAndShootAutonomous.h"
+
+#include "Robot.h"
+#include "commands/CheckForHotGoal.h"
+#include "commands/CloseClaw.h"
+#include "commands/DriveForward.h"
+#include "commands/SetPivotSetpoint.h"
+#include "commands/Shoot.h"
+#include "commands/WaitForPressure.h"
+
+DriveAndShootAutonomous::DriveAndShootAutonomous() {
+  AddSequential(new CloseClaw());
+  AddSequential(new WaitForPressure(), 2);
+#ifndef SIMULATION
+  // NOTE: Simulation doesn't currently have the concept of hot.
+  AddSequential(new CheckForHotGoal(2));
+#endif
+  AddSequential(new SetPivotSetpoint(45));
+  AddSequential(new DriveForward(8, 0.3));
+  AddSequential(new Shoot());
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveForward.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveForward.cpp
new file mode 100644
index 0000000..1de5846
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveForward.cpp
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/DriveForward.h"
+
+#include <cmath>
+
+#include "Robot.h"
+
+void DriveForward::init(double dist, double maxSpeed) {
+  Requires(&Robot::drivetrain);
+  m_distance = dist;
+  m_driveForwardSpeed = maxSpeed;
+}
+
+DriveForward::DriveForward() { init(10, 0.5); }
+
+DriveForward::DriveForward(double dist) { init(dist, 0.5); }
+
+DriveForward::DriveForward(double dist, double maxSpeed) {
+  init(dist, maxSpeed);
+}
+
+// Called just before this Command runs the first time
+void DriveForward::Initialize() {
+  Robot::drivetrain.GetRightEncoder().Reset();
+  SetTimeout(2);
+}
+
+// Called repeatedly when this Command is scheduled to run
+void DriveForward::Execute() {
+  m_error = (m_distance - Robot::drivetrain.GetRightEncoder().GetDistance());
+  if (m_driveForwardSpeed * kP * m_error >= m_driveForwardSpeed) {
+    Robot::drivetrain.TankDrive(m_driveForwardSpeed, m_driveForwardSpeed);
+  } else {
+    Robot::drivetrain.TankDrive(m_driveForwardSpeed * kP * m_error,
+                                m_driveForwardSpeed * kP * m_error);
+  }
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool DriveForward::IsFinished() {
+  return (std::fabs(m_error) <= kTolerance) || IsTimedOut();
+}
+
+// Called once after isFinished returns true
+void DriveForward::End() { Robot::drivetrain.Stop(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveWithJoystick.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveWithJoystick.cpp
new file mode 100644
index 0000000..7704d70
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/DriveWithJoystick.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/DriveWithJoystick.h"
+
+#include "Robot.h"
+
+DriveWithJoystick::DriveWithJoystick() { Requires(&Robot::drivetrain); }
+
+// Called repeatedly when this Command is scheduled to run
+void DriveWithJoystick::Execute() {
+  auto& joystick = Robot::oi.GetJoystick();
+  Robot::drivetrain.TankDrive(joystick.GetY(), joystick.GetRawAxis(4));
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool DriveWithJoystick::IsFinished() { return false; }
+
+// Called once after isFinished returns true
+void DriveWithJoystick::End() { Robot::drivetrain.Stop(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/ExtendShooter.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/ExtendShooter.cpp
new file mode 100644
index 0000000..53494c9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/ExtendShooter.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/ExtendShooter.h"
+
+#include "Robot.h"
+
+ExtendShooter::ExtendShooter() : frc::TimedCommand(1.0) {
+  Requires(&Robot::shooter);
+}
+
+// Called just before this Command runs the first time
+void ExtendShooter::Initialize() { Robot::shooter.ExtendBoth(); }
+
+// Called once after isFinished returns true
+void ExtendShooter::End() { Robot::shooter.RetractBoth(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/LowGoal.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/LowGoal.cpp
new file mode 100644
index 0000000..f4ed788
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/LowGoal.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/LowGoal.h"
+
+#include "Robot.h"
+#include "commands/ExtendShooter.h"
+#include "commands/SetCollectionSpeed.h"
+#include "commands/SetPivotSetpoint.h"
+
+LowGoal::LowGoal() {
+  AddSequential(new SetPivotSetpoint(Pivot::kLowGoal));
+  AddSequential(new SetCollectionSpeed(Collector::kReverse));
+  AddSequential(new ExtendShooter());
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/OpenClaw.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/OpenClaw.cpp
new file mode 100644
index 0000000..4e4a9c8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/OpenClaw.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/OpenClaw.h"
+
+#include "Robot.h"
+
+OpenClaw::OpenClaw() { Requires(&Robot::collector); }
+
+// Called just before this Command runs the first time
+void OpenClaw::Initialize() { Robot::collector.Open(); }
+
+// Make this return true when this Command no longer needs to run execute()
+bool OpenClaw::IsFinished() { return Robot::collector.IsOpen(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/SetCollectionSpeed.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/SetCollectionSpeed.cpp
new file mode 100644
index 0000000..2011a02
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/SetCollectionSpeed.cpp
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/SetCollectionSpeed.h"
+
+#include "Robot.h"
+
+SetCollectionSpeed::SetCollectionSpeed(double speed) {
+  Requires(&Robot::collector);
+  m_speed = speed;
+}
+
+// Called just before this Command runs the first time
+void SetCollectionSpeed::Initialize() { Robot::collector.SetSpeed(m_speed); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/SetPivotSetpoint.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/SetPivotSetpoint.cpp
new file mode 100644
index 0000000..f9929de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/SetPivotSetpoint.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/SetPivotSetpoint.h"
+
+#include "Robot.h"
+
+SetPivotSetpoint::SetPivotSetpoint(double setpoint) {
+  m_setpoint = setpoint;
+  Requires(&Robot::pivot);
+}
+
+// Called just before this Command runs the first time
+void SetPivotSetpoint::Initialize() {
+  Robot::pivot.Enable();
+  Robot::pivot.SetSetpoint(m_setpoint);
+}
+
+// Make this return true when this Command no longer needs to run execute()
+bool SetPivotSetpoint::IsFinished() { return Robot::pivot.OnTarget(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/Shoot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/Shoot.cpp
new file mode 100644
index 0000000..836ccd2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/Shoot.cpp
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/Shoot.h"
+
+#include "Robot.h"
+#include "commands/ExtendShooter.h"
+#include "commands/OpenClaw.h"
+#include "commands/SetCollectionSpeed.h"
+#include "commands/WaitForPressure.h"
+
+Shoot::Shoot() {
+  AddSequential(new WaitForPressure());
+  AddSequential(new SetCollectionSpeed(Collector::kStop));
+  AddSequential(new OpenClaw());
+  AddSequential(new ExtendShooter());
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/WaitForBall.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/WaitForBall.cpp
new file mode 100644
index 0000000..daf9665
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/WaitForBall.cpp
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/WaitForBall.h"
+
+#include "Robot.h"
+
+WaitForBall::WaitForBall() { Requires(&Robot::collector); }
+
+// Make this return true when this Command no longer needs to run execute()
+bool WaitForBall::IsFinished() { return Robot::collector.HasBall(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/WaitForPressure.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/WaitForPressure.cpp
new file mode 100644
index 0000000..00cc454
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/commands/WaitForPressure.cpp
@@ -0,0 +1,15 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/WaitForPressure.h"
+
+#include "Robot.h"
+
+WaitForPressure::WaitForPressure() { Requires(&Robot::pneumatics); }
+
+// Make this return true when this Command no longer needs to run execute()
+bool WaitForPressure::IsFinished() { return Robot::pneumatics.IsPressurized(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Collector.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Collector.cpp
new file mode 100644
index 0000000..8f345ce
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Collector.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/Collector.h"
+
+#include <frc/livewindow/LiveWindow.h>
+
+Collector::Collector() : frc::Subsystem("Collector") {
+  // Put everything to the LiveWindow for testing.
+  AddChild("Roller Motor", m_rollerMotor);
+  AddChild("Ball Detector", m_ballDetector);
+  AddChild("Claw Open Detector", m_openDetector);
+  AddChild("Piston", m_piston);
+}
+
+bool Collector::HasBall() {
+  return m_ballDetector.Get();  // TODO: prepend ! to reflect real robot
+}
+
+void Collector::SetSpeed(double speed) { m_rollerMotor.Set(-speed); }
+
+void Collector::Stop() { m_rollerMotor.Set(0); }
+
+bool Collector::IsOpen() {
+  return m_openDetector.Get();  // TODO: prepend ! to reflect real robot
+}
+
+void Collector::Open() { m_piston.Set(true); }
+
+void Collector::Close() { m_piston.Set(false); }
+
+void Collector::InitDefaultCommand() {}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/DriveTrain.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/DriveTrain.cpp
new file mode 100644
index 0000000..53cb625
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/DriveTrain.cpp
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/DriveTrain.h"
+
+#include <cmath>
+
+#include <frc/Joystick.h>
+
+#include "commands/DriveWithJoystick.h"
+
+DriveTrain::DriveTrain() : frc::Subsystem("DriveTrain") {
+  // AddChild("Front Left CIM", m_frontLeftCIM);
+  // AddChild("Front Right CIM", m_frontRightCIM);
+  // AddChild("Back Left CIM", m_backLeftCIM);
+  // AddChild("Back Right CIM", m_backRightCIM);
+
+  // Configure the DifferentialDrive to reflect the fact that all our
+  // motors are wired backwards and our drivers sensitivity preferences.
+  m_robotDrive.SetSafetyEnabled(false);
+  m_robotDrive.SetExpiration(0.1);
+  m_robotDrive.SetMaxOutput(1.0);
+  m_leftCIMs.SetInverted(true);
+  m_rightCIMs.SetInverted(true);
+
+  // Configure encoders
+  m_rightEncoder.SetPIDSourceType(frc::PIDSourceType::kDisplacement);
+  m_leftEncoder.SetPIDSourceType(frc::PIDSourceType::kDisplacement);
+
+#ifndef SIMULATION
+  // Converts to feet
+  m_rightEncoder.SetDistancePerPulse(0.0785398);
+  m_leftEncoder.SetDistancePerPulse(0.0785398);
+#else
+  // Convert to feet 4in diameter wheels with 360 tick simulated encoders
+  m_rightEncoder.SetDistancePerPulse((4.0 /*in*/ * M_PI) /
+                                     (360.0 * 12.0 /*in/ft*/));
+  m_leftEncoder.SetDistancePerPulse((4.0 /*in*/ * M_PI) /
+                                    (360.0 * 12.0 /*in/ft*/));
+#endif
+
+  AddChild("Right Encoder", m_rightEncoder);
+  AddChild("Left Encoder", m_leftEncoder);
+
+// Configure gyro
+#ifndef SIMULATION
+  m_gyro.SetSensitivity(0.007);  // TODO: Handle more gracefully?
+#endif
+  AddChild("Gyro", m_gyro);
+}
+
+void DriveTrain::InitDefaultCommand() {
+  SetDefaultCommand(new DriveWithJoystick());
+}
+
+void DriveTrain::TankDrive(double leftAxis, double rightAxis) {
+  m_robotDrive.TankDrive(leftAxis, rightAxis);
+}
+
+void DriveTrain::Stop() { m_robotDrive.TankDrive(0.0, 0.0); }
+
+frc::Encoder& DriveTrain::GetLeftEncoder() { return m_leftEncoder; }
+
+frc::Encoder& DriveTrain::GetRightEncoder() { return m_rightEncoder; }
+
+double DriveTrain::GetAngle() { return m_gyro.GetAngle(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pivot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pivot.cpp
new file mode 100644
index 0000000..861d583
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pivot.cpp
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/Pivot.h"
+
+Pivot::Pivot() : frc::PIDSubsystem("Pivot", 7.0, 0.0, 8.0) {
+  SetAbsoluteTolerance(0.005);
+  GetPIDController()->SetContinuous(false);
+#ifdef SIMULATION
+  // PID is different in simulation.
+  GetPIDController()->SetPID(0.5, 0.001, 2);
+  SetAbsoluteTolerance(5);
+#endif
+
+  // Put everything to the LiveWindow for testing.
+  AddChild("Upper Limit Switch", m_upperLimitSwitch);
+  AddChild("Lower Limit Switch", m_lowerLimitSwitch);
+  AddChild("Pot", m_pot);
+  AddChild("Motor", m_motor);
+}
+
+void InitDefaultCommand() {}
+
+double Pivot::ReturnPIDInput() { return m_pot.Get(); }
+
+void Pivot::UsePIDOutput(double output) { m_motor.PIDWrite(output); }
+
+bool Pivot::IsAtUpperLimit() {
+  return m_upperLimitSwitch.Get();  // TODO: inverted from real robot
+                                    // (prefix with !)
+}
+
+bool Pivot::IsAtLowerLimit() {
+  return m_lowerLimitSwitch.Get();  // TODO: inverted from real robot
+                                    // (prefix with !)
+}
+
+double Pivot::GetAngle() { return m_pot.Get(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pneumatics.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pneumatics.cpp
new file mode 100644
index 0000000..dd1a824
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Pneumatics.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/Pneumatics.h"
+
+#include <frc/smartdashboard/SmartDashboard.h>
+
+Pneumatics::Pneumatics() : frc::Subsystem("Pneumatics") {
+  AddChild("Pressure Sensor", m_pressureSensor);
+}
+
+void Pneumatics::InitDefaultCommand() {
+  // No default command
+}
+
+void Pneumatics::Start() {
+#ifndef SIMULATION
+  m_compressor.Start();
+#endif
+}
+
+bool Pneumatics::IsPressurized() {
+#ifndef SIMULATION
+  return kMaxPressure <= m_pressureSensor.GetVoltage();
+#else
+  return true;  // NOTE: Simulation always has full pressure
+#endif
+}
+
+void Pneumatics::WritePressure() {
+  frc::SmartDashboard::PutNumber("Pressure", m_pressureSensor.GetVoltage());
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Shooter.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Shooter.cpp
new file mode 100644
index 0000000..80d7ac3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/subsystems/Shooter.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/Shooter.h"
+
+Shooter::Shooter() : Subsystem("Shooter") {
+  // Put everything to the LiveWindow for testing.
+  AddChild("Hot Goal Sensor", m_hotGoalSensor);
+  AddChild("Piston1 Reed Switch Front ", m_piston1ReedSwitchFront);
+  AddChild("Piston1 Reed Switch Back ", m_piston1ReedSwitchBack);
+  AddChild("Latch Piston", m_latchPiston);
+}
+
+void Shooter::InitDefaultCommand() {
+  // Set the default command for a subsystem here.
+  // SetDefaultCommand(new MySpecialCommand());
+}
+
+void Shooter::ExtendBoth() {
+  m_piston1.Set(frc::DoubleSolenoid::kForward);
+  m_piston2.Set(frc::DoubleSolenoid::kForward);
+}
+
+void Shooter::RetractBoth() {
+  m_piston1.Set(frc::DoubleSolenoid::kReverse);
+  m_piston2.Set(frc::DoubleSolenoid::kReverse);
+}
+
+void Shooter::Extend1() { m_piston1.Set(frc::DoubleSolenoid::kForward); }
+
+void Shooter::Retract1() { m_piston1.Set(frc::DoubleSolenoid::kReverse); }
+
+void Shooter::Extend2() { m_piston2.Set(frc::DoubleSolenoid::kReverse); }
+
+void Shooter::Retract2() { m_piston2.Set(frc::DoubleSolenoid::kForward); }
+
+void Shooter::Off1() { m_piston1.Set(frc::DoubleSolenoid::kOff); }
+
+void Shooter::Off2() { m_piston2.Set(frc::DoubleSolenoid::kOff); }
+
+void Shooter::Unlatch() { m_latchPiston.Set(true); }
+
+void Shooter::Latch() { m_latchPiston.Set(false); }
+
+void Shooter::ToggleLatchPosition() { m_latchPiston.Set(!m_latchPiston.Get()); }
+
+bool Shooter::Piston1IsExtended() { return !m_piston1ReedSwitchFront.Get(); }
+
+bool Shooter::Piston1IsRetracted() { return !m_piston1ReedSwitchBack.Get(); }
+
+void Shooter::OffBoth() {
+  m_piston1.Set(frc::DoubleSolenoid::kOff);
+  m_piston2.Set(frc::DoubleSolenoid::kOff);
+}
+
+bool Shooter::GoalIsHot() { return m_hotGoalSensor.Get(); }
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/triggers/DoubleButton.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/triggers/DoubleButton.cpp
new file mode 100644
index 0000000..f2f7f64
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/cpp/triggers/DoubleButton.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "triggers/DoubleButton.h"
+
+#include <frc/Joystick.h>
+
+DoubleButton::DoubleButton(frc::Joystick* joy, int button1, int button2)
+    : m_joy(*joy) {
+  m_button1 = button1;
+  m_button2 = button2;
+}
+
+bool DoubleButton::Get() {
+  return m_joy.GetRawButton(m_button1) && m_joy.GetRawButton(m_button2);
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/OI.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/OI.h
new file mode 100644
index 0000000..2df4395
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/OI.h
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/Joystick.h>
+#include <frc/buttons/JoystickButton.h>
+
+#include "triggers/DoubleButton.h"
+
+class OI {
+ public:
+  OI();
+  frc::Joystick& GetJoystick();
+
+ private:
+  frc::Joystick m_joystick{0};
+
+  frc::JoystickButton m_l1{&m_joystick, 11};
+  frc::JoystickButton m_l2{&m_joystick, 9};
+  frc::JoystickButton m_r1{&m_joystick, 12};
+  frc::JoystickButton m_r2{&m_joystick, 10};
+
+  DoubleButton m_sticks{&m_joystick, 2, 3};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/Robot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/Robot.h
new file mode 100644
index 0000000..b24085d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/Robot.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/TimedRobot.h>
+#include <frc/commands/Command.h>
+#include <frc/smartdashboard/SendableChooser.h>
+
+#include "OI.h"
+#include "commands/DriveAndShootAutonomous.h"
+#include "commands/DriveForward.h"
+#include "subsystems/Collector.h"
+#include "subsystems/DriveTrain.h"
+#include "subsystems/Pivot.h"
+#include "subsystems/Pneumatics.h"
+#include "subsystems/Shooter.h"
+
+class Robot : public frc::TimedRobot {
+ public:
+  static DriveTrain drivetrain;
+  static Pivot pivot;
+  static Collector collector;
+  static Shooter shooter;
+  static Pneumatics pneumatics;
+  static OI oi;
+
+ private:
+  frc::Command* m_autonomousCommand = nullptr;
+  DriveAndShootAutonomous m_driveAndShootAuto;
+  DriveForward m_driveForwardAuto;
+  frc::SendableChooser<frc::Command*> m_autoChooser;
+
+  void RobotInit() override;
+  void AutonomousInit() override;
+  void AutonomousPeriodic() override;
+  void TeleopInit() override;
+  void TeleopPeriodic() override;
+  void TestPeriodic() override;
+  void DisabledInit() override;
+  void DisabledPeriodic() override;
+
+  void Log();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/CheckForHotGoal.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/CheckForHotGoal.h
new file mode 100644
index 0000000..9f42461
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/CheckForHotGoal.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * This command looks for the hot goal and waits until it's detected or timed
+ * out. The timeout is because it's better to shoot and get some autonomous
+ * points than get none. When called sequentially, this command will block until
+ * the hot goal is detected or until it is timed out.
+ */
+class CheckForHotGoal : public frc::Command {
+ public:
+  explicit CheckForHotGoal(double time);
+  bool IsFinished() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/CloseClaw.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/CloseClaw.h
new file mode 100644
index 0000000..60f12a9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/CloseClaw.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/InstantCommand.h>
+
+/**
+ * Close the claw.
+ *
+ * NOTE: It doesn't wait for the claw to close since there is no sensor to
+ * detect that.
+ */
+class CloseClaw : public frc::InstantCommand {
+ public:
+  CloseClaw();
+  void Initialize() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/Collect.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/Collect.h
new file mode 100644
index 0000000..c2965c2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/Collect.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+/**
+ * Get the robot set to collect balls.
+ */
+class Collect : public frc::CommandGroup {
+ public:
+  Collect();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveAndShootAutonomous.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveAndShootAutonomous.h
new file mode 100644
index 0000000..e143738
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveAndShootAutonomous.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+/**
+ * Drive over the line and then shoot the ball. If the hot goal is not detected,
+ * it will wait briefly.
+ */
+class DriveAndShootAutonomous : public frc::CommandGroup {
+ public:
+  DriveAndShootAutonomous();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveForward.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveForward.h
new file mode 100644
index 0000000..a89134e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveForward.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * This command drives the robot over a given distance with simple proportional
+ * control This command will drive a given distance limiting to a maximum speed.
+ */
+class DriveForward : public frc::Command {
+ public:
+  DriveForward();
+  explicit DriveForward(double dist);
+  DriveForward(double dist, double maxSpeed);
+  void Initialize() override;
+  void Execute() override;
+  bool IsFinished() override;
+  void End() override;
+
+ private:
+  double m_driveForwardSpeed;
+  double m_distance;
+  double m_error = 0;
+  static constexpr double kTolerance = 0.1;
+  static constexpr double kP = -1.0 / 5.0;
+
+  void init(double dist, double maxSpeed);
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveWithJoystick.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveWithJoystick.h
new file mode 100644
index 0000000..e6d9b0e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/DriveWithJoystick.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * This command allows PS3 joystick to drive the robot. It is always running
+ * except when interrupted by another command.
+ */
+class DriveWithJoystick : public frc::Command {
+ public:
+  DriveWithJoystick();
+  void Execute() override;
+  bool IsFinished() override;
+  void End() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/ExtendShooter.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/ExtendShooter.h
new file mode 100644
index 0000000..634860e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/ExtendShooter.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/TimedCommand.h>
+
+/**
+ * Extend the shooter and then retract it after a second.
+ */
+class ExtendShooter : public frc::TimedCommand {
+ public:
+  ExtendShooter();
+  void Initialize() override;
+  void End() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/LowGoal.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/LowGoal.h
new file mode 100644
index 0000000..62237fe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/LowGoal.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+/**
+ * Spit the ball out into the low goal assuming that the robot is in front of
+ * it.
+ */
+class LowGoal : public frc::CommandGroup {
+ public:
+  LowGoal();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/OpenClaw.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/OpenClaw.h
new file mode 100644
index 0000000..0d78877
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/OpenClaw.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Opens the claw
+ */
+class OpenClaw : public frc::Command {
+ public:
+  OpenClaw();
+  void Initialize() override;
+  bool IsFinished() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/SetCollectionSpeed.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/SetCollectionSpeed.h
new file mode 100644
index 0000000..24bb4e3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/SetCollectionSpeed.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/InstantCommand.h>
+
+/**
+ * This command sets the collector rollers spinning at the given speed. Since
+ * there is no sensor for detecting speed, it finishes immediately. As a result,
+ * the spinners may still be adjusting their speed.
+ */
+class SetCollectionSpeed : public frc::InstantCommand {
+ public:
+  explicit SetCollectionSpeed(double speed);
+  void Initialize() override;
+
+ private:
+  double m_speed;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/SetPivotSetpoint.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/SetPivotSetpoint.h
new file mode 100644
index 0000000..8f8f615
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/SetPivotSetpoint.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Moves the  pivot to a given angle. This command finishes when it is within
+ * the tolerance, but leaves the PID loop running to maintain the position.
+ * Other commands using the pivot should make sure they disable PID!
+ */
+class SetPivotSetpoint : public frc::Command {
+ public:
+  explicit SetPivotSetpoint(double setpoint);
+  void Initialize() override;
+  bool IsFinished() override;
+
+ private:
+  double m_setpoint;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/Shoot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/Shoot.h
new file mode 100644
index 0000000..242221c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/Shoot.h
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/CommandGroup.h>
+
+/**
+ * Shoot the ball at the current angle.
+ */
+class Shoot : public frc::CommandGroup {
+ public:
+  Shoot();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/WaitForBall.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/WaitForBall.h
new file mode 100644
index 0000000..b6d8d99
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/WaitForBall.h
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Wait until the collector senses that it has the ball. This command does
+ * nothing and is intended to be used in command groups to wait for this
+ * condition.
+ */
+class WaitForBall : public frc::Command {
+ public:
+  WaitForBall();
+  bool IsFinished() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/WaitForPressure.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/WaitForPressure.h
new file mode 100644
index 0000000..49e1f17
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/commands/WaitForPressure.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+/**
+ * Wait until the pneumatics are fully pressurized. This command does nothing
+ * and is intended to be used in command groups to wait for this condition.
+ */
+class WaitForPressure : public frc::Command {
+ public:
+  WaitForPressure();
+  bool IsFinished() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Collector.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Collector.h
new file mode 100644
index 0000000..3e237fa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Collector.h
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/DigitalInput.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/Solenoid.h>
+#include <frc/commands/Subsystem.h>
+
+/**
+ * The Collector subsystem has one motor for the rollers, a limit switch for
+ * ball
+ * detection, a piston for opening and closing the claw, and a reed switch to
+ * check if the piston is open.
+ */
+class Collector : public frc::Subsystem {
+ public:
+  // Constants for some useful speeds
+  static constexpr double kForward = 1;
+  static constexpr double kStop = 0;
+  static constexpr double kReverse = -1;
+
+  Collector();
+
+  /**
+   * NOTE: The current simulation model uses the the lower part of the
+   * claw
+   * since the limit switch wasn't exported. At some point, this will be
+   * updated.
+   *
+   * @return Whether or not the robot has the ball.
+   */
+  bool HasBall();
+
+  /**
+   * @param speed The speed to spin the rollers.
+   */
+  void SetSpeed(double speed);
+
+  /**
+   * Stop the rollers from spinning
+   */
+  void Stop();
+
+  /**
+   * @return Whether or not the claw is open.
+   */
+  bool IsOpen();
+
+  /**
+   * Open the claw up. (For shooting)
+   */
+  void Open();
+
+  /**
+   * Close the claw. (For collecting and driving)
+   */
+  void Close();
+
+  /**
+   * No default command.
+   */
+  void InitDefaultCommand() override;
+
+ private:
+  // Subsystem devices
+  frc::PWMVictorSPX m_rollerMotor{6};
+  frc::DigitalInput m_ballDetector{10};
+  frc::Solenoid m_piston{1};
+  frc::DigitalInput m_openDetector{6};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/DriveTrain.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/DriveTrain.h
new file mode 100644
index 0000000..0afa3eb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/DriveTrain.h
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/AnalogGyro.h>
+#include <frc/Encoder.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/SpeedControllerGroup.h>
+#include <frc/commands/Subsystem.h>
+#include <frc/drive/DifferentialDrive.h>
+
+namespace frc {
+class Joystick;
+}  // namespace frc
+
+/**
+ * The DriveTrain subsystem controls the robot's chassis and reads in
+ * information about it's speed and position.
+ */
+class DriveTrain : public frc::Subsystem {
+ public:
+  DriveTrain();
+
+  /**
+   * When other commands aren't using the drivetrain, allow tank drive
+   * with
+   * the joystick.
+   */
+  void InitDefaultCommand();
+
+  /**
+   * @param leftAxis Left sides value
+   * @param rightAxis Right sides value
+   */
+  void TankDrive(double leftAxis, double rightAxis);
+
+  /**
+   * Stop the drivetrain from moving.
+   */
+  void Stop();
+
+  /**
+   * @return The encoder getting the distance and speed of left side of
+   * the drivetrain.
+   */
+  frc::Encoder& GetLeftEncoder();
+
+  /**
+   * @return The encoder getting the distance and speed of right side of
+   * the drivetrain.
+   */
+  frc::Encoder& GetRightEncoder();
+
+  /**
+   * @return The current angle of the drivetrain.
+   */
+  double GetAngle();
+
+ private:
+  // Subsystem devices
+  frc::PWMVictorSPX m_frontLeftCIM{1};
+  frc::PWMVictorSPX m_rearLeftCIM{2};
+  frc::SpeedControllerGroup m_leftCIMs{m_frontLeftCIM, m_rearLeftCIM};
+
+  frc::PWMVictorSPX m_frontRightCIM{3};
+  frc::PWMVictorSPX m_rearRightCIM{4};
+  frc::SpeedControllerGroup m_rightCIMs{m_frontRightCIM, m_rearRightCIM};
+
+  frc::DifferentialDrive m_robotDrive{m_leftCIMs, m_rightCIMs};
+
+  frc::Encoder m_rightEncoder{1, 2, true, frc::Encoder::k4X};
+  frc::Encoder m_leftEncoder{3, 4, false, frc::Encoder::k4X};
+  frc::AnalogGyro m_gyro{0};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pivot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pivot.h
new file mode 100644
index 0000000..f9a3c25
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pivot.h
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/AnalogPotentiometer.h>
+#include <frc/DigitalInput.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/commands/PIDSubsystem.h>
+
+/**
+ * The Pivot subsystem contains the Van-door motor and the pot for PID control
+ * of angle of the pivot and claw.
+ */
+class Pivot : public frc::PIDSubsystem {
+ public:
+  // Constants for some useful angles
+  static constexpr double kCollect = 105;
+  static constexpr double kLowGoal = 90;
+  static constexpr double kShoot = 45;
+  static constexpr double kShootNear = 30;
+
+  Pivot();
+
+  /**
+   *  No default command, if PID is enabled, the current setpoint will be
+   * maintained.
+   */
+  void InitDefaultCommand() override {}
+
+  /**
+   * @return The angle read in by the potentiometer
+   */
+  double ReturnPIDInput() override;
+
+  /**
+   * Set the motor speed based off of the PID output
+   */
+  void UsePIDOutput(double output) override;
+
+  /**
+   * @return If the pivot is at its upper limit.
+   */
+  bool IsAtUpperLimit();
+
+  /**
+   * @return If the pivot is at its lower limit.
+   */
+  bool IsAtLowerLimit();
+
+  /**
+   * @return The current angle of the pivot.
+   */
+  double GetAngle();
+
+ private:
+  // Subsystem devices
+
+  // Sensors for measuring the position of the pivot
+  frc::DigitalInput m_upperLimitSwitch{13};
+  frc::DigitalInput m_lowerLimitSwitch{12};
+
+  /* 0 degrees is vertical facing up.
+   * Angle increases the more forward the pivot goes.
+   */
+  frc::AnalogPotentiometer m_pot{1};
+
+  // Motor to move the pivot
+  frc::PWMVictorSPX m_motor{5};
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pneumatics.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pneumatics.h
new file mode 100644
index 0000000..d321895
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Pneumatics.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/AnalogInput.h>
+#include <frc/Compressor.h>
+#include <frc/commands/Subsystem.h>
+
+/**
+ * The Pneumatics subsystem contains the compressor and a pressure sensor.
+ *
+ * NOTE: The simulator currently doesn't support the compressor or pressure
+ * sensors.
+ */
+class Pneumatics : public frc::Subsystem {
+ public:
+  Pneumatics();
+
+  /**
+   * No default command
+   */
+  void InitDefaultCommand() override;
+
+  /**
+   * Start the compressor going. The compressor automatically starts and
+   * stops as it goes above and below maximum pressure.
+   */
+  void Start();
+
+  /**
+   * @return Whether or not the system is fully pressurized.
+   */
+  bool IsPressurized();
+
+  /**
+   * Puts the pressure on the SmartDashboard.
+   */
+  void WritePressure();
+
+ private:
+  frc::AnalogInput m_pressureSensor{3};
+
+#ifndef SIMULATION
+  frc::Compressor m_compressor{1};  // TODO: (1, 14, 1, 8);
+#endif
+
+  static constexpr double kMaxPressure = 2.55;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Shooter.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Shooter.h
new file mode 100644
index 0000000..43f111a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/subsystems/Shooter.h
@@ -0,0 +1,127 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/DigitalInput.h>
+#include <frc/DoubleSolenoid.h>
+#include <frc/Solenoid.h>
+#include <frc/commands/Subsystem.h>
+
+/**
+ * The Shooter subsystem handles shooting. The mechanism for shooting is
+ * slightly complicated because it has to pneumatic cylinders for shooting, and
+ * a third latch to allow the pressure to partially build up and reduce the
+ * effect of the airflow. For shorter shots, when full power isn't needed, only
+ * one cylinder fires.
+ *
+ * NOTE: Simulation currently approximates this as as single pneumatic cylinder
+ * and ignores the latch.
+ */
+class Shooter : public frc::Subsystem {
+ public:
+  Shooter();
+  void InitDefaultCommand() override;
+
+  /**
+   * Extend both solenoids to shoot.
+   */
+  void ExtendBoth();
+
+  /**
+   * Retract both solenoids to prepare to shoot.
+   */
+  void RetractBoth();
+
+  /**
+   * Extend solenoid 1 to shoot.
+   */
+  void Extend1();
+
+  /**
+   * Retract solenoid 1 to prepare to shoot.
+   */
+  void Retract1();
+
+  /**
+   * Extend solenoid 2 to shoot.
+   */
+  void Extend2();
+
+  /**
+   * Retract solenoid 2 to prepare to shoot.
+   */
+  void Retract2();
+
+  /**
+   * Turns off the piston1 double solenoid. This won't actuate anything
+   * because double solenoids preserve their state when turned off. This
+   * should be called in order to reduce the amount of time that the coils
+   * are
+   * powered.
+   */
+  void Off1();
+
+  /**
+   * Turns off the piston1 double solenoid. This won't actuate anything
+   * because double solenoids preserve their state when turned off. This
+   * should be called in order to reduce the amount of time that the coils
+   * are
+   * powered.
+   */
+  void Off2();
+
+  /**
+   * Release the latch so that we can shoot
+   */
+  void Unlatch();
+
+  /**
+   * Latch so that pressure can build up and we aren't limited by air
+   * flow.
+   */
+  void Latch();
+
+  /**
+   * Toggles the latch postions
+   */
+  void ToggleLatchPosition();
+
+  /**
+   * @return Whether or not piston 1 is fully extended.
+   */
+  bool Piston1IsExtended();
+
+  /**
+   * @return Whether or not piston 1 is fully retracted.
+   */
+  bool Piston1IsRetracted();
+
+  /**
+   * Turns off all double solenoids. Double solenoids hold their position
+   * when
+   * they are turned off. We should turn them off whenever possible to
+   * extend
+   * the life of the coils
+   */
+  void OffBoth();
+
+  /**
+   * @return Whether or not the goal is hot as read by the banner sensor
+   */
+  bool GoalIsHot();
+
+ private:
+  // Devices
+  frc::DoubleSolenoid m_piston1{3, 4};
+  frc::DoubleSolenoid m_piston2{5, 6};
+  frc::Solenoid m_latchPiston{1, 2};
+  frc::DigitalInput m_piston1ReedSwitchFront{9};
+  frc::DigitalInput m_piston1ReedSwitchBack{11};
+  frc::DigitalInput m_hotGoalSensor{
+      7};  // NOTE: Currently ignored in simulation
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/triggers/DoubleButton.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/triggers/DoubleButton.h
new file mode 100644
index 0000000..562154b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PacGoat/include/triggers/DoubleButton.h
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/buttons/Trigger.h>
+
+namespace frc {
+class Joystick;
+}  // namespace frc
+
+class DoubleButton : public frc::Trigger {
+ public:
+  DoubleButton(frc::Joystick* joy, int button1, int button2);
+
+  bool Get();
+
+ private:
+  frc::Joystick& m_joy;
+  int m_button1;
+  int m_button2;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp
new file mode 100644
index 0000000..e01a04f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <frc/AnalogInput.h>
+#include <frc/Joystick.h>
+#include <frc/PIDController.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+
+/**
+ * This is a sample program to demonstrate how to use a soft potentiometer and a
+ * PID Controller to reach and maintain position setpoints on an elevator
+ * mechanism.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override { m_pidController.SetInputRange(0, 5); }
+
+  void TeleopInit() override { m_pidController.Enable(); }
+
+  void TeleopPeriodic() override {
+    // When the button is pressed once, the selected elevator setpoint is
+    // incremented.
+    bool currentButtonValue = m_joystick.GetTrigger();
+    if (currentButtonValue && !m_previousButtonValue) {
+      // Index of the elevator setpoint wraps around
+      m_index = (m_index + 1) % (sizeof(kSetPoints) / 8);
+    }
+    m_previousButtonValue = currentButtonValue;
+
+    m_pidController.SetSetpoint(kSetPoints[m_index]);
+  }
+
+ private:
+  static constexpr int kPotChannel = 1;
+  static constexpr int kMotorChannel = 7;
+  static constexpr int kJoystickChannel = 0;
+
+  // Bottom, middle, and top elevator setpoints
+  static constexpr std::array<double, 3> kSetPoints = {{1.0, 2.6, 4.3}};
+
+  /* Proportional, integral, and derivative speed constants; motor inverted.
+   *
+   * DANGER: When tuning PID constants, high/inappropriate values for pGain,
+   * iGain, and dGain may cause dangerous, uncontrollable, or undesired
+   * behavior!
+   *
+   * These may need to be positive for a non-inverted motor.
+   */
+  static constexpr double kP = -5.0;
+  static constexpr double kI = -0.02;
+  static constexpr double kD = -2.0;
+
+  int m_index = 0;
+  bool m_previousButtonValue = false;
+
+  frc::AnalogInput m_potentiometer{kPotChannel};
+  frc::Joystick m_joystick{kJoystickChannel};
+  frc::PWMVictorSPX m_elevatorMotor{kMotorChannel};
+
+  /* Potentiometer (AnalogInput) and elevatorMotor (Victor) can be used as a
+   * PIDSource and PIDOutput respectively.
+   */
+  frc::PIDController m_pidController{kP, kI, kD, m_potentiometer,
+                                     m_elevatorMotor};
+};
+
+constexpr std::array<double, 3> Robot::kSetPoints;
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp
new file mode 100644
index 0000000..1ad76de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <cameraserver/CameraServer.h>
+#include <frc/TimedRobot.h>
+#include <wpi/raw_ostream.h>
+
+/**
+ * Uses the CameraServer class to automatically capture video from a USB webcam
+ * and send it to the FRC dashboard without doing any vision processing. This is
+ * the easiest way to get camera images to the dashboard. Just add this to the
+ * RobotInit() method in your program.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override {
+#if defined(__linux__)
+    frc::CameraServer::GetInstance()->StartAutomaticCapture();
+#else
+    wpi::errs() << "Vision only available on Linux.\n";
+    wpi::errs().flush();
+#endif
+  }
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Relay/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Relay/cpp/Robot.cpp
new file mode 100644
index 0000000..8225b1c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Relay/cpp/Robot.cpp
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/Joystick.h>
+#include <frc/Relay.h>
+#include <frc/TimedRobot.h>
+
+/**
+ * This is a sample program which uses joystick buttons to control a relay.
+ *
+ * A Relay (generally a spike) has two outputs, each of which can be at either
+ * 0V or 12V and so can be used for actions such as turning a motor off, full
+ * forwards, or full reverse, and is generally used on the compressor.
+ *
+ * This program uses two buttons on a joystick and each button corresponds to
+ * one output; pressing the button sets the output to 12V and releasing sets it
+ * to 0V.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void TeleopPeriodic() override {
+    /* Retrieve the button values. GetRawButton() will return true if the button
+     * is pressed and false if not.
+     */
+    bool forward = m_stick.GetRawButton(kRelayForwardButton);
+    bool reverse = m_stick.GetRawButton(kRelayReverseButton);
+
+    /* Depending on the button values, we want to use one of kOn, kOff,
+     * kForward, or kReverse.
+     *
+     * kOn sets both outputs to 12V, kOff sets both to 0V.
+     * kForward sets forward to 12V and reverse to 0V.
+     * kReverse sets reverse to 12V and forward to 0V.
+     */
+    if (forward && reverse) {
+      m_relay.Set(frc::Relay::kOn);
+    } else if (forward) {
+      m_relay.Set(frc::Relay::kForward);
+    } else if (reverse) {
+      m_relay.Set(frc::Relay::kReverse);
+    } else {
+      m_relay.Set(frc::Relay::kOff);
+    }
+  }
+
+ private:
+  frc::Joystick m_stick{0};
+  frc::Relay m_relay{0};
+
+  static constexpr int kRelayForwardButton = 1;
+  static constexpr int kRelayReverseButton = 2;
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp
new file mode 100644
index 0000000..3447504
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/AnalogPotentiometer.h>
+#include <frc/Encoder.h>
+#include <frc/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/drive/DifferentialDrive.h>
+#include <frc/shuffleboard/Shuffleboard.h>
+#include <frc/shuffleboard/ShuffleboardLayout.h>
+#include <frc/shuffleboard/ShuffleboardTab.h>
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+
+/**
+ * This sample program provides an example for ShuffleBoard, an alternative
+ * to SmartDashboard for displaying values and properties of different robot
+ * parts.
+ *
+ * ShuffleBoard can use pre-programmed widgets to display various values, such
+ * as Boolean Boxes, Sliders, Graphs, and more. In addition, they can display
+ * things in various Tabs.
+ *
+ * For more information on how to create personal layouts and more in
+ * ShuffleBoard, feel free to reference the official FIRST WPILib documentation
+ * online.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override {
+    // Add a widget titled 'Max Speed' with a number slider.
+    m_maxSpeed = frc::Shuffleboard::GetTab("Configuration")
+                     .Add("Max Speed", 1)
+                     .WithWidget("Number Slider")
+                     .GetEntry();
+
+    // Create a 'DriveBase' tab and add the drivetrain object to it.
+    frc::ShuffleboardTab& driveBaseTab = frc::Shuffleboard::GetTab("DriveBase");
+    driveBaseTab.Add("TankDrive", m_robotDrive);
+
+    // Put encoders in a list layout.
+    frc::ShuffleboardLayout& encoders =
+        driveBaseTab.GetLayout("List Layout", "Encoders")
+            .WithPosition(0, 0)
+            .WithSize(2, 2);
+    encoders.Add("Left Encoder", m_leftEncoder);
+    encoders.Add("Right Encoder", m_rightEncoder);
+
+    // Create a 'Elevator' tab and add the potentiometer and elevator motor to
+    // it.
+    frc::ShuffleboardTab& elevatorTab = frc::Shuffleboard::GetTab("Elevator");
+    elevatorTab.Add("Motor", m_elevatorMotor);
+    elevatorTab.Add("Potentiometer", m_ElevatorPot);
+  }
+
+  void AutonomousInit() override {
+    // Update the Max Output for the drivetrain.
+    m_robotDrive.SetMaxOutput(m_maxSpeed.GetDouble(1.0));
+  }
+
+ private:
+  frc::PWMVictorSPX m_left{0};
+  frc::PWMVictorSPX m_right{1};
+  frc::PWMVictorSPX m_elevatorMotor{2};
+
+  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+
+  frc::Joystick m_stick{0};
+
+  frc::Encoder m_leftEncoder{0, 1};
+  frc::Encoder m_rightEncoder{2, 3};
+  frc::AnalogPotentiometer m_ElevatorPot{0};
+
+  nt::NetworkTableEntry m_maxSpeed;
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp
new file mode 100644
index 0000000..523a227
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/DoubleSolenoid.h>
+#include <frc/Joystick.h>
+#include <frc/Solenoid.h>
+#include <frc/TimedRobot.h>
+
+/**
+ * This is a sample program showing the use of the solenoid classes during
+ * operator control.
+ *
+ * Three buttons from a joystick will be used to control two solenoids: One
+ * button to control the position of a single solenoid and the other two buttons
+ * to control a double solenoid.
+ *
+ * Single solenoids can either be on or off, such that the air diverted through
+ * them goes through either one channel or the other.
+ *
+ * Double solenoids have three states: Off, Forward, and Reverse. Forward and
+ * Reverse divert the air through the two channels and correspond to the on and
+ * off of a single solenoid, but a double solenoid can also be "off", where both
+ * channels are diverted to exhaust such that there is no pressure in either
+ * channel.
+ *
+ * Additionally, double solenoids take up two channels on your PCM whereas
+ * single solenoids only take a single channel.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  void TeleopPeriodic() override {
+    /* The output of GetRawButton is true/false depending on whether the button
+     * is pressed; Set takes a boolean for for whether to use the default
+     * (false) channel or the other (true).
+     */
+    m_solenoid.Set(m_stick.GetRawButton(kSolenoidButton));
+
+    /* In order to set the double solenoid, we will say that if neither button
+     * is pressed, it is off, if just one button is pressed, set the solenoid to
+     * correspond to that button, and if both are pressed, set the solenoid to
+     * Forwards.
+     */
+    if (m_stick.GetRawButton(kDoubleSolenoidForward)) {
+      m_doubleSolenoid.Set(frc::DoubleSolenoid::kForward);
+    } else if (m_stick.GetRawButton(kDoubleSolenoidReverse)) {
+      m_doubleSolenoid.Set(frc::DoubleSolenoid::kReverse);
+    } else {
+      m_doubleSolenoid.Set(frc::DoubleSolenoid::kOff);
+    }
+  }
+
+ private:
+  frc::Joystick m_stick{0};
+
+  // Solenoid corresponds to a single solenoid.
+  frc::Solenoid m_solenoid{0};
+
+  // DoubleSolenoid corresponds to a double solenoid.
+  frc::DoubleSolenoid m_doubleSolenoid{1, 2};
+
+  static constexpr int kSolenoidButton = 1;
+  static constexpr int kDoubleSolenoidForward = 2;
+  static constexpr int kDoubleSolenoidReverse = 3;
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp
new file mode 100644
index 0000000..2cc2131
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/Ultrasonic/cpp/Robot.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/AnalogInput.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/drive/DifferentialDrive.h>
+
+/**
+ * This is a sample program demonstrating how to use an ultrasonic sensor and
+ * proportional control to maintain a set distance from an object.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  /**
+   * Tells the robot to drive to a set distance (in inches) from an object using
+   * proportional control.
+   */
+  void TeleopPeriodic() override {
+    // Sensor returns a value from 0-4095 that is scaled to inches
+    double currentDistance = m_ultrasonic.GetValue() * kValueToInches;
+    // Convert distance error to a motor speed
+    double currentSpeed = (kHoldDistance - currentDistance) * kP;
+    // Drive robot
+    m_robotDrive.ArcadeDrive(currentSpeed, 0);
+  }
+
+ private:
+  // Distance in inches the robot wants to stay from an object
+  static constexpr int kHoldDistance = 12;
+
+  // Factor to convert sensor values to a distance in inches
+  static constexpr double kValueToInches = 0.125;
+
+  // Proportional speed constant
+  static constexpr double kP = 0.05;
+
+  static constexpr int kLeftMotorPort = 0;
+  static constexpr int kRightMotorPort = 1;
+  static constexpr int kUltrasonicPort = 0;
+
+  frc::AnalogInput m_ultrasonic{kUltrasonicPort};
+
+  frc::PWMVictorSPX m_left{kLeftMotorPort};
+  frc::PWMVictorSPX m_right{kRightMotorPort};
+  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp
new file mode 100644
index 0000000..67aec78
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/UltrasonicPID/cpp/Robot.cpp
@@ -0,0 +1,85 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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/AnalogInput.h>
+#include <frc/PIDController.h>
+#include <frc/PIDOutput.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/TimedRobot.h>
+#include <frc/drive/DifferentialDrive.h>
+
+/**
+ * This is a sample program demonstrating how to use an ultrasonic sensor and
+ * proportional control to maintain a set distance from an object.
+ */
+class Robot : public frc::TimedRobot {
+ public:
+  /**
+   * Drives the robot a set distance from an object using PID control and the
+   * ultrasonic sensor.
+   */
+  void TeleopInit() override {
+    // Set expected range to 0-24 inches; e.g. at 24 inches from object go full
+    // forward, at 0 inches from object go full backward.
+    m_pidController.SetInputRange(0, 24 * kValueToInches);
+
+    // Set setpoint of the PID Controller
+    m_pidController.SetSetpoint(kHoldDistance * kValueToInches);
+
+    // Begin PID control
+    m_pidController.Enable();
+  }
+
+ private:
+  // Internal class to write to robot drive using a PIDOutput
+  class MyPIDOutput : public frc::PIDOutput {
+   public:
+    explicit MyPIDOutput(frc::DifferentialDrive& r) : m_rd(r) {
+      m_rd.SetSafetyEnabled(false);
+    }
+
+    void PIDWrite(double output) override {
+      // Write to robot drive by reference
+      m_rd.ArcadeDrive(output, 0);
+    }
+
+   private:
+    frc::DifferentialDrive& m_rd;
+  };
+
+  // Distance in inches the robot wants to stay from an object
+  static constexpr int kHoldDistance = 12;
+
+  // Factor to convert sensor values to a distance in inches
+  static constexpr double kValueToInches = 0.125;
+
+  // proportional speed constant
+  static constexpr double kP = 7.0;
+
+  // integral speed constant
+  static constexpr double kI = 0.018;
+
+  // derivative speed constant
+  static constexpr double kD = 1.5;
+
+  static constexpr int kLeftMotorPort = 0;
+  static constexpr int kRightMotorPort = 1;
+  static constexpr int kUltrasonicPort = 0;
+
+  frc::AnalogInput m_ultrasonic{kUltrasonicPort};
+
+  frc::PWMVictorSPX m_left{kLeftMotorPort};
+  frc::PWMVictorSPX m_right{kRightMotorPort};
+  frc::DifferentialDrive m_robotDrive{m_left, m_right};
+  MyPIDOutput m_pidOutput{m_robotDrive};
+
+  frc::PIDController m_pidController{kP, kI, kD, m_ultrasonic, m_pidOutput};
+};
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/examples.json b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/examples.json
new file mode 100644
index 0000000..8859134
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/examples/examples.json
@@ -0,0 +1,247 @@
+[
+  {
+    "name": "Motor Controller",
+    "description": "Demonstrate controlling a single motor with a Joystick.",
+    "tags": [
+      "Robot and Motor",
+      "Actuators",
+      "Joystick",
+      "Complete List"
+    ],
+    "foldername": "MotorControl",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Motor Control With Encoder",
+    "description": "Demonstrate controlling a single motor with a Joystick and displaying the net movement of the motor using an encoder.",
+    "tags": [
+      "Robot and Motor",
+      "Digital",
+      "Sensors",
+      "Actuators",
+      "Joystick",
+      "Complete List"
+    ],
+    "foldername": "MotorControlEncoder",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Relay",
+    "description": "Demonstrate controlling a Relay from Joystick buttons.",
+    "tags": [
+      "Actuators",
+      "Joystick",
+      "Complete List"
+    ],
+    "foldername": "Relay",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "PDP CAN Monitoring",
+    "description": "Demonstrate using CAN to monitor the voltage, current, and temperature in the Power Distribution Panel.",
+    "tags": [
+      "Complete List",
+      "CAN",
+      "Sensors"
+    ],
+    "foldername": "CANPDP",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Solenoids",
+    "description": "Demonstrate controlling a single and double solenoid from Joystick buttons.",
+    "tags": [
+      "Actuators",
+      "Joystick",
+      "Pneumatics",
+      "Complete List"
+    ],
+    "foldername": "Solenoid",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Encoder",
+    "description": "Demonstrate displaying the value of a quadrature encoder on the SmartDashboard.",
+    "tags": [
+      "Complete List",
+      "Digital",
+      "Sensors"
+    ],
+    "foldername": "Encoder",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Arcade Drive",
+    "description": "An example program which demonstrates the use of Arcade Drive with the DifferentialDrive class",
+    "tags": [
+      "Getting Started with C++",
+      "Robot and Motor",
+      "Joystick",
+      "Complete List"
+    ],
+    "foldername": "ArcadeDrive",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Mecanum Drive",
+    "description": "An example program which demonstrates the use of Mecanum Drive with the MecanumDrive class",
+    "tags": [
+      "Getting Started with C++",
+      "Robot and Motor",
+      "Joystick",
+      "Complete List"
+    ],
+    "foldername": "MecanumDrive",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Ultrasonic",
+    "description": "Demonstrate maintaining a set distance using an ultrasonic sensor.",
+    "tags": [
+      "Robot and Motor",
+      "Complete List",
+      "Sensors",
+      "Analog"
+    ],
+    "foldername": "Ultrasonic",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "UltrasonicPID",
+    "description": "Demonstrate maintaining a set distance using an ultrasonic sensor and PID control.",
+    "tags": [
+      "Robot and Motor",
+      "Complete List",
+      "Sensors",
+      "Analog"
+    ],
+    "foldername": "UltrasonicPID",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Gyro",
+    "description": "An example program showing how to drive straight with using a gyro sensor.",
+    "tags": [
+      "Robot and Motor",
+      "Complete List",
+      "Sensors",
+      "Analog",
+      "Joystick"
+    ],
+    "foldername": "Gyro",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Gyro Mecanum",
+    "description": "An example program showing how to perform mecanum drive with field oriented controls.",
+    "tags": [
+      "Robot and Motor",
+      "Complete List",
+      "Sensors",
+      "Analog",
+      "Joysitck"
+    ],
+    "foldername": "GyroMecanum",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "HID Rumble",
+    "description": "An example program showing how to make human interface devices rumble.",
+    "tags": [
+      "Joystick"
+    ],
+    "foldername": "HidRumble",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "PotentiometerPID",
+    "description": "An example to demonstrate the use of a potentiometer and PID control to reach elevator position setpoints.",
+    "tags": [
+      "Joystick",
+      "Actuators",
+      "Complete List",
+      "Sensors",
+      "Analog"
+    ],
+    "foldername": "PotentiometerPID",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Getting Started",
+    "description": "An example program which demonstrates the simplest autonomous and teleoperated routines.",
+    "tags": [
+      "Getting Started with C++",
+      "Complete List"
+    ],
+    "foldername": "GettingStarted",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Simple Vision",
+    "description": "The minimal program to acquire images from an attached USB camera on the robot and send them to the dashboard.",
+    "tags": [
+      "Vision",
+      "Complete List"
+    ],
+    "foldername": "QuickVision",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Intermediate Vision",
+    "description": "An example program that acquires images from an attached USB camera and adds some annotation to the image as you might do for showing operators the result of some image recognition, and sends it to the dashboard for display.",
+    "tags": [
+      "Vision",
+      "Complete List"
+    ],
+    "foldername": "IntermediateVision",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Axis Camera Sample",
+    "description": "An example program that acquires images from an Axis network camera and adds some annotation to the image as you might do for showing operators the result of some image recognition, and sends it to the dashboard for display. This demonstrates the use of the AxisCamera class.",
+    "tags": [
+      "Vision",
+      "Complete List"
+    ],
+    "foldername": "AxisCameraSample",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "GearsBot",
+    "description": "A fully functional example CommandBased program for WPIs GearsBot robot. This code can run on your computer if it supports simulation.",
+    "tags": [
+      "CommandBased Robot",
+      "Complete List"
+    ],
+    "foldername": "GearsBot",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "PacGoat",
+    "description": "A fully functional example CommandBased program for FRC Team 190&#39;s 2014 robot. This code can run on your computer if it supports simulation.",
+    "tags": [
+      "CommandBased Robot",
+      "Complete List"
+    ],
+    "foldername": "PacGoat",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "HAL",
+    "description": "A program created using the HAL exclusively. This example is for advanced users",
+    "tags": [
+      "HAL"
+    ],
+    "foldername": "HAL",
+    "gradlebase": "c"
+  },
+  {
+    "name": "ShuffleBoard",
+    "description": "An example program that uses ShuffleBoard with its Widgets and Tabs.",
+    "tags": [
+      "ShuffleBoard"
+    ],
+    "foldername": "ShuffleBoard",
+    "gradlebase": "cpp"
+  }
+]
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/OI.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/OI.cpp
new file mode 100644
index 0000000..5974f1f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/OI.cpp
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "OI.h"
+
+#include <frc/WPILib.h>
+
+OI::OI() {
+  // Process operator interface input here.
+}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp
new file mode 100644
index 0000000..df2a9cc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "Robot.h"
+
+#include <frc/commands/Scheduler.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+ExampleSubsystem Robot::m_subsystem;
+OI Robot::m_oi;
+
+void Robot::RobotInit() {
+  m_chooser.SetDefaultOption("Default Auto", &m_defaultAuto);
+  m_chooser.AddOption("My Auto", &m_myAuto);
+  frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
+}
+
+/**
+ * This function is called every robot packet, no matter the mode. Use
+ * this for items like diagnostics that you want ran during disabled,
+ * autonomous, teleoperated and test.
+ *
+ * <p> This runs after the mode specific periodic functions, but before
+ * LiveWindow and SmartDashboard integrated updating.
+ */
+void Robot::RobotPeriodic() {}
+
+/**
+ * This function is called once each time the robot enters Disabled mode. You
+ * can use it to reset any subsystem information you want to clear when the
+ * robot is disabled.
+ */
+void Robot::DisabledInit() {}
+
+void Robot::DisabledPeriodic() { frc::Scheduler::GetInstance()->Run(); }
+
+/**
+ * This autonomous (along with the chooser code above) shows how to select
+ * between different autonomous modes using the dashboard. The sendable chooser
+ * code works with the Java SmartDashboard. If you prefer the LabVIEW Dashboard,
+ * remove all of the chooser code and uncomment the GetString code to get the
+ * auto name from the text box below the Gyro.
+ *
+ * You can add additional auto modes by adding additional commands to the
+ * chooser code above (like the commented example) or additional comparisons to
+ * the if-else structure below with additional strings & commands.
+ */
+void Robot::AutonomousInit() {
+  // std::string autoSelected = frc::SmartDashboard::GetString(
+  //     "Auto Selector", "Default");
+  // if (autoSelected == "My Auto") {
+  //   m_autonomousCommand = &m_myAuto;
+  // } else {
+  //   m_autonomousCommand = &m_defaultAuto;
+  // }
+
+  m_autonomousCommand = m_chooser.GetSelected();
+
+  if (m_autonomousCommand != nullptr) {
+    m_autonomousCommand->Start();
+  }
+}
+
+void Robot::AutonomousPeriodic() { frc::Scheduler::GetInstance()->Run(); }
+
+void Robot::TeleopInit() {
+  // This makes sure that the autonomous stops running when
+  // teleop starts running. If you want the autonomous to
+  // continue until interrupted by another command, remove
+  // this line or comment it out.
+  if (m_autonomousCommand != nullptr) {
+    m_autonomousCommand->Cancel();
+    m_autonomousCommand = nullptr;
+  }
+}
+
+void Robot::TeleopPeriodic() { frc::Scheduler::GetInstance()->Run(); }
+
+void Robot::TestPeriodic() {}
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/ExampleCommand.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/ExampleCommand.cpp
new file mode 100644
index 0000000..fa83682
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/ExampleCommand.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/ExampleCommand.h"
+
+#include "Robot.h"
+
+ExampleCommand::ExampleCommand() {
+  // Use Requires() here to declare subsystem dependencies
+  Requires(&Robot::m_subsystem);
+}
+
+// Called just before this Command runs the first time
+void ExampleCommand::Initialize() {}
+
+// Called repeatedly when this Command is scheduled to run
+void ExampleCommand::Execute() {}
+
+// Make this return true when this Command no longer needs to run execute()
+bool ExampleCommand::IsFinished() { return false; }
+
+// Called once after isFinished returns true
+void ExampleCommand::End() {}
+
+// Called when another command which requires one or more of the same
+// subsystems is scheduled to run
+void ExampleCommand::Interrupted() {}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/MyAutoCommand.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/MyAutoCommand.cpp
new file mode 100644
index 0000000..a8e9406
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/MyAutoCommand.cpp
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "commands/MyAutoCommand.h"
+
+#include "Robot.h"
+
+MyAutoCommand::MyAutoCommand() {
+  // Use Requires() here to declare subsystem dependencies
+  Requires(&Robot::m_subsystem);
+}
+
+// Called just before this Command runs the first time
+void MyAutoCommand::Initialize() {}
+
+// Called repeatedly when this Command is scheduled to run
+void MyAutoCommand::Execute() {}
+
+// Make this return true when this Command no longer needs to run execute()
+bool MyAutoCommand::IsFinished() { return false; }
+
+// Called once after isFinished returns true
+void MyAutoCommand::End() {}
+
+// Called when another command which requires one or more of the same
+// subsystems is scheduled to run
+void MyAutoCommand::Interrupted() {}
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp
new file mode 100644
index 0000000..cdde203
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "subsystems/ExampleSubsystem.h"
+
+#include "RobotMap.h"
+
+ExampleSubsystem::ExampleSubsystem() : frc::Subsystem("ExampleSubsystem") {}
+
+void ExampleSubsystem::InitDefaultCommand() {
+  // Set the default command for a subsystem here.
+  // SetDefaultCommand(new MySpecialCommand());
+}
+
+// Put methods for controlling this subsystem
+// here. Call these from Commands.
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/OI.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/OI.h
new file mode 100644
index 0000000..0b7713e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/OI.h
@@ -0,0 +1,13 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+class OI {
+ public:
+  OI();
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h
new file mode 100644
index 0000000..7dd5093
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.h
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/TimedRobot.h>
+#include <frc/commands/Command.h>
+#include <frc/smartdashboard/SendableChooser.h>
+
+#include "OI.h"
+#include "commands/ExampleCommand.h"
+#include "commands/MyAutoCommand.h"
+#include "subsystems/ExampleSubsystem.h"
+
+class Robot : public frc::TimedRobot {
+ public:
+  static ExampleSubsystem m_subsystem;
+  static OI m_oi;
+
+  void RobotInit() override;
+  void RobotPeriodic() override;
+  void DisabledInit() override;
+  void DisabledPeriodic() override;
+  void AutonomousInit() override;
+  void AutonomousPeriodic() override;
+  void TeleopInit() override;
+  void TeleopPeriodic() override;
+  void TestPeriodic() override;
+
+ private:
+  // Have it null by default so that if testing teleop it
+  // doesn't have undefined behavior and potentially crash.
+  frc::Command* m_autonomousCommand = nullptr;
+  ExampleCommand m_defaultAuto;
+  MyAutoCommand m_myAuto;
+  frc::SendableChooser<frc::Command*> m_chooser;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotMap.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotMap.h
new file mode 100644
index 0000000..dd78a21
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotMap.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+/**
+ * The RobotMap is a mapping from the ports sensors and actuators are wired into
+ * to a variable name. This provides flexibility changing wiring, makes checking
+ * the wiring easier and significantly reduces the number of magic numbers
+ * floating around.
+ */
+
+// For example to map the left and right motors, you could define the
+// following variables to use with your drivetrain subsystem.
+// constexpr int kLeftMotor = 1;
+// constexpr int kRightMotor = 2;
+
+// If you are using multiple modules, make sure to define both the port
+// number and the module. For example you with a rangefinder:
+// constexpr int kRangeFinderPort = 1;
+// constexpr int kRangeFinderModule = 1;
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h
new file mode 100644
index 0000000..1d11728
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+class ExampleCommand : public frc::Command {
+ public:
+  ExampleCommand();
+  void Initialize() override;
+  void Execute() override;
+  bool IsFinished() override;
+  void End() override;
+  void Interrupted() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/MyAutoCommand.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/MyAutoCommand.h
new file mode 100644
index 0000000..ce25e76
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/MyAutoCommand.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Command.h>
+
+class MyAutoCommand : public frc::Command {
+ public:
+  MyAutoCommand();
+  void Initialize() override;
+  void Execute() override;
+  bool IsFinished() override;
+  void End() override;
+  void Interrupted() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h
new file mode 100644
index 0000000..66bc329
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/commands/Subsystem.h>
+
+class ExampleSubsystem : public frc::Subsystem {
+ public:
+  ExampleSubsystem();
+  void InitDefaultCommand() override;
+
+ private:
+  // It's desirable that everything possible under private except
+  // for methods that implement subsystem capabilities
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/iterative/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/iterative/cpp/Robot.cpp
new file mode 100644
index 0000000..942fc9a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/iterative/cpp/Robot.cpp
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "Robot.h"
+
+#include <iostream>
+
+#include <frc/smartdashboard/SmartDashboard.h>
+
+void Robot::RobotInit() {
+  m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
+  m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
+  frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
+}
+
+/**
+ * This function is called every robot packet, no matter the mode. Use
+ * this for items like diagnostics that you want ran during disabled,
+ * autonomous, teleoperated and test.
+ *
+ * <p> This runs after the mode specific periodic functions, but before
+ * LiveWindow and SmartDashboard integrated updating.
+ */
+void Robot::RobotPeriodic() {}
+
+/**
+ * This autonomous (along with the chooser code above) shows how to select
+ * between different autonomous modes using the dashboard. The sendable chooser
+ * code works with the Java SmartDashboard. If you prefer the LabVIEW Dashboard,
+ * remove all of the chooser code and uncomment the GetString line to get the
+ * auto name from the text box below the Gyro.
+ *
+ * You can add additional auto modes by adding additional comparisons to the
+ * if-else structure below with additional strings. If using the SendableChooser
+ * make sure to add them to the chooser code above as well.
+ */
+void Robot::AutonomousInit() {
+  m_autoSelected = m_chooser.GetSelected();
+  // m_autoSelected = SmartDashboard::GetString(
+  //     "Auto Selector", kAutoNameDefault);
+  std::cout << "Auto selected: " << m_autoSelected << std::endl;
+
+  if (m_autoSelected == kAutoNameCustom) {
+    // Custom Auto goes here
+  } else {
+    // Default Auto goes here
+  }
+}
+
+void Robot::AutonomousPeriodic() {
+  if (m_autoSelected == kAutoNameCustom) {
+    // Custom Auto goes here
+  } else {
+    // Default Auto goes here
+  }
+}
+
+void Robot::TeleopInit() {}
+
+void Robot::TeleopPeriodic() {}
+
+void Robot::TestPeriodic() {}
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/iterative/include/Robot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/iterative/include/Robot.h
new file mode 100644
index 0000000..2c70b8f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/iterative/include/Robot.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <frc/IterativeRobot.h>
+#include <frc/smartdashboard/SendableChooser.h>
+
+class Robot : public frc::IterativeRobot {
+ public:
+  void RobotInit() override;
+  void RobotPeriodic() override;
+  void AutonomousInit() override;
+  void AutonomousPeriodic() override;
+  void TeleopInit() override;
+  void TeleopPeriodic() override;
+  void TestPeriodic() override;
+
+ private:
+  frc::SendableChooser<std::string> m_chooser;
+  const std::string kAutoNameDefault = "Default";
+  const std::string kAutoNameCustom = "My Auto";
+  std::string m_autoSelected;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/sample/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/sample/cpp/Robot.cpp
new file mode 100644
index 0000000..06352ea
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/sample/cpp/Robot.cpp
@@ -0,0 +1,92 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "Robot.h"
+
+#include <iostream>
+
+#include <frc/Timer.h>
+#include <frc/smartdashboard/SmartDashboard.h>
+
+Robot::Robot() {
+  // Note SmartDashboard is not initialized here, wait until RobotInit() to make
+  // SmartDashboard calls
+  m_robotDrive.SetExpiration(0.1);
+}
+
+void Robot::RobotInit() {
+  m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
+  m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
+  frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
+}
+
+/**
+ * This autonomous (along with the chooser code above) shows how to select
+ * between different autonomous modes using the dashboard. The sendable chooser
+ * code works with the Java SmartDashboard. If you prefer the LabVIEW Dashboard,
+ * remove all of the chooser code and uncomment the GetString line to get the
+ * auto name from the text box below the Gyro.
+ *
+ * You can add additional auto modes by adding additional comparisons to the
+ * if-else structure below with additional strings. If using the SendableChooser
+ * make sure to add them to the chooser code above as well.
+ */
+void Robot::Autonomous() {
+  std::string autoSelected = m_chooser.GetSelected();
+  // std::string autoSelected = frc::SmartDashboard::GetString(
+  // "Auto Selector", kAutoNameDefault);
+  std::cout << "Auto selected: " << autoSelected << std::endl;
+
+  // MotorSafety improves safety when motors are updated in loops but is
+  // disabled here because motor updates are not looped in this autonomous mode.
+  m_robotDrive.SetSafetyEnabled(false);
+
+  if (autoSelected == kAutoNameCustom) {
+    // Custom Auto goes here
+    std::cout << "Running custom Autonomous" << std::endl;
+
+    // Spin at half speed for two seconds
+    m_robotDrive.ArcadeDrive(0.0, 0.5);
+    frc::Wait(2.0);
+
+    // Stop robot
+    m_robotDrive.ArcadeDrive(0.0, 0.0);
+  } else {
+    // Default Auto goes here
+    std::cout << "Running default Autonomous" << std::endl;
+
+    // Drive forwards at half speed for two seconds
+    m_robotDrive.ArcadeDrive(-0.5, 0.0);
+    frc::Wait(2.0);
+
+    // Stop robot
+    m_robotDrive.ArcadeDrive(0.0, 0.0);
+  }
+}
+
+/**
+ * Runs the motors with arcade steering.
+ */
+void Robot::OperatorControl() {
+  m_robotDrive.SetSafetyEnabled(true);
+  while (IsOperatorControl() && IsEnabled()) {
+    // Drive with arcade style (use right stick)
+    m_robotDrive.ArcadeDrive(-m_stick.GetY(), m_stick.GetX());
+
+    // The motors will be updated every 5ms
+    frc::Wait(0.005);
+  }
+}
+
+/**
+ * Runs during test mode
+ */
+void Robot::Test() {}
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/sample/include/Robot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/sample/include/Robot.h
new file mode 100644
index 0000000..d568111
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/sample/include/Robot.h
@@ -0,0 +1,49 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <frc/Joystick.h>
+#include <frc/PWMVictorSPX.h>
+#include <frc/SampleRobot.h>
+#include <frc/drive/DifferentialDrive.h>
+#include <frc/smartdashboard/SendableChooser.h>
+
+/**
+ * This is a demo program showing the use of the DifferentialDrive class. The
+ * SampleRobot class is the base of a robot application that will automatically
+ * call your Autonomous and OperatorControl methods at the right time as
+ * controlled by the switches on the driver station or the field controls.
+ *
+ * WARNING: While it may look like a good choice to use for your code if you're
+ * inexperienced, don't. Unless you know what you are doing, complex code will
+ * be much more difficult under this system. Use TimedRobot or Command-Based
+ * instead if you're new.
+ */
+class Robot : public frc::SampleRobot {
+ public:
+  Robot();
+
+  void RobotInit() override;
+  void Autonomous() override;
+  void OperatorControl() override;
+  void Test() override;
+
+ private:
+  // Robot drive system
+  frc::PWMVictorSPX m_leftMotor{0};
+  frc::PWMVictorSPX m_rightMotor{1};
+  frc::DifferentialDrive m_robotDrive{m_leftMotor, m_rightMotor};
+
+  frc::Joystick m_stick{0};
+
+  frc::SendableChooser<std::string> m_chooser;
+  const std::string kAutoNameDefault = "Default";
+  const std::string kAutoNameCustom = "My Auto";
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/templates.json b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/templates.json
new file mode 100644
index 0000000..089ea16
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/templates.json
@@ -0,0 +1,47 @@
+[
+  {
+    "name": "Iterative Robot",
+    "description": "Iterative style",
+    "tags": [
+      "Iterative"
+    ],
+    "foldername": "iterative",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Timed Robot",
+    "description": "Timed style",
+    "tags": [
+      "Timed"
+    ],
+    "foldername": "timed",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Timed Skeleton (Advanced)",
+    "description": "Skeleton (stub) code for TimedRobot",
+    "tags": [
+      "Timed", "Skeleton"
+    ],
+    "foldername": "timedskeleton",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Command Robot",
+    "description": "Command style",
+    "tags": [
+      "Command"
+    ],
+    "foldername": "commandbased",
+    "gradlebase": "cpp"
+  },
+  {
+    "name": "Sample Robot",
+    "description": "Sample style",
+    "tags": [
+      "Sample"
+    ],
+    "foldername": "sample",
+    "gradlebase": "cpp"
+  }
+]
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp
new file mode 100644
index 0000000..07d843d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "Robot.h"
+
+#include <iostream>
+
+#include <frc/smartdashboard/SmartDashboard.h>
+
+void Robot::RobotInit() {
+  m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
+  m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
+  frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
+}
+
+/**
+ * This function is called every robot packet, no matter the mode. Use
+ * this for items like diagnostics that you want ran during disabled,
+ * autonomous, teleoperated and test.
+ *
+ * <p> This runs after the mode specific periodic functions, but before
+ * LiveWindow and SmartDashboard integrated updating.
+ */
+void Robot::RobotPeriodic() {}
+
+/**
+ * This autonomous (along with the chooser code above) shows how to select
+ * between different autonomous modes using the dashboard. The sendable chooser
+ * code works with the Java SmartDashboard. If you prefer the LabVIEW Dashboard,
+ * remove all of the chooser code and uncomment the GetString line to get the
+ * auto name from the text box below the Gyro.
+ *
+ * You can add additional auto modes by adding additional comparisons to the
+ * if-else structure below with additional strings. If using the SendableChooser
+ * make sure to add them to the chooser code above as well.
+ */
+void Robot::AutonomousInit() {
+  m_autoSelected = m_chooser.GetSelected();
+  // m_autoSelected = SmartDashboard::GetString("Auto Selector",
+  //     kAutoNameDefault);
+  std::cout << "Auto selected: " << m_autoSelected << std::endl;
+
+  if (m_autoSelected == kAutoNameCustom) {
+    // Custom Auto goes here
+  } else {
+    // Default Auto goes here
+  }
+}
+
+void Robot::AutonomousPeriodic() {
+  if (m_autoSelected == kAutoNameCustom) {
+    // Custom Auto goes here
+  } else {
+    // Default Auto goes here
+  }
+}
+
+void Robot::TeleopInit() {}
+
+void Robot::TeleopPeriodic() {}
+
+void Robot::TestPeriodic() {}
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h
new file mode 100644
index 0000000..09183dc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.h
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <string>
+
+#include <frc/TimedRobot.h>
+#include <frc/smartdashboard/SendableChooser.h>
+
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override;
+  void RobotPeriodic() override;
+  void AutonomousInit() override;
+  void AutonomousPeriodic() override;
+  void TeleopInit() override;
+  void TeleopPeriodic() override;
+  void TestPeriodic() override;
+
+ private:
+  frc::SendableChooser<std::string> m_chooser;
+  const std::string kAutoNameDefault = "Default";
+  const std::string kAutoNameCustom = "My Auto";
+  std::string m_autoSelected;
+};
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp
new file mode 100644
index 0000000..76adfc4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "Robot.h"
+
+void Robot::RobotInit() {}
+
+void Robot::AutonomousInit() {}
+void Robot::AutonomousPeriodic() {}
+
+void Robot::TeleopInit() {}
+void Robot::TeleopPeriodic() {}
+
+void Robot::TestInit() {}
+void Robot::TestPeriodic() {}
+
+#ifndef RUNNING_FRC_TESTS
+int main() { return frc::StartRobot<Robot>(); }
+#endif
diff --git a/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h
new file mode 100644
index 0000000..bf4dae1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <frc/TimedRobot.h>
+
+class Robot : public frc::TimedRobot {
+ public:
+  void RobotInit() override;
+
+  void AutonomousInit() override;
+  void AutonomousPeriodic() override;
+
+  void TeleopInit() override;
+  void TeleopPeriodic() override;
+
+  void TestInit() override;
+  void TestPeriodic() override;
+};
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/build.gradle b/third_party/allwpilib_2019/wpilibcIntegrationTests/build.gradle
new file mode 100644
index 0000000..0dea400
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/build.gradle
@@ -0,0 +1,106 @@
+import org.gradle.language.base.internal.ProjectLayout
+
+apply plugin: 'cpp'
+apply plugin: 'visual-studio'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: ExtraTasks
+
+apply from: '../shared/config.gradle'
+
+ext {
+    sharedCvConfigs = [wpilibcIntegrationTests: []]
+    staticCvConfigs = [:]
+    useJava = false
+    useCpp = true
+    staticGtestConfigs = [wpilibcIntegrationTests: []]
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+apply from: "${rootDir}/shared/googletest.gradle"
+
+ext {
+    chipObjectComponents = ['wpilibcIntegrationTests']
+    netCommComponents = ['wpilibcIntegrationTests']
+    useNiJava = false
+}
+
+apply from: "${rootDir}/shared/nilibraries.gradle"
+
+model {
+    components {
+        wpilibcIntegrationTests(NativeExecutableSpec) {
+            targetBuildTypes 'debug'
+            baseName = 'FRCUserProgram'
+            binaries.all { binary ->
+                if (binary.targetPlatform.architecture.name == 'athena') {
+                    binary.sources {
+                        athenaCpp(CppSourceSet) {
+                            source {
+                                srcDirs = ['src/main/native/cpp']
+                                includes = ['**/*.cpp']
+                            }
+                            exportedHeaders {
+                                srcDirs = ['src/main/native/include']
+                                includes = ['**/*.h']
+                            }
+                        }
+                    }
+                    binary.tasks.withType(CppCompile) {
+                        cppCompiler.args "-Wno-missing-field-initializers"
+                        cppCompiler.args "-Wno-unused-variable"
+                        cppCompiler.args "-Wno-error=deprecated-declarations"
+                    }
+                    lib project: ':wpilibc', library: 'wpilibc', linkage: 'shared'
+                    lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                    lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                    lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
+                    lib project: ':cscore', library: 'cscoreJNIShared', linkage: 'shared'
+                    project(':hal').addHalDependency(binary, 'shared')
+                    project(':hal').addHalJniDependency(binary)
+                    lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                    lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                } else {
+                    binary.sources {
+                        simCpp(CppSourceSet) {
+                            source {
+                                srcDirs 'src/main/native/dt'
+                                includes = ['**/*.cpp']
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+def testOutputFolder = file("${project(':').buildDir}/integrationTestFiles")
+
+model {
+    tasks {
+        copyWpilibCTestLibrariesToOutput(Copy) {
+            def task = it
+            $.binaries.each {
+                if (it in NativeExecutableBinarySpec && it.targetPlatform.architecture.name == 'athena') {
+                    def installTask = it.tasks.install
+                    task.dependsOn installTask
+                    task.from(installTask.executableFile) {
+                        into '/cpp'
+                    }
+                    installTask.libs.each {
+                        task.from(it) {
+                            into '/libs'
+                        }
+                    }
+                }
+            }
+            destinationDir testOutputFolder
+        }
+        // This is in a separate if statement because of what I would assume is a bug in grade.
+        // Will file an issue on their side.
+        if (!project.hasProperty('skipAthena')) {
+            build.dependsOn copyWpilibCTestLibrariesToOutput
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/AnalogLoopTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/AnalogLoopTest.cpp
new file mode 100644
index 0000000..40fd87c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/AnalogLoopTest.cpp
@@ -0,0 +1,131 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "TestBench.h"
+#include "frc/AnalogInput.h"
+#include "frc/AnalogOutput.h"
+#include "frc/AnalogTrigger.h"
+#include "frc/Counter.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const double kDelayTime = 0.01;
+
+/**
+ * A fixture with an analog input and an analog output wired together
+ */
+class AnalogLoopTest : public testing::Test {
+ protected:
+  AnalogInput* m_input;
+  AnalogOutput* m_output;
+
+  void SetUp() override {
+    m_input = new AnalogInput(TestBench::kFakeAnalogOutputChannel);
+    m_output = new AnalogOutput(TestBench::kAnalogOutputChannel);
+  }
+
+  void TearDown() override {
+    delete m_input;
+    delete m_output;
+  }
+};
+
+/**
+ * Test analog inputs and outputs by setting one and making sure the other
+ * matches.
+ */
+TEST_F(AnalogLoopTest, AnalogInputWorks) {
+  // Set the output voltage and check if the input measures the same voltage
+  for (int32_t i = 0; i < 50; i++) {
+    m_output->SetVoltage(i / 10.0);
+
+    Wait(kDelayTime);
+
+    EXPECT_NEAR(m_output->GetVoltage(), m_input->GetVoltage(), 0.01);
+  }
+}
+
+/**
+ * Test if we can use an analog trigger to  check if the output is within a
+ * range correctly.
+ */
+TEST_F(AnalogLoopTest, AnalogTriggerWorks) {
+  AnalogTrigger trigger(m_input);
+  trigger.SetLimitsVoltage(2.0, 3.0);
+
+  m_output->SetVoltage(1.0);
+  Wait(kDelayTime);
+
+  EXPECT_FALSE(trigger.GetInWindow())
+      << "Analog trigger is in the window (2V, 3V)";
+  EXPECT_FALSE(trigger.GetTriggerState()) << "Analog trigger is on";
+
+  m_output->SetVoltage(2.5);
+  Wait(kDelayTime);
+
+  EXPECT_TRUE(trigger.GetInWindow())
+      << "Analog trigger is not in the window (2V, 3V)";
+  EXPECT_FALSE(trigger.GetTriggerState()) << "Analog trigger is on";
+
+  m_output->SetVoltage(4.0);
+  Wait(kDelayTime);
+
+  EXPECT_FALSE(trigger.GetInWindow())
+      << "Analog trigger is in the window (2V, 3V)";
+  EXPECT_TRUE(trigger.GetTriggerState()) << "Analog trigger is not on";
+}
+
+/**
+ * Test if we can count the right number of ticks from an analog trigger with
+ * a counter.
+ */
+TEST_F(AnalogLoopTest, AnalogTriggerCounterWorks) {
+  AnalogTrigger trigger(m_input);
+  trigger.SetLimitsVoltage(2.0, 3.0);
+
+  Counter counter(trigger);
+
+  // Turn the analog output low and high 50 times
+  for (int32_t i = 0; i < 50; i++) {
+    m_output->SetVoltage(1.0);
+    Wait(kDelayTime);
+    m_output->SetVoltage(4.0);
+    Wait(kDelayTime);
+  }
+
+  // The counter should be 50
+  EXPECT_EQ(50, counter.Get())
+      << "Analog trigger counter did not count 50 ticks";
+}
+
+static void InterruptHandler(uint32_t interruptAssertedMask, void* param) {
+  *reinterpret_cast<int32_t*>(param) = 12345;
+}
+
+TEST_F(AnalogLoopTest, AsynchronusInterruptWorks) {
+  int32_t param = 0;
+  AnalogTrigger trigger(m_input);
+  trigger.SetLimitsVoltage(2.0, 3.0);
+
+  // Given an interrupt handler that sets an int32_t to 12345
+  std::shared_ptr<AnalogTriggerOutput> triggerOutput =
+      trigger.CreateOutput(AnalogTriggerType::kState);
+  triggerOutput->RequestInterrupts(InterruptHandler, &param);
+  triggerOutput->EnableInterrupts();
+
+  // If the analog output moves from below to above the window
+  m_output->SetVoltage(0.0);
+  Wait(kDelayTime);
+  m_output->SetVoltage(5.0);
+  triggerOutput->CancelInterrupts();
+
+  // Then the int32_t should be 12345
+  Wait(kDelayTime);
+  EXPECT_EQ(12345, param) << "The interrupt did not run.";
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/AnalogPotentiometerTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/AnalogPotentiometerTest.cpp
new file mode 100644
index 0000000..4497051
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/AnalogPotentiometerTest.cpp
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/AnalogPotentiometer.h"  // NOLINT(build/include_order)
+
+#include "TestBench.h"
+#include "frc/AnalogOutput.h"
+#include "frc/RobotController.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const double kScale = 270.0;
+static const double kAngle = 180.0;
+
+class AnalogPotentiometerTest : public testing::Test {
+ protected:
+  AnalogOutput* m_fakePot;
+  AnalogPotentiometer* m_pot;
+
+  void SetUp() override {
+    m_fakePot = new AnalogOutput(TestBench::kAnalogOutputChannel);
+    m_pot =
+        new AnalogPotentiometer(TestBench::kFakeAnalogOutputChannel, kScale);
+  }
+
+  void TearDown() override {
+    delete m_fakePot;
+    delete m_pot;
+  }
+};
+
+TEST_F(AnalogPotentiometerTest, TestInitialSettings) {
+  m_fakePot->SetVoltage(0.0);
+  Wait(0.1);
+  EXPECT_NEAR(0.0, m_pot->Get(), 5.0)
+      << "The potentiometer did not initialize to 0.";
+}
+
+TEST_F(AnalogPotentiometerTest, TestRangeValues) {
+  m_fakePot->SetVoltage(kAngle / kScale * RobotController::GetVoltage5V());
+  Wait(0.1);
+  EXPECT_NEAR(kAngle, m_pot->Get(), 2.0)
+      << "The potentiometer did not measure the correct angle.";
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/BuiltInAccelerometerTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/BuiltInAccelerometerTest.cpp
new file mode 100644
index 0000000..bfb5f21
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/BuiltInAccelerometerTest.cpp
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/BuiltInAccelerometer.h"  // NOLINT(build/include_order)
+
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kAccelerationTolerance = 0.1;
+/**
+ * There's not much we can automatically test with the on-board accelerometer,
+ * but checking for gravity is probably good enough to tell that it's working.
+ */
+TEST(BuiltInAccelerometerTest, Accelerometer) {
+  BuiltInAccelerometer accelerometer;
+
+  /* The testbench sometimes shakes a little from a previous test.  Give it
+          some time. */
+  Wait(1.0);
+
+  ASSERT_NEAR(0.0, accelerometer.GetX(), kAccelerationTolerance);
+  ASSERT_NEAR(1.0, accelerometer.GetY(), kAccelerationTolerance);
+  ASSERT_NEAR(0.0, accelerometer.GetZ(), kAccelerationTolerance);
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/CounterTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/CounterTest.cpp
new file mode 100644
index 0000000..a3ddbd2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/CounterTest.cpp
@@ -0,0 +1,176 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/Counter.h"  // NOLINT(build/include_order)
+
+#include "TestBench.h"
+#include "frc/Jaguar.h"
+#include "frc/Talon.h"
+#include "frc/Timer.h"
+#include "frc/Victor.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const double kMotorDelay = 2.5;
+
+static const double kMaxPeriod = 2.0;
+
+class CounterTest : public testing::Test {
+ protected:
+  Counter* m_talonCounter;
+  Counter* m_victorCounter;
+  Counter* m_jaguarCounter;
+  Talon* m_talon;
+  Victor* m_victor;
+  Jaguar* m_jaguar;
+
+  void SetUp() override {
+    m_talonCounter = new Counter(TestBench::kTalonEncoderChannelA);
+    m_victorCounter = new Counter(TestBench::kVictorEncoderChannelA);
+    m_jaguarCounter = new Counter(TestBench::kJaguarEncoderChannelA);
+    m_victor = new Victor(TestBench::kVictorChannel);
+    m_talon = new Talon(TestBench::kTalonChannel);
+    m_jaguar = new Jaguar(TestBench::kJaguarChannel);
+  }
+
+  void TearDown() override {
+    delete m_talonCounter;
+    delete m_victorCounter;
+    delete m_jaguarCounter;
+    delete m_victor;
+    delete m_talon;
+    delete m_jaguar;
+  }
+
+  void Reset() {
+    m_talonCounter->Reset();
+    m_victorCounter->Reset();
+    m_jaguarCounter->Reset();
+    m_talon->Set(0.0);
+    m_victor->Set(0.0);
+    m_jaguar->Set(0.0);
+  }
+};
+
+/**
+ * Tests the counter by moving the motor and determining if the
+ * counter is counting.
+ */
+TEST_F(CounterTest, CountTalon) {
+  Reset();
+
+  /* Run the motor forward and determine if the counter is counting. */
+  m_talon->Set(1.0);
+  Wait(0.5);
+
+  EXPECT_NE(0.0, m_talonCounter->Get()) << "The counter did not count (talon)";
+
+  /* Set the motor to 0 and determine if the counter resets to 0. */
+  m_talon->Set(0.0);
+  Wait(0.5);
+  m_talonCounter->Reset();
+
+  EXPECT_FLOAT_EQ(0.0, m_talonCounter->Get())
+      << "The counter did not restart to 0 (talon)";
+}
+
+TEST_F(CounterTest, CountVictor) {
+  Reset();
+
+  /* Run the motor forward and determine if the counter is counting. */
+  m_victor->Set(1.0);
+  Wait(0.5);
+
+  EXPECT_NE(0.0, m_victorCounter->Get())
+      << "The counter did not count (victor)";
+
+  /* Set the motor to 0 and determine if the counter resets to 0. */
+  m_victor->Set(0.0);
+  Wait(0.5);
+  m_victorCounter->Reset();
+
+  EXPECT_FLOAT_EQ(0.0, m_victorCounter->Get())
+      << "The counter did not restart to 0 (jaguar)";
+}
+
+TEST_F(CounterTest, CountJaguar) {
+  Reset();
+
+  /* Run the motor forward and determine if the counter is counting. */
+  m_jaguar->Set(1.0);
+  Wait(0.5);
+
+  EXPECT_NE(0.0, m_jaguarCounter->Get())
+      << "The counter did not count (jaguar)";
+
+  /* Set the motor to 0 and determine if the counter resets to 0. */
+  m_jaguar->Set(0.0);
+  Wait(0.5);
+  m_jaguarCounter->Reset();
+
+  EXPECT_FLOAT_EQ(0.0, m_jaguarCounter->Get())
+      << "The counter did not restart to 0 (jaguar)";
+}
+
+/**
+ * Tests the GetStopped and SetMaxPeriod methods by setting the Max Period and
+ * getting the value after a period of time.
+ */
+TEST_F(CounterTest, TalonGetStopped) {
+  Reset();
+
+  /* Set the Max Period of the counter and run the motor */
+  m_talonCounter->SetMaxPeriod(kMaxPeriod);
+  m_talon->Set(1.0);
+  Wait(0.5);
+
+  EXPECT_FALSE(m_talonCounter->GetStopped()) << "The counter did not count.";
+
+  /* Stop the motor and wait until the Max Period is exceeded */
+  m_talon->Set(0.0);
+  Wait(kMotorDelay);
+
+  EXPECT_TRUE(m_talonCounter->GetStopped())
+      << "The counter did not stop counting.";
+}
+
+TEST_F(CounterTest, VictorGetStopped) {
+  Reset();
+
+  /* Set the Max Period of the counter and run the motor */
+  m_victorCounter->SetMaxPeriod(kMaxPeriod);
+  m_victor->Set(1.0);
+  Wait(0.5);
+
+  EXPECT_FALSE(m_victorCounter->GetStopped()) << "The counter did not count.";
+
+  /* Stop the motor and wait until the Max Period is exceeded */
+  m_victor->Set(0.0);
+  Wait(kMotorDelay);
+
+  EXPECT_TRUE(m_victorCounter->GetStopped())
+      << "The counter did not stop counting.";
+}
+
+TEST_F(CounterTest, JaguarGetStopped) {
+  Reset();
+
+  /* Set the Max Period of the counter and run the motor */
+  m_jaguarCounter->SetMaxPeriod(kMaxPeriod);
+  m_jaguar->Set(1.0);
+  Wait(0.5);
+
+  EXPECT_FALSE(m_jaguarCounter->GetStopped()) << "The counter did not count.";
+
+  /* Stop the motor and wait until the Max Period is exceeded */
+  m_jaguar->Set(0.0);
+  Wait(kMotorDelay);
+
+  EXPECT_TRUE(m_jaguarCounter->GetStopped())
+      << "The counter did not stop counting.";
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DIOLoopTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DIOLoopTest.cpp
new file mode 100644
index 0000000..10b64d5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DIOLoopTest.cpp
@@ -0,0 +1,188 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/DigitalInput.h"  // NOLINT(build/include_order)
+
+#include "frc/DigitalOutput.h"  // NOLINT(build/include_order)
+
+#include "TestBench.h"
+#include "frc/Counter.h"
+#include "frc/InterruptableSensorBase.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const double kCounterTime = 0.001;
+
+static const double kDelayTime = 0.1;
+
+static const double kSynchronousInterruptTime = 2.0;
+static const double kSynchronousInterruptTimeTolerance = 0.01;
+
+/**
+ * A fixture with a digital input and a digital output physically wired
+ * together.
+ */
+class DIOLoopTest : public testing::Test {
+ protected:
+  DigitalInput* m_input;
+  DigitalOutput* m_output;
+
+  void SetUp() override {
+    m_input = new DigitalInput(TestBench::kLoop1InputChannel);
+    m_output = new DigitalOutput(TestBench::kLoop1OutputChannel);
+  }
+
+  void TearDown() override {
+    delete m_input;
+    delete m_output;
+  }
+
+  void Reset() { m_output->Set(false); }
+};
+
+/**
+ * Test the DigitalInput and DigitalOutput classes by setting the output and
+ * reading the input.
+ */
+TEST_F(DIOLoopTest, Loop) {
+  Reset();
+
+  m_output->Set(false);
+  Wait(kDelayTime);
+  EXPECT_FALSE(m_input->Get()) << "The digital output was turned off, but "
+                               << "the digital input is on.";
+
+  m_output->Set(true);
+  Wait(kDelayTime);
+  EXPECT_TRUE(m_input->Get()) << "The digital output was turned on, but "
+                              << "the digital input is off.";
+}
+/**
+ * Tests to see if the DIO PWM functionality works.
+ */
+TEST_F(DIOLoopTest, DIOPWM) {
+  Reset();
+
+  m_output->Set(false);
+  Wait(kDelayTime);
+  EXPECT_FALSE(m_input->Get()) << "The digital output was turned off, but "
+                               << "the digital input is on.";
+
+  // Set frequency to 2.0 Hz
+  m_output->SetPWMRate(2.0);
+  // Enable PWM, but leave it off
+  m_output->EnablePWM(0.0);
+  Wait(0.5);
+  m_output->UpdateDutyCycle(0.5);
+  m_input->RequestInterrupts();
+  m_input->SetUpSourceEdge(false, true);
+  InterruptableSensorBase::WaitResult result =
+      m_input->WaitForInterrupt(3.0, true);
+
+  Wait(0.5);
+  bool firstCycle = m_input->Get();
+  Wait(0.5);
+  bool secondCycle = m_input->Get();
+  Wait(0.5);
+  bool thirdCycle = m_input->Get();
+  Wait(0.5);
+  bool forthCycle = m_input->Get();
+  Wait(0.5);
+  bool fifthCycle = m_input->Get();
+  Wait(0.5);
+  bool sixthCycle = m_input->Get();
+  Wait(0.5);
+  bool seventhCycle = m_input->Get();
+  m_output->DisablePWM();
+  Wait(0.5);
+  bool firstAfterStop = m_input->Get();
+  Wait(0.5);
+  bool secondAfterStop = m_input->Get();
+
+  EXPECT_EQ(InterruptableSensorBase::WaitResult::kFallingEdge, result)
+      << "WaitForInterrupt was not falling.";
+
+  EXPECT_FALSE(firstCycle) << "Input not low after first delay";
+  EXPECT_TRUE(secondCycle) << "Input not high after second delay";
+  EXPECT_FALSE(thirdCycle) << "Input not low after third delay";
+  EXPECT_TRUE(forthCycle) << "Input not high after forth delay";
+  EXPECT_FALSE(fifthCycle) << "Input not low after fifth delay";
+  EXPECT_TRUE(sixthCycle) << "Input not high after sixth delay";
+  EXPECT_FALSE(seventhCycle) << "Input not low after seventh delay";
+  EXPECT_FALSE(firstAfterStop) << "Input not low after stopping first read";
+  EXPECT_FALSE(secondAfterStop) << "Input not low after stopping second read";
+}
+
+/**
+ * Test a fake "counter" that uses the DIO loop as an input to make sure the
+ * Counter class works
+ */
+TEST_F(DIOLoopTest, FakeCounter) {
+  Reset();
+
+  Counter counter(m_input);
+
+  EXPECT_EQ(0, counter.Get()) << "Counter did not initialize to 0.";
+
+  /* Count 100 ticks.  The counter value should be 100 after this loop. */
+  for (int32_t i = 0; i < 100; i++) {
+    m_output->Set(true);
+    Wait(kCounterTime);
+    m_output->Set(false);
+    Wait(kCounterTime);
+  }
+
+  EXPECT_EQ(100, counter.Get()) << "Counter did not count up to 100.";
+}
+
+static void InterruptHandler(uint32_t interruptAssertedMask, void* param) {
+  *reinterpret_cast<int32_t*>(param) = 12345;
+}
+
+TEST_F(DIOLoopTest, AsynchronousInterruptWorks) {
+  int32_t param = 0;
+
+  // Given an interrupt handler that sets an int32_t to 12345
+  m_input->RequestInterrupts(InterruptHandler, &param);
+  m_input->EnableInterrupts();
+
+  // If the voltage rises
+  m_output->Set(false);
+  m_output->Set(true);
+  m_input->CancelInterrupts();
+
+  // Then the int32_t should be 12345
+  Wait(kDelayTime);
+  EXPECT_EQ(12345, param) << "The interrupt did not run.";
+}
+
+static void* InterruptTriggerer(void* data) {
+  DigitalOutput* output = static_cast<DigitalOutput*>(data);
+  output->Set(false);
+  Wait(kSynchronousInterruptTime);
+  output->Set(true);
+  return nullptr;
+}
+
+TEST_F(DIOLoopTest, SynchronousInterruptWorks) {
+  // Given a synchronous interrupt
+  m_input->RequestInterrupts();
+
+  // If we have another thread trigger the interrupt in a few seconds
+  pthread_t interruptTriggererLoop;
+  pthread_create(&interruptTriggererLoop, nullptr, InterruptTriggerer,
+                 m_output);
+
+  // Then this thread should pause and resume after that number of seconds
+  Timer timer;
+  timer.Start();
+  m_input->WaitForInterrupt(kSynchronousInterruptTime + 1.0);
+  EXPECT_NEAR(kSynchronousInterruptTime, timer.Get(),
+              kSynchronousInterruptTimeTolerance);
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DigitalGlitchFilterTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DigitalGlitchFilterTest.cpp
new file mode 100644
index 0000000..fa39e79
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DigitalGlitchFilterTest.cpp
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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/DigitalGlitchFilter.h"  // NOLINT(build/include_order)
+
+#include "frc/Counter.h"
+#include "frc/DigitalInput.h"
+#include "frc/Encoder.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+/**
+ * Tests that configuring inputs to be filtered succeeds.
+ *
+ * This test actually tests everything except that the actual FPGA
+ * implementation works as intended.  We configure the FPGA and then query it to
+ * make sure that the acutal configuration matches.
+ */
+TEST(DigitalGlitchFilterTest, BasicTest) {
+  DigitalInput input1(1);
+  DigitalInput input2(2);
+  DigitalInput input3(3);
+  DigitalInput input4(4);
+  Encoder encoder5(5, 6);
+  Counter counter7(7);
+
+  // Check that we can make a single filter and set the period.
+  DigitalGlitchFilter filter1;
+  filter1.Add(&input1);
+  filter1.SetPeriodNanoSeconds(4200);
+
+  // Check that we can make a second filter with 2 inputs.
+  DigitalGlitchFilter filter2;
+  filter2.Add(&input2);
+  filter2.Add(&input3);
+  filter2.SetPeriodNanoSeconds(97100);
+
+  // Check that we can make a third filter with an input, an encoder, and a
+  // counter.
+  DigitalGlitchFilter filter3;
+  filter3.Add(&input4);
+  filter3.Add(&encoder5);
+  filter3.Add(&counter7);
+  filter3.SetPeriodNanoSeconds(167800);
+
+  // Verify that the period was properly set for all 3 filters.
+  EXPECT_EQ(4200u, filter1.GetPeriodNanoSeconds());
+  EXPECT_EQ(97100u, filter2.GetPeriodNanoSeconds());
+  EXPECT_EQ(167800u, filter3.GetPeriodNanoSeconds());
+
+  // Clean up.
+  filter1.Remove(&input1);
+  filter2.Remove(&input2);
+  filter2.Remove(&input3);
+  filter3.Remove(&input4);
+  filter3.Remove(&encoder5);
+  filter3.Remove(&counter7);
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DriverStationTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DriverStationTest.cpp
new file mode 100644
index 0000000..df8eef3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/DriverStationTest.cpp
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/DriverStation.h"  // NOLINT(build/include_order)
+
+#include "TestBench.h"
+#include "frc/RobotController.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+constexpr double TIMER_TOLERANCE = 0.2;
+constexpr int64_t TIMER_RUNTIME = 1000000;  // 1 second
+
+class DriverStationTest : public testing::Test {};
+
+/**
+ * Test if the WaitForData function works
+ */
+TEST_F(DriverStationTest, WaitForData) {
+  uint64_t initialTime = RobotController::GetFPGATime();
+
+  for (int i = 0; i < 50; i++) {
+    DriverStation::GetInstance().WaitForData();
+  }
+
+  uint64_t finalTime = RobotController::GetFPGATime();
+
+  EXPECT_NEAR(TIMER_RUNTIME, finalTime - initialTime,
+              TIMER_TOLERANCE * TIMER_RUNTIME);
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/FakeEncoderTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/FakeEncoderTest.cpp
new file mode 100644
index 0000000..bf5a8ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/FakeEncoderTest.cpp
@@ -0,0 +1,161 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/Encoder.h"  // NOLINT(build/include_order)
+
+#include "TestBench.h"
+#include "frc/AnalogOutput.h"
+#include "frc/AnalogTrigger.h"
+#include "frc/DigitalOutput.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const double kDelayTime = 0.001;
+
+class FakeEncoderTest : public testing::Test {
+ protected:
+  DigitalOutput* m_outputA;
+  DigitalOutput* m_outputB;
+  AnalogOutput* m_indexOutput;
+
+  Encoder* m_encoder;
+  AnalogTrigger* m_indexAnalogTrigger;
+  std::shared_ptr<AnalogTriggerOutput> m_indexAnalogTriggerOutput;
+
+  void SetUp() override {
+    m_outputA = new DigitalOutput(TestBench::kLoop2OutputChannel);
+    m_outputB = new DigitalOutput(TestBench::kLoop1OutputChannel);
+    m_indexOutput = new AnalogOutput(TestBench::kAnalogOutputChannel);
+    m_outputA->Set(false);
+    m_outputB->Set(false);
+    m_encoder = new Encoder(TestBench::kLoop1InputChannel,
+                            TestBench::kLoop2InputChannel);
+    m_indexAnalogTrigger =
+        new AnalogTrigger(TestBench::kFakeAnalogOutputChannel);
+    m_indexAnalogTrigger->SetLimitsVoltage(2.0, 3.0);
+    m_indexAnalogTriggerOutput =
+        m_indexAnalogTrigger->CreateOutput(AnalogTriggerType::kState);
+  }
+
+  void TearDown() override {
+    delete m_outputA;
+    delete m_outputB;
+    delete m_indexOutput;
+    delete m_encoder;
+    delete m_indexAnalogTrigger;
+  }
+
+  /**
+   * Output pulses to the encoder's input channels to simulate a change of 100
+   * ticks
+   */
+  void Simulate100QuadratureTicks() {
+    for (int32_t i = 0; i < 100; i++) {
+      m_outputA->Set(true);
+      Wait(kDelayTime);
+      m_outputB->Set(true);
+      Wait(kDelayTime);
+      m_outputA->Set(false);
+      Wait(kDelayTime);
+      m_outputB->Set(false);
+      Wait(kDelayTime);
+    }
+  }
+
+  void SetIndexHigh() {
+    m_indexOutput->SetVoltage(5.0);
+    Wait(kDelayTime);
+  }
+
+  void SetIndexLow() {
+    m_indexOutput->SetVoltage(0.0);
+    Wait(kDelayTime);
+  }
+};
+
+/**
+ * Test the encoder by reseting it to 0 and reading the value.
+ */
+TEST_F(FakeEncoderTest, TestDefaultState) {
+  EXPECT_FLOAT_EQ(0.0, m_encoder->Get()) << "The encoder did not start at 0.";
+}
+
+/**
+ * Test the encoder by setting the digital outputs and reading the value.
+ */
+TEST_F(FakeEncoderTest, TestCountUp) {
+  m_encoder->Reset();
+  Simulate100QuadratureTicks();
+
+  EXPECT_FLOAT_EQ(100.0, m_encoder->Get()) << "Encoder did not count to 100.";
+}
+
+/**
+ * Test that the encoder can stay reset while the index source is high
+ */
+TEST_F(FakeEncoderTest, TestResetWhileHigh) {
+  m_encoder->SetIndexSource(*m_indexAnalogTriggerOutput,
+                            Encoder::IndexingType::kResetWhileHigh);
+
+  SetIndexLow();
+  Simulate100QuadratureTicks();
+  SetIndexHigh();
+  EXPECT_EQ(0, m_encoder->Get());
+
+  Simulate100QuadratureTicks();
+  EXPECT_EQ(0, m_encoder->Get());
+}
+
+/**
+ * Test that the encoder can reset when the index source goes from low to high
+ */
+TEST_F(FakeEncoderTest, TestResetOnRisingEdge) {
+  m_encoder->SetIndexSource(*m_indexAnalogTriggerOutput,
+                            Encoder::IndexingType::kResetOnRisingEdge);
+
+  SetIndexLow();
+  Simulate100QuadratureTicks();
+  SetIndexHigh();
+  EXPECT_EQ(0, m_encoder->Get());
+
+  Simulate100QuadratureTicks();
+  EXPECT_EQ(100, m_encoder->Get());
+}
+
+/**
+ * Test that the encoder can stay reset while the index source is low
+ */
+TEST_F(FakeEncoderTest, TestResetWhileLow) {
+  m_encoder->SetIndexSource(*m_indexAnalogTriggerOutput,
+                            Encoder::IndexingType::kResetWhileLow);
+
+  SetIndexHigh();
+  Simulate100QuadratureTicks();
+  SetIndexLow();
+  EXPECT_EQ(0, m_encoder->Get());
+
+  Simulate100QuadratureTicks();
+  EXPECT_EQ(0, m_encoder->Get());
+}
+
+/**
+ * Test that the encoder can reset when the index source goes from high to low
+ */
+TEST_F(FakeEncoderTest, TestResetOnFallingEdge) {
+  m_encoder->SetIndexSource(*m_indexAnalogTriggerOutput,
+                            Encoder::IndexingType::kResetOnFallingEdge);
+
+  SetIndexHigh();
+  Simulate100QuadratureTicks();
+  SetIndexLow();
+  EXPECT_EQ(0, m_encoder->Get());
+
+  Simulate100QuadratureTicks();
+  EXPECT_EQ(100, m_encoder->Get());
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp
new file mode 100644
index 0000000..e750f88
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/MotorEncoderTest.cpp
@@ -0,0 +1,194 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "TestBench.h"
+#include "frc/Encoder.h"
+#include "frc/Jaguar.h"
+#include "frc/PIDController.h"
+#include "frc/Talon.h"
+#include "frc/Timer.h"
+#include "frc/Victor.h"
+#include "frc/filters/LinearDigitalFilter.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+enum MotorEncoderTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON };
+
+std::ostream& operator<<(std::ostream& os, MotorEncoderTestType const& type) {
+  switch (type) {
+    case TEST_VICTOR:
+      os << "Victor";
+      break;
+    case TEST_JAGUAR:
+      os << "Jaguar";
+      break;
+    case TEST_TALON:
+      os << "Talon";
+      break;
+  }
+
+  return os;
+}
+
+static constexpr double kMotorTime = 0.5;
+
+/**
+ * A fixture that includes a PWM speed controller and an encoder connected to
+ * the same motor.
+ */
+class MotorEncoderTest : public testing::TestWithParam<MotorEncoderTestType> {
+ protected:
+  SpeedController* m_speedController;
+  Encoder* m_encoder;
+  LinearDigitalFilter* m_filter;
+
+  void SetUp() override {
+    switch (GetParam()) {
+      case TEST_VICTOR:
+        m_speedController = new Victor(TestBench::kVictorChannel);
+        m_encoder = new Encoder(TestBench::kVictorEncoderChannelA,
+                                TestBench::kVictorEncoderChannelB);
+        break;
+
+      case TEST_JAGUAR:
+        m_speedController = new Jaguar(TestBench::kJaguarChannel);
+        m_encoder = new Encoder(TestBench::kJaguarEncoderChannelA,
+                                TestBench::kJaguarEncoderChannelB);
+        break;
+
+      case TEST_TALON:
+        m_speedController = new Talon(TestBench::kTalonChannel);
+        m_encoder = new Encoder(TestBench::kTalonEncoderChannelA,
+                                TestBench::kTalonEncoderChannelB);
+        break;
+    }
+    m_filter = new LinearDigitalFilter(
+        LinearDigitalFilter::MovingAverage(*m_encoder, 50));
+  }
+
+  void TearDown() override {
+    delete m_speedController;
+    delete m_encoder;
+    delete m_filter;
+  }
+
+  void Reset() {
+    m_speedController->Set(0.0);
+    m_encoder->Reset();
+    m_filter->Reset();
+  }
+};
+
+/**
+ * Test if the encoder value increments after the motor drives forward
+ */
+TEST_P(MotorEncoderTest, Increment) {
+  Reset();
+
+  /* Drive the speed controller briefly to move the encoder */
+  m_speedController->Set(0.2f);
+  Wait(kMotorTime);
+  m_speedController->Set(0.0);
+
+  /* The encoder should be positive now */
+  EXPECT_GT(m_encoder->Get(), 0)
+      << "Encoder should have incremented after the motor moved";
+}
+
+/**
+ * Test if the encoder value decrements after the motor drives backwards
+ */
+TEST_P(MotorEncoderTest, Decrement) {
+  Reset();
+
+  /* Drive the speed controller briefly to move the encoder */
+  m_speedController->Set(-0.2);
+  Wait(kMotorTime);
+  m_speedController->Set(0.0);
+
+  /* The encoder should be positive now */
+  EXPECT_LT(m_encoder->Get(), 0.0)
+      << "Encoder should have decremented after the motor moved";
+}
+
+/**
+ * Test if motor speeds are clamped to [-1,1]
+ */
+TEST_P(MotorEncoderTest, ClampSpeed) {
+  Reset();
+
+  m_speedController->Set(2.0);
+  Wait(kMotorTime);
+
+  EXPECT_FLOAT_EQ(1.0, m_speedController->Get());
+
+  m_speedController->Set(-2.0);
+  Wait(kMotorTime);
+
+  EXPECT_FLOAT_EQ(-1.0, m_speedController->Get());
+}
+
+/**
+ * Test if position PID loop works
+ */
+TEST_P(MotorEncoderTest, PositionPIDController) {
+  Reset();
+  double goal = 1000;
+  m_encoder->SetPIDSourceType(PIDSourceType::kDisplacement);
+  PIDController pid(0.001, 0.0005, 0.0, m_encoder, m_speedController);
+  pid.SetAbsoluteTolerance(50.0);
+  pid.SetOutputRange(-0.2, 0.2);
+  pid.SetSetpoint(goal);
+
+  /* 10 seconds should be plenty time to get to the setpoint */
+  pid.Enable();
+  Wait(10.0);
+  pid.Disable();
+
+  RecordProperty("PIDError", pid.GetError());
+
+  EXPECT_TRUE(pid.OnTarget())
+      << "PID loop did not converge within 10 seconds. Goal was: " << goal
+      << " Error was: " << pid.GetError();
+}
+
+/**
+ * Test if velocity PID loop works
+ */
+TEST_P(MotorEncoderTest, VelocityPIDController) {
+  Reset();
+
+  m_encoder->SetPIDSourceType(PIDSourceType::kRate);
+  PIDController pid(1e-5, 0.0, 3e-5, 8e-5, m_filter, m_speedController);
+  pid.SetAbsoluteTolerance(200.0);
+  pid.SetOutputRange(-0.3, 0.3);
+  pid.SetSetpoint(600);
+
+  /* 10 seconds should be plenty time to get to the setpoint */
+  pid.Enable();
+  Wait(10.0);
+  pid.Disable();
+  RecordProperty("PIDError", pid.GetError());
+
+  EXPECT_TRUE(pid.OnTarget())
+      << "PID loop did not converge within 10 seconds. Goal was: " << 600
+      << " Error was: " << pid.GetError();
+}
+
+/**
+ * Test resetting encoders
+ */
+TEST_P(MotorEncoderTest, Reset) {
+  Reset();
+
+  EXPECT_EQ(0, m_encoder->Get()) << "Encoder did not reset to 0";
+}
+
+INSTANTIATE_TEST_CASE_P(Test, MotorEncoderTest,
+                        testing::Values(TEST_VICTOR, TEST_JAGUAR,
+                                        TEST_TALON), );
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp
new file mode 100644
index 0000000..1e73d97
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/MotorInvertingTest.cpp
@@ -0,0 +1,157 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "TestBench.h"
+#include "frc/Encoder.h"
+#include "frc/Jaguar.h"
+#include "frc/Talon.h"
+#include "frc/Timer.h"
+#include "frc/Victor.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+enum MotorInvertingTestType { TEST_VICTOR, TEST_JAGUAR, TEST_TALON };
+static const double motorSpeed = 0.15;
+static const double delayTime = 0.5;
+std::ostream& operator<<(std::ostream& os, MotorInvertingTestType const& type) {
+  switch (type) {
+    case TEST_VICTOR:
+      os << "Victor";
+      break;
+    case TEST_JAGUAR:
+      os << "Jaguar";
+      break;
+    case TEST_TALON:
+      os << "Talon";
+      break;
+  }
+
+  return os;
+}
+class MotorInvertingTest
+    : public testing::TestWithParam<MotorInvertingTestType> {
+ protected:
+  SpeedController* m_speedController;
+  Encoder* m_encoder;
+
+  void SetUp() override {
+    switch (GetParam()) {
+      case TEST_VICTOR:
+        m_speedController = new Victor(TestBench::kVictorChannel);
+        m_encoder = new Encoder(TestBench::kVictorEncoderChannelA,
+                                TestBench::kVictorEncoderChannelB);
+        break;
+
+      case TEST_JAGUAR:
+        m_speedController = new Jaguar(TestBench::kJaguarChannel);
+        m_encoder = new Encoder(TestBench::kJaguarEncoderChannelA,
+                                TestBench::kJaguarEncoderChannelB);
+        break;
+
+      case TEST_TALON:
+        m_speedController = new Talon(TestBench::kTalonChannel);
+        m_encoder = new Encoder(TestBench::kTalonEncoderChannelA,
+                                TestBench::kTalonEncoderChannelB);
+        break;
+    }
+  }
+
+  void TearDown() override {
+    delete m_speedController;
+    delete m_encoder;
+  }
+
+  void Reset() {
+    m_speedController->SetInverted(false);
+    m_speedController->Set(0.0);
+    m_encoder->Reset();
+  }
+};
+
+TEST_P(MotorInvertingTest, InvertingPositive) {
+  Reset();
+
+  m_speedController->Set(motorSpeed);
+
+  Wait(delayTime);
+
+  bool initDirection = m_encoder->GetDirection();
+  m_speedController->SetInverted(true);
+  m_speedController->Set(motorSpeed);
+
+  Wait(delayTime);
+
+  EXPECT_TRUE(m_encoder->GetDirection() != initDirection)
+      << "Inverting with Positive value does not change direction";
+
+  Reset();
+}
+
+TEST_P(MotorInvertingTest, InvertingNegative) {
+  Reset();
+
+  m_speedController->SetInverted(false);
+  m_speedController->Set(-motorSpeed);
+
+  Wait(delayTime);
+
+  bool initDirection = m_encoder->GetDirection();
+  m_speedController->SetInverted(true);
+  m_speedController->Set(-motorSpeed);
+
+  Wait(delayTime);
+
+  EXPECT_TRUE(m_encoder->GetDirection() != initDirection)
+      << "Inverting with Negative value does not change direction";
+
+  Reset();
+}
+
+TEST_P(MotorInvertingTest, InvertingSwitchingPosToNeg) {
+  Reset();
+
+  m_speedController->SetInverted(false);
+  m_speedController->Set(motorSpeed);
+
+  Wait(delayTime);
+
+  bool initDirection = m_encoder->GetDirection();
+  m_speedController->SetInverted(true);
+  m_speedController->Set(-motorSpeed);
+
+  Wait(delayTime);
+
+  EXPECT_TRUE(m_encoder->GetDirection() == initDirection)
+      << "Inverting with Switching value does change direction";
+
+  Reset();
+}
+
+TEST_P(MotorInvertingTest, InvertingSwitchingNegToPos) {
+  Reset();
+
+  m_speedController->SetInverted(false);
+  m_speedController->Set(-motorSpeed);
+
+  Wait(delayTime);
+
+  bool initDirection = m_encoder->GetDirection();
+  m_speedController->SetInverted(true);
+  m_speedController->Set(motorSpeed);
+
+  Wait(delayTime);
+
+  EXPECT_TRUE(m_encoder->GetDirection() == initDirection)
+      << "Inverting with Switching value does change direction";
+
+  Reset();
+}
+
+INSTANTIATE_TEST_CASE_P(Test, MotorInvertingTest,
+                        testing::Values(TEST_VICTOR, TEST_JAGUAR,
+                                        TEST_TALON), );
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/NotifierTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/NotifierTest.cpp
new file mode 100644
index 0000000..d7f0d6e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/NotifierTest.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/Notifier.h"  // NOLINT(build/include_order)
+
+#include <wpi/raw_ostream.h>
+
+#include "TestBench.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+unsigned notifierCounter;
+
+void notifierHandler(void*) { notifierCounter++; }
+
+/**
+ * Test if the Wait function works
+ */
+TEST(NotifierTest, DISABLED_TestTimerNotifications) {
+  wpi::outs() << "NotifierTest...\n";
+  notifierCounter = 0;
+  wpi::outs() << "notifier(notifierHandler, nullptr)...\n";
+  Notifier notifier(notifierHandler, nullptr);
+  wpi::outs() << "Start Periodic...\n";
+  notifier.StartPeriodic(1.0);
+
+  wpi::outs() << "Wait...\n";
+  Wait(10.5);
+  wpi::outs() << "...Wait\n";
+
+  EXPECT_EQ(10u, notifierCounter)
+      << "Received " << notifierCounter << " notifications in 10.5 seconds";
+  wpi::outs() << "Received " << notifierCounter
+              << " notifications in 10.5 seconds";
+
+  wpi::outs() << "...NotifierTest\n";
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PCMTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PCMTest.cpp
new file mode 100644
index 0000000..5be4d3f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PCMTest.cpp
@@ -0,0 +1,241 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "TestBench.h"
+#include "frc/AnalogInput.h"
+#include "frc/Compressor.h"
+#include "frc/DigitalInput.h"
+#include "frc/DigitalOutput.h"
+#include "frc/DoubleSolenoid.h"
+#include "frc/Solenoid.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+/* The PCM switches the compressor up to a couple seconds after the pressure
+        switch changes. */
+static const double kCompressorDelayTime = 3.0;
+
+/* Solenoids should change much more quickly */
+static const double kSolenoidDelayTime = 0.5;
+
+/* The voltage divider on the test bench should bring the compressor output
+        to around these values. */
+static const double kCompressorOnVoltage = 5.00;
+static const double kCompressorOffVoltage = 1.68;
+
+class PCMTest : public testing::Test {
+ protected:
+  Compressor* m_compressor;
+
+  DigitalOutput* m_fakePressureSwitch;
+  AnalogInput* m_fakeCompressor;
+  DoubleSolenoid* m_doubleSolenoid;
+  DigitalInput *m_fakeSolenoid1, *m_fakeSolenoid2;
+
+  void SetUp() override {
+    m_compressor = new Compressor();
+
+    m_fakePressureSwitch =
+        new DigitalOutput(TestBench::kFakePressureSwitchChannel);
+    m_fakeCompressor = new AnalogInput(TestBench::kFakeCompressorChannel);
+    m_fakeSolenoid1 = new DigitalInput(TestBench::kFakeSolenoid1Channel);
+    m_fakeSolenoid2 = new DigitalInput(TestBench::kFakeSolenoid2Channel);
+  }
+
+  void TearDown() override {
+    delete m_compressor;
+    delete m_fakePressureSwitch;
+    delete m_fakeCompressor;
+    delete m_fakeSolenoid1;
+    delete m_fakeSolenoid2;
+  }
+
+  void Reset() {
+    m_compressor->Stop();
+    m_fakePressureSwitch->Set(false);
+  }
+};
+
+/**
+ * Test if the compressor turns on and off when the pressure switch is toggled
+ */
+TEST_F(PCMTest, PressureSwitch) {
+  Reset();
+
+  m_compressor->SetClosedLoopControl(true);
+
+  // Turn on the compressor
+  m_fakePressureSwitch->Set(true);
+  Wait(kCompressorDelayTime);
+  EXPECT_NEAR(kCompressorOnVoltage, m_fakeCompressor->GetVoltage(), 0.5)
+      << "Compressor did not turn on when the pressure switch turned on.";
+
+  // Turn off the compressor
+  m_fakePressureSwitch->Set(false);
+  Wait(kCompressorDelayTime);
+  EXPECT_NEAR(kCompressorOffVoltage, m_fakeCompressor->GetVoltage(), 0.5)
+      << "Compressor did not turn off when the pressure switch turned off.";
+}
+
+/**
+ * Test if the correct solenoids turn on and off when they should
+ */
+TEST_F(PCMTest, Solenoid) {
+  Reset();
+  Solenoid solenoid1(TestBench::kSolenoidChannel1);
+  Solenoid solenoid2(TestBench::kSolenoidChannel2);
+
+  // Turn both solenoids off
+  solenoid1.Set(false);
+  solenoid2.Set(false);
+  Wait(kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_FALSE(solenoid2.Get()) << "Solenoid #2 did not read off";
+
+  // Turn one solenoid on and one off
+  solenoid1.Set(true);
+  solenoid2.Set(false);
+  Wait(kSolenoidDelayTime);
+  EXPECT_FALSE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn on";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_TRUE(solenoid1.Get()) << "Solenoid #1 did not read on";
+  EXPECT_FALSE(solenoid2.Get()) << "Solenoid #2 did not read off";
+
+  // Turn one solenoid on and one off
+  solenoid1.Set(false);
+  solenoid2.Set(true);
+  Wait(kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_FALSE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn on";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_TRUE(solenoid2.Get()) << "Solenoid #2 did not read on";
+
+  // Turn both on
+  solenoid1.Set(true);
+  solenoid2.Set(true);
+  Wait(kSolenoidDelayTime);
+  EXPECT_FALSE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn on";
+  EXPECT_FALSE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn on";
+  EXPECT_TRUE(solenoid1.Get()) << "Solenoid #1 did not read on";
+  EXPECT_TRUE(solenoid2.Get()) << "Solenoid #2 did not read on";
+}
+
+/**
+ * Test if the correct solenoids turn on and off when they should when used
+ * with the DoubleSolenoid class.
+ */
+TEST_F(PCMTest, DoubleSolenoid) {
+  DoubleSolenoid solenoid(TestBench::kSolenoidChannel1,
+                          TestBench::kSolenoidChannel2);
+
+  solenoid.Set(DoubleSolenoid::kOff);
+  Wait(kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_TRUE(solenoid.Get() == DoubleSolenoid::kOff)
+      << "Solenoid does not read off";
+
+  solenoid.Set(DoubleSolenoid::kForward);
+  Wait(kSolenoidDelayTime);
+  EXPECT_FALSE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn on";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_TRUE(solenoid.Get() == DoubleSolenoid::kForward)
+      << "Solenoid does not read forward";
+
+  solenoid.Set(DoubleSolenoid::kReverse);
+  Wait(kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_FALSE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn on";
+  EXPECT_TRUE(solenoid.Get() == DoubleSolenoid::kReverse)
+      << "Solenoid does not read reverse";
+}
+
+TEST_F(PCMTest, OneShot) {
+  Reset();
+  Solenoid solenoid1(TestBench::kSolenoidChannel1);
+  Solenoid solenoid2(TestBench::kSolenoidChannel2);
+
+  // Turn both solenoids off
+  solenoid1.Set(false);
+  solenoid2.Set(false);
+  Wait(kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_FALSE(solenoid2.Get()) << "Solenoid #2 did not read off";
+
+  // Pulse Solenoid #1 on, and turn Solenoid #2 off
+  solenoid1.SetPulseDuration(2 * kSolenoidDelayTime);
+  solenoid2.Set(false);
+  solenoid1.StartPulse();
+  Wait(kSolenoidDelayTime);
+  EXPECT_FALSE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn on";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_TRUE(solenoid1.Get()) << "Solenoid #1 did not read on";
+  EXPECT_FALSE(solenoid2.Get()) << "Solenoid #2 did not read off";
+  Wait(2 * kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_FALSE(solenoid2.Get()) << "Solenoid #2 did not read off";
+
+  // Turn Solenoid #1 off, and pulse Solenoid #2 on
+  solenoid1.Set(false);
+  solenoid2.SetPulseDuration(2 * kSolenoidDelayTime);
+  solenoid2.StartPulse();
+  Wait(kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_FALSE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn on";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_TRUE(solenoid2.Get()) << "Solenoid #2 did not read on";
+  Wait(2 * kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_FALSE(solenoid2.Get()) << "Solenoid #2 did not read off";
+
+  // Pulse both Solenoids on
+  solenoid1.SetPulseDuration(2 * kSolenoidDelayTime);
+  solenoid2.SetPulseDuration(2 * kSolenoidDelayTime);
+  solenoid1.StartPulse();
+  solenoid2.StartPulse();
+  Wait(kSolenoidDelayTime);
+  EXPECT_FALSE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn on";
+  EXPECT_FALSE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn on";
+  EXPECT_TRUE(solenoid1.Get()) << "Solenoid #1 did not read on";
+  EXPECT_TRUE(solenoid2.Get()) << "Solenoid #2 did not read on";
+  Wait(2 * kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_FALSE(solenoid2.Get()) << "Solenoid #2 did not read off";
+
+  // Pulse both Solenoids on with different durations
+  solenoid1.SetPulseDuration(1.5 * kSolenoidDelayTime);
+  solenoid2.SetPulseDuration(2.5 * kSolenoidDelayTime);
+  solenoid1.StartPulse();
+  solenoid2.StartPulse();
+  Wait(kSolenoidDelayTime);
+  EXPECT_FALSE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn on";
+  EXPECT_FALSE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn on";
+  EXPECT_TRUE(solenoid1.Get()) << "Solenoid #1 did not read on";
+  EXPECT_TRUE(solenoid2.Get()) << "Solenoid #2 did not read on";
+  Wait(kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_FALSE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn on";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_TRUE(solenoid2.Get()) << "Solenoid #2 did not read on";
+  Wait(2 * kSolenoidDelayTime);
+  EXPECT_TRUE(m_fakeSolenoid1->Get()) << "Solenoid #1 did not turn off";
+  EXPECT_TRUE(m_fakeSolenoid2->Get()) << "Solenoid #2 did not turn off";
+  EXPECT_FALSE(solenoid1.Get()) << "Solenoid #1 did not read off";
+  EXPECT_FALSE(solenoid2.Get()) << "Solenoid #2 did not read off";
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PIDToleranceTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PIDToleranceTest.cpp
new file mode 100644
index 0000000..ec3b85a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PIDToleranceTest.cpp
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "TestBench.h"
+#include "frc/PIDController.h"
+#include "frc/PIDOutput.h"
+#include "frc/PIDSource.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class PIDToleranceTest : public testing::Test {
+ protected:
+  const double setpoint = 50.0;
+  const double range = 200;
+  const double tolerance = 10.0;
+
+  class FakeInput : public PIDSource {
+   public:
+    double val = 0;
+
+    void SetPIDSourceType(PIDSourceType pidSource) {}
+
+    PIDSourceType GetPIDSourceType() { return PIDSourceType::kDisplacement; }
+
+    double PIDGet() { return val; }
+  };
+
+  class FakeOutput : public PIDOutput {
+    void PIDWrite(double output) {}
+  };
+
+  FakeInput inp;
+  FakeOutput out;
+  PIDController* pid;
+
+  void SetUp() override {
+    pid = new PIDController(0.5, 0.0, 0.0, &inp, &out);
+    pid->SetInputRange(-range / 2, range / 2);
+  }
+
+  void TearDown() override { delete pid; }
+
+  void Reset() { inp.val = 0; }
+};
+
+TEST_F(PIDToleranceTest, Absolute) {
+  Reset();
+
+  pid->SetAbsoluteTolerance(tolerance);
+  pid->SetSetpoint(setpoint);
+  pid->Enable();
+
+  EXPECT_FALSE(pid->OnTarget())
+      << "Error was in tolerance when it should not have been. Error was "
+      << pid->GetError();
+
+  inp.val = setpoint + tolerance / 2;
+  Wait(1.0);
+
+  EXPECT_TRUE(pid->OnTarget())
+      << "Error was not in tolerance when it should have been. Error was "
+      << pid->GetError();
+
+  inp.val = setpoint + 10 * tolerance;
+  Wait(1.0);
+
+  EXPECT_FALSE(pid->OnTarget())
+      << "Error was in tolerance when it should not have been. Error was "
+      << pid->GetError();
+}
+
+TEST_F(PIDToleranceTest, Percent) {
+  Reset();
+
+  pid->SetPercentTolerance(tolerance);
+  pid->SetSetpoint(setpoint);
+  pid->Enable();
+
+  EXPECT_FALSE(pid->OnTarget())
+      << "Error was in tolerance when it should not have been. Error was "
+      << pid->GetError();
+
+  inp.val =
+      setpoint + (tolerance) / 200 *
+                     range;  // half of percent tolerance away from setpoint
+  Wait(1.0);
+
+  EXPECT_TRUE(pid->OnTarget())
+      << "Error was not in tolerance when it should have been. Error was "
+      << pid->GetError();
+
+  inp.val =
+      setpoint +
+      (tolerance) / 50 * range;  // double percent tolerance away from setPoint
+
+  Wait(1.0);
+
+  EXPECT_FALSE(pid->OnTarget())
+      << "Error was in tolerance when it should not have been. Error was "
+      << pid->GetError();
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PowerDistributionPanelTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PowerDistributionPanelTest.cpp
new file mode 100644
index 0000000..5917361
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PowerDistributionPanelTest.cpp
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/PowerDistributionPanel.h"  // NOLINT(build/include_order)
+
+#include <thread>
+
+#include <hal/Ports.h>
+
+#include "TestBench.h"
+#include "frc/Jaguar.h"
+#include "frc/Talon.h"
+#include "frc/Timer.h"
+#include "frc/Victor.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const double kMotorTime = 0.25;
+
+class PowerDistributionPanelTest : public testing::Test {
+ protected:
+  PowerDistributionPanel* m_pdp;
+  Talon* m_talon;
+  Victor* m_victor;
+  Jaguar* m_jaguar;
+
+  void SetUp() override {
+    m_pdp = new PowerDistributionPanel();
+    m_talon = new Talon(TestBench::kTalonChannel);
+    m_victor = new Victor(TestBench::kVictorChannel);
+    m_jaguar = new Jaguar(TestBench::kJaguarChannel);
+  }
+
+  void TearDown() override {
+    delete m_pdp;
+    delete m_talon;
+    delete m_victor;
+    delete m_jaguar;
+  }
+};
+
+TEST_F(PowerDistributionPanelTest, CheckRepeatedCalls) {
+  auto numChannels = HAL_GetNumPDPChannels();
+  // 1 second
+  for (int i = 0; i < 50; i++) {
+    for (int j = 0; j < numChannels; j++) {
+      m_pdp->GetCurrent(j);
+      ASSERT_TRUE(m_pdp->GetError().GetCode() == 0);
+    }
+    m_pdp->GetVoltage();
+    ASSERT_TRUE(m_pdp->GetError().GetCode() == 0);
+  }
+  std::this_thread::sleep_for(std::chrono::milliseconds(20));
+}
+
+/**
+ * Test if the current changes when the motor is driven using a talon
+ */
+TEST_F(PowerDistributionPanelTest, CheckCurrentTalon) {
+  Wait(kMotorTime);
+
+  /* The Current should be 0 */
+  EXPECT_FLOAT_EQ(0, m_pdp->GetCurrent(TestBench::kTalonPDPChannel))
+      << "The Talon current was non-zero";
+
+  /* Set the motor to full forward */
+  m_talon->Set(1.0);
+  Wait(kMotorTime);
+
+  /* The current should now be positive */
+  ASSERT_GT(m_pdp->GetCurrent(TestBench::kTalonPDPChannel), 0)
+      << "The Talon current was not positive";
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PreferencesTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PreferencesTest.cpp
new file mode 100644
index 0000000..ffb4d9f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/PreferencesTest.cpp
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/Preferences.h"  // NOLINT(build/include_order)
+
+#include <cstdio>
+#include <fstream>
+
+#include <networktables/NetworkTableInstance.h>
+#include <ntcore.h>
+
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const char* kFileName = "networktables.ini";
+static const double kSaveTime = 1.2;
+
+/**
+ * If we write a new networktables.ini with some sample values, test that
+ * we get those same values back using the Preference class.
+ */
+TEST(PreferencesTest, ReadPreferencesFromFile) {
+  auto inst = nt::NetworkTableInstance::GetDefault();
+  inst.StopServer();
+  std::remove(kFileName);
+  std::ofstream preferencesFile(kFileName);
+  preferencesFile << "[NetworkTables Storage 3.0]" << std::endl;
+  preferencesFile
+      << "string \"/Preferences/testFileGetString\"=\"Hello, preferences file\""
+      << std::endl;
+  preferencesFile << "double \"/Preferences/testFileGetInt\"=1" << std::endl;
+  preferencesFile << "double \"/Preferences/testFileGetDouble\"=0.5"
+                  << std::endl;
+  preferencesFile << "double \"/Preferences/testFileGetFloat\"=0.25"
+                  << std::endl;
+  preferencesFile << "boolean \"/Preferences/testFileGetBoolean\"=true"
+                  << std::endl;
+  preferencesFile
+      << "double \"/Preferences/testFileGetLong\"=1000000000000000000"
+      << std::endl;
+  preferencesFile.close();
+  inst.StartServer();
+
+  Preferences* preferences = Preferences::GetInstance();
+  EXPECT_EQ("Hello, preferences file",
+            preferences->GetString("testFileGetString"));
+  EXPECT_EQ(1, preferences->GetInt("testFileGetInt"));
+  EXPECT_FLOAT_EQ(0.5, preferences->GetDouble("testFileGetDouble"));
+  EXPECT_FLOAT_EQ(0.25f, preferences->GetFloat("testFileGetFloat"));
+  EXPECT_TRUE(preferences->GetBoolean("testFileGetBoolean"));
+  EXPECT_EQ(1000000000000000000ll, preferences->GetLong("testFileGetLong"));
+}
+
+/**
+ * If we set some values using the Preferences class, test that they show up
+ * in networktables.ini
+ */
+TEST(PreferencesTest, WritePreferencesToFile) {
+  auto inst = nt::NetworkTableInstance::GetDefault();
+  inst.StartServer();
+  Preferences* preferences = Preferences::GetInstance();
+  preferences->Remove("testFileGetString");
+  preferences->Remove("testFileGetInt");
+  preferences->Remove("testFileGetDouble");
+  preferences->Remove("testFileGetFloat");
+  preferences->Remove("testFileGetBoolean");
+  preferences->Remove("testFileGetLong");
+
+  Wait(kSaveTime);
+
+  preferences->PutString("testFilePutString", "Hello, preferences file");
+  preferences->PutInt("testFilePutInt", 1);
+  preferences->PutDouble("testFilePutDouble", 0.5);
+  preferences->PutFloat("testFilePutFloat", 0.25f);
+  preferences->PutBoolean("testFilePutBoolean", true);
+  preferences->PutLong("testFilePutLong", 1000000000000000000ll);
+
+  Wait(kSaveTime);
+
+  static char const* kExpectedFileContents[] = {
+      "[NetworkTables Storage 3.0]",
+      "string \"/Preferences/.type\"=\"RobotPreferences\"",
+      "boolean \"/Preferences/testFilePutBoolean\"=true",
+      "double \"/Preferences/testFilePutDouble\"=0.5",
+      "double \"/Preferences/testFilePutFloat\"=0.25",
+      "double \"/Preferences/testFilePutInt\"=1",
+      "double \"/Preferences/testFilePutLong\"=1e+18",
+      "string \"/Preferences/testFilePutString\"=\"Hello, preferences file\""};
+
+  std::ifstream preferencesFile(kFileName);
+  for (auto& kExpectedFileContent : kExpectedFileContents) {
+    ASSERT_FALSE(preferencesFile.eof())
+        << "Preferences file prematurely reached EOF";
+
+    std::string line;
+    std::getline(preferencesFile, line);
+
+    ASSERT_EQ(kExpectedFileContent, line)
+        << "A line in networktables.ini was not correct";
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/RelayTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/RelayTest.cpp
new file mode 100644
index 0000000..eb45eeb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/RelayTest.cpp
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/Relay.h"  // NOLINT(build/include_order)
+
+#include "TestBench.h"
+#include "frc/DigitalInput.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const double kDelayTime = 0.01;
+
+class RelayTest : public testing::Test {
+ protected:
+  Relay* m_relay;
+  DigitalInput* m_forward;
+  DigitalInput* m_reverse;
+
+  void SetUp() override {
+    m_relay = new Relay(TestBench::kRelayChannel);
+    m_forward = new DigitalInput(TestBench::kFakeRelayForward);
+    m_reverse = new DigitalInput(TestBench::kFakeRelayReverse);
+  }
+
+  void TearDown() override {
+    delete m_relay;
+    delete m_forward;
+    delete m_reverse;
+  }
+
+  void Reset() { m_relay->Set(Relay::kOff); }
+};
+
+/**
+ * Test the relay by setting it forward, reverse, off, and on.
+ */
+TEST_F(RelayTest, Relay) {
+  Reset();
+
+  // set the relay to forward
+  m_relay->Set(Relay::kForward);
+  Wait(kDelayTime);
+  EXPECT_TRUE(m_forward->Get()) << "Relay did not set forward";
+  EXPECT_FALSE(m_reverse->Get()) << "Relay did not set forward";
+  EXPECT_EQ(m_relay->Get(), Relay::kForward);
+
+  // set the relay to reverse
+  m_relay->Set(Relay::kReverse);
+  Wait(kDelayTime);
+  EXPECT_TRUE(m_reverse->Get()) << "Relay did not set reverse";
+  EXPECT_FALSE(m_forward->Get()) << "Relay did not set reverse";
+  EXPECT_EQ(m_relay->Get(), Relay::kReverse);
+
+  // set the relay to off
+  m_relay->Set(Relay::kOff);
+  Wait(kDelayTime);
+  EXPECT_FALSE(m_forward->Get()) << "Relay did not set off";
+  EXPECT_FALSE(m_reverse->Get()) << "Relay did not set off";
+  EXPECT_EQ(m_relay->Get(), Relay::kOff);
+
+  // set the relay to on
+  m_relay->Set(Relay::kOn);
+  Wait(kDelayTime);
+  EXPECT_TRUE(m_forward->Get()) << "Relay did not set on";
+  EXPECT_TRUE(m_reverse->Get()) << "Relay did not set on";
+  EXPECT_EQ(m_relay->Get(), Relay::kOn);
+
+  // test forward direction
+  delete m_relay;
+  m_relay = new Relay(TestBench::kRelayChannel, Relay::kForwardOnly);
+
+  m_relay->Set(Relay::kOn);
+  Wait(kDelayTime);
+  EXPECT_TRUE(m_forward->Get()) << "Relay did not set forward";
+  EXPECT_FALSE(m_reverse->Get()) << "Relay did not set forward";
+  EXPECT_EQ(m_relay->Get(), Relay::kOn);
+
+  // test reverse direction
+  delete m_relay;
+  m_relay = new Relay(TestBench::kRelayChannel, Relay::kReverseOnly);
+
+  m_relay->Set(Relay::kOn);
+  Wait(kDelayTime);
+  EXPECT_FALSE(m_forward->Get()) << "Relay did not set reverse";
+  EXPECT_TRUE(m_reverse->Get()) << "Relay did not set reverse";
+  EXPECT_EQ(m_relay->Get(), Relay::kOn);
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TestEnvironment.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TestEnvironment.cpp
new file mode 100644
index 0000000..2bfe1b3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TestEnvironment.cpp
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 <cstdlib>
+
+#include <hal/HAL.h>
+#include <wpi/raw_ostream.h>
+
+#include "frc/DriverStation.h"
+#include "frc/Timer.h"
+#include "frc/livewindow/LiveWindow.h"
+#include "gtest/gtest.h"
+#include "mockds/MockDS.h"
+
+using namespace frc;
+
+class TestEnvironment : public testing::Environment {
+  bool m_alreadySetUp = false;
+  MockDS m_mockDS;
+
+ public:
+  void SetUp() override {
+    /* Only set up once.  This allows gtest_repeat to be used to
+            automatically repeat tests. */
+    if (m_alreadySetUp) return;
+    m_alreadySetUp = true;
+
+    if (!HAL_Initialize(500, 0)) {
+      wpi::errs() << "FATAL ERROR: HAL could not be initialized\n";
+      std::exit(-1);
+    }
+
+    m_mockDS.start();
+
+    /* This sets up the network communications library to enable the driver
+            station. After starting network coms, it will loop until the driver
+            station returns that the robot is enabled, to ensure that tests
+            will be able to run on the hardware. */
+    HAL_ObserveUserProgramStarting();
+    LiveWindow::GetInstance()->SetEnabled(false);
+
+    wpi::outs() << "Started coms\n";
+
+    int enableCounter = 0;
+    while (!DriverStation::GetInstance().IsEnabled()) {
+      if (enableCounter > 50) {
+        // Robot did not enable properly after 5 seconds.
+        // Force exit
+        wpi::errs() << " Failed to enable. Aborting\n";
+        std::terminate();
+      }
+
+      Wait(0.1);
+
+      wpi::outs() << "Waiting for enable: " << enableCounter++ << "\n";
+    }
+  }
+
+  void TearDown() override { m_mockDS.stop(); }
+};
+
+testing::Environment* const environment =
+    testing::AddGlobalTestEnvironment(new TestEnvironment);
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TiltPanCameraTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TiltPanCameraTest.cpp
new file mode 100644
index 0000000..852429b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TiltPanCameraTest.cpp
@@ -0,0 +1,172 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 <cmath>
+
+#include "TestBench.h"
+#include "frc/ADXL345_SPI.h"
+#include "frc/AnalogGyro.h"
+#include "frc/Servo.h"
+#include "frc/Timer.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static constexpr double kServoResetTime = 2.0;
+
+static constexpr double kTestAngle = 90.0;
+
+static constexpr double kTiltSetpoint0 = 0.22;
+static constexpr double kTiltSetpoint45 = 0.45;
+static constexpr double kTiltSetpoint90 = 0.68;
+static constexpr double kTiltTime = 1.0;
+static constexpr double kAccelerometerTolerance = 0.2;
+static constexpr double kSensitivity = 0.013;
+
+/**
+ * A fixture for the camera with two servos and a gyro
+ */
+class TiltPanCameraTest : public testing::Test {
+ protected:
+  static AnalogGyro* m_gyro;
+  Servo *m_tilt, *m_pan;
+  Accelerometer* m_spiAccel;
+
+  static void SetUpTestCase() {
+    // The gyro object blocks for 5 seconds in the constructor, so only
+    // construct it once for the whole test case
+    m_gyro = new AnalogGyro(TestBench::kCameraGyroChannel);
+    m_gyro->SetSensitivity(kSensitivity);
+  }
+
+  static void TearDownTestCase() { delete m_gyro; }
+
+  void SetUp() override {
+    m_tilt = new Servo(TestBench::kCameraTiltChannel);
+    m_pan = new Servo(TestBench::kCameraPanChannel);
+    m_spiAccel = new ADXL345_SPI(SPI::kOnboardCS1);
+
+    m_tilt->Set(kTiltSetpoint45);
+    m_pan->SetAngle(0.0);
+
+    Wait(kServoResetTime);
+
+    m_gyro->Reset();
+  }
+
+  void DefaultGyroAngle();
+  void GyroAngle();
+  void GyroCalibratedParameters();
+
+  void TearDown() override {
+    delete m_tilt;
+    delete m_pan;
+    delete m_spiAccel;
+  }
+};
+
+AnalogGyro* TiltPanCameraTest::m_gyro = nullptr;
+
+/**
+ * Test if the gyro angle defaults to 0 immediately after being reset.
+ */
+void TiltPanCameraTest::DefaultGyroAngle() {
+  EXPECT_NEAR(0.0, m_gyro->GetAngle(), 1.0);
+}
+
+/**
+ * Test if the servo turns 90 degrees and the gyroscope measures this angle
+ * Note servo on TestBench is not the same type of servo that servo class
+ * was designed for so setAngle is significantly off. This has been calibrated
+ * for the servo on the rig.
+ */
+void TiltPanCameraTest::GyroAngle() {
+  // Make sure that the gyro doesn't get jerked when the servo goes to zero.
+  m_pan->SetAngle(0.0);
+  Wait(0.5);
+  m_gyro->Reset();
+
+  for (int32_t i = 0; i < 600; i++) {
+    m_pan->Set(i / 1000.0);
+    Wait(0.001);
+  }
+
+  double gyroAngle = m_gyro->GetAngle();
+
+  EXPECT_NEAR(gyroAngle, kTestAngle, 10.0)
+      << "Gyro measured " << gyroAngle << " degrees, servo should have turned "
+      << kTestAngle << " degrees";
+}
+
+/**
+ * Gets calibrated parameters from previously calibrated gyro, allocates a new
+ * gyro with the given parameters for center and offset, and re-runs tests on
+ * the new gyro.
+ */
+void TiltPanCameraTest::GyroCalibratedParameters() {
+  uint32_t cCenter = m_gyro->GetCenter();
+  double cOffset = m_gyro->GetOffset();
+  delete m_gyro;
+  m_gyro = new AnalogGyro(TestBench::kCameraGyroChannel, cCenter, cOffset);
+  m_gyro->SetSensitivity(kSensitivity);
+
+  // Default gyro angle test
+  // Accumulator needs a small amount of time to reset before being tested
+  m_gyro->Reset();
+  Wait(0.001);
+  EXPECT_NEAR(0.0, m_gyro->GetAngle(), 1.0);
+
+  // Gyro angle test
+  // Make sure that the gyro doesn't get jerked when the servo goes to zero.
+  m_pan->SetAngle(0.0);
+  Wait(0.5);
+  m_gyro->Reset();
+
+  for (int32_t i = 0; i < 600; i++) {
+    m_pan->Set(i / 1000.0);
+    Wait(0.001);
+  }
+
+  double gyroAngle = m_gyro->GetAngle();
+
+  EXPECT_NEAR(gyroAngle, kTestAngle, 10.0)
+      << "Gyro measured " << gyroAngle << " degrees, servo should have turned "
+      << kTestAngle << " degrees";
+}
+
+/**
+ * Run all gyro tests in one function to make sure they are run in order.
+ */
+TEST_F(TiltPanCameraTest, TestAllGyroTests) {
+  DefaultGyroAngle();
+  GyroAngle();
+  GyroCalibratedParameters();
+}
+
+/**
+ * Test if the accelerometer measures gravity along the correct axes when the
+ * camera rotates
+ */
+TEST_F(TiltPanCameraTest, SPIAccelerometer) {
+  m_tilt->Set(kTiltSetpoint0);
+  Wait(kTiltTime);
+  EXPECT_NEAR(-1.0, m_spiAccel->GetX(), kAccelerometerTolerance);
+  EXPECT_NEAR(0.0, m_spiAccel->GetY(), kAccelerometerTolerance);
+  EXPECT_NEAR(0.0, m_spiAccel->GetZ(), kAccelerometerTolerance);
+
+  m_tilt->Set(kTiltSetpoint45);
+  Wait(kTiltTime);
+  EXPECT_NEAR(-std::sqrt(0.5), m_spiAccel->GetX(), kAccelerometerTolerance);
+  EXPECT_NEAR(0.0, m_spiAccel->GetY(), kAccelerometerTolerance);
+  EXPECT_NEAR(std::sqrt(0.5), m_spiAccel->GetZ(), kAccelerometerTolerance);
+
+  m_tilt->Set(kTiltSetpoint90);
+  Wait(kTiltTime);
+  EXPECT_NEAR(0.0, m_spiAccel->GetX(), kAccelerometerTolerance);
+  EXPECT_NEAR(0.0, m_spiAccel->GetY(), kAccelerometerTolerance);
+  EXPECT_NEAR(1.0, m_spiAccel->GetZ(), kAccelerometerTolerance);
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TimerTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TimerTest.cpp
new file mode 100644
index 0000000..b8f859c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/TimerTest.cpp
@@ -0,0 +1,41 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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/Timer.h"  // NOLINT(build/include_order)
+
+#include "TestBench.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+static const double kWaitTime = 0.5;
+
+class TimerTest : public testing::Test {
+ protected:
+  Timer* m_timer;
+
+  void SetUp() override { m_timer = new Timer; }
+
+  void TearDown() override { delete m_timer; }
+
+  void Reset() { m_timer->Reset(); }
+};
+
+/**
+ * Test if the Wait function works
+ */
+TEST_F(TimerTest, Wait) {
+  Reset();
+
+  double initialTime = m_timer->GetFPGATimestamp();
+
+  Wait(kWaitTime);
+
+  double finalTime = m_timer->GetFPGATimestamp();
+
+  EXPECT_NEAR(kWaitTime, finalTime - initialTime, 0.001);
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/CommandTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/CommandTest.cpp
new file mode 100644
index 0000000..fec442a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/CommandTest.cpp
@@ -0,0 +1,440 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "command/MockCommand.h"
+#include "frc/DriverStation.h"
+#include "frc/RobotState.h"
+#include "frc/Timer.h"
+#include "frc/commands/CommandGroup.h"
+#include "frc/commands/Scheduler.h"
+#include "frc/commands/Subsystem.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class CommandTest : public testing::Test {
+ protected:
+  void SetUp() override { Scheduler::GetInstance()->SetEnabled(true); }
+
+  /**
+   * Tears Down the Scheduler at the end of each test.
+   * Must be called at the end of each test inside each test in order to prevent
+   * them being deallocated
+   * when they leave the scope of the test (causing a segfault).
+   * This can not be done within the virtual void Teardown() method because it
+   * is called outside of the
+   * scope of the test.
+   */
+  void TeardownScheduler() { Scheduler::GetInstance()->ResetAll(); }
+
+  void AssertCommandState(MockCommand* command, int32_t initialize,
+                          int32_t execute, int32_t isFinished, int32_t end,
+                          int32_t interrupted) {
+    EXPECT_EQ(initialize, command->GetInitializeCount());
+    EXPECT_EQ(execute, command->GetExecuteCount());
+    EXPECT_EQ(isFinished, command->GetIsFinishedCount());
+    EXPECT_EQ(end, command->GetEndCount());
+    EXPECT_EQ(interrupted, command->GetInterruptedCount());
+  }
+};
+
+class ASubsystem : public Subsystem {
+ private:
+  Command* m_command = nullptr;
+
+ public:
+  explicit ASubsystem(const std::string& name) : Subsystem(name) {}
+
+  void InitDefaultCommand() override {
+    if (m_command != nullptr) {
+      SetDefaultCommand(m_command);
+    }
+  }
+
+  void Init(Command* command) { m_command = command; }
+};
+
+// CommandParallelGroupTest ported from CommandParallelGroupTest.java
+TEST_F(CommandTest, ParallelCommands) {
+  auto command1 = new MockCommand;
+  auto command2 = new MockCommand;
+  CommandGroup commandGroup;
+
+  commandGroup.AddParallel(command1);
+  commandGroup.AddParallel(command2);
+
+  AssertCommandState(command1, 0, 0, 0, 0, 0);
+  AssertCommandState(command2, 0, 0, 0, 0, 0);
+  commandGroup.Start();
+  AssertCommandState(command1, 0, 0, 0, 0, 0);
+  AssertCommandState(command2, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 0, 0, 0, 0, 0);
+  AssertCommandState(command2, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 1, 1, 0, 0);
+  AssertCommandState(command2, 1, 1, 1, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 2, 2, 0, 0);
+  AssertCommandState(command2, 1, 2, 2, 0, 0);
+  command1->SetHasFinished(true);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 3, 3, 1, 0);
+  AssertCommandState(command2, 1, 3, 3, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 3, 3, 1, 0);
+  AssertCommandState(command2, 1, 4, 4, 0, 0);
+  command2->SetHasFinished(true);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 3, 3, 1, 0);
+  AssertCommandState(command2, 1, 5, 5, 1, 0);
+
+  TeardownScheduler();
+}
+// END CommandParallelGroupTest
+
+// CommandScheduleTest ported from CommandScheduleTest.java
+TEST_F(CommandTest, RunAndTerminate) {
+  MockCommand command;
+  command.Start();
+  AssertCommandState(&command, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 1, 1, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 2, 2, 0, 0);
+  command.SetHasFinished(true);
+  AssertCommandState(&command, 1, 2, 2, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 3, 3, 1, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 3, 3, 1, 0);
+
+  TeardownScheduler();
+}
+
+TEST_F(CommandTest, RunAndCancel) {
+  MockCommand command;
+  command.Start();
+  AssertCommandState(&command, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 1, 1, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 2, 2, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 3, 3, 0, 0);
+  command.Cancel();
+  AssertCommandState(&command, 1, 3, 3, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 3, 3, 0, 1);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 3, 3, 0, 1);
+
+  TeardownScheduler();
+}
+// END CommandScheduleTest
+
+// CommandSequentialGroupTest ported from CommandSequentialGroupTest.java
+TEST_F(CommandTest, ThreeCommandOnSubSystem) {
+  ASubsystem subsystem("Three Command Test Subsystem");
+  auto command1 = new MockCommand;
+  command1->Requires(&subsystem);
+  auto command2 = new MockCommand;
+  command2->Requires(&subsystem);
+  auto command3 = new MockCommand;
+  command3->Requires(&subsystem);
+
+  CommandGroup commandGroup;
+  commandGroup.AddSequential(command1, 1.0);
+  commandGroup.AddSequential(command2, 2.0);
+  commandGroup.AddSequential(command3);
+
+  AssertCommandState(command1, 0, 0, 0, 0, 0);
+  AssertCommandState(command2, 0, 0, 0, 0, 0);
+  AssertCommandState(command3, 0, 0, 0, 0, 0);
+
+  commandGroup.Start();
+  AssertCommandState(command1, 0, 0, 0, 0, 0);
+  AssertCommandState(command2, 0, 0, 0, 0, 0);
+  AssertCommandState(command3, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 0, 0, 0, 0, 0);
+  AssertCommandState(command2, 0, 0, 0, 0, 0);
+  AssertCommandState(command3, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 1, 1, 0, 0);
+  AssertCommandState(command2, 0, 0, 0, 0, 0);
+  AssertCommandState(command3, 0, 0, 0, 0, 0);
+  Wait(1);  // command 1 timeout
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 1, 1, 0, 1);
+  AssertCommandState(command2, 1, 1, 1, 0, 0);
+  AssertCommandState(command3, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 1, 1, 0, 1);
+  AssertCommandState(command2, 1, 2, 2, 0, 0);
+  AssertCommandState(command3, 0, 0, 0, 0, 0);
+  Wait(2);  // command 2 timeout
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 1, 1, 0, 1);
+  AssertCommandState(command2, 1, 2, 2, 0, 1);
+  AssertCommandState(command3, 1, 1, 1, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 1, 1, 0, 1);
+  AssertCommandState(command2, 1, 2, 2, 0, 1);
+  AssertCommandState(command3, 1, 2, 2, 0, 0);
+  command3->SetHasFinished(true);
+  AssertCommandState(command1, 1, 1, 1, 0, 1);
+  AssertCommandState(command2, 1, 2, 2, 0, 1);
+  AssertCommandState(command3, 1, 2, 2, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 1, 1, 0, 1);
+  AssertCommandState(command2, 1, 2, 2, 0, 1);
+  AssertCommandState(command3, 1, 3, 3, 1, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(command1, 1, 1, 1, 0, 1);
+  AssertCommandState(command2, 1, 2, 2, 0, 1);
+  AssertCommandState(command3, 1, 3, 3, 1, 0);
+
+  TeardownScheduler();
+}
+// END CommandSequentialGroupTest
+
+// CommandSequentialGroupTest ported from CommandSequentialGroupTest.java
+TEST_F(CommandTest, OneCommandSupersedingAnotherBecauseOfDependencies) {
+  ASubsystem subsystem("Command Superseding Test Subsystem");
+  MockCommand command1;
+  command1.Requires(&subsystem);
+  MockCommand command2;
+  command2.Requires(&subsystem);
+
+  AssertCommandState(&command1, 0, 0, 0, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  command1.Start();
+  AssertCommandState(&command1, 0, 0, 0, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 0, 0, 0, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 1, 1, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 2, 2, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 3, 3, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  command2.Start();
+  AssertCommandState(&command1, 1, 3, 3, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 4, 4, 0, 1);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 4, 4, 0, 1);
+  AssertCommandState(&command2, 1, 1, 1, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 4, 4, 0, 1);
+  AssertCommandState(&command2, 1, 2, 2, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 4, 4, 0, 1);
+  AssertCommandState(&command2, 1, 3, 3, 0, 0);
+
+  TeardownScheduler();
+}
+
+TEST_F(CommandTest,
+       OneCommandFailingSupersedingBecauseFirstCanNotBeInterrupted) {
+  ASubsystem subsystem("Command Superseding Test Subsystem");
+  MockCommand command1;
+
+  command1.Requires(&subsystem);
+
+  command1.SetInterruptible(false);
+  MockCommand command2;
+  command2.Requires(&subsystem);
+
+  AssertCommandState(&command1, 0, 0, 0, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  command1.Start();
+  AssertCommandState(&command1, 0, 0, 0, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 0, 0, 0, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 1, 1, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 2, 2, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 3, 3, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  command2.Start();
+  AssertCommandState(&command1, 1, 3, 3, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command1, 1, 4, 4, 0, 0);
+  AssertCommandState(&command2, 0, 0, 0, 0, 0);
+
+  TeardownScheduler();
+}
+
+// END CommandSequentialGroupTest
+
+class ModifiedMockCommand : public MockCommand {
+ public:
+  ModifiedMockCommand() : MockCommand() { SetTimeout(2.0); }
+  bool IsFinished() override {
+    return MockCommand::IsFinished() || IsTimedOut();
+  }
+};
+
+TEST_F(CommandTest, TwoSecondTimeout) {
+  ASubsystem subsystem("Two Second Timeout Test Subsystem");
+  ModifiedMockCommand command;
+  command.Requires(&subsystem);
+
+  command.Start();
+  AssertCommandState(&command, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 1, 1, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 2, 2, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 3, 3, 0, 0);
+  Wait(2);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 4, 4, 1, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(&command, 1, 4, 4, 1, 0);
+
+  TeardownScheduler();
+}
+
+TEST_F(CommandTest, DefaultCommandWhereTheInteruptingCommandEndsItself) {
+  ASubsystem subsystem("Default Command Test Subsystem");
+  auto defaultCommand = new MockCommand;
+  defaultCommand->Requires(&subsystem);
+  MockCommand anotherCommand;
+  anotherCommand.Requires(&subsystem);
+
+  AssertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+  subsystem.Init(defaultCommand);
+
+  AssertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 1, 1, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 2, 2, 0, 0);
+
+  anotherCommand.Start();
+  AssertCommandState(defaultCommand, 1, 2, 2, 0, 0);
+  AssertCommandState(&anotherCommand, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 1, 1, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 2, 2, 0, 0);
+  anotherCommand.SetHasFinished(true);
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 2, 2, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 3, 3, 1, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 2, 4, 4, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 3, 3, 1, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 2, 5, 5, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 3, 3, 1, 0);
+
+  TeardownScheduler();
+}
+
+TEST_F(CommandTest, DefaultCommandsInterruptingCommandCanceled) {
+  ASubsystem subsystem("Default Command Test Subsystem");
+  auto defaultCommand = new MockCommand;
+  defaultCommand->Requires(&subsystem);
+  MockCommand anotherCommand;
+  anotherCommand.Requires(&subsystem);
+
+  AssertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+  subsystem.Init(defaultCommand);
+  AssertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 1, 1, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 2, 2, 0, 0);
+
+  anotherCommand.Start();
+  AssertCommandState(defaultCommand, 1, 2, 2, 0, 0);
+  AssertCommandState(&anotherCommand, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 0, 0, 0, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 1, 1, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 2, 2, 0, 0);
+  anotherCommand.Cancel();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 2, 2, 0, 0);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 2, 2, 0, 1);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 2, 4, 4, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 2, 2, 0, 1);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(defaultCommand, 2, 5, 5, 0, 1);
+  AssertCommandState(&anotherCommand, 1, 2, 2, 0, 1);
+
+  TeardownScheduler();
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/ConditionalCommandTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/ConditionalCommandTest.cpp
new file mode 100644
index 0000000..ca14e55
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/ConditionalCommandTest.cpp
@@ -0,0 +1,435 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "command/MockCommand.h"
+#include "command/MockConditionalCommand.h"
+#include "frc/DriverStation.h"
+#include "frc/RobotState.h"
+#include "frc/commands/ConditionalCommand.h"
+#include "frc/commands/Scheduler.h"
+#include "frc/commands/Subsystem.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class ConditionalCommandTest : public testing::Test {
+ public:
+  MockConditionalCommand* m_command;
+  MockCommand* m_onTrue;
+  MockCommand* m_onFalse;
+  MockConditionalCommand* m_commandNull;
+  Subsystem* m_subsystem;
+
+ protected:
+  void SetUp() override {
+    Scheduler::GetInstance()->SetEnabled(true);
+
+    m_subsystem = new Subsystem("MockSubsystem");
+    m_onTrue = new MockCommand(m_subsystem);
+    m_onFalse = new MockCommand(m_subsystem);
+    m_command = new MockConditionalCommand(m_onTrue, m_onFalse);
+    m_commandNull = new MockConditionalCommand(m_onTrue, nullptr);
+  }
+
+  void TearDown() override { delete m_command; }
+
+  /**
+   * Tears Down the Scheduler at the end of each test.
+   *
+   * Must be called at the end of each test inside each test in order to prevent
+   * them being deallocated when they leave the scope of the test (causing a
+   * segfault). This cannot be done within the virtual void Teardown() method
+   * because it is called outside of the scope of the test.
+   */
+  void TeardownScheduler() { Scheduler::GetInstance()->ResetAll(); }
+
+  void AssertCommandState(MockCommand& command, int32_t initialize,
+                          int32_t execute, int32_t isFinished, int32_t end,
+                          int32_t interrupted) {
+    EXPECT_EQ(initialize, command.GetInitializeCount());
+    EXPECT_EQ(execute, command.GetExecuteCount());
+    EXPECT_EQ(isFinished, command.GetIsFinishedCount());
+    EXPECT_EQ(end, command.GetEndCount());
+    EXPECT_EQ(interrupted, command.GetInterruptedCount());
+  }
+
+  void AssertConditionalCommandState(MockConditionalCommand& command,
+                                     int32_t initialize, int32_t execute,
+                                     int32_t isFinished, int32_t end,
+                                     int32_t interrupted) {
+    EXPECT_EQ(initialize, command.GetInitializeCount());
+    EXPECT_EQ(execute, command.GetExecuteCount());
+    EXPECT_EQ(isFinished, command.GetIsFinishedCount());
+    EXPECT_EQ(end, command.GetEndCount());
+    EXPECT_EQ(interrupted, command.GetInterruptedCount());
+  }
+};
+
+TEST_F(ConditionalCommandTest, OnTrueTest) {
+  m_command->SetCondition(true);
+
+  SCOPED_TRACE("1");
+  Scheduler::GetInstance()->AddCommand(m_command);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("2");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("3");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 1, 1, 0, 0);
+  SCOPED_TRACE("4");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 1, 1, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 0, 0);
+  SCOPED_TRACE("5");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 0);
+  SCOPED_TRACE("6");
+  m_onTrue->SetHasFinished(true);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 3, 3, 1, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+  SCOPED_TRACE("7");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 3, 3, 1, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+
+  EXPECT_TRUE(m_onTrue->GetInitializeCount() > 0)
+      << "Did not initialize the true command\n";
+  EXPECT_TRUE(m_onFalse->GetInitializeCount() == 0)
+      << "Initialized the false command\n";
+
+  TeardownScheduler();
+}
+
+TEST_F(ConditionalCommandTest, OnFalseTest) {
+  m_command->SetCondition(false);
+
+  SCOPED_TRACE("1");
+  Scheduler::GetInstance()->AddCommand(m_command);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("2");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("3");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 1, 1, 0, 0);
+  SCOPED_TRACE("4");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onFalse, 1, 1, 1, 0, 0);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 0, 0);
+  SCOPED_TRACE("5");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onFalse, 1, 2, 2, 0, 0);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 0);
+  SCOPED_TRACE("6");
+  m_onFalse->SetHasFinished(true);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onFalse, 1, 3, 3, 1, 0);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+  SCOPED_TRACE("7");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onFalse, 1, 3, 3, 1, 0);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+
+  EXPECT_TRUE(m_onFalse->GetInitializeCount() > 0)
+      << "Did not initialize the false command";
+  EXPECT_TRUE(m_onTrue->GetInitializeCount() == 0)
+      << "Initialized the true command";
+
+  TeardownScheduler();
+}
+
+TEST_F(ConditionalCommandTest, CancelSubCommandTest) {
+  m_command->SetCondition(true);
+
+  SCOPED_TRACE("1");
+  Scheduler::GetInstance()->AddCommand(m_command);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("2");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("3");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 1, 1, 0, 0);
+  SCOPED_TRACE("4");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 1, 1, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 0, 0);
+  SCOPED_TRACE("5");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 0);
+  SCOPED_TRACE("6");
+  m_onTrue->Cancel();
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 1);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+  SCOPED_TRACE("7");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 1);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+
+  TeardownScheduler();
+}
+
+TEST_F(ConditionalCommandTest, CancelCondCommandTest) {
+  m_command->SetCondition(true);
+
+  SCOPED_TRACE("1");
+  Scheduler::GetInstance()->AddCommand(m_command);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("2");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("3");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 1, 1, 0, 0);
+  SCOPED_TRACE("4");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 1, 1, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 0, 0);
+  SCOPED_TRACE("5");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 0);
+  SCOPED_TRACE("6");
+  m_command->Cancel();
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 1);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 1);
+  SCOPED_TRACE("7");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 1);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 1);
+
+  TeardownScheduler();
+}
+
+TEST_F(ConditionalCommandTest, OnTrueTwiceTest) {
+  m_command->SetCondition(true);
+
+  SCOPED_TRACE("1");
+  Scheduler::GetInstance()->AddCommand(m_command);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("2");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("3");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 1, 1, 0, 0);
+  SCOPED_TRACE("4");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 1, 1, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 0, 0);
+  SCOPED_TRACE("5");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 0);
+  SCOPED_TRACE("6");
+  m_onTrue->SetHasFinished(true);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 3, 3, 1, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+  SCOPED_TRACE("7");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 3, 3, 1, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+
+  m_onTrue->ResetCounters();
+  m_command->ResetCounters();
+  Scheduler::GetInstance()->AddCommand(m_command);
+
+  SCOPED_TRACE("11");
+  Scheduler::GetInstance()->AddCommand(m_command);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("12");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("13");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 1, 1, 0, 0);
+  SCOPED_TRACE("14");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 1, 1, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 0, 0);
+  SCOPED_TRACE("15");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 0);
+  SCOPED_TRACE("16");
+  m_onTrue->SetHasFinished(true);
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 3, 3, 1, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+  SCOPED_TRACE("17");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 3, 3, 1, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 1, 0);
+
+  TeardownScheduler();
+}
+
+TEST_F(ConditionalCommandTest, OnTrueInstantTest) {
+  m_command->SetCondition(true);
+  m_onTrue->SetHasFinished(true);
+
+  SCOPED_TRACE("1");
+  Scheduler::GetInstance()->AddCommand(m_command);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("2");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("3");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 1, 1, 0, 0);
+  SCOPED_TRACE("4");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 1, 1, 1, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 1, 0);
+  SCOPED_TRACE("5");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 1, 1, 1, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 1, 0);
+
+  TeardownScheduler();
+}
+
+TEST_F(ConditionalCommandTest, CancelRequiresTest) {
+  m_command->SetCondition(true);
+
+  SCOPED_TRACE("1");
+  Scheduler::GetInstance()->AddCommand(m_command);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("2");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("3");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 1, 1, 0, 0);
+  SCOPED_TRACE("4");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 1, 1, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 2, 2, 0, 0);
+  SCOPED_TRACE("5");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 2, 2, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 3, 3, 0, 0);
+  SCOPED_TRACE("6");
+  m_onFalse->Start();
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 3, 3, 0, 0);
+  AssertCommandState(*m_onFalse, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 0, 1);
+  SCOPED_TRACE("7");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 1, 3, 3, 0, 1);
+  AssertCommandState(*m_onFalse, 1, 1, 1, 0, 0);
+  AssertConditionalCommandState(*m_command, 1, 4, 4, 0, 1);
+
+  TeardownScheduler();
+}
+
+TEST_F(ConditionalCommandTest, OnFalseNullTest) {
+  m_command->SetCondition(false);
+
+  SCOPED_TRACE("1");
+  Scheduler::GetInstance()->AddCommand(m_commandNull);
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_commandNull, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("2");
+  Scheduler::GetInstance()->Run();  // init command and select m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_commandNull, 0, 0, 0, 0, 0);
+  SCOPED_TRACE("3");
+  Scheduler::GetInstance()->Run();  // init m_onTrue
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_commandNull, 1, 1, 1, 1, 0);
+  SCOPED_TRACE("4");
+  Scheduler::GetInstance()->Run();
+  AssertCommandState(*m_onTrue, 0, 0, 0, 0, 0);
+  AssertConditionalCommandState(*m_commandNull, 1, 1, 1, 1, 0);
+
+  TeardownScheduler();
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/MockCommand.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/MockCommand.cpp
new file mode 100644
index 0000000..bcaed0b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/MockCommand.cpp
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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 "command/MockCommand.h"
+
+using namespace frc;
+
+MockCommand::MockCommand(Subsystem* subsys) : MockCommand() {
+  Requires(subsys);
+}
+
+MockCommand::MockCommand() {
+  m_initializeCount = 0;
+  m_executeCount = 0;
+  m_isFinishedCount = 0;
+  m_hasFinished = false;
+  m_endCount = 0;
+  m_interruptedCount = 0;
+}
+
+bool MockCommand::HasInitialized() { return GetInitializeCount() > 0; }
+
+bool MockCommand::HasEnd() { return GetEndCount() > 0; }
+
+bool MockCommand::HasInterrupted() { return GetInterruptedCount() > 0; }
+
+void MockCommand::Initialize() { ++m_initializeCount; }
+
+void MockCommand::Execute() { ++m_executeCount; }
+
+bool MockCommand::IsFinished() {
+  ++m_isFinishedCount;
+  return IsHasFinished();
+}
+
+void MockCommand::End() { ++m_endCount; }
+
+void MockCommand::Interrupted() { ++m_interruptedCount; }
+
+void MockCommand::ResetCounters() {
+  m_initializeCount = 0;
+  m_executeCount = 0;
+  m_isFinishedCount = 0;
+  m_hasFinished = false;
+  m_endCount = 0;
+  m_interruptedCount = 0;
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/MockConditionalCommand.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/MockConditionalCommand.cpp
new file mode 100644
index 0000000..9434131
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/command/MockConditionalCommand.cpp
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "command/MockConditionalCommand.h"
+
+using namespace frc;
+
+MockConditionalCommand::MockConditionalCommand(MockCommand* onTrue,
+                                               MockCommand* onFalse)
+    : ConditionalCommand(onTrue, onFalse) {
+  m_initializeCount = 0;
+  m_executeCount = 0;
+  m_isFinishedCount = 0;
+  m_endCount = 0;
+  m_interruptedCount = 0;
+}
+
+void MockConditionalCommand::SetCondition(bool condition) {
+  m_condition = condition;
+}
+
+bool MockConditionalCommand::Condition() { return m_condition; }
+
+bool MockConditionalCommand::HasInitialized() {
+  return GetInitializeCount() > 0;
+}
+
+bool MockConditionalCommand::HasEnd() { return GetEndCount() > 0; }
+
+bool MockConditionalCommand::HasInterrupted() {
+  return GetInterruptedCount() > 0;
+}
+
+void MockConditionalCommand::Initialize() { ++m_initializeCount; }
+
+void MockConditionalCommand::Execute() { ++m_executeCount; }
+
+bool MockConditionalCommand::IsFinished() {
+  ++m_isFinishedCount;
+  return ConditionalCommand::IsFinished();
+}
+
+void MockConditionalCommand::End() { ++m_endCount; }
+
+void MockConditionalCommand::Interrupted() { ++m_interruptedCount; }
+
+void MockConditionalCommand::ResetCounters() {
+  m_initializeCount = 0;
+  m_executeCount = 0;
+  m_isFinishedCount = 0;
+  m_endCount = 0;
+  m_interruptedCount = 0;
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/main.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/main.cpp
new file mode 100644
index 0000000..1e5ecf0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/main.cpp
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp
new file mode 100644
index 0000000..173a23c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.cpp
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "MockDS.h"
+
+#include <stdint.h>
+
+#include <hal/cpp/fpga_clock.h>
+#include <wpi/Logger.h>
+#include <wpi/SmallString.h>
+#include <wpi/SmallVector.h>
+#include <wpi/UDPClient.h>
+#include <wpi/raw_ostream.h>
+
+static void LoggerFunc(unsigned int level, const char* file, unsigned int line,
+                       const char* msg) {
+  wpi::SmallString<128> buf;
+  wpi::raw_svector_ostream oss(buf);
+  if (level == 20) {
+    oss << "DS: " << msg << '\n';
+    wpi::errs() << oss.str();
+    return;
+  }
+
+  wpi::StringRef levelmsg;
+  if (level >= 50)
+    levelmsg = "CRITICAL: ";
+  else if (level >= 40)
+    levelmsg = "ERROR: ";
+  else if (level >= 30)
+    levelmsg = "WARNING: ";
+  else
+    return;
+  oss << "DS: " << levelmsg << msg << " (" << file << ':' << line << ")\n";
+  wpi::errs() << oss.str();
+}
+
+static void generateEnabledDsPacket(wpi::SmallVectorImpl<uint8_t>& data,
+                                    uint16_t sendCount) {
+  data.clear();
+  data.push_back(sendCount >> 8);
+  data.push_back(sendCount);
+  data.push_back(0x01);  // general data tag
+  data.push_back(0x04);  // teleop enabled
+  data.push_back(0x10);  // normal data request
+  data.push_back(0x00);  // red 1 station
+}
+
+using namespace frc;
+
+void MockDS::start() {
+  if (m_active) return;
+  m_active = true;
+  m_thread = std::thread([&]() {
+    wpi::Logger logger(LoggerFunc);
+    wpi::UDPClient client(logger);
+    client.start();
+    auto timeout_time = hal::fpga_clock::now();
+    int initCount = 0;
+    uint16_t sendCount = 0;
+    wpi::SmallVector<uint8_t, 8> data;
+    while (m_active) {
+      // Keep 20ms intervals, and increase time to next interval
+      auto current = hal::fpga_clock::now();
+      while (timeout_time <= current) {
+        timeout_time += std::chrono::milliseconds(20);
+      }
+      std::this_thread::sleep_until(timeout_time);
+      generateEnabledDsPacket(data, sendCount++);
+      // ~10 disabled packets are required to make the robot actually enable
+      // 1 is definitely not enough.
+      if (initCount < 10) {
+        initCount++;
+        data[3] = 0;
+      }
+      client.send(data, "127.0.0.1", 1110);
+    }
+    client.shutdown();
+  });
+}
+
+void MockDS::stop() {
+  m_active = false;
+  if (m_thread.joinable()) m_thread.join();
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.h b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.h
new file mode 100644
index 0000000..99b17b1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/mockds/MockDS.h
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <thread>
+
+namespace frc {
+class MockDS {
+ public:
+  MockDS() = default;
+  ~MockDS() { stop(); }
+  MockDS(const MockDS& other) = delete;
+  MockDS& operator=(const MockDS& other) = delete;
+
+  void start();
+  void stop();
+
+ private:
+  std::thread m_thread;
+  std::atomic_bool m_active{false};
+};
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/MockActuatorSendable.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/MockActuatorSendable.cpp
new file mode 100644
index 0000000..3c9e411
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/MockActuatorSendable.cpp
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "shuffleboard/MockActuatorSendable.h"
+
+using namespace frc;
+
+MockActuatorSendable::MockActuatorSendable(wpi::StringRef name)
+    : SendableBase(false) {
+  SetName(name);
+}
+
+void MockActuatorSendable::InitSendable(SendableBuilder& builder) {
+  builder.SetActuator(true);
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
new file mode 100644
index 0000000..d06f510
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardInstance.h"  // NOLINT(build/include_order)
+
+#include <memory>
+#include <string>
+
+#include <networktables/NetworkTableEntry.h>
+#include <networktables/NetworkTableInstance.h>
+
+#include "frc/shuffleboard/ShuffleboardInstance.h"
+#include "gtest/gtest.h"
+#include "shuffleboard/MockActuatorSendable.h"
+
+using namespace frc;
+
+class ShuffleboardInstanceTest : public testing::Test {
+  void SetUp() override {
+    m_ntInstance = nt::NetworkTableInstance::Create();
+    m_shuffleboardInstance =
+        std::make_unique<detail::ShuffleboardInstance>(m_ntInstance);
+  }
+
+ protected:
+  nt::NetworkTableInstance m_ntInstance;
+  std::unique_ptr<detail::ShuffleboardInstance> m_shuffleboardInstance;
+};
+
+TEST_F(ShuffleboardInstanceTest, PathFluent) {
+  auto entry = m_shuffleboardInstance->GetTab("Tab Title")
+                   .GetLayout("List", "List Layout")
+                   .Add("Data", "string")
+                   .WithWidget("Text View")
+                   .GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab Title/List/Data", entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedLayoutsFluent) {
+  auto entry = m_shuffleboardInstance->GetTab("Tab")
+                   .GetLayout("First", "List")
+                   .GetLayout("Second", "List")
+                   .GetLayout("Third", "List")
+                   .GetLayout("Fourth", "List")
+                   .Add("Value", "string")
+                   .GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
+            entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedLayoutsOop) {
+  ShuffleboardTab& tab = m_shuffleboardInstance->GetTab("Tab");
+  ShuffleboardLayout& first = tab.GetLayout("First", "List");
+  ShuffleboardLayout& second = first.GetLayout("Second", "List");
+  ShuffleboardLayout& third = second.GetLayout("Third", "List");
+  ShuffleboardLayout& fourth = third.GetLayout("Fourth", "List");
+  SimpleWidget& widget = fourth.Add("Value", "string");
+  auto entry = widget.GetEntry();
+
+  EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value";
+  EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value",
+            entry.GetName())
+      << "Entry path generated incorrectly";
+}
+
+TEST_F(ShuffleboardInstanceTest, LayoutTypeIsSet) {
+  std::string layoutType = "Type";
+  m_shuffleboardInstance->GetTab("Tab").GetLayout("Title", layoutType);
+  m_shuffleboardInstance->Update();
+  nt::NetworkTableEntry entry = m_ntInstance.GetEntry(
+      "/Shuffleboard/.metadata/Tab/Title/PreferredComponent");
+  EXPECT_EQ(layoutType, entry.GetString("Not Set")) << "Layout type not set";
+}
+
+TEST_F(ShuffleboardInstanceTest, NestedActuatorWidgetsAreDisabled) {
+  MockActuatorSendable sendable("Actuator");
+  m_shuffleboardInstance->GetTab("Tab")
+      .GetLayout("Title", "Layout")
+      .Add(sendable);
+  auto controllableEntry =
+      m_ntInstance.GetEntry("/Shuffleboard/Tab/Title/Actuator/.controllable");
+  m_shuffleboardInstance->Update();
+
+  // Note: we use the unsafe `GetBoolean()` method because if the value is NOT
+  // a boolean, or if it is not present, then something has clearly gone very,
+  // very wrong
+  bool controllable = controllableEntry.GetValue()->GetBoolean();
+  // Sanity check
+  EXPECT_TRUE(controllable)
+      << "The nested actuator widget should be enabled by default";
+  m_shuffleboardInstance->DisableActuatorWidgets();
+  controllable = controllableEntry.GetValue()->GetBoolean();
+  EXPECT_FALSE(controllable)
+      << "The nested actuator widget should have been disabled";
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardTabTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardTabTest.cpp
new file mode 100644
index 0000000..23f3e3a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardTabTest.cpp
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* 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/ShuffleboardInstance.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+#include "frc/smartdashboard/Sendable.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class ShuffleboardTabTest : 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(ShuffleboardTabTest, AddDouble) {
+  auto entry = m_tab->Add("Double", 1.0).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/Double", entry.GetName());
+  EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
+}
+
+TEST_F(ShuffleboardTabTest, AddInteger) {
+  auto entry = m_tab->Add("Int", 1).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/Int", entry.GetName());
+  EXPECT_FLOAT_EQ(1.0, entry.GetValue()->GetDouble());
+}
+
+TEST_F(ShuffleboardTabTest, AddBoolean) {
+  auto entry = m_tab->Add("Bool", false).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/Bool", entry.GetName());
+  EXPECT_FALSE(entry.GetValue()->GetBoolean());
+}
+
+TEST_F(ShuffleboardTabTest, AddString) {
+  auto entry = m_tab->Add("String", "foobar").GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/String", entry.GetName());
+  EXPECT_EQ("foobar", entry.GetValue()->GetString());
+}
+
+TEST_F(ShuffleboardTabTest, AddNamedSendableWithProperties) {
+  InstantCommand sendable("Command");
+  std::string widgetType = "Command Widget";
+  wpi::StringMap<std::shared_ptr<nt::Value>> map;
+  map.try_emplace("foo", nt::Value::MakeDouble(1234));
+  map.try_emplace("bar", nt::Value::MakeString("baz"));
+  m_tab->Add(sendable).WithWidget(widgetType).WithProperties(map);
+
+  m_instance->Update();
+  std::string meta = "/Shuffleboard/.metadata/Tab/Command";
+
+  EXPECT_EQ(1234, m_ntInstance.GetEntry(meta + "/Properties/foo").GetDouble(-1))
+      << "Property 'foo' not set correctly";
+  EXPECT_EQ("baz",
+            m_ntInstance.GetEntry(meta + "/Properties/bar").GetString(""))
+      << "Property 'bar' not set correctly";
+  EXPECT_EQ(widgetType,
+            m_ntInstance.GetEntry(meta + "/PreferredComponent").GetString(""))
+      << "Preferred component not set correctly";
+}
+
+TEST_F(ShuffleboardTabTest, AddNumberArray) {
+  std::array<double, 3> expect = {{1.0, 2.0, 3.0}};
+  auto entry = m_tab->Add("DoubleArray", expect).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/DoubleArray", entry.GetName());
+
+  auto actual = entry.GetValue()->GetDoubleArray();
+  EXPECT_EQ(expect.size(), actual.size());
+  for (size_t i = 0; i < expect.size(); i++) {
+    EXPECT_FLOAT_EQ(expect[i], actual[i]);
+  }
+}
+
+TEST_F(ShuffleboardTabTest, AddBooleanArray) {
+  std::array<bool, 2> expect = {{true, false}};
+  auto entry = m_tab->Add("BoolArray", expect).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/BoolArray", entry.GetName());
+
+  auto actual = entry.GetValue()->GetBooleanArray();
+  EXPECT_EQ(expect.size(), actual.size());
+  for (size_t i = 0; i < expect.size(); i++) {
+    EXPECT_EQ(expect[i], actual[i]);
+  }
+}
+
+TEST_F(ShuffleboardTabTest, AddStringArray) {
+  std::array<std::string, 2> expect = {{"foo", "bar"}};
+  auto entry = m_tab->Add("StringArray", expect).GetEntry();
+  EXPECT_EQ("/Shuffleboard/Tab/StringArray", entry.GetName());
+
+  auto actual = entry.GetValue()->GetStringArray();
+  EXPECT_EQ(expect.size(), actual.size());
+  for (size_t i = 0; i < expect.size(); i++) {
+    EXPECT_EQ(expect[i], actual[i]);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardTest.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardTest.cpp
new file mode 100644
index 0000000..d39d59d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/cpp/shuffleboard/ShuffleboardTest.cpp
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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/Shuffleboard.h"
+#include "frc/shuffleboard/ShuffleboardTab.h"
+#include "gtest/gtest.h"
+
+using namespace frc;
+
+class ShuffleboardTest : public testing::Test {};
+
+TEST_F(ShuffleboardTest, TabObjectsCached) {
+  ShuffleboardTab& tab1 = Shuffleboard::GetTab("testTabObjectsCached");
+  ShuffleboardTab& tab2 = Shuffleboard::GetTab("testTabObjectsCached");
+  EXPECT_EQ(&tab1, &tab2) << "Tab objects were not cached";
+}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/dt/main.cpp b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/dt/main.cpp
new file mode 100644
index 0000000..e324b44
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/dt/main.cpp
@@ -0,0 +1,8 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+int main() {}
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/TestBench.h b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/TestBench.h
new file mode 100644
index 0000000..f9b5f30
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/TestBench.h
@@ -0,0 +1,59 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <stdint.h>
+
+class TestBench {
+ public:
+  /* Analog input channels */
+  static const uint32_t kCameraGyroChannel = 0;
+  static const uint32_t kFakeCompressorChannel = 1;
+  static const uint32_t kFakeAnalogOutputChannel = 2;
+
+  /* Analog output channels */
+  static const uint32_t kAnalogOutputChannel = 0;
+
+  /* DIO channels */
+  static const uint32_t kTalonEncoderChannelA = 0;
+  static const uint32_t kTalonEncoderChannelB = 1;
+  static const uint32_t kVictorEncoderChannelA = 2;
+  static const uint32_t kVictorEncoderChannelB = 3;
+  static const uint32_t kJaguarEncoderChannelA = 4;
+  static const uint32_t kJaguarEncoderChannelB = 5;
+  static const uint32_t kLoop1OutputChannel = 6;
+  static const uint32_t kLoop1InputChannel = 7;
+  static const uint32_t kLoop2OutputChannel = 8;
+  static const uint32_t kLoop2InputChannel = 9;
+
+  /* PWM channels */
+  static const uint32_t kVictorChannel = 1;
+  static const uint32_t kJaguarChannel = 2;
+  static const uint32_t kCameraPanChannel = 8;
+  static const uint32_t kCameraTiltChannel = 9;
+
+  /* MXP digital channels */
+  static const uint32_t kTalonChannel = 10;
+  static const uint32_t kFakePressureSwitchChannel = 11;
+  static const uint32_t kFakeSolenoid1Channel = 12;
+  static const uint32_t kFakeSolenoid2Channel = 13;
+  static const uint32_t kFakeRelayForward = 18;
+  static const uint32_t kFakeRelayReverse = 19;
+
+  /* Relay channels */
+  static const uint32_t kRelayChannel = 0;
+
+  /* PDP channels */
+  static const uint32_t kJaguarPDPChannel = 6;
+  static const uint32_t kVictorPDPChannel = 8;
+  static const uint32_t kTalonPDPChannel = 10;
+
+  /* PCM channels */
+  static const int32_t kSolenoidChannel1 = 0;
+  static const int32_t kSolenoidChannel2 = 1;
+};
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/command/MockCommand.h b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/command/MockCommand.h
new file mode 100644
index 0000000..bbcc419
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/command/MockCommand.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "frc/commands/Command.h"
+
+namespace frc {
+
+class MockCommand : public Command {
+ public:
+  explicit MockCommand(Subsystem*);
+  MockCommand();
+  int32_t GetInitializeCount() { return m_initializeCount; }
+  bool HasInitialized();
+
+  int32_t GetExecuteCount() { return m_executeCount; }
+  int32_t GetIsFinishedCount() { return m_isFinishedCount; }
+  bool IsHasFinished() { return m_hasFinished; }
+  void SetHasFinished(bool hasFinished) { m_hasFinished = hasFinished; }
+  int32_t GetEndCount() { return m_endCount; }
+  bool HasEnd();
+
+  int32_t GetInterruptedCount() { return m_interruptedCount; }
+  bool HasInterrupted();
+  void ResetCounters();
+
+ protected:
+  void Initialize() override;
+  void Execute() override;
+  bool IsFinished() override;
+  void End() override;
+  void Interrupted() override;
+
+ private:
+  int32_t m_initializeCount;
+  int32_t m_executeCount;
+  int32_t m_isFinishedCount;
+  bool m_hasFinished;
+  int32_t m_endCount;
+  int32_t m_interruptedCount;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/command/MockConditionalCommand.h b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/command/MockConditionalCommand.h
new file mode 100644
index 0000000..fc9d4ec
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/command/MockConditionalCommand.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include "command/MockCommand.h"
+#include "frc/commands/ConditionalCommand.h"
+
+namespace frc {
+
+class MockConditionalCommand : public ConditionalCommand {
+ public:
+  MockConditionalCommand(MockCommand* onTrue, MockCommand* onFalse);
+  void SetCondition(bool condition);
+  int32_t GetInitializeCount() { return m_initializeCount; }
+  bool HasInitialized();
+
+  int32_t GetExecuteCount() { return m_executeCount; }
+  int32_t GetIsFinishedCount() { return m_isFinishedCount; }
+  int32_t GetEndCount() { return m_endCount; }
+  bool HasEnd();
+
+  int32_t GetInterruptedCount() { return m_interruptedCount; }
+  bool HasInterrupted();
+  void ResetCounters();
+
+ protected:
+  bool Condition() override;
+  void Initialize() override;
+  void Execute() override;
+  bool IsFinished() override;
+  void End() override;
+  void Interrupted() override;
+
+ private:
+  bool m_condition = false;
+  int32_t m_initializeCount;
+  int32_t m_executeCount;
+  int32_t m_isFinishedCount;
+  int32_t m_endCount;
+  int32_t m_interruptedCount;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/shuffleboard/MockActuatorSendable.h b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/shuffleboard/MockActuatorSendable.h
new file mode 100644
index 0000000..f56215c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibcIntegrationTests/src/main/native/include/shuffleboard/MockActuatorSendable.h
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <wpi/StringRef.h>
+
+#include "frc/smartdashboard/SendableBase.h"
+#include "frc/smartdashboard/SendableBuilder.h"
+
+namespace frc {
+
+/**
+ * A mock sendable that marks itself as an actuator.
+ */
+class MockActuatorSendable : public SendableBase {
+ public:
+  explicit MockActuatorSendable(wpi::StringRef name);
+
+  void InitSendable(SendableBuilder& builder) override;
+};
+
+}  // namespace frc
diff --git a/third_party/allwpilib_2019/wpilibj/CMakeLists.txt b/third_party/allwpilib_2019/wpilibj/CMakeLists.txt
new file mode 100644
index 0000000..61fb558
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/CMakeLists.txt
@@ -0,0 +1,33 @@
+project (wpilibj)
+
+find_package( OpenCV REQUIRED )
+
+# Java bindings
+if (NOT WITHOUT_JAVA)
+    find_package(Java REQUIRED)
+    include(UseJava)
+    set(CMAKE_JAVA_COMPILE_FLAGS "-Xlint:unchecked")
+
+    set(OPENCV_JAVA_INSTALL_DIR ${OpenCV_INSTALL_PATH}/share/OpenCV/java/)
+
+    find_file(OPENCV_JAR_FILE NAMES opencv-${OpenCV_VERSION_MAJOR}${OpenCV_VERSION_MINOR}${OpenCV_VERSION_PATCH}.jar PATHS ${OPENCV_JAVA_INSTALL_DIR} ${OpenCV_INSTALL_PATH}/bin NO_DEFAULT_PATH)
+
+    configure_file(src/generate/WPILibVersion.java.in WPILibVersion.java)
+
+    file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+
+    add_jar(wpilibj_jar ${JAVA_SOURCES} ${CMAKE_CURRENT_BINARY_DIR}/WPILibVersion.java INCLUDE_JARS hal_jar ntcore_jar ${OPENCV_JAR_FILE} cscore_jar cameraserver_jar wpiutil_jar OUTPUT_NAME wpilibj)
+
+    get_property(WPILIBJ_JAR_FILE TARGET wpilibj_jar PROPERTY JAR_FILE)
+    install(FILES ${WPILIBJ_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+    set_property(TARGET wpilibj_jar PROPERTY FOLDER "java")
+
+    if (MSVC)
+        set (wpilibj_config_dir ${wpilib_dest})
+    else()
+        set (wpilibj_config_dir share/wpilibj)
+    endif()
+
+    install(FILES wpilibj-config.cmake DESTINATION ${wpilibj_config_dir})
+endif()
diff --git a/third_party/allwpilib_2019/wpilibj/build.gradle b/third_party/allwpilib_2019/wpilibj/build.gradle
new file mode 100644
index 0000000..b86d04e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/build.gradle
@@ -0,0 +1,171 @@
+evaluationDependsOn(':hal')
+evaluationDependsOn(':ntcore')
+evaluationDependsOn(':cscore')
+evaluationDependsOn(':cameraserver')
+
+ext {
+    baseId = 'wpilibj'
+    groupId = 'edu.wpi.first.wpilibj'
+    devMain = 'edu.wpi.first.wpilibj.DevMain'
+}
+
+apply from: "${rootDir}/shared/java/javacommon.gradle"
+
+def wpilibVersionFileInput = file("src/generate/WPILibVersion.java.in")
+def wpilibVersionFileOutput = file("$buildDir/generated/java/edu/wpi/first/wpilibj/util/WPILibVersion.java")
+
+task generateJavaVersion() {
+    description = 'Generates the wpilib version class'
+    group = 'WPILib'
+
+    outputs.file wpilibVersionFileOutput
+    inputs.file wpilibVersionFileInput
+
+    if (WPILibVersion.releaseType.toString().equalsIgnoreCase('official')) {
+        outputs.upToDateWhen { false }
+    }
+
+    // We follow a simple set of checks to determine whether we should generate a new version file:
+    // 1. If the release type is not development, we generate a new verison file
+    // 2. If there is no generated version number, we generate a new version file
+    // 3. If there is a generated build number, and the release type is development, then we will
+    //    only generate if the publish task is run.
+    doLast {
+        println "Writing version ${WPILibVersion.version} to $wpilibVersionFileOutput"
+
+        if (wpilibVersionFileOutput.exists()) {
+            wpilibVersionFileOutput.delete()
+        }
+        def read = wpilibVersionFileInput.text.replace('${wpilib_version}', WPILibVersion.version)
+        wpilibVersionFileOutput.write(read)
+    }
+}
+
+gradle.taskGraph.addTaskExecutionGraphListener { graph ->
+    def willPublish = graph.hasTask(publish)
+    if (willPublish) {
+        generateJavaVersion.outputs.upToDateWhen { false }
+    }
+}
+
+sourceSets.main.java.srcDir "${buildDir}/generated/java/"
+
+compileJava {
+    dependsOn generateJavaVersion
+}
+
+dependencies {
+    compile project(':hal')
+    compile project(':wpiutil')
+    compile project(':ntcore')
+    compile project(':cscore')
+    compile project(':cameraserver')
+    testCompile 'com.google.guava:guava:19.0'
+    devCompile project(':hal')
+    devCompile project(':wpiutil')
+    devCompile project(':ntcore')
+    devCompile project(':cscore')
+    devCompile project(':cameraserver')
+    devCompile sourceSets.main.output
+}
+
+apply plugin: 'cpp'
+apply plugin: 'edu.wpi.first.NativeUtils'
+apply plugin: ExtraTasks
+apply from: "${rootDir}/shared/config.gradle"
+
+project(':').libraryBuild.dependsOn build
+
+ext {
+    sharedCvConfigs = [wpilibjDev: []]
+    staticCvConfigs = [:]
+    useJava = true
+    useCpp = true
+}
+
+ext {
+    chipObjectComponents = ['wpilibjDev']
+    netCommComponents = ['wpilibjDev']
+    useNiJava = true
+}
+
+apply from: "${rootDir}/shared/nilibraries.gradle"
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+model {
+    components {
+        wpilibjDev(NativeExecutableSpec) {
+            targetBuildTypes 'debug'
+            sources {
+                cpp {
+                    source {
+                        srcDirs 'src/dev/native/cpp'
+                        include '**/*.cpp'
+                        lib project: ':ntcore', library: 'ntcore', linkage: 'shared'
+                        lib project: ':cscore', library: 'cscore', linkage: 'shared'
+                        lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                        lib project: ':ntcore', library: 'ntcoreJNIShared', linkage: 'shared'
+                        lib project: ':cscore', library: 'cscoreJNIShared', linkage: 'shared'
+                        lib project: ':wpiutil', library: 'wpiutil', linkage: 'shared'
+                        lib project: ':cameraserver', library: 'cameraserver', linkage: 'shared'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/dev/native/include'
+                    }
+                }
+            }
+            binaries.all {
+                project(':hal').addHalDependency(it, 'shared')
+                project(':hal').addHalJniDependency(it)
+            }
+        }
+    }
+    tasks {
+        def c = $.components
+        project.tasks.create('runCpp', Exec) {
+            group = 'WPILib'
+            description = "Run the wpilibjDev executable"
+            def found = false
+            def systemArch = getCurrentArch()
+            c.each {
+                //println it.name
+                if (it in NativeExecutableSpec && it.name == "wpilibjDev") {
+                    it.binaries.each {
+                        if (!found) {
+                            def arch = it.targetPlatform.architecture.name
+                            if (arch == systemArch) {
+                                dependsOn it.tasks.install
+                                commandLine it.tasks.install.runScriptFile.get().asFile.toString()
+                                def filePath = it.tasks.install.installDirectory.get().toString() + File.separatorChar + 'lib'
+                                test.dependsOn it.tasks.install
+                                test.systemProperty 'java.library.path', filePath
+                                test.environment 'LD_LIBRARY_PATH', filePath
+                                test.workingDir filePath
+                                run.dependsOn it.tasks.install
+                                run.systemProperty 'java.library.path', filePath
+                                run.environment 'LD_LIBRARY_PATH', filePath
+                                run.workingDir filePath
+
+                                found = true
+                            }
+                        }
+                    }
+                }
+            }
+        }
+    }
+}
+
+def oldWpilibVersionFile = file('src/main/java/edu/wpi/first/wpilibj/util/WPILibVersion.java')
+
+clean {
+    delete oldWpilibVersionFile
+}
+
+test {
+    testLogging {
+        outputs.upToDateWhen {false}
+        showStandardStreams = true
+    }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/dev/java/edu/wpi/first/wpilibj/DevMain.java b/third_party/allwpilib_2019/wpilibj/src/dev/java/edu/wpi/first/wpilibj/DevMain.java
new file mode 100644
index 0000000..2c08b17
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/dev/java/edu/wpi/first/wpilibj/DevMain.java
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.HALUtil;
+import edu.wpi.first.networktables.NetworkTablesJNI;
+import edu.wpi.first.wpiutil.RuntimeDetector;
+
+public final class DevMain {
+  /**
+   * Main entry point.
+   */
+  public static void main(String[] args) {
+    System.out.println("Hello World!");
+    System.out.println(RuntimeDetector.getPlatformPath());
+    System.out.println(NetworkTablesJNI.now());
+    System.out.println(HALUtil.getHALRuntimeType());
+  }
+
+  private DevMain() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/wpilibj/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..e324b44
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/dev/native/cpp/main.cpp
@@ -0,0 +1,8 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+int main() {}
diff --git a/third_party/allwpilib_2019/wpilibj/src/generate/WPILibVersion.java.in b/third_party/allwpilib_2019/wpilibj/src/generate/WPILibVersion.java.in
new file mode 100644
index 0000000..cc5e6b0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/generate/WPILibVersion.java.in
@@ -0,0 +1,10 @@
+package edu.wpi.first.wpilibj.util;
+
+/*
+ * Autogenerated file! Do not manually edit this file. This version is regenerated
+ * any time the publish task is run, or when this file is deleted.
+ */
+
+public final class WPILibVersion {
+  public static final String Version = "${wpilib_version}";
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java
new file mode 100644
index 0000000..e91b8d2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_I2C.java
@@ -0,0 +1,187 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.wpilibj.interfaces.Accelerometer;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * ADXL345 I2C Accelerometer.
+ */
+@SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"})
+public class ADXL345_I2C extends SendableBase implements Accelerometer {
+  private static final byte kAddress = 0x1D;
+  private static final byte kPowerCtlRegister = 0x2D;
+  private static final byte kDataFormatRegister = 0x31;
+  private static final byte kDataRegister = 0x32;
+  private static final double kGsPerLSB = 0.00390625;
+  private static final byte kPowerCtl_Link = 0x20;
+  private static final byte kPowerCtl_AutoSleep = 0x10;
+  private static final byte kPowerCtl_Measure = 0x08;
+  private static final byte kPowerCtl_Sleep = 0x04;
+
+  private static final byte kDataFormat_SelfTest = (byte) 0x80;
+  private static final byte kDataFormat_SPI = 0x40;
+  private static final byte kDataFormat_IntInvert = 0x20;
+  private static final byte kDataFormat_FullRes = 0x08;
+  private static final byte kDataFormat_Justify = 0x04;
+
+  public enum Axes {
+    kX((byte) 0x00),
+    kY((byte) 0x02),
+    kZ((byte) 0x04);
+
+    /**
+     * The integer value representing this enumeration.
+     */
+    @SuppressWarnings("MemberName")
+    public final byte value;
+
+    Axes(byte value) {
+      this.value = value;
+    }
+  }
+
+  @SuppressWarnings("MemberName")
+  public static class AllAxes {
+    public double XAxis;
+    public double YAxis;
+    public double ZAxis;
+  }
+
+  protected I2C m_i2c;
+
+  /**
+   * Constructs the ADXL345 Accelerometer with I2C address 0x1D.
+   *
+   * @param port  The I2C port the accelerometer is attached to
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  public ADXL345_I2C(I2C.Port port, Range range) {
+    this(port, range, kAddress);
+  }
+
+  /**
+   * Constructs the ADXL345 Accelerometer over I2C.
+   *
+   * @param port          The I2C port the accelerometer is attached to
+   * @param range         The range (+ or -) that the accelerometer will measure.
+   * @param deviceAddress I2C address of the accelerometer (0x1D or 0x53)
+   */
+  public ADXL345_I2C(I2C.Port port, Range range, int deviceAddress) {
+    m_i2c = new I2C(port, deviceAddress);
+
+    // Turn on the measurements
+    m_i2c.write(kPowerCtlRegister, kPowerCtl_Measure);
+
+    setRange(range);
+
+    HAL.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_I2C);
+    setName("ADXL345_I2C", port.value);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    m_i2c.close();
+  }
+
+  @Override
+  public void setRange(Range range) {
+    final byte value;
+
+    switch (range) {
+      case k2G:
+        value = 0;
+        break;
+      case k4G:
+        value = 1;
+        break;
+      case k8G:
+        value = 2;
+        break;
+      case k16G:
+        value = 3;
+        break;
+      default:
+        throw new IllegalArgumentException(range + " unsupported range type");
+    }
+
+    // Specify the data format to read
+    m_i2c.write(kDataFormatRegister, kDataFormat_FullRes | value);
+  }
+
+  @Override
+  public double getX() {
+    return getAcceleration(Axes.kX);
+  }
+
+  @Override
+  public double getY() {
+    return getAcceleration(Axes.kY);
+  }
+
+  @Override
+  public double getZ() {
+    return getAcceleration(Axes.kZ);
+  }
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL345 in Gs.
+   */
+  public double getAcceleration(Axes axis) {
+    ByteBuffer rawAccel = ByteBuffer.allocate(2);
+    m_i2c.read(kDataRegister + axis.value, 2, rawAccel);
+
+    // Sensor is little endian... swap bytes
+    rawAccel.order(ByteOrder.LITTLE_ENDIAN);
+    return rawAccel.getShort(0) * kGsPerLSB;
+  }
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the ADXL345 in Gs.
+   */
+  public AllAxes getAccelerations() {
+    AllAxes data = new AllAxes();
+    ByteBuffer rawData = ByteBuffer.allocate(6);
+    m_i2c.read(kDataRegister, 6, rawData);
+
+    // Sensor is little endian... swap bytes
+    rawData.order(ByteOrder.LITTLE_ENDIAN);
+    data.XAxis = rawData.getShort(0) * kGsPerLSB;
+    data.YAxis = rawData.getShort(2) * kGsPerLSB;
+    data.ZAxis = rawData.getShort(4) * kGsPerLSB;
+    return data;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("3AxisAccelerometer");
+    NetworkTableEntry entryX = builder.getEntry("X");
+    NetworkTableEntry entryY = builder.getEntry("Y");
+    NetworkTableEntry entryZ = builder.getEntry("Z");
+    builder.setUpdateTable(() -> {
+      AllAxes data = getAccelerations();
+      entryX.setDouble(data.XAxis);
+      entryY.setDouble(data.YAxis);
+      entryZ.setDouble(data.ZAxis);
+    });
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java
new file mode 100644
index 0000000..b5d3618
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL345_SPI.java
@@ -0,0 +1,203 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.wpilibj.interfaces.Accelerometer;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * ADXL345 SPI Accelerometer.
+ */
+@SuppressWarnings({"TypeName", "PMD.UnusedPrivateField"})
+public class ADXL345_SPI extends SendableBase implements Accelerometer {
+  private static final int kPowerCtlRegister = 0x2D;
+  private static final int kDataFormatRegister = 0x31;
+  private static final int kDataRegister = 0x32;
+  private static final double kGsPerLSB = 0.00390625;
+
+  private static final int kAddress_Read = 0x80;
+  private static final int kAddress_MultiByte = 0x40;
+
+  private static final int kPowerCtl_Link = 0x20;
+  private static final int kPowerCtl_AutoSleep = 0x10;
+  private static final int kPowerCtl_Measure = 0x08;
+  private static final int kPowerCtl_Sleep = 0x04;
+
+  private static final int kDataFormat_SelfTest = 0x80;
+  private static final int kDataFormat_SPI = 0x40;
+  private static final int kDataFormat_IntInvert = 0x20;
+  private static final int kDataFormat_FullRes = 0x08;
+  private static final int kDataFormat_Justify = 0x04;
+
+  public enum Axes {
+    kX((byte) 0x00),
+    kY((byte) 0x02),
+    kZ((byte) 0x04);
+
+    /**
+     * The integer value representing this enumeration.
+     */
+    @SuppressWarnings("MemberName")
+    public final byte value;
+
+    Axes(byte value) {
+      this.value = value;
+    }
+  }
+
+  @SuppressWarnings("MemberName")
+  public static class AllAxes {
+    public double XAxis;
+    public double YAxis;
+    public double ZAxis;
+  }
+
+  protected SPI m_spi;
+
+  /**
+   * Constructor.
+   *
+   * @param port  The SPI port that the accelerometer is connected to
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  public ADXL345_SPI(SPI.Port port, Range range) {
+    m_spi = new SPI(port);
+    init(range);
+    setName("ADXL345_SPI", port.value);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    m_spi.close();
+  }
+
+  /**
+   * Set SPI bus parameters, bring device out of sleep and set format.
+   *
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  private void init(Range range) {
+    m_spi.setClockRate(500000);
+    m_spi.setMSBFirst();
+    m_spi.setSampleDataOnTrailingEdge();
+    m_spi.setClockActiveLow();
+    m_spi.setChipSelectActiveHigh();
+
+    // Turn on the measurements
+    byte[] commands = new byte[2];
+    commands[0] = kPowerCtlRegister;
+    commands[1] = kPowerCtl_Measure;
+    m_spi.write(commands, 2);
+
+    setRange(range);
+
+    HAL.report(tResourceType.kResourceType_ADXL345, tInstances.kADXL345_SPI);
+  }
+
+  @Override
+  public void setRange(Range range) {
+    final byte value;
+
+    switch (range) {
+      case k2G:
+        value = 0;
+        break;
+      case k4G:
+        value = 1;
+        break;
+      case k8G:
+        value = 2;
+        break;
+      case k16G:
+        value = 3;
+        break;
+      default:
+        throw new IllegalArgumentException(range + " unsupported");
+    }
+
+    // Specify the data format to read
+    byte[] commands = new byte[]{kDataFormatRegister, (byte) (kDataFormat_FullRes | value)};
+    m_spi.write(commands, commands.length);
+  }
+
+  @Override
+  public double getX() {
+    return getAcceleration(Axes.kX);
+  }
+
+  @Override
+  public double getY() {
+    return getAcceleration(Axes.kY);
+  }
+
+  @Override
+  public double getZ() {
+    return getAcceleration(Axes.kZ);
+  }
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL345 in Gs.
+   */
+  public double getAcceleration(ADXL345_SPI.Axes axis) {
+    ByteBuffer transferBuffer = ByteBuffer.allocate(3);
+    transferBuffer.put(0,
+        (byte) ((kAddress_Read | kAddress_MultiByte | kDataRegister) + axis.value));
+    m_spi.transaction(transferBuffer, transferBuffer, 3);
+    // Sensor is little endian
+    transferBuffer.order(ByteOrder.LITTLE_ENDIAN);
+
+    return transferBuffer.getShort(1) * kGsPerLSB;
+  }
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the ADXL345 in Gs.
+   */
+  public ADXL345_SPI.AllAxes getAccelerations() {
+    ADXL345_SPI.AllAxes data = new ADXL345_SPI.AllAxes();
+    if (m_spi != null) {
+      ByteBuffer dataBuffer = ByteBuffer.allocate(7);
+      // Select the data address.
+      dataBuffer.put(0, (byte) (kAddress_Read | kAddress_MultiByte | kDataRegister));
+      m_spi.transaction(dataBuffer, dataBuffer, 7);
+      // Sensor is little endian... swap bytes
+      dataBuffer.order(ByteOrder.LITTLE_ENDIAN);
+
+      data.XAxis = dataBuffer.getShort(1) * kGsPerLSB;
+      data.YAxis = dataBuffer.getShort(3) * kGsPerLSB;
+      data.ZAxis = dataBuffer.getShort(5) * kGsPerLSB;
+    }
+    return data;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("3AxisAccelerometer");
+    NetworkTableEntry entryX = builder.getEntry("X");
+    NetworkTableEntry entryY = builder.getEntry("Y");
+    NetworkTableEntry entryZ = builder.getEntry("Z");
+    builder.setUpdateTable(() -> {
+      AllAxes data = getAccelerations();
+      entryX.setDouble(data.XAxis);
+      entryY.setDouble(data.YAxis);
+      entryZ.setDouble(data.ZAxis);
+    });
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java
new file mode 100644
index 0000000..5324b63
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXL362.java
@@ -0,0 +1,227 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.wpilibj.interfaces.Accelerometer;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * ADXL362 SPI Accelerometer.
+ *
+ * <p>This class allows access to an Analog Devices ADXL362 3-axis accelerometer.
+ */
+@SuppressWarnings("PMD.UnusedPrivateField")
+public class ADXL362 extends SendableBase implements Accelerometer {
+  private static final byte kRegWrite = 0x0A;
+  private static final byte kRegRead = 0x0B;
+
+  private static final byte kPartIdRegister = 0x02;
+  private static final byte kDataRegister = 0x0E;
+  private static final byte kFilterCtlRegister = 0x2C;
+  private static final byte kPowerCtlRegister = 0x2D;
+
+  private static final byte kFilterCtl_Range2G = 0x00;
+  private static final byte kFilterCtl_Range4G = 0x40;
+  private static final byte kFilterCtl_Range8G = (byte) 0x80;
+  private static final byte kFilterCtl_ODR_100Hz = 0x03;
+
+  private static final byte kPowerCtl_UltraLowNoise = 0x20;
+  private static final byte kPowerCtl_AutoSleep = 0x04;
+  private static final byte kPowerCtl_Measure = 0x02;
+
+  public enum Axes {
+    kX((byte) 0x00),
+    kY((byte) 0x02),
+    kZ((byte) 0x04);
+
+    @SuppressWarnings("MemberName")
+    public final byte value;
+
+    Axes(byte value) {
+      this.value = value;
+    }
+  }
+
+  @SuppressWarnings("MemberName")
+  public static class AllAxes {
+    public double XAxis;
+    public double YAxis;
+    public double ZAxis;
+  }
+
+  private SPI m_spi;
+  private double m_gsPerLSB;
+
+  /**
+   * Constructor.  Uses the onboard CS1.
+   *
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  public ADXL362(Range range) {
+    this(SPI.Port.kOnboardCS1, range);
+  }
+
+  /**
+   * Constructor.
+   *
+   * @param port  The SPI port that the accelerometer is connected to
+   * @param range The range (+ or -) that the accelerometer will measure.
+   */
+  public ADXL362(SPI.Port port, Range range) {
+    m_spi = new SPI(port);
+
+    m_spi.setClockRate(3000000);
+    m_spi.setMSBFirst();
+    m_spi.setSampleDataOnTrailingEdge();
+    m_spi.setClockActiveLow();
+    m_spi.setChipSelectActiveLow();
+
+    // Validate the part ID
+    ByteBuffer transferBuffer = ByteBuffer.allocate(3);
+    transferBuffer.put(0, kRegRead);
+    transferBuffer.put(1, kPartIdRegister);
+    m_spi.transaction(transferBuffer, transferBuffer, 3);
+    if (transferBuffer.get(2) != (byte) 0xF2) {
+      m_spi.close();
+      m_spi = null;
+      DriverStation.reportError("could not find ADXL362 on SPI port " + port.value, false);
+      return;
+    }
+
+    setRange(range);
+
+    // Turn on the measurements
+    transferBuffer.put(0, kRegWrite);
+    transferBuffer.put(1, kPowerCtlRegister);
+    transferBuffer.put(2, (byte) (kPowerCtl_Measure | kPowerCtl_UltraLowNoise));
+    m_spi.write(transferBuffer, 3);
+
+    HAL.report(tResourceType.kResourceType_ADXL362, port.value);
+    setName("ADXL362", port.value);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    if (m_spi != null) {
+      m_spi.close();
+      m_spi = null;
+    }
+  }
+
+  @Override
+  public void setRange(Range range) {
+    if (m_spi == null) {
+      return;
+    }
+
+    final byte value;
+    switch (range) {
+      case k2G:
+        value = kFilterCtl_Range2G;
+        m_gsPerLSB = 0.001;
+        break;
+      case k4G:
+        value = kFilterCtl_Range4G;
+        m_gsPerLSB = 0.002;
+        break;
+      case k8G:
+      case k16G:  // 16G not supported; treat as 8G
+        value = kFilterCtl_Range8G;
+        m_gsPerLSB = 0.004;
+        break;
+      default:
+        throw new IllegalArgumentException(range + " unsupported");
+
+    }
+
+    // Specify the data format to read
+    byte[] commands = new byte[]{kRegWrite, kFilterCtlRegister, (byte) (kFilterCtl_ODR_100Hz
+        | value)};
+    m_spi.write(commands, commands.length);
+  }
+
+
+  @Override
+  public double getX() {
+    return getAcceleration(Axes.kX);
+  }
+
+  @Override
+  public double getY() {
+    return getAcceleration(Axes.kY);
+  }
+
+  @Override
+  public double getZ() {
+    return getAcceleration(Axes.kZ);
+  }
+
+  /**
+   * Get the acceleration of one axis in Gs.
+   *
+   * @param axis The axis to read from.
+   * @return Acceleration of the ADXL362 in Gs.
+   */
+  public double getAcceleration(ADXL362.Axes axis) {
+    if (m_spi == null) {
+      return 0.0;
+    }
+    ByteBuffer transferBuffer = ByteBuffer.allocate(4);
+    transferBuffer.put(0, kRegRead);
+    transferBuffer.put(1, (byte) (kDataRegister + axis.value));
+    m_spi.transaction(transferBuffer, transferBuffer, 4);
+    // Sensor is little endian
+    transferBuffer.order(ByteOrder.LITTLE_ENDIAN);
+
+    return transferBuffer.getShort(2) * m_gsPerLSB;
+  }
+
+  /**
+   * Get the acceleration of all axes in Gs.
+   *
+   * @return An object containing the acceleration measured on each axis of the ADXL362 in Gs.
+   */
+  public ADXL362.AllAxes getAccelerations() {
+    ADXL362.AllAxes data = new ADXL362.AllAxes();
+    if (m_spi != null) {
+      ByteBuffer dataBuffer = ByteBuffer.allocate(8);
+      // Select the data address.
+      dataBuffer.put(0, kRegRead);
+      dataBuffer.put(1, kDataRegister);
+      m_spi.transaction(dataBuffer, dataBuffer, 8);
+      // Sensor is little endian... swap bytes
+      dataBuffer.order(ByteOrder.LITTLE_ENDIAN);
+
+      data.XAxis = dataBuffer.getShort(2) * m_gsPerLSB;
+      data.YAxis = dataBuffer.getShort(4) * m_gsPerLSB;
+      data.ZAxis = dataBuffer.getShort(6) * m_gsPerLSB;
+    }
+    return data;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("3AxisAccelerometer");
+    NetworkTableEntry entryX = builder.getEntry("X");
+    NetworkTableEntry entryY = builder.getEntry("Y");
+    NetworkTableEntry entryZ = builder.getEntry("Z");
+    builder.setUpdateTable(() -> {
+      AllAxes data = getAccelerations();
+      entryX.setDouble(data.XAxis);
+      entryY.setDouble(data.YAxis);
+      entryZ.setDouble(data.ZAxis);
+    });
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java
new file mode 100644
index 0000000..a34b373
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ADXRS450_Gyro.java
@@ -0,0 +1,167 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.interfaces.Gyro;
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position. The Gyro class
+ * tracks the robots heading based on the starting position. As the robot rotates the new heading is
+ * computed by integrating the rate of rotation returned by the sensor. When the class is
+ * instantiated, it does a short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to determine the heading.
+ *
+ * <p>This class is for the digital ADXRS450 gyro sensor that connects via SPI.
+ */
+@SuppressWarnings({"TypeName", "AbbreviationAsWordInName", "PMD.UnusedPrivateField"})
+public class ADXRS450_Gyro extends GyroBase implements Gyro, PIDSource, Sendable {
+  private static final double kSamplePeriod = 0.0005;
+  private static final double kCalibrationSampleTime = 5.0;
+  private static final double kDegreePerSecondPerLSB = 0.0125;
+
+  private static final int kRateRegister = 0x00;
+  private static final int kTemRegister = 0x02;
+  private static final int kLoCSTRegister = 0x04;
+  private static final int kHiCSTRegister = 0x06;
+  private static final int kQuadRegister = 0x08;
+  private static final int kFaultRegister = 0x0A;
+  private static final int kPIDRegister = 0x0C;
+  private static final int kSNHighRegister = 0x0E;
+  private static final int kSNLowRegister = 0x10;
+
+  private SPI m_spi;
+
+  /**
+   * Constructor.  Uses the onboard CS0.
+   */
+  public ADXRS450_Gyro() {
+    this(SPI.Port.kOnboardCS0);
+  }
+
+  /**
+   * Constructor.
+   *
+   * @param port The SPI port that the gyro is connected to
+   */
+  public ADXRS450_Gyro(SPI.Port port) {
+    m_spi = new SPI(port);
+
+    m_spi.setClockRate(3000000);
+    m_spi.setMSBFirst();
+    m_spi.setSampleDataOnLeadingEdge();
+    m_spi.setClockActiveHigh();
+    m_spi.setChipSelectActiveLow();
+
+    // Validate the part ID
+    if ((readRegister(kPIDRegister) & 0xff00) != 0x5200) {
+      m_spi.close();
+      m_spi = null;
+      DriverStation.reportError("could not find ADXRS450 gyro on SPI port " + port.value,
+          false);
+      return;
+    }
+
+    m_spi.initAccumulator(kSamplePeriod, 0x20000000, 4, 0x0c00000e, 0x04000000, 10, 16,
+        true, true);
+
+    calibrate();
+
+    HAL.report(tResourceType.kResourceType_ADXRS450, port.value);
+    setName("ADXRS450_Gyro", port.value);
+  }
+
+  public boolean isConnected() {
+    return m_spi != null;
+  }
+
+  @Override
+  public void calibrate() {
+    if (m_spi == null) {
+      return;
+    }
+
+    Timer.delay(0.1);
+
+    m_spi.setAccumulatorIntegratedCenter(0);
+    m_spi.resetAccumulator();
+
+    Timer.delay(kCalibrationSampleTime);
+
+    m_spi.setAccumulatorIntegratedCenter(m_spi.getAccumulatorIntegratedAverage());
+    m_spi.resetAccumulator();
+  }
+
+  private boolean calcParity(int value) {
+    boolean parity = false;
+    while (value != 0) {
+      parity = !parity;
+      value = value & (value - 1);
+    }
+    return parity;
+  }
+
+  private int readRegister(int reg) {
+    int cmdhi = 0x8000 | (reg << 1);
+    boolean parity = calcParity(cmdhi);
+
+    ByteBuffer buf = ByteBuffer.allocate(4);
+    buf.order(ByteOrder.BIG_ENDIAN);
+    buf.put(0, (byte) (cmdhi >> 8));
+    buf.put(1, (byte) (cmdhi & 0xff));
+    buf.put(2, (byte) 0);
+    buf.put(3, (byte) (parity ? 0 : 1));
+
+    m_spi.write(buf, 4);
+    m_spi.read(false, buf, 4);
+
+    if ((buf.get(0) & 0xe0) == 0) {
+      return 0;  // error, return 0
+    }
+    return (buf.getInt(0) >> 5) & 0xffff;
+  }
+
+  @Override
+  public void reset() {
+    if (m_spi != null) {
+      m_spi.resetAccumulator();
+    }
+  }
+
+  /**
+   * Delete (free) the spi port used for the gyro and stop accumulating.
+   */
+  @Override
+  public void close() {
+    super.close();
+    if (m_spi != null) {
+      m_spi.close();
+      m_spi = null;
+    }
+  }
+
+  @Override
+  public double getAngle() {
+    if (m_spi == null) {
+      return 0.0;
+    }
+    return m_spi.getAccumulatorIntegratedValue() * kDegreePerSecondPerLSB;
+  }
+
+  @Override
+  public double getRate() {
+    if (m_spi == null) {
+      return 0.0;
+    }
+    return m_spi.getAccumulatorLastValue() * kDegreePerSecondPerLSB;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java
new file mode 100644
index 0000000..cd64dc8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogAccelerometer.java
@@ -0,0 +1,143 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Handle operation of an analog accelerometer. The accelerometer reads acceleration directly
+ * through the sensor. Many sensors have multiple axis and can be treated as multiple devices. Each
+ * is calibrated by finding the center value over a period of time.
+ */
+public class AnalogAccelerometer extends SendableBase implements PIDSource {
+  private AnalogInput m_analogChannel;
+  private double m_voltsPerG = 1.0;
+  private double m_zeroGVoltage = 2.5;
+  private final boolean m_allocatedChannel;
+  protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
+
+  /**
+   * Common initialization.
+   */
+  private void initAccelerometer() {
+    HAL.report(tResourceType.kResourceType_Accelerometer,
+                                   m_analogChannel.getChannel());
+    setName("Accelerometer", m_analogChannel.getChannel());
+  }
+
+  /**
+   * Create a new instance of an accelerometer.
+   *
+   * <p>The constructor allocates desired analog channel.
+   *
+   * @param channel The channel number for the analog input the accelerometer is connected to
+   */
+  public AnalogAccelerometer(final int channel) {
+    this(new AnalogInput(channel), true);
+    addChild(m_analogChannel);
+  }
+
+  /**
+   * Create a new instance of Accelerometer from an existing AnalogChannel. Make a new instance of
+   * accelerometer given an AnalogChannel. This is particularly useful if the port is going to be
+   * read as an analog channel as well as through the Accelerometer class.
+   *
+   * @param channel The existing AnalogInput object for the analog input the accelerometer is
+   *                connected to
+   */
+  public AnalogAccelerometer(final AnalogInput channel) {
+    this(channel, false);
+  }
+
+  private AnalogAccelerometer(final AnalogInput channel, final boolean allocatedChannel) {
+    requireNonNull(channel, "Analog Channel given was null");
+    m_allocatedChannel = allocatedChannel;
+    m_analogChannel = channel;
+    initAccelerometer();
+  }
+
+  /**
+   * Delete the analog components used for the accelerometer.
+   */
+  @Override
+  public void close() {
+    super.close();
+    if (m_analogChannel != null && m_allocatedChannel) {
+      m_analogChannel.close();
+    }
+    m_analogChannel = null;
+  }
+
+  /**
+   * Return the acceleration in Gs.
+   *
+   * <p>The acceleration is returned units of Gs.
+   *
+   * @return The current acceleration of the sensor in Gs.
+   */
+  public double getAcceleration() {
+    if (m_analogChannel == null) {
+      return 0.0;
+    }
+    return (m_analogChannel.getAverageVoltage() - m_zeroGVoltage) / m_voltsPerG;
+  }
+
+  /**
+   * Set the accelerometer sensitivity.
+   *
+   * <p>This sets the sensitivity of the accelerometer used for calculating the acceleration. The
+   * sensitivity varies by accelerometer model. There are constants defined for various models.
+   *
+   * @param sensitivity The sensitivity of accelerometer in Volts per G.
+   */
+  public void setSensitivity(double sensitivity) {
+    m_voltsPerG = sensitivity;
+  }
+
+  /**
+   * Set the voltage that corresponds to 0 G.
+   *
+   * <p>The zero G voltage varies by accelerometer model. There are constants defined for various
+   * models.
+   *
+   * @param zero The zero G voltage.
+   */
+  public void setZero(double zero) {
+    m_zeroGVoltage = zero;
+  }
+
+  @Override
+  public void setPIDSourceType(PIDSourceType pidSource) {
+    m_pidSource = pidSource;
+  }
+
+  @Override
+  public PIDSourceType getPIDSourceType() {
+    return m_pidSource;
+  }
+
+  /**
+   * Get the Acceleration for the PID Source parent.
+   *
+   * @return The current acceleration in Gs.
+   */
+  @Override
+  public double pidGet() {
+    return getAcceleration();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Accelerometer");
+    builder.addDoubleProperty("Value", this::getAcceleration, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java
new file mode 100644
index 0000000..4283aa0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogGyro.java
@@ -0,0 +1,189 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.AnalogGyroJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.interfaces.Gyro;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Use a rate gyro to return the robots heading relative to a starting position. The Gyro class
+ * tracks the robots heading based on the starting position. As the robot rotates the new heading is
+ * computed by integrating the rate of rotation returned by the sensor. When the class is
+ * instantiated, it does a short calibration routine where it samples the gyro while at rest to
+ * determine the default offset. This is subtracted from each sample to determine the heading.
+ *
+ * <p>This class is for gyro sensors that connect to an analog input.
+ */
+public class AnalogGyro extends GyroBase implements Gyro, PIDSource, Sendable {
+  private static final double kDefaultVoltsPerDegreePerSecond = 0.007;
+  protected AnalogInput m_analog;
+  private boolean m_channelAllocated;
+
+  private int m_gyroHandle;
+
+  /**
+   * Initialize the gyro. Calibration is handled by calibrate().
+   */
+  public void initGyro() {
+    if (m_gyroHandle == 0) {
+      m_gyroHandle = AnalogGyroJNI.initializeAnalogGyro(m_analog.m_port);
+    }
+
+    AnalogGyroJNI.setupAnalogGyro(m_gyroHandle);
+
+    HAL.report(tResourceType.kResourceType_Gyro, m_analog.getChannel());
+    setName("AnalogGyro", m_analog.getChannel());
+  }
+
+  @Override
+  public void calibrate() {
+    AnalogGyroJNI.calibrateAnalogGyro(m_gyroHandle);
+  }
+
+  /**
+   * Gyro constructor using the channel number.
+   *
+   * @param channel The analog channel the gyro is connected to. Gyros can only be used on on-board
+   *                channels 0-1.
+   */
+  public AnalogGyro(int channel) {
+    this(new AnalogInput(channel));
+    m_channelAllocated = true;
+    addChild(m_analog);
+  }
+
+  /**
+   * Gyro constructor with a precreated analog channel object. Use this constructor when the analog
+   * channel needs to be shared.
+   *
+   * @param channel The AnalogInput object that the gyro is connected to. Gyros can only be used on
+   *                on-board channels 0-1.
+   */
+  public AnalogGyro(AnalogInput channel) {
+    requireNonNull(channel, "AnalogInput supplied to Gyro constructor is null");
+
+    m_analog = channel;
+    initGyro();
+    calibrate();
+  }
+
+  /**
+   * Gyro constructor using the channel number along with parameters for presetting the center and
+   * offset values. Bypasses calibration.
+   *
+   * @param channel The analog channel the gyro is connected to. Gyros can only be used on on-board
+   *                channels 0-1.
+   * @param center  Preset uncalibrated value to use as the accumulator center value.
+   * @param offset  Preset uncalibrated value to use as the gyro offset.
+   */
+  public AnalogGyro(int channel, int center, double offset) {
+    this(new AnalogInput(channel), center, offset);
+    m_channelAllocated = true;
+    addChild(m_analog);
+  }
+
+  /**
+   * Gyro constructor with a precreated analog channel object along with parameters for presetting
+   * the center and offset values. Bypasses calibration.
+   *
+   * @param channel The analog channel the gyro is connected to. Gyros can only be used on on-board
+   *                channels 0-1.
+   * @param center  Preset uncalibrated value to use as the accumulator center value.
+   * @param offset  Preset uncalibrated value to use as the gyro offset.
+   */
+  public AnalogGyro(AnalogInput channel, int center, double offset) {
+    requireNonNull(channel, "AnalogInput supplied to Gyro constructor is null");
+
+    m_analog = channel;
+    initGyro();
+    AnalogGyroJNI.setAnalogGyroParameters(m_gyroHandle, kDefaultVoltsPerDegreePerSecond,
+                                          offset, center);
+    reset();
+  }
+
+  @Override
+  public void reset() {
+    AnalogGyroJNI.resetAnalogGyro(m_gyroHandle);
+  }
+
+  /**
+   * Delete (free) the accumulator and the analog components used for the gyro.
+   */
+  @Override
+  public void close() {
+    super.close();
+    if (m_analog != null && m_channelAllocated) {
+      m_analog.close();
+    }
+    m_analog = null;
+    AnalogGyroJNI.freeAnalogGyro(m_gyroHandle);
+  }
+
+  @Override
+  public double getAngle() {
+    if (m_analog == null) {
+      return 0.0;
+    } else {
+      return AnalogGyroJNI.getAnalogGyroAngle(m_gyroHandle);
+    }
+  }
+
+  @Override
+  public double getRate() {
+    if (m_analog == null) {
+      return 0.0;
+    } else {
+      return AnalogGyroJNI.getAnalogGyroRate(m_gyroHandle);
+    }
+  }
+
+  /**
+   * Return the gyro offset value set during calibration to use as a future preset.
+   *
+   * @return the current offset value
+   */
+  public double getOffset() {
+    return AnalogGyroJNI.getAnalogGyroOffset(m_gyroHandle);
+  }
+
+  /**
+   * Return the gyro center value set during calibration to use as a future preset.
+   *
+   * @return the current center value
+   */
+  public int getCenter() {
+    return AnalogGyroJNI.getAnalogGyroCenter(m_gyroHandle);
+  }
+
+  /**
+   * Set the gyro sensitivity. This takes the number of volts/degree/second sensitivity of the gyro
+   * and uses it in subsequent calculations to allow the code to work with multiple gyros. This
+   * value is typically found in the gyro datasheet.
+   *
+   * @param voltsPerDegreePerSecond The sensitivity in Volts/degree/second.
+   */
+  public void setSensitivity(double voltsPerDegreePerSecond) {
+    AnalogGyroJNI.setAnalogGyroVoltsPerDegreePerSecond(m_gyroHandle,
+                                                       voltsPerDegreePerSecond);
+  }
+
+  /**
+   * Set the size of the neutral zone. Any voltage from the gyro less than this amount from the
+   * center is considered stationary. Setting a deadband will decrease the amount of drift when the
+   * gyro isn't rotating, but will make it less accurate.
+   *
+   * @param volts The size of the deadband in volts
+   */
+  void setDeadband(double volts) {
+    AnalogGyroJNI.setAnalogGyroDeadband(m_gyroHandle, volts);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java
new file mode 100644
index 0000000..74eb866
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogInput.java
@@ -0,0 +1,356 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.AccumulatorResult;
+import edu.wpi.first.hal.AnalogJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.sim.AnalogInSim;
+import edu.wpi.first.hal.util.AllocationException;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Analog channel class.
+ *
+ * <p>Each analog channel is read from hardware as a 12-bit number representing 0V to 5V.
+ *
+ * <p>Connected to each analog channel is an averaging and oversampling engine. This engine
+ * accumulates the specified ( by setAverageBits() and setOversampleBits() ) number of samples
+ * before returning a new value. This is not a sliding window average. The only difference between
+ * the oversampled samples and the averaged samples is that the oversampled samples are simply
+ * accumulated effectively increasing the resolution, while the averaged samples are divided by the
+ * number of samples to retain the resolution, but get more stable values.
+ */
+public class AnalogInput extends SendableBase implements PIDSource {
+  private static final int kAccumulatorSlot = 1;
+  int m_port; // explicit no modifier, private and package accessible.
+  private int m_channel;
+  private static final int[] kAccumulatorChannels = {0, 1};
+  private long m_accumulatorOffset;
+  protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
+
+  /**
+   * Construct an analog channel.
+   *
+   * @param channel The channel number to represent. 0-3 are on-board 4-7 are on the MXP port.
+   */
+  public AnalogInput(final int channel) {
+    AnalogJNI.checkAnalogInputChannel(channel);
+    m_channel = channel;
+
+    final int portHandle = HAL.getPort((byte) channel);
+    m_port = AnalogJNI.initializeAnalogInputPort(portHandle);
+
+    HAL.report(tResourceType.kResourceType_AnalogChannel, channel);
+    setName("AnalogInput", channel);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    AnalogJNI.freeAnalogInputPort(m_port);
+    m_port = 0;
+    m_channel = 0;
+    m_accumulatorOffset = 0;
+  }
+
+  /**
+   * Get a sample straight from this channel. The sample is a 12-bit value representing the 0V to 5V
+   * range of the A/D converter. The units are in A/D converter codes. Use GetVoltage() to get the
+   * analog value in calibrated units.
+   *
+   * @return A sample straight from this channel.
+   */
+  public int getValue() {
+    return AnalogJNI.getAnalogValue(m_port);
+  }
+
+  /**
+   * Get a sample from the output of the oversample and average engine for this channel. The sample
+   * is 12-bit + the bits configured in SetOversampleBits(). The value configured in
+   * setAverageBits() will cause this value to be averaged 2^bits number of samples. This is not a
+   * sliding window. The sample will not change until 2^(OversampleBits + AverageBits) samples have
+   * been acquired from this channel. Use getAverageVoltage() to get the analog value in calibrated
+   * units.
+   *
+   * @return A sample from the oversample and average engine for this channel.
+   */
+  public int getAverageValue() {
+    return AnalogJNI.getAnalogAverageValue(m_port);
+  }
+
+  /**
+   * Get a scaled sample straight from this channel. The value is scaled to units of Volts using the
+   * calibrated scaling data from getLSBWeight() and getOffset().
+   *
+   * @return A scaled sample straight from this channel.
+   */
+  public double getVoltage() {
+    return AnalogJNI.getAnalogVoltage(m_port);
+  }
+
+  /**
+   * Get a scaled sample from the output of the oversample and average engine for this channel. The
+   * value is scaled to units of Volts using the calibrated scaling data from getLSBWeight() and
+   * getOffset(). Using oversampling will cause this value to be higher resolution, but it will
+   * update more slowly. Using averaging will cause this value to be more stable, but it will update
+   * more slowly.
+   *
+   * @return A scaled sample from the output of the oversample and average engine for this channel.
+   */
+  public double getAverageVoltage() {
+    return AnalogJNI.getAnalogAverageVoltage(m_port);
+  }
+
+  /**
+   * Get the factory scaling least significant bit weight constant. The least significant bit weight
+   * constant for the channel that was calibrated in manufacturing and stored in an eeprom.
+   *
+   * <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+   *
+   * @return Least significant bit weight.
+   */
+  public long getLSBWeight() {
+    return AnalogJNI.getAnalogLSBWeight(m_port);
+  }
+
+  /**
+   * Get the factory scaling offset constant. The offset constant for the channel that was
+   * calibrated in manufacturing and stored in an eeprom.
+   *
+   * <p>Volts = ((LSB_Weight * 1e-9) * raw) - (Offset * 1e-9)
+   *
+   * @return Offset constant.
+   */
+  public int getOffset() {
+    return AnalogJNI.getAnalogOffset(m_port);
+  }
+
+  /**
+   * Get the channel number.
+   *
+   * @return The channel number.
+   */
+  public int getChannel() {
+    return m_channel;
+  }
+
+  /**
+   * Set the number of averaging bits. This sets the number of averaging bits. The actual number of
+   * averaged samples is 2^bits. The averaging is done automatically in the FPGA.
+   *
+   * @param bits The number of averaging bits.
+   */
+  public void setAverageBits(final int bits) {
+    AnalogJNI.setAnalogAverageBits(m_port, bits);
+  }
+
+  /**
+   * Get the number of averaging bits. This gets the number of averaging bits from the FPGA. The
+   * actual number of averaged samples is 2^bits. The averaging is done automatically in the FPGA.
+   *
+   * @return The number of averaging bits.
+   */
+  public int getAverageBits() {
+    return AnalogJNI.getAnalogAverageBits(m_port);
+  }
+
+  /**
+   * Set the number of oversample bits. This sets the number of oversample bits. The actual number
+   * of oversampled values is 2^bits. The oversampling is done automatically in the FPGA.
+   *
+   * @param bits The number of oversample bits.
+   */
+  public void setOversampleBits(final int bits) {
+    AnalogJNI.setAnalogOversampleBits(m_port, bits);
+  }
+
+  /**
+   * Get the number of oversample bits. This gets the number of oversample bits from the FPGA. The
+   * actual number of oversampled values is 2^bits. The oversampling is done automatically in the
+   * FPGA.
+   *
+   * @return The number of oversample bits.
+   */
+  public int getOversampleBits() {
+    return AnalogJNI.getAnalogOversampleBits(m_port);
+  }
+
+  /**
+   * Initialize the accumulator.
+   */
+  public void initAccumulator() {
+    if (!isAccumulatorChannel()) {
+      throw new AllocationException("Accumulators are only available on slot " + kAccumulatorSlot
+          + " on channels " + kAccumulatorChannels[0] + ", " + kAccumulatorChannels[1]);
+    }
+    m_accumulatorOffset = 0;
+    AnalogJNI.initAccumulator(m_port);
+  }
+
+  /**
+   * Set an initial value for the accumulator.
+   *
+   * <p>This will be added to all values returned to the user.
+   *
+   * @param initialValue The value that the accumulator should start from when reset.
+   */
+  public void setAccumulatorInitialValue(long initialValue) {
+    m_accumulatorOffset = initialValue;
+  }
+
+  /**
+   * Resets the accumulator to the initial value.
+   */
+  public void resetAccumulator() {
+    AnalogJNI.resetAccumulator(m_port);
+
+    // Wait until the next sample, so the next call to getAccumulator*()
+    // won't have old values.
+    final double sampleTime = 1.0 / getGlobalSampleRate();
+    final double overSamples = 1 << getOversampleBits();
+    final double averageSamples = 1 << getAverageBits();
+    Timer.delay(sampleTime * overSamples * averageSamples);
+
+  }
+
+  /**
+   * Set the center value of the accumulator.
+   *
+   * <p>The center value is subtracted from each A/D value before it is added to the accumulator.
+   * This is used for the center value of devices like gyros and accelerometers to take the device
+   * offset into account when integrating.
+   *
+   * <p>This center value is based on the output of the oversampled and averaged source the
+   * accumulator channel. Because of this, any non-zero oversample bits will affect the size of the
+   * value for this field.
+   */
+  public void setAccumulatorCenter(int center) {
+    AnalogJNI.setAccumulatorCenter(m_port, center);
+  }
+
+  /**
+   * Set the accumulator's deadband.
+   *
+   * @param deadband The deadband size in ADC codes (12-bit value)
+   */
+  public void setAccumulatorDeadband(int deadband) {
+    AnalogJNI.setAccumulatorDeadband(m_port, deadband);
+  }
+
+  /**
+   * Read the accumulated value.
+   *
+   * <p>Read the value that has been accumulating. The accumulator is attached after the oversample
+   * and average engine.
+   *
+   * @return The 64-bit value accumulated since the last Reset().
+   */
+  public long getAccumulatorValue() {
+    return AnalogJNI.getAccumulatorValue(m_port) + m_accumulatorOffset;
+  }
+
+  /**
+   * Read the number of accumulated values.
+   *
+   * <p>Read the count of the accumulated values since the accumulator was last Reset().
+   *
+   * @return The number of times samples from the channel were accumulated.
+   */
+  public long getAccumulatorCount() {
+    return AnalogJNI.getAccumulatorCount(m_port);
+  }
+
+  /**
+   * Read the accumulated value and the number of accumulated values atomically.
+   *
+   * <p>This function reads the value and count from the FPGA atomically. This can be used for
+   * averaging.
+   *
+   * @param result AccumulatorResult object to store the results in.
+   */
+  public void getAccumulatorOutput(AccumulatorResult result) {
+    if (result == null) {
+      throw new IllegalArgumentException("Null parameter `result'");
+    }
+    if (!isAccumulatorChannel()) {
+      throw new IllegalArgumentException(
+          "Channel " + m_channel + " is not an accumulator channel.");
+    }
+    AnalogJNI.getAccumulatorOutput(m_port, result);
+    result.value += m_accumulatorOffset;
+  }
+
+  /**
+   * Is the channel attached to an accumulator.
+   *
+   * @return The analog channel is attached to an accumulator.
+   */
+  public boolean isAccumulatorChannel() {
+    for (int channel : kAccumulatorChannels) {
+      if (m_channel == channel) {
+        return true;
+      }
+    }
+    return false;
+  }
+
+  /**
+   * Set the sample rate per channel.
+   *
+   * <p>This is a global setting for all channels. The maximum rate is 500kS/s divided by the number
+   * of channels in use. This is 62500 samples/s per channel if all 8 channels are used.
+   *
+   * @param samplesPerSecond The number of samples per second.
+   */
+  public static void setGlobalSampleRate(final double samplesPerSecond) {
+    AnalogJNI.setAnalogSampleRate(samplesPerSecond);
+  }
+
+  /**
+   * Get the current sample rate.
+   *
+   * <p>This assumes one entry in the scan list. This is a global setting for all channels.
+   *
+   * @return Sample rate.
+   */
+  public static double getGlobalSampleRate() {
+    return AnalogJNI.getAnalogSampleRate();
+  }
+
+  @Override
+  public void setPIDSourceType(PIDSourceType pidSource) {
+    m_pidSource = pidSource;
+  }
+
+  @Override
+  public PIDSourceType getPIDSourceType() {
+    return m_pidSource;
+  }
+
+  /**
+   * Get the average voltage for use with PIDController.
+   *
+   * @return the average voltage
+   */
+  @Override
+  public double pidGet() {
+    return getAverageVoltage();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Analog Input");
+    builder.addDoubleProperty("Value", this::getAverageVoltage, null);
+  }
+
+  public AnalogInSim getSimObject() {
+    return new AnalogInSim(m_channel);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java
new file mode 100644
index 0000000..ff81e9e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogOutput.java
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.AnalogJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.sim.AnalogOutSim;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Analog output class.
+ */
+public class AnalogOutput extends SendableBase {
+  private int m_port;
+  private int m_channel;
+
+  /**
+   * Construct an analog output on a specified MXP channel.
+   *
+   * @param channel The channel number to represent.
+   */
+  public AnalogOutput(final int channel) {
+    SensorUtil.checkAnalogOutputChannel(channel);
+    m_channel = channel;
+
+    final int portHandle = HAL.getPort((byte) channel);
+    m_port = AnalogJNI.initializeAnalogOutputPort(portHandle);
+
+    HAL.report(tResourceType.kResourceType_AnalogOutput, channel);
+    setName("AnalogOutput", channel);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    AnalogJNI.freeAnalogOutputPort(m_port);
+    m_port = 0;
+    m_channel = 0;
+  }
+
+  /**
+   * Get the channel of this AnalogOutput.
+   */
+  public int getChannel() {
+    return m_channel;
+  }
+
+  public void setVoltage(double voltage) {
+    AnalogJNI.setAnalogOutput(m_port, voltage);
+  }
+
+  public double getVoltage() {
+    return AnalogJNI.getAnalogOutput(m_port);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Analog Output");
+    builder.addDoubleProperty("Value", this::getVoltage, this::setVoltage);
+  }
+
+  public AnalogOutSim getSimObject() {
+    return new AnalogOutSim(m_channel);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java
new file mode 100644
index 0000000..d1a9018
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometer.java
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.interfaces.Potentiometer;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Class for reading analog potentiometers. Analog potentiometers read in an analog voltage that
+ * corresponds to a position. The position is in whichever units you choose, by way of the scaling
+ * and offset constants passed to the constructor.
+ */
+public class AnalogPotentiometer extends SendableBase implements Potentiometer {
+  private AnalogInput m_analogInput;
+  private boolean m_initAnalogInput;
+  private double m_fullRange;
+  private double m_offset;
+  protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
+
+  /**
+   * AnalogPotentiometer constructor.
+   *
+   * <p>Use the fullRange and offset values so that the output produces meaningful values. I.E: you
+   * have a 270 degree potentiometer and you want the output to be degrees with the halfway point as
+   * 0 degrees. The fullRange value is 270.0(degrees) and the offset is -135.0 since the halfway
+   * point after scaling is 135 degrees. This will calculate the result from the fullRange times
+   * the fraction of the supply voltage, plus the offset.
+   *
+   * @param channel   The analog channel this potentiometer is plugged into.
+   * @param fullRange The scaling to multiply the fraction by to get a meaningful unit.
+   * @param offset    The offset to add to the scaled value for controlling the zero value
+   */
+  public AnalogPotentiometer(final int channel, double fullRange, double offset) {
+    this(new AnalogInput(channel), fullRange, offset);
+    m_initAnalogInput = true;
+    addChild(m_analogInput);
+  }
+
+  /**
+   * AnalogPotentiometer constructor.
+   *
+   * <p>Use the fullRange and offset values so that the output produces meaningful values. I.E: you
+   * have a 270 degree potentiometer and you want the output to be degrees with the halfway point as
+   * 0 degrees. The fullRange value is 270.0(degrees) and the offset is -135.0 since the halfway
+   * point after scaling is 135 degrees. This will calculate the result from the fullRange times
+   * the fraction of the supply voltage, plus the offset.
+   *
+   * @param input     The {@link AnalogInput} this potentiometer is plugged into.
+   * @param fullRange The scaling to multiply the fraction by to get a meaningful unit.
+   * @param offset    The offset to add to the scaled value for controlling the zero value
+   */
+  public AnalogPotentiometer(final AnalogInput input, double fullRange, double offset) {
+    setName("AnalogPotentiometer", input.getChannel());
+    m_analogInput = input;
+    m_initAnalogInput = false;
+
+    m_fullRange = fullRange;
+    m_offset = offset;
+  }
+
+  /**
+   * AnalogPotentiometer constructor.
+   *
+   * <p>Use the fullRange and offset values so that the output produces meaningful values. I.E: you
+   * have a 270 degree potentiometer and you want the output to be degrees with the halfway point as
+   * 0 degrees. The fullRange value is 270.0(degrees) and the offset is -135.0 since the halfway
+   * point after scaling is 135 degrees.
+   *
+   * @param channel The analog channel this potentiometer is plugged into.
+   * @param scale   The scaling to multiply the voltage by to get a meaningful unit.
+   */
+  public AnalogPotentiometer(final int channel, double scale) {
+    this(channel, scale, 0);
+  }
+
+  /**
+   * AnalogPotentiometer constructor.
+   *
+   * <p>Use the fullRange and offset values so that the output produces meaningful values. I.E: you
+   * have a 270 degree potentiometer and you want the output to be degrees with the halfway point as
+   * 0 degrees. The fullRange value is 270.0(degrees) and the offset is -135.0 since the halfway
+   * point after scaling is 135 degrees.
+   *
+   * @param input The {@link AnalogInput} this potentiometer is plugged into.
+   * @param scale The scaling to multiply the voltage by to get a meaningful unit.
+   */
+  public AnalogPotentiometer(final AnalogInput input, double scale) {
+    this(input, scale, 0);
+  }
+
+  /**
+   * AnalogPotentiometer constructor.
+   *
+   * @param channel The analog channel this potentiometer is plugged into.
+   */
+  public AnalogPotentiometer(final int channel) {
+    this(channel, 1, 0);
+  }
+
+  /**
+   * AnalogPotentiometer constructor.
+   *
+   * @param input The {@link AnalogInput} this potentiometer is plugged into.
+   */
+  public AnalogPotentiometer(final AnalogInput input) {
+    this(input, 1, 0);
+  }
+
+  /**
+   * Get the current reading of the potentiometer.
+   *
+   * @return The current position of the potentiometer.
+   */
+  @Override
+  public double get() {
+    if (m_analogInput == null) {
+      return m_offset;
+    }
+    return (m_analogInput.getVoltage() / RobotController.getVoltage5V()) * m_fullRange + m_offset;
+  }
+
+  @Override
+  public void setPIDSourceType(PIDSourceType pidSource) {
+    if (!pidSource.equals(PIDSourceType.kDisplacement)) {
+      throw new IllegalArgumentException("Only displacement PID is allowed for potentiometers.");
+    }
+    m_pidSource = pidSource;
+  }
+
+  @Override
+  public PIDSourceType getPIDSourceType() {
+    return m_pidSource;
+  }
+
+  /**
+   * Implement the PIDSource interface.
+   *
+   * @return The current reading.
+   */
+  @Override
+  public double pidGet() {
+    return get();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    if (m_analogInput != null) {
+      m_analogInput.initSendable(builder);
+    }
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    if (m_initAnalogInput) {
+      m_analogInput.close();
+      m_analogInput = null;
+      m_initAnalogInput = false;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java
new file mode 100644
index 0000000..e429246
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTrigger.java
@@ -0,0 +1,184 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+
+import edu.wpi.first.hal.AnalogJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.util.BoundaryException;
+import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+
+/**
+ * Class for creating and configuring Analog Triggers.
+ */
+public class AnalogTrigger extends SendableBase {
+  /**
+   * Exceptions dealing with improper operation of the Analog trigger.
+   */
+  public static class AnalogTriggerException extends RuntimeException {
+    /**
+     * Create a new exception with the given message.
+     *
+     * @param message the message to pass with the exception
+     */
+    public AnalogTriggerException(String message) {
+      super(message);
+    }
+
+  }
+
+  /**
+   * Where the analog trigger is attached.
+   */
+  protected int m_port;
+  protected int m_index;
+  protected AnalogInput m_analogInput;
+  protected boolean m_ownsAnalog;
+
+  /**
+   * Constructor for an analog trigger given a channel number.
+   *
+   * @param channel the port to use for the analog trigger
+   */
+  public AnalogTrigger(final int channel) {
+    this(new AnalogInput(channel));
+    m_ownsAnalog = true;
+    addChild(m_analogInput);
+  }
+
+  /**
+   * Construct an analog trigger given an analog channel. This should be used in the case of sharing
+   * an analog channel between the trigger and an analog input object.
+   *
+   * @param channel the AnalogInput to use for the analog trigger
+   */
+  public AnalogTrigger(AnalogInput channel) {
+    m_analogInput = channel;
+    ByteBuffer index = ByteBuffer.allocateDirect(4);
+    index.order(ByteOrder.LITTLE_ENDIAN);
+
+    m_port =
+        AnalogJNI.initializeAnalogTrigger(channel.m_port, index.asIntBuffer());
+    m_index = index.asIntBuffer().get(0);
+
+    HAL.report(tResourceType.kResourceType_AnalogTrigger, channel.getChannel());
+    setName("AnalogTrigger", channel.getChannel());
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    AnalogJNI.cleanAnalogTrigger(m_port);
+    m_port = 0;
+    if (m_ownsAnalog && m_analogInput != null) {
+      m_analogInput.close();
+    }
+  }
+
+  /**
+   * Set the upper and lower limits of the analog trigger. The limits are given in ADC codes. If
+   * oversampling is used, the units must be scaled appropriately.
+   *
+   * @param lower the lower raw limit
+   * @param upper the upper raw limit
+   */
+  public void setLimitsRaw(final int lower, final int upper) {
+    if (lower > upper) {
+      throw new BoundaryException("Lower bound is greater than upper");
+    }
+    AnalogJNI.setAnalogTriggerLimitsRaw(m_port, lower, upper);
+  }
+
+  /**
+   * Set the upper and lower limits of the analog trigger. The limits are given as floating point
+   * voltage values.
+   *
+   * @param lower the lower voltage limit
+   * @param upper the upper voltage limit
+   */
+  public void setLimitsVoltage(double lower, double upper) {
+    if (lower > upper) {
+      throw new BoundaryException("Lower bound is greater than upper bound");
+    }
+    AnalogJNI.setAnalogTriggerLimitsVoltage(m_port, lower, upper);
+  }
+
+  /**
+   * Configure the analog trigger to use the averaged vs. raw values. If the value is true, then the
+   * averaged value is selected for the analog trigger, otherwise the immediate value is used.
+   *
+   * @param useAveragedValue true to use an averaged value, false otherwise
+   */
+  public void setAveraged(boolean useAveragedValue) {
+    AnalogJNI.setAnalogTriggerAveraged(m_port, useAveragedValue);
+  }
+
+  /**
+   * Configure the analog trigger to use a filtered value. The analog trigger will operate with a 3
+   * point average rejection filter. This is designed to help with 360 degree pot applications for
+   * the period where the pot crosses through zero.
+   *
+   * @param useFilteredValue true to use a filtered value, false otherwise
+   */
+  public void setFiltered(boolean useFilteredValue) {
+    AnalogJNI.setAnalogTriggerFiltered(m_port, useFilteredValue);
+  }
+
+  /**
+   * Return the index of the analog trigger. This is the FPGA index of this analog trigger
+   * instance.
+   *
+   * @return The index of the analog trigger.
+   */
+  public int getIndex() {
+    return m_index;
+  }
+
+  /**
+   * Return the InWindow output of the analog trigger. True if the analog input is between the upper
+   * and lower limits.
+   *
+   * @return The InWindow output of the analog trigger.
+   */
+  public boolean getInWindow() {
+    return AnalogJNI.getAnalogTriggerInWindow(m_port);
+  }
+
+  /**
+   * Return the TriggerState output of the analog trigger. True if above upper limit. False if below
+   * lower limit. If in Hysteresis, maintain previous state.
+   *
+   * @return The TriggerState output of the analog trigger.
+   */
+  public boolean getTriggerState() {
+    return AnalogJNI.getAnalogTriggerTriggerState(m_port);
+  }
+
+  /**
+   * Creates an AnalogTriggerOutput object. Gets an output object that can be used for routing.
+   * Caller is responsible for deleting the AnalogTriggerOutput object.
+   *
+   * @param type An enum of the type of output object to create.
+   * @return A pointer to a new AnalogTriggerOutput object.
+   */
+  public AnalogTriggerOutput createOutput(AnalogTriggerType type) {
+    return new AnalogTriggerOutput(this, type);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    if (m_ownsAnalog) {
+      m_analogInput.initSendable(builder);
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java
new file mode 100644
index 0000000..04971c8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/AnalogTriggerOutput.java
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.AnalogJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Class to represent a specific output from an analog trigger. This class is used to get the
+ * current output value and also as a DigitalSource to provide routing of an output to digital
+ * subsystems on the FPGA such as Counter, Encoder, and Interrupt.
+ *
+ * <p>The TriggerState output indicates the primary output value of the trigger. If the analog
+ * signal is less than the lower limit, the output is false. If the analog value is greater than the
+ * upper limit, then the output is true. If the analog value is in between, then the trigger output
+ * state maintains its most recent value.
+ *
+ * <p>The InWindow output indicates whether or not the analog signal is inside the range defined by
+ * the limits.
+ *
+ * <p>The RisingPulse and FallingPulse outputs detect an instantaneous transition from above the
+ * upper limit to below the lower limit, and vise versa. These pulses represent a rollover condition
+ * of a sensor and can be routed to an up / down counter or to interrupts. Because the outputs
+ * generate a pulse, they cannot be read directly. To help ensure that a rollover condition is not
+ * missed, there is an average rejection filter available that operates on the upper 8 bits of a 12
+ * bit number and selects the nearest outlier of 3 samples. This will reject a sample that is (due
+ * to averaging or sampling) errantly between the two limits. This filter will fail if more than one
+ * sample in a row is errantly in between the two limits. You may see this problem if attempting to
+ * use this feature with a mechanical rollover sensor, such as a 360 degree no-stop potentiometer
+ * without signal conditioning, because the rollover transition is not sharp / clean enough. Using
+ * the averaging engine may help with this, but rotational speeds of the sensor will then be
+ * limited.
+ */
+public class AnalogTriggerOutput extends DigitalSource {
+  /**
+   * Exceptions dealing with improper operation of the Analog trigger output.
+   */
+  public static class AnalogTriggerOutputException extends RuntimeException {
+    /**
+     * Create a new exception with the given message.
+     *
+     * @param message the message to pass with the exception
+     */
+    public AnalogTriggerOutputException(String message) {
+      super(message);
+    }
+  }
+
+  private final AnalogTrigger m_trigger;
+  private final AnalogTriggerType m_outputType;
+
+  /**
+   * Create an object that represents one of the four outputs from an analog trigger.
+   *
+   * <p>Because this class derives from DigitalSource, it can be passed into routing functions for
+   * Counter, Encoder, etc.
+   *
+   * @param trigger    The trigger for which this is an output.
+   * @param outputType An enum that specifies the output on the trigger to represent.
+   */
+  public AnalogTriggerOutput(AnalogTrigger trigger, final AnalogTriggerType outputType) {
+    requireNonNull(trigger, "Analog Trigger given was null");
+    requireNonNull(outputType, "Analog Trigger Type given was null");
+
+    m_trigger = trigger;
+    m_outputType = outputType;
+    HAL.report(tResourceType.kResourceType_AnalogTriggerOutput,
+        trigger.getIndex(), outputType.value);
+  }
+
+  /**
+   * Get the state of the analog trigger output.
+   *
+   * @return The state of the analog trigger output.
+   */
+  public boolean get() {
+    return AnalogJNI.getAnalogTriggerOutput(m_trigger.m_port, m_outputType.value);
+  }
+
+  @Override
+  public int getPortHandleForRouting() {
+    return m_trigger.m_port;
+  }
+
+  @Override
+  public int getAnalogTriggerTypeForRouting() {
+    return m_outputType.value;
+  }
+
+  @Override
+  public int getChannel() {
+    return m_trigger.m_index;
+  }
+
+  @Override
+  public boolean isAnalogTrigger() {
+    return true;
+  }
+
+  /**
+   * Defines the state in which the AnalogTrigger triggers.
+   */
+  public enum AnalogTriggerType {
+    kInWindow(AnalogJNI.AnalogTriggerType.kInWindow), kState(AnalogJNI.AnalogTriggerType.kState),
+    kRisingPulse(AnalogJNI.AnalogTriggerType.kRisingPulse),
+    kFallingPulse(AnalogJNI.AnalogTriggerType.kFallingPulse);
+
+    @SuppressWarnings("MemberName")
+    private final int value;
+
+    AnalogTriggerType(int value) {
+      this.value = value;
+    }
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java
new file mode 100644
index 0000000..d8dbafe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometer.java
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.AccelerometerJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.sim.AccelerometerSim;
+import edu.wpi.first.wpilibj.interfaces.Accelerometer;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Built-in accelerometer.
+ *
+ * <p>This class allows access to the roboRIO's internal accelerometer.
+ */
+public class BuiltInAccelerometer extends SendableBase implements Accelerometer {
+  /**
+   * Constructor.
+   *
+   * @param range The range the accelerometer will measure
+   */
+  public BuiltInAccelerometer(Range range) {
+    setRange(range);
+    HAL.report(tResourceType.kResourceType_Accelerometer, 0, 0, "Built-in accelerometer");
+    setName("BuiltInAccel", 0);
+  }
+
+  /**
+   * Constructor. The accelerometer will measure +/-8 g-forces
+   */
+  public BuiltInAccelerometer() {
+    this(Range.k8G);
+  }
+
+  @Override
+  public void setRange(Range range) {
+    AccelerometerJNI.setAccelerometerActive(false);
+
+    switch (range) {
+      case k2G:
+        AccelerometerJNI.setAccelerometerRange(0);
+        break;
+      case k4G:
+        AccelerometerJNI.setAccelerometerRange(1);
+        break;
+      case k8G:
+        AccelerometerJNI.setAccelerometerRange(2);
+        break;
+      case k16G:
+      default:
+        throw new IllegalArgumentException(range + " range not supported (use k2G, k4G, or k8G)");
+
+    }
+
+    AccelerometerJNI.setAccelerometerActive(true);
+  }
+
+  /**
+   * The acceleration in the X axis.
+   *
+   * @return The acceleration of the roboRIO along the X axis in g-forces
+   */
+  @Override
+  public double getX() {
+    return AccelerometerJNI.getAccelerometerX();
+  }
+
+  /**
+   * The acceleration in the Y axis.
+   *
+   * @return The acceleration of the roboRIO along the Y axis in g-forces
+   */
+  @Override
+  public double getY() {
+    return AccelerometerJNI.getAccelerometerY();
+  }
+
+  /**
+   * The acceleration in the Z axis.
+   *
+   * @return The acceleration of the roboRIO along the Z axis in g-forces
+   */
+  @Override
+  public double getZ() {
+    return AccelerometerJNI.getAccelerometerZ();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("3AxisAccelerometer");
+    builder.addDoubleProperty("X", this::getX, null);
+    builder.addDoubleProperty("Y", this::getY, null);
+    builder.addDoubleProperty("Z", this::getZ, null);
+  }
+
+  public AccelerometerSim getSimObject() {
+    return new AccelerometerSim();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java
new file mode 100644
index 0000000..c6eac3a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CAN.java
@@ -0,0 +1,155 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.io.Closeable;
+
+import edu.wpi.first.hal.CANAPIJNI;
+import edu.wpi.first.hal.CANData;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * High level class for interfacing with CAN devices conforming to
+ * the standard CAN spec.
+ *
+ * <p>No packets that can be sent gets blocked by the RoboRIO, so all methods
+ * work identically in all robot modes.
+ *
+ * <p>All methods are thread safe, however the CANData object passed into the
+ * read methods and the byte[] passed into the write methods need to not
+ * be modified for the duration of their respective calls.
+ */
+public class CAN implements Closeable {
+  public static final int kTeamManufacturer = 8;
+  public static final int kTeamDeviceType = 10;
+
+  private final int m_handle;
+
+  /**
+   * Create a new CAN communication interface with the specific device ID.
+   * This uses the team manufacturer and device types.
+   * The device ID is 6 bits (0-63).
+   *
+   * @param deviceId The device id
+   */
+  public CAN(int deviceId) {
+    m_handle = CANAPIJNI.initializeCAN(kTeamManufacturer, deviceId, kTeamDeviceType);
+    HAL.report(tResourceType.kResourceType_CAN, deviceId);
+  }
+
+  /**
+   * Create a new CAN communication interface with a specific device ID,
+   * manufacturer and device type. The device ID is 6 bits, the
+   * manufacturer is 8 bits, and the device type is 5 bits.
+   *
+   * @param deviceId           The device ID
+   * @param deviceManufacturer The device manufacturer
+   * @param deviceType         The device type
+   */
+  public CAN(int deviceId, int deviceManufacturer, int deviceType) {
+    m_handle = CANAPIJNI.initializeCAN(deviceManufacturer, deviceId, deviceType);
+    HAL.report(tResourceType.kResourceType_CAN, deviceId);
+  }
+
+  /**
+   * Closes the CAN communication.
+   */
+  @Override
+  public void close() {
+    if (m_handle != 0) {
+      CANAPIJNI.cleanCAN(m_handle);
+    }
+  }
+
+  /**
+   * Write a packet to the CAN device with a specific ID. This ID is 10 bits.
+   *
+   * @param data The data to write (8 bytes max)
+   * @param apiId The API ID to write.
+   */
+  public void writePacket(byte[] data, int apiId) {
+    CANAPIJNI.writeCANPacket(m_handle, data, apiId);
+  }
+
+  /**
+   * Write a repeating packet to the CAN device with a specific ID. This ID is 10 bits.
+   * The RoboRIO will automatically repeat the packet at the specified interval
+   *
+   * @param data The data to write (8 bytes max)
+   * @param apiId The API ID to write.
+   * @param repeatMs The period to repeat the packet at.
+   */
+  public void writePacketRepeating(byte[] data, int apiId, int repeatMs) {
+    CANAPIJNI.writeCANPacketRepeating(m_handle, data, apiId, repeatMs);
+  }
+
+  /**
+   * Stop a repeating packet with a specific ID. This ID is 10 bits.
+   *
+   * @param apiId The API ID to stop repeating
+   */
+  public void stopPacketRepeating(int apiId) {
+    CANAPIJNI.stopCANPacketRepeating(m_handle, apiId);
+  }
+
+  /**
+   * Read a new CAN packet. This will only return properly once per packet
+   * received. Multiple calls without receiving another packet will return false.
+   *
+   * @param apiId The API ID to read.
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  public boolean readPacketNew(int apiId, CANData data) {
+    return CANAPIJNI.readCANPacketNew(m_handle, apiId, data);
+  }
+
+  /**
+   * Read a CAN packet. The will continuously return the last packet received,
+   * without accounting for packet age.
+   *
+   * @param apiId The API ID to read.
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  public boolean readPacketLatest(int apiId, CANData data) {
+    return CANAPIJNI.readCANPacketLatest(m_handle, apiId, data);
+  }
+
+  /**
+   * Read a CAN packet. The will return the last packet received until the
+   * packet is older then the requested timeout. Then it will return false.
+   *
+   * @param apiId The API ID to read.
+   * @param timeoutMs The timeout time for the packet
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  public boolean readPacketTimeout(int apiId, int timeoutMs, CANData data) {
+    return CANAPIJNI.readCANPacketTimeout(m_handle, apiId, timeoutMs, data);
+  }
+
+  /**
+   * Read a CAN packet. The will return the last packet received until the
+   * packet is older then the requested timeout. Then it will return false.
+   * The period parameter is used when you know the packet is sent at specific
+   * intervals, so calls will not attempt to read a new packet from the
+   * network until that period has passed. We do not recommend users use this
+   * API unless they know the implications.
+   *
+   * @param apiId The API ID to read.
+   * @param timeoutMs The timeout time for the packet
+   * @param periodMs The usual period for the packet
+   * @param data Storage for the received data.
+   * @return True if the data is valid, otherwise false.
+   */
+  public boolean readPeriodicPacket(int apiId, int timeoutMs, int periodMs, CANData data) {
+    return CANAPIJNI.readCANPeriodicPacket(m_handle, apiId, timeoutMs, periodMs, data);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CameraServer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CameraServer.java
new file mode 100644
index 0000000..a25ab2e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CameraServer.java
@@ -0,0 +1,780 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.Hashtable;
+import java.util.Map;
+import java.util.concurrent.atomic.AtomicInteger;
+
+import edu.wpi.cscore.AxisCamera;
+import edu.wpi.cscore.CameraServerJNI;
+import edu.wpi.cscore.CvSink;
+import edu.wpi.cscore.CvSource;
+import edu.wpi.cscore.MjpegServer;
+import edu.wpi.cscore.UsbCamera;
+import edu.wpi.cscore.VideoEvent;
+import edu.wpi.cscore.VideoException;
+import edu.wpi.cscore.VideoListener;
+import edu.wpi.cscore.VideoMode;
+import edu.wpi.cscore.VideoMode.PixelFormat;
+import edu.wpi.cscore.VideoProperty;
+import edu.wpi.cscore.VideoSink;
+import edu.wpi.cscore.VideoSource;
+import edu.wpi.first.cameraserver.CameraServerSharedStore;
+import edu.wpi.first.networktables.EntryListenerFlags;
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+/**
+ * Singleton class for creating and keeping camera servers.
+ * Also publishes camera information to NetworkTables.
+ *
+ * @deprecated Replaced with edu.wpi.first.cameraserver.CameraServer
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+@Deprecated
+public final class CameraServer {
+  public static final int kBasePort = 1181;
+
+  @Deprecated
+  public static final int kSize640x480 = 0;
+  @Deprecated
+  public static final int kSize320x240 = 1;
+  @Deprecated
+  public static final int kSize160x120 = 2;
+
+  private static final String kPublishName = "/CameraPublisher";
+  private static CameraServer server;
+
+  /**
+   * Get the CameraServer instance.
+   */
+  public static synchronized CameraServer getInstance() {
+    if (server == null) {
+      server = new 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 final NetworkTable m_publishTable;
+  private final VideoListener m_videoListener; //NOPMD
+  private final int m_tableListener; //NOPMD
+  private int m_nextPort;
+  private String[] m_addresses;
+
+  @SuppressWarnings("JavadocMethod")
+  private static String makeSourceValue(int source) {
+    switch (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))) {
+      case kUsb:
+        return "usb:" + CameraServerJNI.getUsbCameraPath(source);
+      case kHttp: {
+        String[] urls = CameraServerJNI.getHttpCameraUrls(source);
+        if (urls.length > 0) {
+          return "ip:" + urls[0];
+        } else {
+          return "ip:";
+        }
+      }
+      case kCv:
+        // FIXME: Should be "cv:", but LabVIEW dashboard requires "usb:".
+        // https://github.com/wpilibsuite/allwpilib/issues/407
+        return "usb:";
+      default:
+        return "unknown:";
+    }
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  private static String makeStreamValue(String address, int port) {
+    return "mjpg:http://" + address + ":" + port + "/?action=stream";
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.AvoidUsingHardCodedIP"})
+  private synchronized String[] getSinkStreamValues(int sink) {
+    // Ignore all but MjpegServer
+    if (VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) != VideoSink.Kind.kMjpeg) {
+      return new String[0];
+    }
+
+    // Get port
+    int port = CameraServerJNI.getMjpegServerPort(sink);
+
+    // Generate values
+    ArrayList<String> values = new ArrayList<>(m_addresses.length + 1);
+    String listenAddress = CameraServerJNI.getMjpegServerListenAddress(sink);
+    if (!listenAddress.isEmpty()) {
+      // If a listen address is specified, only use that
+      values.add(makeStreamValue(listenAddress, port));
+    } else {
+      // Otherwise generate for hostname and all interface addresses
+      values.add(makeStreamValue(CameraServerJNI.getHostname() + ".local", port));
+      for (String addr : m_addresses) {
+        if ("127.0.0.1".equals(addr)) {
+          continue;  // ignore localhost
+        }
+        values.add(makeStreamValue(addr, port));
+      }
+    }
+
+    return values.toArray(new String[0]);
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.AvoidUsingHardCodedIP"})
+  private synchronized String[] getSourceStreamValues(int source) {
+    // Ignore all but HttpCamera
+    if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))
+            != VideoSource.Kind.kHttp) {
+      return new String[0];
+    }
+
+    // Generate values
+    String[] values = CameraServerJNI.getHttpCameraUrls(source);
+    for (int j = 0; j < values.length; j++) {
+      values[j] = "mjpg:" + values[j];
+    }
+
+    // Look to see if we have a passthrough server for this source
+    for (VideoSink i : m_sinks.values()) {
+      int sink = i.getHandle();
+      int sinkSource = CameraServerJNI.getSinkSource(sink);
+      if (source == sinkSource
+          && VideoSink.getKindFromInt(CameraServerJNI.getSinkKind(sink)) == VideoSink.Kind.kMjpeg) {
+        // Add USB-only passthrough
+        String[] finalValues = Arrays.copyOf(values, values.length + 1);
+        int port = CameraServerJNI.getMjpegServerPort(sink);
+        finalValues[values.length] = makeStreamValue("172.22.11.2", port);
+        return finalValues;
+      }
+    }
+
+    return values;
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.AvoidUsingHardCodedIP"})
+  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);
+      if (source == 0) {
+        continue;
+      }
+      NetworkTable table = m_tables.get(source);
+      if (table != null) {
+        // Don't set stream values if this is a HttpCamera passthrough
+        if (VideoSource.getKindFromInt(CameraServerJNI.getSourceKind(source))
+            == VideoSource.Kind.kHttp) {
+          continue;
+        }
+
+        // Set table value
+        String[] values = getSinkStreamValues(sink);
+        if (values.length > 0) {
+          table.getEntry("streams").setStringArray(values);
+        }
+      }
+    }
+
+    // Over all the sources...
+    for (VideoSource i : m_sources.values()) {
+      int source = i.getHandle();
+
+      // Get the source's subtable (if none exists, we're done)
+      NetworkTable table = m_tables.get(source);
+      if (table != null) {
+        // Set table value
+        String[] values = getSourceStreamValues(source);
+        if (values.length > 0) {
+          table.getEntry("streams").setStringArray(values);
+        }
+      }
+    }
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  private static String pixelFormatToString(PixelFormat pixelFormat) {
+    switch (pixelFormat) {
+      case kMJPEG:
+        return "MJPEG";
+      case kYUYV:
+        return "YUYV";
+      case kRGB565:
+        return "RGB565";
+      case kBGR:
+        return "BGR";
+      case kGray:
+        return "Gray";
+      default:
+        return "Unknown";
+    }
+  }
+
+  /// Provide string description of video mode.
+  /// The returned string is "{width}x{height} {format} {fps} fps".
+  @SuppressWarnings("JavadocMethod")
+  private static String videoModeToString(VideoMode mode) {
+    return mode.width + "x" + mode.height + " " + pixelFormatToString(mode.pixelFormat)
+        + " " + mode.fps + " fps";
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  private static String[] getSourceModeValues(int sourceHandle) {
+    VideoMode[] modes = CameraServerJNI.enumerateSourceVideoModes(sourceHandle);
+    String[] modeStrings = new String[modes.length];
+    for (int i = 0; i < modes.length; i++) {
+      modeStrings[i] = videoModeToString(modes[i]);
+    }
+    return modeStrings;
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.CyclomaticComplexity"})
+  private static void putSourcePropertyValue(NetworkTable table, VideoEvent event, boolean isNew) {
+    String name;
+    String infoName;
+    if (event.name.startsWith("raw_")) {
+      name = "RawProperty/" + event.name;
+      infoName = "RawPropertyInfo/" + event.name;
+    } else {
+      name = "Property/" + event.name;
+      infoName = "PropertyInfo/" + event.name;
+    }
+
+    NetworkTableEntry entry = table.getEntry(name);
+    try {
+      switch (event.propertyKind) {
+        case kBoolean:
+          if (isNew) {
+            entry.setDefaultBoolean(event.value != 0);
+          } else {
+            entry.setBoolean(event.value != 0);
+          }
+          break;
+        case kInteger:
+        case kEnum:
+          if (isNew) {
+            entry.setDefaultDouble(event.value);
+            table.getEntry(infoName + "/min").setDouble(
+                CameraServerJNI.getPropertyMin(event.propertyHandle));
+            table.getEntry(infoName + "/max").setDouble(
+                CameraServerJNI.getPropertyMax(event.propertyHandle));
+            table.getEntry(infoName + "/step").setDouble(
+                CameraServerJNI.getPropertyStep(event.propertyHandle));
+            table.getEntry(infoName + "/default").setDouble(
+                CameraServerJNI.getPropertyDefault(event.propertyHandle));
+          } else {
+            entry.setDouble(event.value);
+          }
+          break;
+        case kString:
+          if (isNew) {
+            entry.setDefaultString(event.valueStr);
+          } else {
+            entry.setString(event.valueStr);
+          }
+          break;
+        default:
+          break;
+      }
+    } catch (VideoException ignored) {
+      // ignore
+    }
+  }
+
+  @SuppressWarnings({"JavadocMethod", "PMD.UnusedLocalVariable", "PMD.ExcessiveMethodLength",
+      "PMD.NPathComplexity"})
+  private CameraServer() {
+    m_defaultUsbDevice = new AtomicInteger();
+    m_sources = new Hashtable<>();
+    m_sinks = new Hashtable<>();
+    m_tables = new Hashtable<>();
+    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);
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * <p>You should call this method to see a camera feed on the dashboard.
+   * If you also want to perform vision processing on the roboRIO, use
+   * getVideo() to get access to the camera images.
+   *
+   * <p>The first time this overload is called, it calls
+   * {@link #startAutomaticCapture(int)} with device 0, creating a camera
+   * named "USB Camera 0".  Subsequent calls increment the device number
+   * (e.g. 1, 2, etc).
+   */
+  public UsbCamera startAutomaticCapture() {
+    UsbCamera camera = startAutomaticCapture(m_defaultUsbDevice.getAndIncrement());
+    CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * <p>This overload calls {@link #startAutomaticCapture(String, int)} with
+   * a name of "USB Camera {dev}".
+   *
+   * @param dev The device number of the camera interface
+   */
+  public UsbCamera startAutomaticCapture(int dev) {
+    UsbCamera camera = new UsbCamera("USB Camera " + dev, dev);
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * @param name The name to give the camera
+   * @param dev The device number of the camera interface
+   */
+  public UsbCamera startAutomaticCapture(String name, int dev) {
+    UsbCamera camera = new UsbCamera(name, dev);
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard.
+   *
+   * @param name The name to give the camera
+   * @param path The device path (e.g. "/dev/video0") of the camera
+   */
+  public UsbCamera startAutomaticCapture(String name, String path) {
+    UsbCamera camera = new UsbCamera(name, path);
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportUsbCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Start automatically capturing images to send to the dashboard from
+   * an existing camera.
+   *
+   * @param camera Camera
+   */
+  public void startAutomaticCapture(VideoSource camera) {
+    addCamera(camera);
+    VideoSink server = addServer("serve_" + camera.getName());
+    server.setSource(camera);
+  }
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #addAxisCamera(String, String)} with
+   * name "Axis Camera".
+   *
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  public AxisCamera addAxisCamera(String host) {
+    return addAxisCamera("Axis Camera", host);
+  }
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * <p>This overload calls {@link #addAxisCamera(String, String[])} with
+   * name "Axis Camera".
+   *
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  public AxisCamera addAxisCamera(String[] hosts) {
+    return addAxisCamera("Axis Camera", hosts);
+  }
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param host Camera host IP or DNS name (e.g. "10.x.y.11")
+   */
+  public AxisCamera addAxisCamera(String name, String host) {
+    AxisCamera camera = new AxisCamera(name, host);
+    // Create a passthrough MJPEG server for USB access
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportAxisCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Adds an Axis IP camera.
+   *
+   * @param name The name to give the camera
+   * @param hosts Array of Camera host IPs/DNS names
+   */
+  public AxisCamera addAxisCamera(String name, String[] hosts) {
+    AxisCamera camera = new AxisCamera(name, hosts);
+    // Create a passthrough MJPEG server for USB access
+    startAutomaticCapture(camera);
+    CameraServerSharedStore.getCameraServerShared().reportAxisCamera(camera.getHandle());
+    return camera;
+  }
+
+  /**
+   * Get OpenCV access to the primary camera feed.  This allows you to
+   * get images from the camera for image processing on the roboRIO.
+   *
+   * <p>This is only valid to call after a camera feed has been added
+   * with startAutomaticCapture() or addServer().
+   */
+  public CvSink getVideo() {
+    VideoSource source;
+    synchronized (this) {
+      if (m_primarySourceName == null) {
+        throw new VideoException("no camera available");
+      }
+      source = m_sources.get(m_primarySourceName);
+    }
+    if (source == null) {
+      throw new VideoException("no camera available");
+    }
+    return getVideo(source);
+  }
+
+  /**
+   * Get OpenCV access to the specified camera.  This allows you to get
+   * images from the camera for image processing on the roboRIO.
+   *
+   * @param camera Camera (e.g. as returned by startAutomaticCapture).
+   */
+  public CvSink getVideo(VideoSource camera) {
+    String name = "opencv_" + camera.getName();
+
+    synchronized (this) {
+      VideoSink sink = m_sinks.get(name);
+      if (sink != null) {
+        VideoSink.Kind kind = sink.getKind();
+        if (kind != VideoSink.Kind.kCv) {
+          throw new VideoException("expected OpenCV sink, but got " + kind);
+        }
+        return (CvSink) sink;
+      }
+    }
+
+    CvSink newsink = new CvSink(name);
+    newsink.setSource(camera);
+    addServer(newsink);
+    return newsink;
+  }
+
+  /**
+   * Get OpenCV access to the specified camera.  This allows you to get
+   * images from the camera for image processing on the roboRIO.
+   *
+   * @param name Camera name
+   */
+  public CvSink getVideo(String name) {
+    VideoSource source;
+    synchronized (this) {
+      source = m_sources.get(name);
+      if (source == null) {
+        throw new VideoException("could not find camera " + name);
+      }
+    }
+    return getVideo(source);
+  }
+
+  /**
+   * Create a MJPEG stream with OpenCV input. This can be called to pass custom
+   * annotated images to the dashboard.
+   *
+   * @param name Name to give the stream
+   * @param width Width of the image being sent
+   * @param height Height of the image being sent
+   */
+  public CvSource putVideo(String name, int width, int height) {
+    CvSource source = new CvSource(name, VideoMode.PixelFormat.kMJPEG, width, height, 30);
+    startAutomaticCapture(source);
+    return source;
+  }
+
+  /**
+   * Adds a MJPEG server at the next available port.
+   *
+   * @param name Server name
+   */
+  public MjpegServer addServer(String name) {
+    int port;
+    synchronized (this) {
+      port = m_nextPort;
+      m_nextPort++;
+    }
+    return addServer(name, port);
+  }
+
+  /**
+   * Adds a MJPEG server.
+   *
+   * @param name Server name
+   */
+  public MjpegServer addServer(String name, int port) {
+    MjpegServer server = new MjpegServer(name, port);
+    addServer(server);
+    return server;
+  }
+
+  /**
+   * Adds an already created server.
+   *
+   * @param server Server
+   */
+  public void addServer(VideoSink server) {
+    synchronized (this) {
+      m_sinks.put(server.getName(), server);
+    }
+  }
+
+  /**
+   * Removes a server by name.
+   *
+   * @param name Server name
+   */
+  public void removeServer(String name) {
+    synchronized (this) {
+      m_sinks.remove(name);
+    }
+  }
+
+  /**
+   * Get server for the primary camera feed.
+   *
+   * <p>This is only valid to call after a camera feed has been added
+   * with startAutomaticCapture() or addServer().
+   */
+  public VideoSink getServer() {
+    synchronized (this) {
+      if (m_primarySourceName == null) {
+        throw new VideoException("no camera available");
+      }
+      return getServer("serve_" + m_primarySourceName);
+    }
+  }
+
+  /**
+   * Gets a server by name.
+   *
+   * @param name Server name
+   */
+  public VideoSink getServer(String name) {
+    synchronized (this) {
+      return m_sinks.get(name);
+    }
+  }
+
+  /**
+   * Adds an already created camera.
+   *
+   * @param camera Camera
+   */
+  public void addCamera(VideoSource camera) {
+    String name = camera.getName();
+    synchronized (this) {
+      if (m_primarySourceName == null) {
+        m_primarySourceName = name;
+      }
+      m_sources.put(name, camera);
+    }
+  }
+
+  /**
+   * Removes a camera by name.
+   *
+   * @param name Camera name
+   */
+  public void removeCamera(String name) {
+    synchronized (this) {
+      m_sources.remove(name);
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CircularBuffer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CircularBuffer.java
new file mode 100644
index 0000000..7e8ecc4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CircularBuffer.java
@@ -0,0 +1,186 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * This is a simple circular buffer so we don't need to "bucket brigade" copy old values.
+ */
+public class CircularBuffer {
+  private double[] m_data;
+
+  // Index of element at front of buffer
+  private int m_front;
+
+  // Number of elements used in buffer
+  private int m_length;
+
+  /**
+   * Create a CircularBuffer with the provided size.
+   *
+   * @param size The size of the circular buffer.
+   */
+  public CircularBuffer(int size) {
+    m_data = new double[size];
+    for (int i = 0; i < m_data.length; i++) {
+      m_data[i] = 0.0;
+    }
+  }
+
+  /**
+   * Returns number of elements in buffer.
+   *
+   * @return number of elements in buffer
+   */
+  double size() {
+    return m_length;
+  }
+
+  /**
+   * Get value at front of buffer.
+   *
+   * @return value at front of buffer
+   */
+  double getFirst() {
+    return m_data[m_front];
+  }
+
+  /**
+   * Get value at back of buffer.
+   *
+   * @return value at back of buffer
+   */
+  double getLast() {
+    // If there are no elements in the buffer, do nothing
+    if (m_length == 0) {
+      return 0.0;
+    }
+
+    return m_data[(m_front + m_length - 1) % m_data.length];
+  }
+
+  /**
+   * Push new value onto front of the buffer. The value at the back is overwritten if the buffer is
+   * full.
+   */
+  public void addFirst(double value) {
+    if (m_data.length == 0) {
+      return;
+    }
+
+    m_front = moduloDec(m_front);
+
+    m_data[m_front] = value;
+
+    if (m_length < m_data.length) {
+      m_length++;
+    }
+  }
+
+  /**
+   * Push new value onto back of the buffer. The value at the front is overwritten if the buffer is
+   * full.
+   */
+  public void addLast(double value) {
+    if (m_data.length == 0) {
+      return;
+    }
+
+    m_data[(m_front + m_length) % m_data.length] = value;
+
+    if (m_length < m_data.length) {
+      m_length++;
+    } else {
+      // Increment front if buffer is full to maintain size
+      m_front = moduloInc(m_front);
+    }
+  }
+
+  /**
+   * Pop value at front of buffer.
+   *
+   * @return value at front of buffer
+   */
+  public double removeFirst() {
+    // If there are no elements in the buffer, do nothing
+    if (m_length == 0) {
+      return 0.0;
+    }
+
+    double temp = m_data[m_front];
+    m_front = moduloInc(m_front);
+    m_length--;
+    return temp;
+  }
+
+
+  /**
+   * Pop value at back of buffer.
+   */
+  public double removeLast() {
+    // If there are no elements in the buffer, do nothing
+    if (m_length == 0) {
+      return 0.0;
+    }
+
+    m_length--;
+    return m_data[(m_front + m_length) % m_data.length];
+  }
+
+  /**
+   * Resizes internal buffer to given size.
+   *
+   * <p>A new buffer is allocated because arrays are not resizable.
+   */
+  void resize(int size) {
+    double[] newBuffer = new double[size];
+    m_length = Math.min(m_length, size);
+    for (int i = 0; i < m_length; i++) {
+      newBuffer[i] = m_data[(m_front + i) % m_data.length];
+    }
+    m_data = newBuffer;
+    m_front = 0;
+  }
+
+  /**
+   * Sets internal buffer contents to zero.
+   */
+  public void clear() {
+    for (int i = 0; i < m_data.length; i++) {
+      m_data[i] = 0.0;
+    }
+    m_front = 0;
+    m_length = 0;
+  }
+
+  /**
+   * Get the element at the provided index relative to the start of the buffer.
+   *
+   * @return Element at index starting from front of buffer.
+   */
+  public double get(int index) {
+    return m_data[(m_front + index) % m_data.length];
+  }
+
+  /**
+   * Increment an index modulo the length of the m_data buffer.
+   */
+  private int moduloInc(int index) {
+    return (index + 1) % m_data.length;
+  }
+
+  /**
+   * Decrement an index modulo the length of the m_data buffer.
+   */
+  private int moduloDec(int index) {
+    if (index == 0) {
+      return m_data.length - 1;
+    } else {
+      return index - 1;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java
new file mode 100644
index 0000000..e95e8a7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Compressor.java
@@ -0,0 +1,205 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.CompressorJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Class for operating a compressor connected to a PCM (Pneumatic Control Module). The PCM will
+ * automatically run in closed loop mode by default whenever a {@link Solenoid} object is created.
+ * For most cases, a Compressor object does not need to be instantiated or used in a robot program.
+ * This class is only required in cases where the robot program needs a more detailed status of the
+ * compressor or to enable/disable closed loop control.
+ *
+ * <p>Note: you cannot operate the compressor directly from this class as doing so would circumvent
+ * the safety provided by using the pressure switch and closed loop control. You can only turn off
+ * closed loop control, thereby stopping the compressor from operating.
+ */
+public class Compressor extends SendableBase {
+  private int m_compressorHandle;
+  private byte m_module;
+
+  /**
+   * Makes a new instance of the compressor using the provided CAN device ID.  Use this constructor
+   * when you have more than one PCM.
+   *
+   * @param module The PCM CAN device ID (0 - 62 inclusive)
+   */
+  public Compressor(int module) {
+    m_module = (byte) module;
+
+    m_compressorHandle = CompressorJNI.initializeCompressor((byte) module);
+
+    HAL.report(tResourceType.kResourceType_Compressor, module);
+    setName("Compressor", module);
+  }
+
+  /**
+   * Makes a new instance of the compressor using the default PCM ID of 0.
+   *
+   * <p>Additional modules can be supported by making a new instance and {@link #Compressor(int)
+   * specifying the CAN ID.}
+   */
+  public Compressor() {
+    this(SensorUtil.getDefaultSolenoidModule());
+  }
+
+  /**
+   * Start the compressor running in closed loop control mode.
+   *
+   * <p>Use the method in cases where you would like to manually stop and start the compressor for
+   * applications such as conserving battery or making sure that the compressor motor doesn't start
+   * during critical operations.
+   */
+  public void start() {
+    setClosedLoopControl(true);
+  }
+
+  /**
+   * Stop the compressor from running in closed loop control mode.
+   *
+   * <p>Use the method in cases where you would like to manually stop and start the compressor for
+   * applications such as conserving battery or making sure that the compressor motor doesn't start
+   * during critical operations.
+   */
+  public void stop() {
+    setClosedLoopControl(false);
+  }
+
+  /**
+   * Get the status of the compressor.
+   *
+   * @return true if the compressor is on
+   */
+  public boolean enabled() {
+    return CompressorJNI.getCompressor(m_compressorHandle);
+  }
+
+  /**
+   * Get the pressure switch value.
+   *
+   * @return true if the pressure is low
+   */
+  public boolean getPressureSwitchValue() {
+    return CompressorJNI.getCompressorPressureSwitch(m_compressorHandle);
+  }
+
+  /**
+   * Get the current being used by the compressor.
+   *
+   * @return current consumed by the compressor in amps
+   */
+  public double getCompressorCurrent() {
+    return CompressorJNI.getCompressorCurrent(m_compressorHandle);
+  }
+
+  /**
+   * Set the PCM in closed loop control mode.
+   *
+   * @param on if true sets the compressor to be in closed loop control mode (default)
+   */
+  public void setClosedLoopControl(boolean on) {
+    CompressorJNI.setCompressorClosedLoopControl(m_compressorHandle, on);
+  }
+
+  /**
+   * Gets the current operating mode of the PCM.
+   *
+   * @return true if compressor is operating on closed-loop mode
+   */
+  public boolean getClosedLoopControl() {
+    return CompressorJNI.getCompressorClosedLoopControl(m_compressorHandle);
+  }
+
+  /**
+   * If PCM is in fault state : Compressor Drive is disabled due to compressor current being too
+   * high.
+   *
+   * @return true if PCM is in fault state.
+   */
+  public boolean getCompressorCurrentTooHighFault() {
+    return CompressorJNI.getCompressorCurrentTooHighFault(m_compressorHandle);
+  }
+
+  /**
+   * If PCM sticky fault is set : Compressor is disabled due to compressor current being too
+   * high.
+   *
+   * @return true if PCM sticky fault is set.
+   */
+  public boolean getCompressorCurrentTooHighStickyFault() {
+    return CompressorJNI.getCompressorCurrentTooHighStickyFault(m_compressorHandle);
+  }
+
+  /**
+   * If PCM sticky fault is set : Compressor output appears to be shorted.
+   *
+   * @return true if PCM sticky fault is set.
+   */
+  public boolean getCompressorShortedStickyFault() {
+    return CompressorJNI.getCompressorShortedStickyFault(m_compressorHandle);
+  }
+
+  /**
+   * If PCM is in fault state : Compressor output appears to be shorted.
+   *
+   * @return true if PCM is in fault state.
+   */
+  public boolean getCompressorShortedFault() {
+    return CompressorJNI.getCompressorShortedFault(m_compressorHandle);
+  }
+
+  /**
+   * If PCM sticky fault is set : Compressor does not appear to be wired, i.e. compressor is not
+   * drawing enough current.
+   *
+   * @return true if PCM sticky fault is set.
+   */
+  public boolean getCompressorNotConnectedStickyFault() {
+    return CompressorJNI.getCompressorNotConnectedStickyFault(m_compressorHandle);
+  }
+
+  /**
+   * If PCM is in fault state : Compressor does not appear to be wired, i.e. compressor is not
+   * drawing enough current.
+   *
+   * @return true if PCM is in fault state.
+   */
+  public boolean getCompressorNotConnectedFault() {
+    return CompressorJNI.getCompressorNotConnectedFault(m_compressorHandle);
+  }
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * <p>If a sticky fault is set, then it will be persistently cleared. The compressor might
+   * momentarily disable while the flags are being cleared. Doo not call this method too
+   * frequently, otherwise normal compressor functionality may be prevented.
+   *
+   * <p>If no sticky faults are set then this call will have no effect.
+   */
+  public void clearAllPCMStickyFaults() {
+    CompressorJNI.clearAllPCMStickyFaults(m_module);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Compressor");
+    builder.addBooleanProperty("Enabled", this::enabled, value -> {
+      if (value) {
+        start();
+      } else {
+        stop();
+      }
+    });
+    builder.addBooleanProperty("Pressure switch", this::getPressureSwitchValue, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Controller.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Controller.java
new file mode 100644
index 0000000..32fc7c3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Controller.java
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * An interface for controllers. Controllers run control loops, the most command are PID controllers
+ * and there variants, but this includes anything that is controlling an actuator in a separate
+ * thread.
+ */
+public interface Controller {
+  /**
+   * Allows the control loop to run.
+   */
+  void enable();
+
+  /**
+   * Stops the control loop from running until explicitly re-enabled by calling {@link #enable()}.
+   */
+  void disable();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ControllerPower.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ControllerPower.java
new file mode 100644
index 0000000..3a03c60
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/ControllerPower.java
@@ -0,0 +1,163 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.PowerJNI;
+
+/**
+ * Old Controller PR class.
+ * @deprecated Use RobotController class instead
+ */
+@Deprecated
+public final class ControllerPower {
+  /**
+   * Get the input voltage to the robot controller.
+   *
+   * @return The controller input voltage value in Volts
+   */
+  @Deprecated
+  public static double getInputVoltage() {
+    return PowerJNI.getVinVoltage();
+  }
+
+  /**
+   * Get the input current to the robot controller.
+   *
+   * @return The controller input current value in Amps
+   */
+  @Deprecated
+  public static double getInputCurrent() {
+    return PowerJNI.getVinCurrent();
+  }
+
+  /**
+   * Get the voltage of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail voltage value in Volts
+   */
+  @Deprecated
+  public static double getVoltage3V3() {
+    return PowerJNI.getUserVoltage3V3();
+  }
+
+  /**
+   * Get the current output of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail output current value in Volts
+   */
+  @Deprecated
+  public static double getCurrent3V3() {
+    return PowerJNI.getUserCurrent3V3();
+  }
+
+  /**
+   * Get the enabled state of the 3.3V rail. The rail may be disabled due to a controller brownout,
+   * a short circuit on the rail, or controller over-voltage.
+   *
+   * @return The controller 3.3V rail enabled value
+   */
+  @Deprecated
+  public static boolean getEnabled3V3() {
+    return PowerJNI.getUserActive3V3();
+  }
+
+  /**
+   * Get the count of the total current faults on the 3.3V rail since the controller has booted.
+   *
+   * @return The number of faults
+   */
+  @Deprecated
+  public static int getFaultCount3V3() {
+    return PowerJNI.getUserCurrentFaults3V3();
+  }
+
+  /**
+   * Get the voltage of the 5V rail.
+   *
+   * @return The controller 5V rail voltage value in Volts
+   */
+  @Deprecated
+  public static double getVoltage5V() {
+    return PowerJNI.getUserVoltage5V();
+  }
+
+  /**
+   * Get the current output of the 5V rail.
+   *
+   * @return The controller 5V rail output current value in Amps
+   */
+  @Deprecated
+  public static double getCurrent5V() {
+    return PowerJNI.getUserCurrent5V();
+  }
+
+  /**
+   * Get the enabled state of the 5V rail. The rail may be disabled due to a controller brownout, a
+   * short circuit on the rail, or controller over-voltage.
+   *
+   * @return The controller 5V rail enabled value
+   */
+  @Deprecated
+  public static boolean getEnabled5V() {
+    return PowerJNI.getUserActive5V();
+  }
+
+  /**
+   * Get the count of the total current faults on the 5V rail since the controller has booted.
+   *
+   * @return The number of faults
+   */
+  @Deprecated
+  public static int getFaultCount5V() {
+    return PowerJNI.getUserCurrentFaults5V();
+  }
+
+  /**
+   * Get the voltage of the 6V rail.
+   *
+   * @return The controller 6V rail voltage value in Volts
+   */
+  @Deprecated
+  public static double getVoltage6V() {
+    return PowerJNI.getUserVoltage6V();
+  }
+
+  /**
+   * Get the current output of the 6V rail.
+   *
+   * @return The controller 6V rail output current value in Amps
+   */
+  @Deprecated
+  public static double getCurrent6V() {
+    return PowerJNI.getUserCurrent6V();
+  }
+
+  /**
+   * Get the enabled state of the 6V rail. The rail may be disabled due to a controller brownout, a
+   * short circuit on the rail, or controller over-voltage.
+   *
+   * @return The controller 6V rail enabled value
+   */
+  @Deprecated
+  public static boolean getEnabled6V() {
+    return PowerJNI.getUserActive6V();
+  }
+
+  /**
+   * Get the count of the total current faults on the 6V rail since the controller has booted.
+   *
+   * @return The number of faults
+   */
+  @Deprecated
+  public static int getFaultCount6V() {
+    return PowerJNI.getUserCurrentFaults6V();
+  }
+
+  private ControllerPower() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java
new file mode 100644
index 0000000..dca332a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Counter.java
@@ -0,0 +1,563 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+
+import edu.wpi.first.hal.CounterJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Class for counting the number of ticks on a digital input channel.
+ *
+ * <p>This is a general purpose class for counting repetitive events. It can return the number of
+ * counts, the period of the most recent cycle, and detect when the signal being counted has
+ * stopped by supplying a maximum cycle time.
+ *
+ * <p>All counters will immediately start counting - reset() them if you need them to be zeroed
+ * before use.
+ */
+public class Counter extends SendableBase implements CounterBase, PIDSource {
+  /**
+   * Mode determines how and what the counter counts.
+   */
+  public enum Mode {
+    /**
+     * mode: two pulse.
+     */
+    kTwoPulse(0),
+    /**
+     * mode: semi period.
+     */
+    kSemiperiod(1),
+    /**
+     * mode: pulse length.
+     */
+    kPulseLength(2),
+    /**
+     * mode: external direction.
+     */
+    kExternalDirection(3);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    Mode(int value) {
+      this.value = value;
+    }
+  }
+
+  protected DigitalSource m_upSource; // /< What makes the counter count up.
+  protected DigitalSource m_downSource; // /< What makes the counter count down.
+  private boolean m_allocatedUpSource;
+  private boolean m_allocatedDownSource;
+  private int m_counter; // /< The FPGA counter object.
+  private int m_index; // /< The index of this counter.
+  private PIDSourceType m_pidSource;
+  private double m_distancePerPulse; // distance of travel for each tick
+
+  /**
+   * Create an instance of a counter with the given mode.
+   */
+  public Counter(final Mode mode) {
+    ByteBuffer index = ByteBuffer.allocateDirect(4);
+    // set the byte order
+    index.order(ByteOrder.LITTLE_ENDIAN);
+    m_counter = CounterJNI.initializeCounter(mode.value, index.asIntBuffer());
+    m_index = index.asIntBuffer().get(0);
+
+    m_allocatedUpSource = false;
+    m_allocatedDownSource = false;
+    m_upSource = null;
+    m_downSource = null;
+
+    setMaxPeriod(.5);
+
+    HAL.report(tResourceType.kResourceType_Counter, m_index, mode.value);
+    setName("Counter", m_index);
+  }
+
+  /**
+   * Create an instance of a counter where no sources are selected. Then they all must be selected
+   * by calling functions to specify the upsource and the downsource independently.
+   *
+   * <p>The counter will start counting immediately.
+   */
+  public Counter() {
+    this(Mode.kTwoPulse);
+  }
+
+  /**
+   * Create an instance of a counter from a Digital Input. This is used if an existing digital input
+   * is to be shared by multiple other objects such as encoders or if the Digital Source is not a
+   * DIO channel (such as an Analog Trigger)
+   *
+   * <p>The counter will start counting immediately.
+   *
+   * @param source the digital source to count
+   */
+  public Counter(DigitalSource source) {
+    this();
+
+    requireNonNull(source, "Digital Source given was null");
+    setUpSource(source);
+  }
+
+  /**
+   * Create an instance of a Counter object. Create an up-Counter instance given a channel.
+   *
+   * <p>The counter will start counting immediately.
+   *
+   * @param channel the DIO channel to use as the up source. 0-9 are on-board, 10-25 are on the MXP
+   */
+  public Counter(int channel) {
+    this();
+    setUpSource(channel);
+  }
+
+  /**
+   * Create an instance of a Counter object. Create an instance of a simple up-Counter given an
+   * analog trigger. Use the trigger state output from the analog trigger.
+   *
+   * <p>The counter will start counting immediately.
+   *
+   * @param encodingType which edges to count
+   * @param upSource     first source to count
+   * @param downSource   second source for direction
+   * @param inverted     true to invert the count
+   */
+  public Counter(EncodingType encodingType, DigitalSource upSource, DigitalSource downSource,
+                 boolean inverted) {
+    this(Mode.kExternalDirection);
+
+    requireNonNull(encodingType, "Encoding type given was null");
+    requireNonNull(upSource, "Up Source given was null");
+    requireNonNull(downSource, "Down Source given was null");
+
+    if (encodingType != EncodingType.k1X && encodingType != EncodingType.k2X) {
+      throw new IllegalArgumentException("Counters only support 1X and 2X quadrature decoding!");
+    }
+
+    setUpSource(upSource);
+    setDownSource(downSource);
+
+    if (encodingType == EncodingType.k1X) {
+      setUpSourceEdge(true, false);
+      CounterJNI.setCounterAverageSize(m_counter, 1);
+    } else {
+      setUpSourceEdge(true, true);
+      CounterJNI.setCounterAverageSize(m_counter, 2);
+    }
+
+    setDownSourceEdge(inverted, true);
+  }
+
+  /**
+   * Create an instance of a Counter object. Create an instance of a simple up-Counter given an
+   * analog trigger. Use the trigger state output from the analog trigger.
+   *
+   * <p>The counter will start counting immediately.
+   *
+   * @param trigger the analog trigger to count
+   */
+  public Counter(AnalogTrigger trigger) {
+    this();
+
+    requireNonNull(trigger, "The Analog Trigger given was null");
+
+    setUpSource(trigger.createOutput(AnalogTriggerType.kState));
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    setUpdateWhenEmpty(true);
+
+    clearUpSource();
+    clearDownSource();
+
+    CounterJNI.freeCounter(m_counter);
+
+    m_upSource = null;
+    m_downSource = null;
+    m_counter = 0;
+  }
+
+  /**
+   * The counter's FPGA index.
+   *
+   * @return the Counter's FPGA index
+   */
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public int getFPGAIndex() {
+    return m_index;
+  }
+
+  /**
+   * Set the upsource for the counter as a digital input channel.
+   *
+   * @param channel the DIO channel to count 0-9 are on-board, 10-25 are on the MXP
+   */
+  public void setUpSource(int channel) {
+    setUpSource(new DigitalInput(channel));
+    m_allocatedUpSource = true;
+    addChild(m_upSource);
+  }
+
+  /**
+   * Set the source object that causes the counter to count up. Set the up counting DigitalSource.
+   *
+   * @param source the digital source to count
+   */
+  public void setUpSource(DigitalSource source) {
+    if (m_upSource != null && m_allocatedUpSource) {
+      m_upSource.close();
+      m_allocatedUpSource = false;
+    }
+    m_upSource = source;
+    CounterJNI.setCounterUpSource(m_counter, source.getPortHandleForRouting(),
+        source.getAnalogTriggerTypeForRouting());
+  }
+
+  /**
+   * Set the up counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Up Source
+   * @param triggerType   The analog trigger output that will trigger the counter.
+   */
+  public void setUpSource(AnalogTrigger analogTrigger, AnalogTriggerType triggerType) {
+    requireNonNull(analogTrigger, "Analog Trigger given was null");
+    requireNonNull(triggerType, "Analog Trigger Type given was null");
+
+    setUpSource(analogTrigger.createOutput(triggerType));
+    m_allocatedUpSource = true;
+  }
+
+  /**
+   * Set the edge sensitivity on an up counting source. Set the up source to either detect rising
+   * edges or falling edges.
+   *
+   * @param risingEdge  true to count rising edge
+   * @param fallingEdge true to count falling edge
+   */
+  public void setUpSourceEdge(boolean risingEdge, boolean fallingEdge) {
+    if (m_upSource == null) {
+      throw new IllegalStateException("Up Source must be set before setting the edge!");
+    }
+    CounterJNI.setCounterUpSourceEdge(m_counter, risingEdge, fallingEdge);
+  }
+
+  /**
+   * Disable the up counting source to the counter.
+   */
+  public void clearUpSource() {
+    if (m_upSource != null && m_allocatedUpSource) {
+      m_upSource.close();
+      m_allocatedUpSource = false;
+    }
+    m_upSource = null;
+
+    CounterJNI.clearCounterUpSource(m_counter);
+  }
+
+  /**
+   * Set the down counting source to be a digital input channel.
+   *
+   * @param channel the DIO channel to count 0-9 are on-board, 10-25 are on the MXP
+   */
+  public void setDownSource(int channel) {
+    setDownSource(new DigitalInput(channel));
+    m_allocatedDownSource = true;
+    addChild(m_downSource);
+  }
+
+  /**
+   * Set the source object that causes the counter to count down. Set the down counting
+   * DigitalSource.
+   *
+   * @param source the digital source to count
+   */
+  public void setDownSource(DigitalSource source) {
+    requireNonNull(source, "The Digital Source given was null");
+
+    if (m_downSource != null && m_allocatedDownSource) {
+      m_downSource.close();
+      m_allocatedDownSource = false;
+    }
+    CounterJNI.setCounterDownSource(m_counter, source.getPortHandleForRouting(),
+        source.getAnalogTriggerTypeForRouting());
+    m_downSource = source;
+  }
+
+  /**
+   * Set the down counting source to be an analog trigger.
+   *
+   * @param analogTrigger The analog trigger object that is used for the Down Source
+   * @param triggerType   The analog trigger output that will trigger the counter.
+   */
+  public void setDownSource(AnalogTrigger analogTrigger, AnalogTriggerType triggerType) {
+    requireNonNull(analogTrigger, "Analog Trigger given was null");
+    requireNonNull(triggerType, "Analog Trigger Type given was null");
+
+    setDownSource(analogTrigger.createOutput(triggerType));
+    m_allocatedDownSource = true;
+  }
+
+  /**
+   * Set the edge sensitivity on a down counting source. Set the down source to either detect rising
+   * edges or falling edges.
+   *
+   * @param risingEdge  true to count the rising edge
+   * @param fallingEdge true to count the falling edge
+   */
+  public void setDownSourceEdge(boolean risingEdge, boolean fallingEdge) {
+    requireNonNull(m_downSource, "Down Source must be set before setting the edge!");
+
+    CounterJNI.setCounterDownSourceEdge(m_counter, risingEdge, fallingEdge);
+  }
+
+  /**
+   * Disable the down counting source to the counter.
+   */
+  public void clearDownSource() {
+    if (m_downSource != null && m_allocatedDownSource) {
+      m_downSource.close();
+      m_allocatedDownSource = false;
+    }
+    m_downSource = null;
+
+    CounterJNI.clearCounterDownSource(m_counter);
+  }
+
+  /**
+   * Set standard up / down counting mode on this counter. Up and down counts are sourced
+   * independently from two inputs.
+   */
+  public void setUpDownCounterMode() {
+    CounterJNI.setCounterUpDownMode(m_counter);
+  }
+
+  /**
+   * Set external direction mode on this counter. Counts are sourced on the Up counter input. The
+   * Down counter input represents the direction to count.
+   */
+  public void setExternalDirectionMode() {
+    CounterJNI.setCounterExternalDirectionMode(m_counter);
+  }
+
+  /**
+   * Set Semi-period mode on this counter. Counts up on both rising and falling edges.
+   *
+   * @param highSemiPeriod true to count up on both rising and falling
+   */
+  public void setSemiPeriodMode(boolean highSemiPeriod) {
+    CounterJNI.setCounterSemiPeriodMode(m_counter, highSemiPeriod);
+  }
+
+  /**
+   * Configure the counter to count in up or down based on the length of the input pulse. This mode
+   * is most useful for direction sensitive gear tooth sensors.
+   *
+   * @param threshold The pulse length beyond which the counter counts the opposite direction. Units
+   *                  are seconds.
+   */
+  public void setPulseLengthMode(double threshold) {
+    CounterJNI.setCounterPulseLengthMode(m_counter, threshold);
+  }
+
+  /**
+   * Read the current counter value. Read the value at this instant. It may still be running, so it
+   * reflects the current value. Next time it is read, it might have a different value.
+   */
+  @Override
+  public int get() {
+    return CounterJNI.getCounter(m_counter);
+  }
+
+  /**
+   * Read the current scaled counter value. Read the value at this instant, scaled by the distance
+   * per pulse (defaults to 1).
+   *
+   * @return The distance since the last reset
+   */
+  public double getDistance() {
+    return get() * m_distancePerPulse;
+  }
+
+  /**
+   * Reset the Counter to zero. Set the counter value to zero. This doesn't effect the running state
+   * of the counter, just sets the current value to zero.
+   */
+  @Override
+  public void reset() {
+    CounterJNI.resetCounter(m_counter);
+  }
+
+  /**
+   * Set the maximum period where the device is still considered "moving". Sets the maximum period
+   * where the device is considered moving. This value is used to determine the "stopped" state of
+   * the counter using the GetStopped method.
+   *
+   * @param maxPeriod The maximum period where the counted device is considered moving in seconds.
+   */
+  @Override
+  public void setMaxPeriod(double maxPeriod) {
+    CounterJNI.setCounterMaxPeriod(m_counter, maxPeriod);
+  }
+
+  /**
+   * Select whether you want to continue updating the event timer output when there are no samples
+   * captured. The output of the event timer has a buffer of periods that are averaged and posted to
+   * a register on the FPGA. When the timer detects that the event source has stopped (based on the
+   * MaxPeriod) the buffer of samples to be averaged is emptied. If you enable the update when
+   * empty, you will be notified of the stopped source and the event time will report 0 samples. If
+   * you disable update when empty, the most recent average will remain on the output until a new
+   * sample is acquired. You will never see 0 samples output (except when there have been no events
+   * since an FPGA reset) and you will likely not see the stopped bit become true (since it is
+   * updated at the end of an average and there are no samples to average).
+   *
+   * @param enabled true to continue updating
+   */
+  public void setUpdateWhenEmpty(boolean enabled) {
+    CounterJNI.setCounterUpdateWhenEmpty(m_counter, enabled);
+  }
+
+  /**
+   * Determine if the clock is stopped. Determine if the clocked input is stopped based on the
+   * MaxPeriod value set using the SetMaxPeriod method. If the clock exceeds the MaxPeriod, then the
+   * device (and counter) are assumed to be stopped and it returns true.
+   *
+   * @return true if the most recent counter period exceeds the MaxPeriod value set by SetMaxPeriod.
+   */
+  @Override
+  public boolean getStopped() {
+    return CounterJNI.getCounterStopped(m_counter);
+  }
+
+  /**
+   * The last direction the counter value changed.
+   *
+   * @return The last direction the counter value changed.
+   */
+  @Override
+  public boolean getDirection() {
+    return CounterJNI.getCounterDirection(m_counter);
+  }
+
+  /**
+   * Set the Counter to return reversed sensing on the direction. This allows counters to change the
+   * direction they are counting in the case of 1X and 2X quadrature encoding only. Any other
+   * counter mode isn't supported.
+   *
+   * @param reverseDirection true if the value counted should be negated.
+   */
+  public void setReverseDirection(boolean reverseDirection) {
+    CounterJNI.setCounterReverseDirection(m_counter, reverseDirection);
+  }
+
+  /**
+   * Get the Period of the most recent count. Returns the time interval of the most recent count.
+   * This can be used for velocity calculations to determine shaft speed.
+   *
+   * @return The period of the last two pulses in units of seconds.
+   */
+  @Override
+  public double getPeriod() {
+    return CounterJNI.getCounterPeriod(m_counter);
+  }
+
+  /**
+   * Get the current rate of the Counter. Read the current rate of the counter accounting for the
+   * distance per pulse value. The default value for distance per pulse (1) yields units of pulses
+   * per second.
+   *
+   * @return The rate in units/sec
+   */
+  public double getRate() {
+    return m_distancePerPulse / getPeriod();
+  }
+
+  /**
+   * Set the Samples to Average which specifies the number of samples of the timer to average when
+   * calculating the period. Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @param samplesToAverage The number of samples to average from 1 to 127.
+   */
+  public void setSamplesToAverage(int samplesToAverage) {
+    CounterJNI.setCounterSamplesToAverage(m_counter, samplesToAverage);
+  }
+
+  /**
+   * Get the Samples to Average which specifies the number of samples of the timer to average when
+   * calculating the period. Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
+   */
+  public int getSamplesToAverage() {
+    return CounterJNI.getCounterSamplesToAverage(m_counter);
+  }
+
+  /**
+   * Set the distance per pulse for this counter. This sets the multiplier used to determine the
+   * distance driven based on the count value from the encoder. Set this value based on the Pulses
+   * per Revolution and factor in any gearing reductions. This distance can be in any units you
+   * like, linear or angular.
+   *
+   * @param distancePerPulse The scale factor that will be used to convert pulses to useful units.
+   */
+  public void setDistancePerPulse(double distancePerPulse) {
+    m_distancePerPulse = distancePerPulse;
+  }
+
+  /**
+   * Set which parameter of the encoder you are using as a process control variable. The counter
+   * class supports the rate and distance parameters.
+   *
+   * @param pidSource An enum to select the parameter.
+   */
+  @Override
+  public void setPIDSourceType(PIDSourceType pidSource) {
+    requireNonNull(pidSource, "PID Source Parameter given was null");
+    if (pidSource != PIDSourceType.kDisplacement && pidSource != PIDSourceType.kRate) {
+      throw new IllegalArgumentException("PID Source parameter was not valid type: " + pidSource);
+    }
+
+    m_pidSource = pidSource;
+  }
+
+  @Override
+  public PIDSourceType getPIDSourceType() {
+    return m_pidSource;
+  }
+
+  @Override
+  public double pidGet() {
+    switch (m_pidSource) {
+      case kDisplacement:
+        return getDistance();
+      case kRate:
+        return getRate();
+      default:
+        return 0.0;
+    }
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Counter");
+    builder.addDoubleProperty("Value", this::get, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CounterBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CounterBase.java
new file mode 100644
index 0000000..9d1d6b7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/CounterBase.java
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * Interface for counting the number of ticks on a digital input channel. Encoders, Gear tooth
+ * sensors, and counters should all subclass this so it can be used to build more advanced classes
+ * for control and driving.
+ *
+ * <p>All counters will immediately start counting - reset() them if you need them to be zeroed
+ * before use.
+ */
+public interface CounterBase {
+  /**
+   * The number of edges for the counterbase to increment or decrement on.
+   */
+  enum EncodingType {
+    /**
+     * Count only the rising edge.
+     */
+    k1X(0),
+    /**
+     * Count both the rising and falling edge.
+     */
+    k2X(1),
+    /**
+     * Count rising and falling on both channels.
+     */
+    k4X(2);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    EncodingType(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Get the count.
+   *
+   * @return the count
+   */
+  int get();
+
+  /**
+   * Reset the count to zero.
+   */
+  void reset();
+
+  /**
+   * Get the time between the last two edges counted.
+   *
+   * @return the time between the last two ticks in seconds
+   */
+  double getPeriod();
+
+  /**
+   * Set the maximum time between edges to be considered stalled.
+   *
+   * @param maxPeriod the maximum period in seconds
+   */
+  void setMaxPeriod(double maxPeriod);
+
+  /**
+   * Determine if the counter is not moving.
+   *
+   * @return true if the counter has not changed for the max period
+   */
+  boolean getStopped();
+
+  /**
+   * Determine which direction the counter is going.
+   *
+   * @return true for one direction, false for the other
+   */
+  boolean getDirection();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMC60.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMC60.java
new file mode 100644
index 0000000..c2f4c9c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DMC60.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * Digilent DMC 60 Speed Controller.
+ */
+public class DMC60 extends PWMSpeedController {
+  /**
+   * Constructor.
+   *
+   * <p>Note that the DMC uses the following bounds for PWM values. These values should work
+   * reasonably well for most controllers, but if users experience issues such as asymmetric
+   * behavior around the deadband or inability to saturate the controller in either direction,
+   * calibration is recommended. The calibration procedure can be found in the DMC 60 User Manual
+   * available from Digilent
+   *
+   * <p>- 2.004ms = full "forward" - 1.52ms = the "high end" of the deadband range - 1.50ms =
+   * center of the deadband range (off) - 1.48ms = the "low end" of the deadband range - .997ms =
+   * full "reverse"
+   *
+   * @param channel The PWM channel that the DMC60 is attached to. 0-9 are
+   *        on-board, 10-19 are on the MXP port
+   */
+  public DMC60(final int channel) {
+    super(channel);
+
+    setBounds(2.004, 1.52, 1.50, 1.48, .997);
+    setPeriodMultiplier(PeriodMultiplier.k1X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_DigilentDMC60, getChannel());
+    setName("DMC60", getChannel());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java
new file mode 100644
index 0000000..ad92f48
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilter.java
@@ -0,0 +1,181 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.concurrent.locks.Lock;
+import java.util.concurrent.locks.ReentrantLock;
+
+import edu.wpi.first.hal.DigitalGlitchFilterJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Class to enable glitch filtering on a set of digital inputs. This class will manage adding and
+ * removing digital inputs from a FPGA glitch filter. The filter lets the user configure the time
+ * that an input must remain high or low before it is classified as high or low.
+ */
+public class DigitalGlitchFilter extends SendableBase {
+  /**
+   * Configures the Digital Glitch Filter to its default settings.
+   */
+  public DigitalGlitchFilter() {
+    synchronized (m_mutex) {
+      int index = 0;
+      while (m_filterAllocated[index] && index < m_filterAllocated.length) {
+        index++;
+      }
+      if (index != m_filterAllocated.length) {
+        m_channelIndex = index;
+        m_filterAllocated[index] = true;
+        HAL.report(tResourceType.kResourceType_DigitalGlitchFilter,
+            m_channelIndex, 0);
+        setName("DigitalGlitchFilter", index);
+      }
+    }
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    if (m_channelIndex >= 0) {
+      synchronized (m_mutex) {
+        m_filterAllocated[m_channelIndex] = false;
+      }
+      m_channelIndex = -1;
+    }
+  }
+
+  private static void setFilter(DigitalSource input, int channelIndex) {
+    if (input != null) { // Counter might have just one input
+      // analog triggers are not supported for DigitalGlitchFilters
+      if (input.isAnalogTrigger()) {
+        throw new IllegalStateException("Analog Triggers not supported for DigitalGlitchFilters");
+      }
+      DigitalGlitchFilterJNI.setFilterSelect(input.getPortHandleForRouting(), channelIndex);
+
+      int selected = DigitalGlitchFilterJNI.getFilterSelect(input.getPortHandleForRouting());
+      if (selected != channelIndex) {
+        throw new IllegalStateException("DigitalGlitchFilterJNI.setFilterSelect("
+            + channelIndex + ") failed -> " + selected);
+      }
+    }
+  }
+
+  /**
+   * Assigns the DigitalSource to this glitch filter.
+   *
+   * @param input The DigitalSource to add.
+   */
+  public void add(DigitalSource input) {
+    setFilter(input, m_channelIndex + 1);
+  }
+
+  /**
+   * Assigns the Encoder to this glitch filter.
+   *
+   * @param input The Encoder to add.
+   */
+  public void add(Encoder input) {
+    add(input.m_aSource);
+    add(input.m_bSource);
+  }
+
+  /**
+   * Assigns the Counter to this glitch filter.
+   *
+   * @param input The Counter to add.
+   */
+  public void add(Counter input) {
+    add(input.m_upSource);
+    add(input.m_downSource);
+  }
+
+  /**
+   * Removes this filter from the given digital input.
+   *
+   * @param input The DigitalSource to stop filtering.
+   */
+  public void remove(DigitalSource input) {
+    setFilter(input, 0);
+  }
+
+  /**
+   * Removes this filter from the given Encoder.
+   *
+   * @param input the Encoder to stop filtering.
+   */
+  public void remove(Encoder input) {
+    remove(input.m_aSource);
+    remove(input.m_bSource);
+  }
+
+  /**
+   * Removes this filter from the given Counter.
+   *
+   * @param input The Counter to stop filtering.
+   */
+  public void remove(Counter input) {
+    remove(input.m_upSource);
+    remove(input.m_downSource);
+  }
+
+  /**
+   * Sets the number of FPGA cycles that the input must hold steady to pass through this glitch
+   * filter.
+   *
+   * @param fpgaCycles The number of FPGA cycles.
+   */
+  public void setPeriodCycles(int fpgaCycles) {
+    DigitalGlitchFilterJNI.setFilterPeriod(m_channelIndex, fpgaCycles);
+  }
+
+  /**
+   * Sets the number of nanoseconds that the input must hold steady to pass through this glitch
+   * filter.
+   *
+   * @param nanoseconds The number of nanoseconds.
+   */
+  public void setPeriodNanoSeconds(long nanoseconds) {
+    int fpgaCycles = (int) (nanoseconds * SensorUtil.kSystemClockTicksPerMicrosecond / 4
+        / 1000);
+    setPeriodCycles(fpgaCycles);
+  }
+
+  /**
+   * Gets the number of FPGA cycles that the input must hold steady to pass through this glitch
+   * filter.
+   *
+   * @return The number of cycles.
+   */
+  public int getPeriodCycles() {
+    return DigitalGlitchFilterJNI.getFilterPeriod(m_channelIndex);
+  }
+
+  /**
+   * Gets the number of nanoseconds that the input must hold steady to pass through this glitch
+   * filter.
+   *
+   * @return The number of nanoseconds.
+   */
+  public long getPeriodNanoSeconds() {
+    int fpgaCycles = getPeriodCycles();
+
+    return (long) fpgaCycles * 1000L
+        / (long) (SensorUtil.kSystemClockTicksPerMicrosecond / 4);
+  }
+
+  @Override
+  @SuppressWarnings("PMD.UnusedFormalParameter")
+  public void initSendable(SendableBuilder builder) {
+  }
+
+  private int m_channelIndex = -1;
+  private static final Lock m_mutex = new ReentrantLock(true);
+  private static final boolean[] m_filterAllocated = new boolean[3];
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java
new file mode 100644
index 0000000..03a0f21
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalInput.java
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.DIOJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Class to read a digital input. This class will read digital inputs and return the current value
+ * on the channel. Other devices such as encoders, gear tooth sensors, etc. that are implemented
+ * elsewhere will automatically allocate digital inputs and outputs as required. This class is only
+ * for devices like switches etc. that aren't implemented anywhere else.
+ */
+public class DigitalInput extends DigitalSource {
+  private final int m_channel;
+  private int m_handle;
+
+  /**
+   * Create an instance of a Digital Input class. Creates a digital input given a channel.
+   *
+   * @param channel the DIO channel for the digital input 0-9 are on-board, 10-25 are on the MXP
+   */
+  public DigitalInput(int channel) {
+    SensorUtil.checkDigitalChannel(channel);
+    m_channel = channel;
+
+    m_handle = DIOJNI.initializeDIOPort(HAL.getPort((byte) channel), true);
+
+    HAL.report(tResourceType.kResourceType_DigitalInput, channel);
+    setName("DigitalInput", channel);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    if (m_interrupt != 0) {
+      cancelInterrupts();
+    }
+    DIOJNI.freeDIOPort(m_handle);
+    m_handle = 0;
+  }
+
+  /**
+   * Get the value from a digital input channel. Retrieve the value of a single digital input
+   * channel from the FPGA.
+   *
+   * @return the status of the digital input
+   */
+  public boolean get() {
+    return DIOJNI.getDIO(m_handle);
+  }
+
+  /**
+   * Get the channel of the digital input.
+   *
+   * @return The GPIO channel number that this object represents.
+   */
+  @Override
+  public int getChannel() {
+    return m_channel;
+  }
+
+  /**
+   * Get the analog trigger type.
+   *
+   * @return false
+   */
+  @Override
+  public int getAnalogTriggerTypeForRouting() {
+    return 0;
+  }
+
+  /**
+   * Is this an analog trigger.
+   *
+   * @return true if this is an analog trigger
+   */
+  @Override
+  public boolean isAnalogTrigger() {
+    return false;
+  }
+
+  /**
+   * Get the HAL Port Handle.
+   *
+   * @return The HAL Handle to the specified source.
+   */
+  @Override
+  public int getPortHandleForRouting() {
+    return m_handle;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Digital Input");
+    builder.addBooleanProperty("Value", this::get, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java
new file mode 100644
index 0000000..f375ccb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalOutput.java
@@ -0,0 +1,169 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.DIOJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Class to write digital outputs. This class will write digital outputs. Other devices that are
+ * implemented elsewhere will automatically allocate digital inputs and outputs as required.
+ */
+public class DigitalOutput extends SendableBase {
+  private static final int invalidPwmGenerator = 0;
+  private int m_pwmGenerator = invalidPwmGenerator;
+
+  private final int m_channel;
+  private int m_handle;
+
+  /**
+   * Create an instance of a digital output. Create an instance of a digital output given a
+   * channel.
+   *
+   * @param channel the DIO channel to use for the digital output. 0-9 are on-board, 10-25 are on
+   *                the MXP
+   */
+  public DigitalOutput(int channel) {
+    SensorUtil.checkDigitalChannel(channel);
+    m_channel = channel;
+
+    m_handle = DIOJNI.initializeDIOPort(HAL.getPort((byte) channel), false);
+
+    HAL.report(tResourceType.kResourceType_DigitalOutput, channel);
+    setName("DigitalOutput", channel);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    // Disable the pwm only if we have allocated it
+    if (m_pwmGenerator != invalidPwmGenerator) {
+      disablePWM();
+    }
+    DIOJNI.freeDIOPort(m_handle);
+    m_handle = 0;
+  }
+
+  /**
+   * Set the value of a digital output.
+   *
+   * @param value true is on, off is false
+   */
+  public void set(boolean value) {
+    DIOJNI.setDIO(m_handle, (short) (value ? 1 : 0));
+  }
+
+  /**
+   * Gets the value being output from the Digital Output.
+   *
+   * @return the state of the digital output.
+   */
+  public boolean get() {
+    return DIOJNI.getDIO(m_handle);
+  }
+
+  /**
+   * Get the GPIO channel number that this object represents.
+   *
+   * @return The GPIO channel number.
+   */
+  public int getChannel() {
+    return m_channel;
+  }
+
+  /**
+   * Generate a single pulse. There can only be a single pulse going at any time.
+   *
+   * @param pulseLength The length of the pulse.
+   */
+  public void pulse(final double pulseLength) {
+    DIOJNI.pulse(m_handle, pulseLength);
+  }
+
+  /**
+   * Determine if the pulse is still going. Determine if a previously started pulse is still going.
+   *
+   * @return true if pulsing
+   */
+  public boolean isPulsing() {
+    return DIOJNI.isPulsing(m_handle);
+  }
+
+  /**
+   * Change the PWM frequency of the PWM output on a Digital Output line.
+   *
+   * <p>The valid range is from 0.6 Hz to 19 kHz. The frequency resolution is logarithmic.
+   *
+   * <p>There is only one PWM frequency for all channels.
+   *
+   * @param rate The frequency to output all digital output PWM signals.
+   */
+  public void setPWMRate(double rate) {
+    DIOJNI.setDigitalPWMRate(rate);
+  }
+
+  /**
+   * Enable a PWM Output on this line.
+   *
+   * <p>Allocate one of the 6 DO PWM generator resources.
+   *
+   * <p>Supply the initial duty-cycle to output so as to avoid a glitch when first starting.
+   *
+   * <p>The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less) but is reduced
+   * the higher the frequency of the PWM signal is.
+   *
+   * @param initialDutyCycle The duty-cycle to start generating. [0..1]
+   */
+  public void enablePWM(double initialDutyCycle) {
+    if (m_pwmGenerator != invalidPwmGenerator) {
+      return;
+    }
+    m_pwmGenerator = DIOJNI.allocateDigitalPWM();
+    DIOJNI.setDigitalPWMDutyCycle(m_pwmGenerator, initialDutyCycle);
+    DIOJNI.setDigitalPWMOutputChannel(m_pwmGenerator, m_channel);
+  }
+
+  /**
+   * Change this line from a PWM output back to a static Digital Output line.
+   *
+   * <p>Free up one of the 6 DO PWM generator resources that were in use.
+   */
+  public void disablePWM() {
+    if (m_pwmGenerator == invalidPwmGenerator) {
+      return;
+    }
+    // Disable the output by routing to a dead bit.
+    DIOJNI.setDigitalPWMOutputChannel(m_pwmGenerator, SensorUtil.kDigitalChannels);
+    DIOJNI.freeDigitalPWM(m_pwmGenerator);
+    m_pwmGenerator = invalidPwmGenerator;
+  }
+
+  /**
+   * Change the duty-cycle that is being generated on the line.
+   *
+   * <p>The resolution of the duty cycle is 8-bit for low frequencies (1kHz or less) but is reduced
+   * the
+   * higher the frequency of the PWM signal is.
+   *
+   * @param dutyCycle The duty-cycle to change to. [0..1]
+   */
+  public void updateDutyCycle(double dutyCycle) {
+    if (m_pwmGenerator == invalidPwmGenerator) {
+      return;
+    }
+    DIOJNI.setDigitalPWMDutyCycle(m_pwmGenerator, dutyCycle);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Digital Output");
+    builder.addBooleanProperty("Value", this::get, this::set);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalSource.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalSource.java
new file mode 100644
index 0000000..d31e191
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DigitalSource.java
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * DigitalSource Interface. The DigitalSource represents all the possible inputs for a counter or a
+ * quadrature encoder. The source may be either a digital input or an analog input. If the caller
+ * just provides a channel, then a digital input will be constructed and freed when finished for the
+ * source. The source can either be a digital input or analog trigger but not both.
+ */
+public abstract class DigitalSource extends InterruptableSensorBase {
+  public abstract boolean isAnalogTrigger();
+
+  public abstract int getChannel();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java
new file mode 100644
index 0000000..8cd60ec
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DoubleSolenoid.java
@@ -0,0 +1,181 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.SolenoidJNI;
+import edu.wpi.first.hal.util.UncleanStatusException;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * DoubleSolenoid class for running 2 channels of high voltage Digital Output on the PCM.
+ *
+ * <p>The DoubleSolenoid class is typically used for pneumatics solenoids that have two positions
+ * controlled by two separate channels.
+ */
+public class DoubleSolenoid extends SolenoidBase {
+  /**
+   * Possible values for a DoubleSolenoid.
+   */
+  public enum Value {
+    kOff,
+    kForward,
+    kReverse
+  }
+
+  private byte m_forwardMask; // The mask for the forward channel.
+  private byte m_reverseMask; // The mask for the reverse channel.
+  private int m_forwardHandle;
+  private int m_reverseHandle;
+
+  /**
+   * Constructor. Uses the default PCM ID (defaults to 0).
+   *
+   * @param forwardChannel The forward channel number on the PCM (0..7).
+   * @param reverseChannel The reverse channel number on the PCM (0..7).
+   */
+  public DoubleSolenoid(final int forwardChannel, final int reverseChannel) {
+    this(SensorUtil.getDefaultSolenoidModule(), forwardChannel, reverseChannel);
+  }
+
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber   The module number of the solenoid module to use.
+   * @param forwardChannel The forward channel on the module to control (0..7).
+   * @param reverseChannel The reverse channel on the module to control (0..7).
+   */
+  public DoubleSolenoid(final int moduleNumber, final int forwardChannel,
+                        final int reverseChannel) {
+    super(moduleNumber);
+
+    SensorUtil.checkSolenoidModule(m_moduleNumber);
+    SensorUtil.checkSolenoidChannel(forwardChannel);
+    SensorUtil.checkSolenoidChannel(reverseChannel);
+
+    int portHandle = HAL.getPortWithModule((byte) m_moduleNumber, (byte) forwardChannel);
+    m_forwardHandle = SolenoidJNI.initializeSolenoidPort(portHandle);
+
+    try {
+      portHandle = HAL.getPortWithModule((byte) m_moduleNumber, (byte) reverseChannel);
+      m_reverseHandle = SolenoidJNI.initializeSolenoidPort(portHandle);
+    } catch (UncleanStatusException ex) {
+      // free the forward handle on exception, then rethrow
+      SolenoidJNI.freeSolenoidPort(m_forwardHandle);
+      m_forwardHandle = 0;
+      m_reverseHandle = 0;
+      throw ex;
+    }
+
+    m_forwardMask = (byte) (1 << forwardChannel);
+    m_reverseMask = (byte) (1 << reverseChannel);
+
+    HAL.report(tResourceType.kResourceType_Solenoid, forwardChannel,
+                                   m_moduleNumber);
+    HAL.report(tResourceType.kResourceType_Solenoid, reverseChannel,
+                                   m_moduleNumber);
+    setName("DoubleSolenoid", m_moduleNumber, forwardChannel);
+  }
+
+  @Override
+  public synchronized void close() {
+    super.close();
+    SolenoidJNI.freeSolenoidPort(m_forwardHandle);
+    SolenoidJNI.freeSolenoidPort(m_reverseHandle);
+  }
+
+  /**
+   * Set the value of a solenoid.
+   *
+   * @param value The value to set (Off, Forward, Reverse)
+   */
+  public void set(final Value value) {
+    boolean forward = false;
+    boolean reverse = false;
+
+    switch (value) {
+      case kOff:
+        forward = false;
+        reverse = false;
+        break;
+      case kForward:
+        forward = true;
+        reverse = false;
+        break;
+      case kReverse:
+        forward = false;
+        reverse = true;
+        break;
+      default:
+        throw new AssertionError("Illegal value: " + value);
+
+    }
+
+    SolenoidJNI.setSolenoid(m_forwardHandle, forward);
+    SolenoidJNI.setSolenoid(m_reverseHandle, reverse);
+  }
+
+  /**
+   * Read the current value of the solenoid.
+   *
+   * @return The current value of the solenoid.
+   */
+  public Value get() {
+    boolean valueForward = SolenoidJNI.getSolenoid(m_forwardHandle);
+    boolean valueReverse = SolenoidJNI.getSolenoid(m_reverseHandle);
+
+    if (valueForward) {
+      return Value.kForward;
+    }
+    if (valueReverse) {
+      return Value.kReverse;
+    }
+    return Value.kOff;
+  }
+
+  /**
+   * Check if the forward solenoid is blacklisted. If a solenoid is shorted, it is added to the
+   * blacklist and disabled until power cycle, or until faults are cleared.
+   *
+   * @return If solenoid is disabled due to short.
+   * @see #clearAllPCMStickyFaults()
+   */
+  public boolean isFwdSolenoidBlackListed() {
+    int blackList = getPCMSolenoidBlackList();
+    return (blackList & m_forwardMask) != 0;
+  }
+
+  /**
+   * Check if the reverse solenoid is blacklisted. If a solenoid is shorted, it is added to the
+   * blacklist and disabled until power cycle, or until faults are cleared.
+   *
+   * @return If solenoid is disabled due to short.
+   * @see #clearAllPCMStickyFaults()
+   */
+  public boolean isRevSolenoidBlackListed() {
+    int blackList = getPCMSolenoidBlackList();
+    return (blackList & m_reverseMask) != 0;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Double Solenoid");
+    builder.setActuator(true);
+    builder.setSafeState(() -> set(Value.kOff));
+    builder.addStringProperty("Value", () -> get().name().substring(1), value -> {
+      if ("Forward".equals(value)) {
+        set(Value.kForward);
+      } else if ("Reverse".equals(value)) {
+        set(Value.kReverse);
+      } else {
+        set(Value.kOff);
+      }
+    });
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
new file mode 100644
index 0000000..b5c46c9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/DriverStation.java
@@ -0,0 +1,1163 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+import java.util.concurrent.TimeUnit;
+import java.util.concurrent.locks.Condition;
+import java.util.concurrent.locks.Lock;
+import java.util.concurrent.locks.ReentrantLock;
+
+import edu.wpi.first.hal.AllianceStationID;
+import edu.wpi.first.hal.ControlWord;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.MatchInfoData;
+import edu.wpi.first.hal.PowerJNI;
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+/**
+ * Provide access to the network communication data to / from the Driver Station.
+ */
+@SuppressWarnings({"PMD.CyclomaticComplexity", "PMD.ExcessiveClassLength",
+                   "PMD.ExcessivePublicCount", "PMD.GodClass", "PMD.TooManyFields",
+                   "PMD.TooManyMethods"})
+public class DriverStation {
+  /**
+   * Number of Joystick Ports.
+   */
+  public static final int kJoystickPorts = 6;
+
+  private static class HALJoystickButtons {
+    public int m_buttons;
+    public byte m_count;
+  }
+
+  private static class HALJoystickAxes {
+    public float[] m_axes;
+    public short m_count;
+
+    HALJoystickAxes(int count) {
+      m_axes = new float[count];
+    }
+  }
+
+  private static class HALJoystickPOVs {
+    public short[] m_povs;
+    public short m_count;
+
+    HALJoystickPOVs(int count) {
+      m_povs = new short[count];
+    }
+  }
+
+  /**
+   * The robot alliance that the robot is a part of.
+   */
+  public enum Alliance {
+    Red, Blue, Invalid
+  }
+
+  public enum MatchType {
+    None, Practice, Qualification, Elimination
+  }
+
+  private static final double JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL = 1.0;
+  private double m_nextMessageTime;
+
+  private static class DriverStationTask implements Runnable {
+    private final DriverStation m_ds;
+
+    DriverStationTask(DriverStation ds) {
+      m_ds = ds;
+    }
+
+    @Override
+    public void run() {
+      m_ds.run();
+    }
+  } /* DriverStationTask */
+
+  private static class MatchDataSender {
+    @SuppressWarnings("MemberName")
+    NetworkTable table;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry typeMetadata;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry gameSpecificMessage;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry eventName;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry matchNumber;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry replayNumber;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry matchType;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry alliance;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry station;
+    @SuppressWarnings("MemberName")
+    NetworkTableEntry controlWord;
+
+    MatchDataSender() {
+      table = NetworkTableInstance.getDefault().getTable("FMSInfo");
+      typeMetadata = table.getEntry(".type");
+      typeMetadata.forceSetString("FMSInfo");
+      gameSpecificMessage = table.getEntry("GameSpecificMessage");
+      gameSpecificMessage.forceSetString("");
+      eventName = table.getEntry("EventName");
+      eventName.forceSetString("");
+      matchNumber = table.getEntry("MatchNumber");
+      matchNumber.forceSetDouble(0);
+      replayNumber = table.getEntry("ReplayNumber");
+      replayNumber.forceSetDouble(0);
+      matchType = table.getEntry("MatchType");
+      matchType.forceSetDouble(0);
+      alliance = table.getEntry("IsRedAlliance");
+      alliance.forceSetBoolean(true);
+      station = table.getEntry("StationNumber");
+      station.forceSetDouble(1);
+      controlWord = table.getEntry("FMSControlData");
+      controlWord.forceSetDouble(0);
+    }
+  }
+
+  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();
+
+  // 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();
+
+  // Joystick button rising/falling edge flags
+  private int[] m_joystickButtonsPressed = new int[kJoystickPorts];
+  private int[] m_joystickButtonsReleased = new int[kJoystickPorts];
+
+  // preallocated byte buffer for button count
+  private final ByteBuffer m_buttonCountBuffer = ByteBuffer.allocateDirect(1);
+
+  private final MatchDataSender m_matchDataSender;
+
+  // Internal Driver Station thread
+  @SuppressWarnings("PMD.SingularField")
+  private final Thread m_thread;
+  private volatile boolean m_threadKeepAlive = true;
+
+  private final ReentrantLock m_cacheDataMutex = new ReentrantLock();
+
+  private final Lock m_waitForDataMutex;
+  private final Condition m_waitForDataCond;
+  private int m_waitForDataCount;
+
+  // Robot state status variables
+  private boolean m_userInDisabled;
+  private boolean m_userInAutonomous;
+  private boolean m_userInTeleop;
+  private boolean m_userInTest;
+
+  // Control word variables
+  private final Object m_controlWordMutex;
+  private final ControlWord m_controlWordCache;
+  private long m_lastControlWordUpdate;
+
+  /**
+   * Gets an instance of the DriverStation.
+   *
+   * @return The DriverStation.
+   */
+  public static DriverStation getInstance() {
+    return DriverStation.instance;
+  }
+
+  /**
+   * DriverStation constructor.
+   *
+   * <p>The single DriverStation instance is created statically with the instance static member
+   * variable.
+   */
+  @SuppressWarnings("PMD.AvoidInstantiatingObjectsInLoops")
+  private DriverStation() {
+    HAL.initialize(500, 0);
+    m_waitForDataCount = 0;
+    m_waitForDataMutex = new ReentrantLock();
+    m_waitForDataCond = m_waitForDataMutex.newCondition();
+
+    for (int i = 0; i < kJoystickPorts; i++) {
+      m_joystickButtons[i] = new HALJoystickButtons();
+      m_joystickAxes[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes);
+      m_joystickPOVs[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs);
+
+      m_joystickButtonsCache[i] = new HALJoystickButtons();
+      m_joystickAxesCache[i] = new HALJoystickAxes(HAL.kMaxJoystickAxes);
+      m_joystickPOVsCache[i] = new HALJoystickPOVs(HAL.kMaxJoystickPOVs);
+    }
+
+    m_controlWordMutex = new Object();
+    m_controlWordCache = new ControlWord();
+    m_lastControlWordUpdate = 0;
+
+    m_matchDataSender = new MatchDataSender();
+
+    m_thread = new Thread(new DriverStationTask(this), "FRCDriverStation");
+    m_thread.setPriority((Thread.NORM_PRIORITY + Thread.MAX_PRIORITY) / 2);
+
+    m_thread.start();
+  }
+
+  /**
+   * Kill the thread.
+   */
+  public void release() {
+    m_threadKeepAlive = false;
+  }
+
+  /**
+   * Report error to Driver Station. Optionally appends Stack trace
+   * to error message.
+   *
+   * @param printTrace If true, append stack trace to error string
+   */
+  public static void reportError(String error, boolean printTrace) {
+    reportErrorImpl(true, 1, error, printTrace);
+  }
+
+  /**
+   * Report error to Driver Station. Appends provided stack trace
+   * to error message.
+   *
+   * @param stackTrace The stack trace to append
+   */
+  public static void reportError(String error, StackTraceElement[] stackTrace) {
+    reportErrorImpl(true, 1, error, stackTrace);
+  }
+
+  /**
+   * Report warning to Driver Station. Optionally appends Stack
+   * trace to warning message.
+   *
+   * @param printTrace If true, append stack trace to warning string
+   */
+  public static void reportWarning(String error, boolean printTrace) {
+    reportErrorImpl(false, 1, error, printTrace);
+  }
+
+  /**
+   * Report warning to Driver Station. Appends provided stack
+   * trace to warning message.
+   *
+   * @param stackTrace The stack trace to append
+   */
+  public static void reportWarning(String error, StackTraceElement[] stackTrace) {
+    reportErrorImpl(false, 1, error, stackTrace);
+  }
+
+  private static void reportErrorImpl(boolean isError, int code, String error, boolean
+      printTrace) {
+    reportErrorImpl(isError, code, error, printTrace, Thread.currentThread().getStackTrace(), 3);
+  }
+
+  private static void reportErrorImpl(boolean isError, int code, String error,
+      StackTraceElement[] stackTrace) {
+    reportErrorImpl(isError, code, error, true, stackTrace, 0);
+  }
+
+  private static void reportErrorImpl(boolean isError, int code, String error,
+      boolean printTrace, StackTraceElement[] stackTrace, int stackTraceFirst) {
+    String locString;
+    if (stackTrace.length >= stackTraceFirst + 1) {
+      locString = stackTrace[stackTraceFirst].toString();
+    } else {
+      locString = "";
+    }
+    StringBuilder traceString = new StringBuilder("");
+    if (printTrace) {
+      boolean haveLoc = false;
+      for (int i = stackTraceFirst; i < stackTrace.length; i++) {
+        String loc = stackTrace[i].toString();
+        traceString.append("\tat ").append(loc).append('\n');
+        // get first user function
+        if (!haveLoc && !loc.startsWith("edu.wpi.first")) {
+          locString = loc;
+          haveLoc = true;
+        }
+      }
+    }
+    HAL.sendError(isError, code, false, error, locString, traceString.toString(), true);
+  }
+
+  /**
+   * The state of one joystick button. Button indexes begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @param button The button index, beginning at 1.
+   * @return The state of the joystick button.
+   */
+  public 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");
+    }
+    if (button <= 0) {
+      reportJoystickUnpluggedError("Button indexes begin at 1 in WPILib for C++ and Java\n");
+      return false;
+    }
+    m_cacheDataMutex.lock();
+    try {
+      if (button > m_joystickButtons[stick].m_count) {
+        // Unlock early so error printing isn't locked.
+        m_cacheDataMutex.unlock();
+        reportJoystickUnpluggedWarning("Joystick Button " + button + " on port " + stick
+            + " not available, check if controller is plugged in");
+      }
+
+      return (m_joystickButtons[stick].m_buttons & 1 << (button - 1)) != 0;
+    } finally {
+      if (m_cacheDataMutex.isHeldByCurrentThread()) {
+        m_cacheDataMutex.unlock();
+      }
+    }
+  }
+
+  /**
+   * Whether one joystick button was pressed since the last check. Button indexes begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @param button The button index, beginning at 1.
+   * @return Whether the joystick button was pressed since the last check.
+   */
+  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;
+    }
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-3");
+    }
+    boolean error = false;
+    boolean retVal = false;
+    synchronized (m_cacheDataMutex) {
+      if (button > m_joystickButtons[stick].m_count) {
+        error = true;
+        retVal = false;
+      } else {
+        // If button was pressed, clear flag and return true
+        if ((m_joystickButtonsPressed[stick] & 1 << (button - 1)) != 0) {
+          m_joystickButtonsPressed[stick] &= ~(1 << (button - 1));
+          retVal = true;
+        } else {
+          retVal = false;
+        }
+      }
+    }
+    if (error) {
+      reportJoystickUnpluggedWarning("Joystick Button " + button + " on port " + stick
+          + " not available, check if controller is plugged in");
+    }
+    return retVal;
+  }
+
+  /**
+   * Whether one joystick button was released since the last check. Button indexes
+   * begin at 1.
+   *
+   * @param stick  The joystick to read.
+   * @param button The button index, beginning at 1.
+   * @return Whether the joystick button was released since the last check.
+   */
+  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;
+    }
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-3");
+    }
+    boolean error = false;
+    boolean retVal = false;
+    synchronized (m_cacheDataMutex) {
+      if (button > m_joystickButtons[stick].m_count) {
+        error = true;
+        retVal = false;
+      } else {
+        // If button was released, clear flag and return true
+        if ((m_joystickButtonsReleased[stick] & 1 << (button - 1)) != 0) {
+          m_joystickButtonsReleased[stick] &= ~(1 << (button - 1));
+          retVal = true;
+        } else {
+          retVal = false;
+        }
+      }
+    }
+    if (error) {
+      reportJoystickUnpluggedWarning("Joystick Button " + button + " on port " + stick
+          + " not available, check if controller is plugged in");
+    }
+    return retVal;
+  }
+
+  /**
+   * Get the value of the axis on a joystick. This depends on the mapping of the joystick connected
+   * to the specified port.
+   *
+   * @param stick The joystick to read.
+   * @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) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+    if (axis < 0 || axis >= HAL.kMaxJoystickAxes) {
+      throw new IllegalArgumentException("Joystick axis is out of range");
+    }
+
+    m_cacheDataMutex.lock();
+    try {
+      if (axis >= m_joystickAxes[stick].m_count) {
+        // Unlock early so error printing isn't locked.
+        m_cacheDataMutex.unlock();
+        reportJoystickUnpluggedWarning("Joystick axis " + axis + " on port " + stick
+            + " not available, check if controller is plugged in");
+        return 0.0;
+      }
+
+      return m_joystickAxes[stick].m_axes[axis];
+    } finally {
+      if (m_cacheDataMutex.isHeldByCurrentThread()) {
+        m_cacheDataMutex.unlock();
+      }
+    }
+  }
+
+  /**
+   * 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.
+   */
+  public int getStickPOV(int stick, int pov) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+    if (pov < 0 || pov >= HAL.kMaxJoystickPOVs) {
+      throw new IllegalArgumentException("Joystick POV is out of range");
+    }
+
+    m_cacheDataMutex.lock();
+    try {
+      if (pov >= m_joystickPOVs[stick].m_count) {
+        // Unlock early so error printing isn't locked.
+        m_cacheDataMutex.unlock();
+        reportJoystickUnpluggedWarning("Joystick POV " + pov + " on port " + stick
+            + " not available, check if controller is plugged in");
+      }
+    } finally {
+      if (m_cacheDataMutex.isHeldByCurrentThread()) {
+        m_cacheDataMutex.unlock();
+      }
+    }
+
+    return m_joystickPOVs[stick].m_povs[pov];
+  }
+
+  /**
+   * The state of the buttons on the joystick.
+   *
+   * @param stick The joystick to read.
+   * @return The state of the buttons on the joystick.
+   */
+  public int getStickButtons(final int stick) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-3");
+    }
+
+    m_cacheDataMutex.lock();
+    try {
+      return m_joystickButtons[stick].m_buttons;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Returns the number of axes on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @return The number of axes on the indicated joystick
+   */
+  public int getStickAxisCount(int stick) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+
+    m_cacheDataMutex.lock();
+    try {
+      return m_joystickAxes[stick].m_count;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Returns the number of POVs on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @return The number of POVs on the indicated joystick
+   */
+  public int getStickPOVCount(int stick) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+
+    m_cacheDataMutex.lock();
+    try {
+      return m_joystickPOVs[stick].m_count;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Gets the number of buttons on a joystick.
+   *
+   * @param stick The joystick port number
+   * @return The number of buttons on the indicated joystick
+   */
+  public int getStickButtonCount(int stick) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+
+    m_cacheDataMutex.lock();
+    try {
+      return m_joystickButtons[stick].m_count;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Gets the value of isXbox on a joystick.
+   *
+   * @param stick The joystick port number
+   * @return A boolean that returns the value of isXbox
+   */
+  public boolean getJoystickIsXbox(int stick) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+
+    return HAL.getJoystickIsXbox((byte) stick) == 1;
+  }
+
+  /**
+   * Gets the value of type on a joystick.
+   *
+   * @param stick The joystick port number
+   * @return The value of type
+   */
+  public int getJoystickType(int stick) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+
+    return HAL.getJoystickType((byte) stick);
+  }
+
+  /**
+   * Gets the name of the joystick at a port.
+   *
+   * @param stick The joystick port number
+   * @return The value of name
+   */
+  public String getJoystickName(int stick) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+
+    return HAL.getJoystickName((byte) stick);
+  }
+
+  /**
+   * Returns the types of Axes on a given joystick port.
+   *
+   * @param stick The joystick port number
+   * @param axis The target axis
+   * @return What type of axis the axis is reporting to be
+   */
+  public int getJoystickAxisType(int stick, int axis) {
+    if (stick < 0 || stick >= kJoystickPorts) {
+      throw new IllegalArgumentException("Joystick index is out of range, should be 0-5");
+    }
+
+    return HAL.getJoystickAxisType((byte) stick, (byte) axis);
+  }
+
+  /**
+   * Gets a value indicating whether the Driver Station requires the robot to be enabled.
+   *
+   * @return True if the robot is enabled, false otherwise.
+   */
+  public boolean isEnabled() {
+    synchronized (m_controlWordMutex) {
+      updateControlWord(false);
+      return m_controlWordCache.getEnabled() && m_controlWordCache.getDSAttached();
+    }
+  }
+
+  /**
+   * Gets a value indicating whether the Driver Station requires the robot to be disabled.
+   *
+   * @return True if the robot should be disabled, false otherwise.
+   */
+  public boolean isDisabled() {
+    return !isEnabled();
+  }
+
+  /**
+   * Gets a value indicating whether the Driver Station requires the robot to be running in
+   * autonomous mode.
+   *
+   * @return True if autonomous mode should be enabled, false otherwise.
+   */
+  public boolean isAutonomous() {
+    synchronized (m_controlWordMutex) {
+      updateControlWord(false);
+      return m_controlWordCache.getAutonomous();
+    }
+  }
+
+  /**
+   * Gets a value indicating whether the Driver Station requires the robot to be running in
+   * operator-controlled mode.
+   *
+   * @return True if operator-controlled mode should be enabled, false otherwise.
+   */
+  public boolean isOperatorControl() {
+    return !(isAutonomous() || isTest());
+  }
+
+  /**
+   * Gets a value indicating whether the Driver Station requires the robot to be running in test
+   * mode.
+   *
+   * @return True if test mode should be enabled, false otherwise.
+   */
+  public boolean isTest() {
+    synchronized (m_controlWordMutex) {
+      updateControlWord(false);
+      return m_controlWordCache.getTest();
+    }
+  }
+
+  /**
+   * Gets a value indicating whether the Driver Station is attached.
+   *
+   * @return True if Driver Station is attached, false otherwise.
+   */
+  public boolean isDSAttached() {
+    synchronized (m_controlWordMutex) {
+      updateControlWord(false);
+      return m_controlWordCache.getDSAttached();
+    }
+  }
+
+  /**
+   * Gets if a new control packet from the driver station arrived since the last time this function
+   * was called.
+   *
+   * @return True if the control data has been updated since the last call.
+   */
+  public boolean isNewControlData() {
+    return HAL.isNewControlData();
+  }
+
+  /**
+   * Gets if the driver station attached to a Field Management System.
+   *
+   * @return true if the robot is competing on a field being controlled by a Field Management System
+   */
+  public boolean isFMSAttached() {
+    synchronized (m_controlWordMutex) {
+      updateControlWord(false);
+      return m_controlWordCache.getFMSAttached();
+    }
+  }
+
+  /**
+   * Gets a value indicating whether the FPGA outputs are enabled. The outputs may be disabled if
+   * the robot is disabled or e-stopped, the watchdog has expired, or if the roboRIO browns out.
+   *
+   * @return True if the FPGA outputs are enabled.
+   * @deprecated Use RobotController.isSysActive()
+   */
+  @Deprecated
+  public boolean isSysActive() {
+    return HAL.getSystemActive();
+  }
+
+  /**
+   * Check if the system is browned out.
+   *
+   * @return True if the system is browned out
+   * @deprecated Use RobotController.isBrownedOut()
+   */
+  @Deprecated
+  public boolean isBrownedOut() {
+    return HAL.getBrownedOut();
+  }
+
+  /**
+   * Get the game specific message.
+   *
+   * @return the game specific message
+   */
+  public String getGameSpecificMessage() {
+    m_cacheDataMutex.lock();
+    try {
+      return m_matchInfo.gameSpecificMessage;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Get the event name.
+   *
+   * @return the event name
+   */
+  public String getEventName() {
+    m_cacheDataMutex.lock();
+    try {
+      return m_matchInfo.eventName;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Get the match type.
+   *
+   * @return the match type
+   */
+  public MatchType getMatchType() {
+    int matchType;
+    m_cacheDataMutex.lock();
+    try {
+      matchType = m_matchInfo.matchType;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+    switch (matchType) {
+      case 1:
+        return MatchType.Practice;
+      case 2:
+        return MatchType.Qualification;
+      case 3:
+        return MatchType.Elimination;
+      default:
+        return MatchType.None;
+    }
+  }
+
+  /**
+   * Get the match number.
+   *
+   * @return the match number
+   */
+  public int getMatchNumber() {
+    m_cacheDataMutex.lock();
+    try {
+      return m_matchInfo.matchNumber;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Get the replay number.
+   *
+   * @return the replay number
+   */
+  public int getReplayNumber() {
+    m_cacheDataMutex.lock();
+    try {
+      return m_matchInfo.replayNumber;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Get the current alliance from the FMS.
+   *
+   * @return the current alliance
+   */
+  public Alliance getAlliance() {
+    AllianceStationID allianceStationID = HAL.getAllianceStation();
+    if (allianceStationID == null) {
+      return Alliance.Invalid;
+    }
+
+    switch (allianceStationID) {
+      case Red1:
+      case Red2:
+      case Red3:
+        return Alliance.Red;
+
+      case Blue1:
+      case Blue2:
+      case Blue3:
+        return Alliance.Blue;
+
+      default:
+        return Alliance.Invalid;
+    }
+  }
+
+  /**
+   * Gets the location of the team's driver station controls.
+   *
+   * @return the location of the team's driver station controls: 1, 2, or 3
+   */
+  public int getLocation() {
+    AllianceStationID allianceStationID = HAL.getAllianceStation();
+    if (allianceStationID == null) {
+      return 0;
+    }
+    switch (allianceStationID) {
+      case Red1:
+      case Blue1:
+        return 1;
+
+      case Red2:
+      case Blue2:
+        return 2;
+
+      case Blue3:
+      case Red3:
+        return 3;
+
+      default:
+        return 0;
+    }
+  }
+
+  /**
+   * Wait for new data from the driver station.
+   */
+  public void waitForData() {
+    waitForData(0);
+  }
+
+  /**
+   * Wait for new data or for timeout, which ever comes first. If timeout is 0, wait for new data
+   * only.
+   *
+   * @param timeout The maximum time in seconds to wait.
+   * @return true if there is new data, otherwise false
+   */
+  public boolean waitForData(double timeout) {
+    long startTime = RobotController.getFPGATime();
+    long timeoutMicros = (long) (timeout * 1000000);
+    m_waitForDataMutex.lock();
+    try {
+      int currentCount = m_waitForDataCount;
+      while (m_waitForDataCount == currentCount) {
+        if (timeout > 0) {
+          long now = RobotController.getFPGATime();
+          if (now < startTime + timeoutMicros) {
+            // We still have time to wait
+            boolean signaled = m_waitForDataCond.await(startTime + timeoutMicros - now,
+                                                TimeUnit.MICROSECONDS);
+            if (!signaled) {
+              // Return false if a timeout happened
+              return false;
+            }
+          } else {
+            // Time has elapsed.
+            return false;
+          }
+        } else {
+          m_waitForDataCond.await();
+        }
+      }
+      // Return true if we have received a proper signal
+      return true;
+    } catch (InterruptedException ex) {
+      // return false on a thread interrupt
+      return false;
+    } finally {
+      m_waitForDataMutex.unlock();
+    }
+  }
+
+  /**
+   * Return the approximate match time. The FMS does not send an official match time to the robots,
+   * but does send an approximate match time. The value will count down the time remaining in the
+   * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to
+   * dispute ref calls or guarantee that a function will trigger before the match ends) The
+   * Practice Match function of the DS approximates the behaviour seen on the field.
+   *
+   * @return Time remaining in current match period (auto or teleop) in seconds
+   */
+  public double getMatchTime() {
+    return HAL.getMatchTime();
+  }
+
+  /**
+   * Read the battery voltage.
+   *
+   * @return The battery voltage in Volts.
+   * @deprecated Use RobotController.getBatteryVoltage
+   */
+  @Deprecated
+  public double getBatteryVoltage() {
+    return PowerJNI.getVinVoltage();
+  }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
+   * purposes only.
+   *
+   * @param entering If true, starting disabled code; if false, leaving disabled code
+   */
+  @SuppressWarnings("MethodName")
+  public void InDisabled(boolean entering) {
+    m_userInDisabled = entering;
+  }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
+   * purposes only.
+   *
+   * @param entering If true, starting autonomous code; if false, leaving autonomous code
+   */
+  @SuppressWarnings("MethodName")
+  public void InAutonomous(boolean entering) {
+    m_userInAutonomous = entering;
+  }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
+   * purposes only.
+   *
+   * @param entering If true, starting teleop code; if false, leaving teleop code
+   */
+  @SuppressWarnings("MethodName")
+  public void InOperatorControl(boolean entering) {
+    m_userInTeleop = entering;
+  }
+
+  /**
+   * Only to be used to tell the Driver Station what code you claim to be executing for diagnostic
+   * purposes only.
+   *
+   * @param entering If true, starting test code; if false, leaving test code
+   */
+  @SuppressWarnings("MethodName")
+  public void InTest(boolean entering) {
+    m_userInTest = entering;
+  }
+
+  private void sendMatchData() {
+    AllianceStationID alliance = HAL.getAllianceStation();
+    boolean isRedAlliance = false;
+    int stationNumber = 1;
+    switch (alliance) {
+      case Blue1:
+        isRedAlliance = false;
+        stationNumber = 1;
+        break;
+      case Blue2:
+        isRedAlliance = false;
+        stationNumber = 2;
+        break;
+      case Blue3:
+        isRedAlliance = false;
+        stationNumber = 3;
+        break;
+      case Red1:
+        isRedAlliance = true;
+        stationNumber = 1;
+        break;
+      case Red2:
+        isRedAlliance = true;
+        stationNumber = 2;
+        break;
+      default:
+        isRedAlliance = true;
+        stationNumber = 3;
+        break;
+    }
+
+
+    String eventName;
+    String gameSpecificMessage;
+    int matchNumber;
+    int replayNumber;
+    int matchType;
+    synchronized (m_cacheDataMutex) {
+      eventName = m_matchInfo.eventName;
+      gameSpecificMessage = m_matchInfo.gameSpecificMessage;
+      matchNumber = m_matchInfo.matchNumber;
+      replayNumber = m_matchInfo.replayNumber;
+      matchType = m_matchInfo.matchType;
+    }
+
+    m_matchDataSender.alliance.setBoolean(isRedAlliance);
+    m_matchDataSender.station.setDouble(stationNumber);
+    m_matchDataSender.eventName.setString(eventName);
+    m_matchDataSender.gameSpecificMessage.setString(gameSpecificMessage);
+    m_matchDataSender.matchNumber.setDouble(matchNumber);
+    m_matchDataSender.replayNumber.setDouble(replayNumber);
+    m_matchDataSender.matchType.setDouble(matchType);
+    m_matchDataSender.controlWord.setDouble(HAL.nativeGetControlWord());
+  }
+
+  /**
+   * 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() {
+    // Get the status of all of the joysticks
+    for (byte stick = 0; stick < kJoystickPorts; stick++) {
+      m_joystickAxesCache[stick].m_count =
+          HAL.getJoystickAxes(stick, m_joystickAxesCache[stick].m_axes);
+      m_joystickPOVsCache[stick].m_count =
+          HAL.getJoystickPOVs(stick, m_joystickPOVsCache[stick].m_povs);
+      m_joystickButtonsCache[stick].m_buttons = HAL.getJoystickButtons(stick, m_buttonCountBuffer);
+      m_joystickButtonsCache[stick].m_count = m_buttonCountBuffer.get(0);
+    }
+
+    HAL.getMatchInfo(m_matchInfoCache);
+
+    // Force a control word update, to make sure the data is the newest.
+    updateControlWord(true);
+
+    // lock joystick mutex to swap cache data
+    m_cacheDataMutex.lock();
+    try {
+      for (int i = 0; i < kJoystickPorts; i++) {
+        // If buttons weren't pressed and are now, set flags in m_buttonsPressed
+        m_joystickButtonsPressed[i] |=
+            ~m_joystickButtons[i].m_buttons & m_joystickButtonsCache[i].m_buttons;
+
+        // If buttons were pressed and aren't now, set flags in m_buttonsReleased
+        m_joystickButtonsReleased[i] |=
+            m_joystickButtons[i].m_buttons & ~m_joystickButtonsCache[i].m_buttons;
+      }
+
+      // move cache to actual data
+      HALJoystickAxes[] currentAxes = m_joystickAxes;
+      m_joystickAxes = m_joystickAxesCache;
+      m_joystickAxesCache = currentAxes;
+
+      HALJoystickButtons[] currentButtons = m_joystickButtons;
+      m_joystickButtons = m_joystickButtonsCache;
+      m_joystickButtonsCache = currentButtons;
+
+      HALJoystickPOVs[] currentPOVs = m_joystickPOVs;
+      m_joystickPOVs = m_joystickPOVsCache;
+      m_joystickPOVsCache = currentPOVs;
+
+      MatchInfoData currentInfo = m_matchInfo;
+      m_matchInfo = m_matchInfoCache;
+      m_matchInfoCache = currentInfo;
+    } finally {
+      m_cacheDataMutex.unlock();
+    }
+
+    m_waitForDataMutex.lock();
+    m_waitForDataCount++;
+    m_waitForDataCond.signalAll();
+    m_waitForDataMutex.unlock();
+
+    sendMatchData();
+  }
+
+  /**
+   * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm
+   * the DS.
+   */
+  private void reportJoystickUnpluggedError(String message) {
+    double currentTime = Timer.getFPGATimestamp();
+    if (currentTime > m_nextMessageTime) {
+      reportError(message, false);
+      m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
+    }
+  }
+
+  /**
+   * Reports errors related to unplugged joysticks Throttles the errors so that they don't overwhelm
+   * the DS.
+   */
+  private void reportJoystickUnpluggedWarning(String message) {
+    double currentTime = Timer.getFPGATimestamp();
+    if (currentTime > m_nextMessageTime) {
+      reportWarning(message, false);
+      m_nextMessageTime = currentTime + JOYSTICK_UNPLUGGED_MESSAGE_INTERVAL;
+    }
+  }
+
+  /**
+   * Provides the service routine for the DS polling m_thread.
+   */
+  private void run() {
+    int safetyCounter = 0;
+    while (m_threadKeepAlive) {
+      HAL.waitForDSData();
+      getData();
+
+      if (isDisabled()) {
+        safetyCounter = 0;
+      }
+
+      safetyCounter++;
+      if (safetyCounter >= 4) {
+        MotorSafety.checkMotors();
+        safetyCounter = 0;
+      }
+      if (m_userInDisabled) {
+        HAL.observeUserProgramDisabled();
+      }
+      if (m_userInAutonomous) {
+        HAL.observeUserProgramAutonomous();
+      }
+      if (m_userInTeleop) {
+        HAL.observeUserProgramTeleop();
+      }
+      if (m_userInTest) {
+        HAL.observeUserProgramTest();
+      }
+    }
+  }
+
+  /**
+   * Updates the data in the control word cache. Updates if the force parameter is set, or if
+   * 50ms have passed since the last update.
+   *
+   * @param force True to force an update to the cache, otherwise update if 50ms have passed.
+   */
+  private void updateControlWord(boolean force) {
+    long now = System.currentTimeMillis();
+    synchronized (m_controlWordMutex) {
+      if (now - m_lastControlWordUpdate > 50 || force) {
+        HAL.getControlWord(m_controlWordCache);
+        m_lastControlWordUpdate = now;
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java
new file mode 100644
index 0000000..594fe0a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Encoder.java
@@ -0,0 +1,575 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.EncoderJNI;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.util.AllocationException;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Class to read quadrature encoders.
+ *
+ * <p>Quadrature encoders are devices that count shaft rotation and can sense direction. The output
+ * of the Encoder class is an integer that can count either up or down, and can go negative for
+ * reverse direction counting. When creating Encoders, a direction can be supplied that inverts the
+ * sense of the output to make code more readable if the encoder is mounted such that forward
+ * movement generates negative values. Quadrature encoders have two digital outputs, an A Channel
+ * and a B Channel, that are out of phase with each other for direction sensing.
+ *
+ * <p>All encoders will immediately start counting - reset() them if you need them to be zeroed
+ * before use.
+ */
+public class Encoder extends SendableBase implements CounterBase, PIDSource {
+  public enum IndexingType {
+    kResetWhileHigh(0), kResetWhileLow(1), kResetOnFallingEdge(2), kResetOnRisingEdge(3);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    IndexingType(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * The a source.
+   */
+  @SuppressWarnings("MemberName")
+  protected DigitalSource m_aSource; // the A phase of the quad encoder
+  /**
+   * The b source.
+   */
+  @SuppressWarnings("MemberName")
+  protected DigitalSource m_bSource; // the B phase of the quad encoder
+  /**
+   * The index source.
+   */
+  protected DigitalSource m_indexSource; // Index on some encoders
+  private boolean m_allocatedA;
+  private boolean m_allocatedB;
+  private boolean m_allocatedI;
+  private PIDSourceType m_pidSource;
+
+  private int m_encoder; // the HAL encoder object
+
+
+  /**
+   * Common initialization code for Encoders. This code allocates resources for Encoders and is
+   * common to all constructors.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param reverseDirection If true, counts down instead of up (this is all relative)
+   */
+  private void initEncoder(boolean reverseDirection, final EncodingType type) {
+    m_encoder = EncoderJNI.initializeEncoder(m_aSource.getPortHandleForRouting(),
+        m_aSource.getAnalogTriggerTypeForRouting(), m_bSource.getPortHandleForRouting(),
+        m_bSource.getAnalogTriggerTypeForRouting(), reverseDirection, type.value);
+
+    m_pidSource = PIDSourceType.kDisplacement;
+
+    int fpgaIndex = getFPGAIndex();
+    HAL.report(tResourceType.kResourceType_Encoder, fpgaIndex, type.value);
+    setName("Encoder", fpgaIndex);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a and b channels.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param channelA         The a channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
+   * @param channelB         The b channel DIO channel. 0-9 are on-board, 10-25 are on the MXP port
+   * @param reverseDirection represents the orientation of the encoder and inverts the output values
+   *                         if necessary so forward represents positive values.
+   */
+  public Encoder(final int channelA, final int channelB, boolean reverseDirection) {
+    this(channelA, channelB, reverseDirection, EncodingType.k4X);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a and b channels.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param channelA The a channel digital input channel.
+   * @param channelB The b channel digital input channel.
+   */
+  public Encoder(final int channelA, final int channelB) {
+    this(channelA, channelB, false);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a and b channels.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param channelA         The a channel digital input channel.
+   * @param channelB         The b channel digital input channel.
+   * @param reverseDirection represents the orientation of the encoder and inverts the output values
+   *                         if necessary so forward represents positive values.
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
+   *                         selected, then an encoder FPGA object is used and the returned counts
+   *                         will be 4x the encoder spec'd value since all rising and falling edges
+   *                         are counted. If 1X or 2X are selected then a m_counter object will be
+   *                         used and the returned value will either exactly match the spec'd count
+   *                         or be double (2x) the spec'd count.
+   */
+  public Encoder(final int channelA, final int channelB, boolean reverseDirection,
+                 final EncodingType encodingType) {
+    requireNonNull(encodingType, "Given encoding type was null");
+
+    m_allocatedA = true;
+    m_allocatedB = true;
+    m_allocatedI = false;
+    m_aSource = new DigitalInput(channelA);
+    m_bSource = new DigitalInput(channelB);
+    addChild(m_aSource);
+    addChild(m_bSource);
+    initEncoder(reverseDirection, encodingType);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a and b channels. Using an index pulse forces 4x
+   * encoding
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param channelA         The a channel digital input channel.
+   * @param channelB         The b channel digital input channel.
+   * @param indexChannel     The index channel digital input channel.
+   * @param reverseDirection represents the orientation of the encoder and inverts the output values
+   *                         if necessary so forward represents positive values.
+   */
+  public Encoder(final int channelA, final int channelB, final int indexChannel,
+                 boolean reverseDirection) {
+    this(channelA, channelB, reverseDirection);
+    m_allocatedI = true;
+    m_indexSource = new DigitalInput(indexChannel);
+    addChild(m_indexSource);
+    setIndexSource(m_indexSource);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a and b channels. Using an index pulse forces 4x
+   * encoding
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param channelA     The a channel digital input channel.
+   * @param channelB     The b channel digital input channel.
+   * @param indexChannel The index channel digital input channel.
+   */
+  public Encoder(final int channelA, final int channelB, final int indexChannel) {
+    this(channelA, channelB, indexChannel, false);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a and b channels as digital inputs. This is used
+   * in the case where the digital inputs are shared. The Encoder class will not allocate the
+   * digital inputs and assume that they already are counted.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param sourceA          The source that should be used for the a channel.
+   * @param sourceB          the source that should be used for the b channel.
+   * @param reverseDirection represents the orientation of the encoder and inverts the output values
+   *                         if necessary so forward represents positive values.
+   */
+  public Encoder(DigitalSource sourceA, DigitalSource sourceB, boolean reverseDirection) {
+    this(sourceA, sourceB, reverseDirection, EncodingType.k4X);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a and b channels as digital inputs. This is used
+   * in the case where the digital inputs are shared. The Encoder class will not allocate the
+   * digital inputs and assume that they already are counted.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param sourceA The source that should be used for the a channel.
+   * @param sourceB the source that should be used for the b channel.
+   */
+  public Encoder(DigitalSource sourceA, DigitalSource sourceB) {
+    this(sourceA, sourceB, false);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a and b channels as digital inputs. This is used
+   * in the case where the digital inputs are shared. The Encoder class will not allocate the
+   * digital inputs and assume that they already are counted.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param sourceA          The source that should be used for the a channel.
+   * @param sourceB          the source that should be used for the b channel.
+   * @param reverseDirection represents the orientation of the encoder and inverts the output values
+   *                         if necessary so forward represents positive values.
+   * @param encodingType     either k1X, k2X, or k4X to indicate 1X, 2X or 4X decoding. If 4X is
+   *                         selected, then an encoder FPGA object is used and the returned counts
+   *                         will be 4x the encoder spec'd value since all rising and falling edges
+   *                         are counted. If 1X or 2X are selected then a m_counter object will be
+   *                         used and the returned value will either exactly match the spec'd count
+   *                         or be double (2x) the spec'd count.
+   */
+  public Encoder(DigitalSource sourceA, DigitalSource sourceB, boolean reverseDirection,
+                 final EncodingType encodingType) {
+    requireNonNull(sourceA, "Digital Source A was null");
+    requireNonNull(sourceB, "Digital Source B was null");
+    requireNonNull(encodingType, "Given encoding type was null");
+
+    m_allocatedA = false;
+    m_allocatedB = false;
+    m_allocatedI = false;
+    m_aSource = sourceA;
+    m_bSource = sourceB;
+    initEncoder(reverseDirection, encodingType);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a, b and index channels as digital inputs. This
+   * is used in the case where the digital inputs are shared. The Encoder class will not allocate
+   * the digital inputs and assume that they already are counted.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param sourceA          The source that should be used for the a channel.
+   * @param sourceB          the source that should be used for the b channel.
+   * @param indexSource      the source that should be used for the index channel.
+   * @param reverseDirection represents the orientation of the encoder and inverts the output values
+   *                         if necessary so forward represents positive values.
+   */
+  public Encoder(DigitalSource sourceA, DigitalSource sourceB, DigitalSource indexSource,
+                 boolean reverseDirection) {
+    this(sourceA, sourceB, reverseDirection);
+    m_allocatedI = false;
+    m_indexSource = indexSource;
+    setIndexSource(indexSource);
+  }
+
+  /**
+   * Encoder constructor. Construct a Encoder given a, b and index channels as digital inputs. This
+   * is used in the case where the digital inputs are shared. The Encoder class will not allocate
+   * the digital inputs and assume that they already are counted.
+   *
+   * <p>The encoder will start counting immediately.
+   *
+   * @param sourceA     The source that should be used for the a channel.
+   * @param sourceB     the source that should be used for the b channel.
+   * @param indexSource the source that should be used for the index channel.
+   */
+  public Encoder(DigitalSource sourceA, DigitalSource sourceB, DigitalSource indexSource) {
+    this(sourceA, sourceB, indexSource, false);
+  }
+
+  /**
+   * Get the FPGA index of the encoder.
+   *
+   * @return The Encoder's FPGA index.
+   */
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public int getFPGAIndex() {
+    return EncoderJNI.getEncoderFPGAIndex(m_encoder);
+  }
+
+  /**
+   * Used to divide raw edge counts down to spec'd counts.
+   *
+   * @return The encoding scale factor 1x, 2x, or 4x, per the requested encoding type.
+   */
+  public int getEncodingScale() {
+    return EncoderJNI.getEncoderEncodingScale(m_encoder);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    if (m_aSource != null && m_allocatedA) {
+      m_aSource.close();
+      m_allocatedA = false;
+    }
+    if (m_bSource != null && m_allocatedB) {
+      m_bSource.close();
+      m_allocatedB = false;
+    }
+    if (m_indexSource != null && m_allocatedI) {
+      m_indexSource.close();
+      m_allocatedI = false;
+    }
+
+    m_aSource = null;
+    m_bSource = null;
+    m_indexSource = null;
+    EncoderJNI.freeEncoder(m_encoder);
+    m_encoder = 0;
+  }
+
+  /**
+   * Gets the raw value from the encoder. The raw value is the actual count unscaled by the 1x, 2x,
+   * or 4x scale factor.
+   *
+   * @return Current raw count from the encoder
+   */
+  public int getRaw() {
+    return EncoderJNI.getEncoderRaw(m_encoder);
+  }
+
+  /**
+   * Gets the current count. Returns the current count on the Encoder. This method compensates for
+   * the decoding type.
+   *
+   * @return Current count from the Encoder adjusted for the 1x, 2x, or 4x scale factor.
+   */
+  @Override
+  public int get() {
+    return EncoderJNI.getEncoder(m_encoder);
+  }
+
+  /**
+   * Reset the Encoder distance to zero. Resets the current count to zero on the encoder.
+   */
+  @Override
+  public void reset() {
+    EncoderJNI.resetEncoder(m_encoder);
+  }
+
+  /**
+   * Returns the period of the most recent pulse. Returns the period of the most recent Encoder
+   * pulse in seconds. This method compensates for the decoding type.
+   *
+   * <p><b>Warning:</b> This returns unscaled periods. Use getRate() for rates that are scaled using
+   * the value from setDistancePerPulse().
+   *
+   * @return Period in seconds of the most recent pulse.
+   * @deprecated Use getRate() in favor of this method.
+   */
+  @Override
+  @Deprecated
+  public double getPeriod() {
+    return EncoderJNI.getEncoderPeriod(m_encoder);
+  }
+
+  /**
+   * Sets the maximum period for stopped detection. Sets the value that represents the maximum
+   * period of the Encoder before it will assume that the attached device is stopped. This timeout
+   * allows users to determine if the wheels or other shaft has stopped rotating. This method
+   * compensates for the decoding type.
+   *
+   * @param maxPeriod The maximum time between rising and falling edges before the FPGA will report
+   *                  the device stopped. This is expressed in seconds.
+   */
+  @Override
+  public void setMaxPeriod(double maxPeriod) {
+    EncoderJNI.setEncoderMaxPeriod(m_encoder, maxPeriod);
+  }
+
+  /**
+   * Determine if the encoder is stopped. Using the MaxPeriod value, a boolean is returned that is
+   * true if the encoder is considered stopped and false if it is still moving. A stopped encoder is
+   * one where the most recent pulse width exceeds the MaxPeriod.
+   *
+   * @return True if the encoder is considered stopped.
+   */
+  @Override
+  public boolean getStopped() {
+    return EncoderJNI.getEncoderStopped(m_encoder);
+  }
+
+  /**
+   * The last direction the encoder value changed.
+   *
+   * @return The last direction the encoder value changed.
+   */
+  @Override
+  public boolean getDirection() {
+    return EncoderJNI.getEncoderDirection(m_encoder);
+  }
+
+  /**
+   * Get the distance the robot has driven since the last reset as scaled by the value from {@link
+   * #setDistancePerPulse(double)}.
+   *
+   * @return The distance driven since the last reset
+   */
+  public double getDistance() {
+    return EncoderJNI.getEncoderDistance(m_encoder);
+  }
+
+  /**
+   * Get the current rate of the encoder. Units are distance per second as scaled by the value from
+   * setDistancePerPulse().
+   *
+   * @return The current rate of the encoder.
+   */
+  public double getRate() {
+    return EncoderJNI.getEncoderRate(m_encoder);
+  }
+
+  /**
+   * Set the minimum rate of the device before the hardware reports it stopped.
+   *
+   * @param minRate The minimum rate. The units are in distance per second as scaled by the value
+   *                from setDistancePerPulse().
+   */
+  public void setMinRate(double minRate) {
+    EncoderJNI.setEncoderMinRate(m_encoder, minRate);
+  }
+
+  /**
+   * Set the distance per pulse for this encoder. This sets the multiplier used to determine the
+   * distance driven based on the count value from the encoder. Do not include the decoding type in
+   * this scale. The library already compensates for the decoding type. Set this value based on the
+   * encoder's rated Pulses per Revolution and factor in gearing reductions following the encoder
+   * shaft. This distance can be in any units you like, linear or angular.
+   *
+   * @param distancePerPulse The scale factor that will be used to convert pulses to useful units.
+   */
+  public void setDistancePerPulse(double distancePerPulse) {
+    EncoderJNI.setEncoderDistancePerPulse(m_encoder, distancePerPulse);
+  }
+
+  /**
+   * Get the distance per pulse for this encoder.
+   *
+   * @return The scale factor that will be used to convert pulses to useful units.
+   */
+  public double getDistancePerPulse() {
+    return EncoderJNI.getEncoderDistancePerPulse(m_encoder);
+  }
+
+  /**
+   * Set the direction sensing for this encoder. This sets the direction sensing on the encoder so
+   * that it could count in the correct software direction regardless of the mounting.
+   *
+   * @param reverseDirection true if the encoder direction should be reversed
+   */
+  public void setReverseDirection(boolean reverseDirection) {
+    EncoderJNI.setEncoderReverseDirection(m_encoder, reverseDirection);
+  }
+
+  /**
+   * Set the Samples to Average which specifies the number of samples of the timer to average when
+   * calculating the period. Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @param samplesToAverage The number of samples to average from 1 to 127.
+   */
+  public void setSamplesToAverage(int samplesToAverage) {
+    EncoderJNI.setEncoderSamplesToAverage(m_encoder, samplesToAverage);
+  }
+
+  /**
+   * Get the Samples to Average which specifies the number of samples of the timer to average when
+   * calculating the period. Perform averaging to account for mechanical imperfections or as
+   * oversampling to increase resolution.
+   *
+   * @return SamplesToAverage The number of samples being averaged (from 1 to 127)
+   */
+  public int getSamplesToAverage() {
+    return EncoderJNI.getEncoderSamplesToAverage(m_encoder);
+  }
+
+  /**
+   * Set which parameter of the encoder you are using as a process control variable. The encoder
+   * class supports the rate and distance parameters.
+   *
+   * @param pidSource An enum to select the parameter.
+   */
+  @Override
+  public void setPIDSourceType(PIDSourceType pidSource) {
+    m_pidSource = pidSource;
+  }
+
+  @Override
+  public PIDSourceType getPIDSourceType() {
+    return m_pidSource;
+  }
+
+  /**
+   * Implement the PIDSource interface.
+   *
+   * @return The current value of the selected source parameter.
+   */
+  @Override
+  public double pidGet() {
+    switch (m_pidSource) {
+      case kDisplacement:
+        return getDistance();
+      case kRate:
+        return getRate();
+      default:
+        return 0.0;
+    }
+  }
+
+  /**
+   * Set the index source for the encoder. When this source is activated, the encoder count
+   * automatically resets.
+   *
+   * @param channel A DIO channel to set as the encoder index
+   */
+  public void setIndexSource(int channel) {
+    setIndexSource(channel, IndexingType.kResetOnRisingEdge);
+  }
+
+  /**
+   * Set the index source for the encoder. When this source is activated, the encoder count
+   * automatically resets.
+   *
+   * @param source A digital source to set as the encoder index
+   */
+  public void setIndexSource(DigitalSource source) {
+    setIndexSource(source, IndexingType.kResetOnRisingEdge);
+  }
+
+  /**
+   * Set the index source for the encoder. When this source rises, the encoder count automatically
+   * resets.
+   *
+   * @param channel A DIO channel to set as the encoder index
+   * @param type    The state that will cause the encoder to reset
+   */
+  public void setIndexSource(int channel, IndexingType type) {
+    if (m_allocatedI) {
+      throw new AllocationException("Digital Input for Indexing already allocated");
+    }
+    m_indexSource = new DigitalInput(channel);
+    m_allocatedI = true;
+    addChild(m_indexSource);
+    setIndexSource(m_indexSource, type);
+  }
+
+  /**
+   * Set the index source for the encoder. When this source rises, the encoder count automatically
+   * resets.
+   *
+   * @param source A digital source to set as the encoder index
+   * @param type   The state that will cause the encoder to reset
+   */
+  public void setIndexSource(DigitalSource source, IndexingType type) {
+    EncoderJNI.setEncoderIndexSource(m_encoder, source.getPortHandleForRouting(),
+        source.getAnalogTriggerTypeForRouting(), type.value);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    if (EncoderJNI.getEncoderEncodingType(m_encoder) == EncodingType.k4X.value) {
+      builder.setSmartDashboardType("Quadrature Encoder");
+    } else {
+      builder.setSmartDashboardType("Encoder");
+    }
+
+    builder.addDoubleProperty("Speed", this::getRate, null);
+    builder.addDoubleProperty("Distance", this::getDistance, null);
+    builder.addDoubleProperty("Distance per Tick", this::getDistancePerPulse, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Filesystem.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Filesystem.java
new file mode 100644
index 0000000..cfefb6a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Filesystem.java
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.io.File;
+
+/**
+ * Class for interacting with the Filesystem, particularly, interacting with
+ * FRC-related paths on the system, such as the launch and deploy directories.
+ *
+ * <p>This class is primarily used for obtaining resources in src/main/deploy, and
+ * the RoboRIO path /home/lvuser in a simulation-compatible way.</p>
+ */
+public final class Filesystem {
+  private Filesystem() { }
+
+  /**
+   * Obtains the current working path that the program was launched with.
+   * This is analogous to the `pwd` command on unix.
+   *
+   * @return The current working directory (launch directory)
+   */
+  public static File getLaunchDirectory() {
+    return new File(System.getProperty("user.dir")).getAbsoluteFile();
+  }
+
+  /**
+   * Obtains the operating directory of the program. On the roboRIO, this is
+   * /home/lvuser. In simulation, it is where the simulation was launched from
+   * (`pwd`).
+   *
+   * @return The operating directory
+   */
+  public static File getOperatingDirectory() {
+    if (RobotBase.isReal()) {
+      return new File("/home/lvuser");
+    } else {
+      return getLaunchDirectory();
+    }
+  }
+
+  /**
+   * Obtains the deploy directory of the program, which is the remote location
+   * src/main/deploy is deployed to by default. On the roboRIO, this is
+   * /home/lvuser/deploy. In simulation, it is where the simulation was launched
+   * from, in the subdirectory "deploy" (`pwd`/deploy).
+   *
+   * @return The deploy directory
+   */
+  public static File getDeployDirectory() {
+    return new File(getOperatingDirectory(), "deploy");
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GamepadBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GamepadBase.java
new file mode 100644
index 0000000..8e878ea
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GamepadBase.java
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * Gamepad Interface.
+ *
+ * @deprecated Inherit directly from GenericHID instead.
+ */
+@Deprecated
+public abstract class GamepadBase extends GenericHID {
+  public GamepadBase(int port) {
+    super(port);
+  }
+
+  @Override
+  public abstract double getRawAxis(int axis);
+
+  /**
+   * Is the bumper pressed.
+   *
+   * @param hand which hand
+   * @return true if the bumper is pressed
+   */
+  public abstract boolean getBumper(Hand hand);
+
+  /**
+   * Is the bumper pressed.
+   *
+   * @return true if the bumper is pressed
+   */
+  public boolean getBumper() {
+    return getBumper(Hand.kRight);
+  }
+
+  public abstract boolean getStickButton(Hand hand);
+
+  public boolean getStickButton() {
+    return getStickButton(Hand.kRight);
+  }
+
+  @Override
+  public abstract boolean getRawButton(int button);
+
+  @Override
+  public abstract int getPOV(int pov);
+
+  @Override
+  public abstract int getPOVCount();
+
+  @Override
+  public abstract HIDType getType();
+
+  @Override
+  public abstract String getName();
+
+  @Override
+  public abstract void setOutput(int outputNumber, boolean value);
+
+  @Override
+  public abstract void setOutputs(int value);
+
+  @Override
+  public abstract void setRumble(RumbleType type, double value);
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GearTooth.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GearTooth.java
new file mode 100644
index 0000000..e937c26
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GearTooth.java
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Alias for counter class. Implement the gear tooth sensor supplied by FIRST. Currently there is no
+ * reverse sensing on the gear tooth sensor, but in future versions we might implement the necessary
+ * timing in the FPGA to sense direction.
+ */
+public class GearTooth extends Counter {
+  private static final double kGearToothThreshold = 55e-6;
+
+  /**
+   * Common code called by the constructors.
+   */
+  public void enableDirectionSensing(boolean directionSensitive) {
+    if (directionSensitive) {
+      setPulseLengthMode(kGearToothThreshold);
+    }
+  }
+
+  /**
+   * Construct a GearTooth sensor given a channel.
+   *
+   * <p>No direction sensing is assumed.
+   *
+   * @param channel The GPIO channel that the sensor is connected to.
+   */
+  public GearTooth(final int channel) {
+    this(channel, false);
+  }
+
+  /**
+   * Construct a GearTooth sensor given a channel.
+   *
+   * @param channel            The DIO channel that the sensor is connected to. 0-9 are on-board,
+   *                           10-25 are on the MXP port
+   * @param directionSensitive True to enable the pulse length decoding in hardware to specify count
+   *                           direction.
+   */
+  public GearTooth(final int channel, boolean directionSensitive) {
+    super(channel);
+    enableDirectionSensing(directionSensitive);
+    if (directionSensitive) {
+      HAL.report(tResourceType.kResourceType_GearTooth, channel, 0, "D");
+    } else {
+      HAL.report(tResourceType.kResourceType_GearTooth, channel, 0);
+    }
+    setName("GearTooth", channel);
+  }
+
+  /**
+   * Construct a GearTooth sensor given a digital input. This should be used when sharing digital
+   * inputs.
+   *
+   * @param source             An existing DigitalSource object (such as a DigitalInput)
+   * @param directionSensitive True to enable the pulse length decoding in hardware to specify count
+   *                           direction.
+   */
+  public GearTooth(DigitalSource source, boolean directionSensitive) {
+    super(source);
+    enableDirectionSensing(directionSensitive);
+    if (directionSensitive) {
+      HAL.report(tResourceType.kResourceType_GearTooth, source.getChannel(), 0, "D");
+    } else {
+      HAL.report(tResourceType.kResourceType_GearTooth, source.getChannel(), 0);
+    }
+    setName("GearTooth", source.getChannel());
+  }
+
+  /**
+   * Construct a GearTooth sensor given a digital input. This should be used when sharing digital
+   * inputs.
+   *
+   * <p>No direction sensing is assumed.
+   *
+   * @param source An object that fully describes the input that the sensor is connected to.
+   */
+  public GearTooth(DigitalSource source) {
+    this(source, false);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+    builder.setSmartDashboardType("Gear Tooth");
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
new file mode 100644
index 0000000..0f884b9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GenericHID.java
@@ -0,0 +1,286 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.HashMap;
+import java.util.Map;
+
+import edu.wpi.first.hal.HAL;
+
+/**
+ * GenericHID Interface.
+ */
+public abstract class GenericHID {
+  /**
+   * Represents a rumble output on the JoyStick.
+   */
+  public enum RumbleType {
+    kLeftRumble, kRightRumble
+  }
+
+  public enum HIDType {
+    kUnknown(-1),
+    kXInputUnknown(0),
+    kXInputGamepad(1),
+    kXInputWheel(2),
+    kXInputArcadeStick(3),
+    kXInputFlightStick(4),
+    kXInputDancePad(5),
+    kXInputGuitar(6),
+    kXInputGuitar2(7),
+    kXInputDrumKit(8),
+    kXInputGuitar3(11),
+    kXInputArcadePad(19),
+    kHIDJoystick(20),
+    kHIDGamepad(21),
+    kHIDDriving(22),
+    kHIDFlight(23),
+    kHID1stPerson(24);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+    @SuppressWarnings("PMD.UseConcurrentHashMap")
+    private static final Map<Integer, HIDType> map = new HashMap<>();
+
+    HIDType(int value) {
+      this.value = value;
+    }
+
+    static {
+      for (HIDType hidType : HIDType.values()) {
+        map.put(hidType.value, hidType);
+      }
+    }
+
+    public static HIDType of(int value) {
+      return map.get(value);
+    }
+  }
+
+  /**
+   * Which hand the Human Interface Device is associated with.
+   */
+  public enum Hand {
+    kLeft(0), kRight(1);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    Hand(int value) {
+      this.value = value;
+    }
+  }
+
+  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;
+  }
+
+  /**
+   * Get the x position of the HID.
+   *
+   * @return the x position of the HID
+   */
+  public final double getX() {
+    return getX(Hand.kRight);
+  }
+
+  /**
+   * Get the x position of HID.
+   *
+   * @param hand which hand, left or right
+   * @return the x position
+   */
+  public abstract double getX(Hand hand);
+
+  /**
+   * Get the y position of the HID.
+   *
+   * @return the y position
+   */
+  public final double getY() {
+    return getY(Hand.kRight);
+  }
+
+  /**
+   * Get the y position of the HID.
+   *
+   * @param hand which hand, left or right
+   * @return the y position
+   */
+  public abstract double getY(Hand hand);
+
+  /**
+   * Get the button value (starting at button 1).
+   *
+   * <p>The buttons are returned in a single 16 bit value with one bit representing the state of
+   * each button. The appropriate button is returned as a boolean value.
+   *
+   * @param button The button number to be read (starting at 1)
+   * @return The state of the button.
+   */
+  public boolean getRawButton(int button) {
+    return m_ds.getStickButton(m_port, (byte) button);
+  }
+
+  /**
+   * Whether the button was pressed since the last check. Button indexes begin at
+   * 1.
+   *
+   * @param button The button index, beginning at 1.
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getRawButtonPressed(int button) {
+    return m_ds.getStickButtonPressed(m_port, (byte) button);
+  }
+
+  /**
+   * Whether the button was released since the last check. Button indexes begin at
+   * 1.
+   *
+   * @param button The button index, beginning at 1.
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getRawButtonReleased(int button) {
+    return m_ds.getStickButtonReleased(m_port, button);
+  }
+
+  /**
+   * Get the value of the axis.
+   *
+   * @param axis The axis to read, starting at 0.
+   * @return The value of the axis.
+   */
+  public double getRawAxis(int axis) {
+    return m_ds.getStickAxis(m_port, axis);
+  }
+
+  /**
+   * Get the angle in degrees of a POV on the HID.
+   *
+   * <p>The POV angles start at 0 in the up direction, and increase clockwise (eg right is 90,
+   * upper-left is 315).
+   *
+   * @param pov The index of the POV to read (starting at 0)
+   * @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);
+  }
+
+  public int getPOV() {
+    return getPOV(0);
+  }
+
+  /**
+   * Get the number of axes for the HID.
+   *
+   * @return the number of axis for the current HID
+   */
+  public int getAxisCount() {
+    return m_ds.getStickAxisCount(m_port);
+  }
+
+  /**
+   * For the current HID, return the number of POVs.
+   */
+  public int getPOVCount() {
+    return m_ds.getStickPOVCount(m_port);
+  }
+
+  /**
+   * For the current HID, return the number of buttons.
+   */
+  public int getButtonCount() {
+    return m_ds.getStickButtonCount(m_port);
+  }
+
+  /**
+   * Get the type of the HID.
+   *
+   * @return the type of the HID.
+   */
+  public HIDType getType() {
+    return HIDType.of(m_ds.getJoystickType(m_port));
+  }
+
+  /**
+   * Get the name of the HID.
+   *
+   * @return the name of the HID.
+   */
+  public String getName() {
+    return m_ds.getJoystickName(m_port);
+  }
+
+  /**
+   * Get the axis type of a joystick axis.
+   *
+   * @return the axis type of a joystick axis.
+   */
+  public int getAxisType(int axis) {
+    return m_ds.getJoystickAxisType(m_port, axis);
+  }
+
+  /**
+   * Get the port number of the HID.
+   *
+   * @return The port number of the HID.
+   */
+  public int getPort() {
+    return m_port;
+  }
+
+  /**
+   * Set a single HID output value for the HID.
+   *
+   * @param outputNumber The index of the output to set (1-32)
+   * @param value        The value to set the output to
+   */
+  public void setOutput(int outputNumber, boolean value) {
+    m_outputs = (m_outputs & ~(1 << (outputNumber - 1))) | ((value ? 1 : 0) << (outputNumber - 1));
+    HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
+  }
+
+  /**
+   * Set all HID output values for the HID.
+   *
+   * @param value The 32 bit output value (1 bit for each output)
+   */
+  public void setOutputs(int value) {
+    m_outputs = value;
+    HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
+  }
+
+  /**
+   * Set the rumble output for the HID. The DS currently supports 2 rumble values, left rumble and
+   * right rumble.
+   *
+   * @param type  Which rumble value to set
+   * @param value The normalized value (0 to 1) to set the rumble to
+   */
+  public void setRumble(RumbleType type, double value) {
+    if (value < 0) {
+      value = 0;
+    } else if (value > 1) {
+      value = 1;
+    }
+    if (type == RumbleType.kLeftRumble) {
+      m_leftRumble = (short) (value * 65535);
+    } else {
+      m_rightRumble = (short) (value * 65535);
+    }
+    HAL.setJoystickOutputs((byte) m_port, m_outputs, m_leftRumble, m_rightRumble);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java
new file mode 100644
index 0000000..4bd47e8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/GyroBase.java
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.interfaces.Gyro;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * GyroBase is the common base class for Gyro implementations such as AnalogGyro.
+ */
+public abstract class GyroBase extends SendableBase implements Gyro, PIDSource {
+  private PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
+
+  /**
+   * Set which parameter of the gyro you are using as a process control variable. The Gyro class
+   * supports the rate and displacement parameters
+   *
+   * @param pidSource An enum to select the parameter.
+   */
+  @Override
+  public void setPIDSourceType(PIDSourceType pidSource) {
+    m_pidSource = pidSource;
+  }
+
+  @Override
+  public PIDSourceType getPIDSourceType() {
+    return m_pidSource;
+  }
+
+  /**
+   * Get the output of the gyro for use with PIDControllers. May be the angle or rate depending on
+   * the set PIDSourceType
+   *
+   * @return the output according to the gyro
+   */
+  @Override
+  public double pidGet() {
+    switch (m_pidSource) {
+      case kRate:
+        return getRate();
+      case kDisplacement:
+        return getAngle();
+      default:
+        return 0.0;
+    }
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Gyro");
+    builder.addDoubleProperty("Value", this::getAngle, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java
new file mode 100644
index 0000000..67a171c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/I2C.java
@@ -0,0 +1,377 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.I2CJNI;
+import edu.wpi.first.hal.util.BoundaryException;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * I2C bus interface class.
+ *
+ * <p>This class is intended to be used by sensor (and other I2C device) drivers. It probably should
+ * not be used directly.
+ */
+@SuppressWarnings({"PMD.GodClass", "PMD.TooManyMethods"})
+public class I2C implements AutoCloseable {
+  public enum Port {
+    kOnboard(0), kMXP(1);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    Port(int value) {
+      this.value = value;
+    }
+  }
+
+  private final int m_port;
+  private final int m_deviceAddress;
+
+  /**
+   * Constructor.
+   *
+   * @param port          The I2C port the device is connected to.
+   * @param deviceAddress The address of the device on the I2C bus.
+   */
+  public I2C(Port port, int deviceAddress) {
+    m_port = port.value;
+    m_deviceAddress = deviceAddress;
+
+    I2CJNI.i2CInitialize((byte) port.value);
+
+    HAL.report(tResourceType.kResourceType_I2C, deviceAddress);
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  @Override
+  public void close() {
+    I2CJNI.i2CClose(m_port);
+  }
+
+  /**
+   * Generic transaction.
+   *
+   * <p>This is a lower-level interface to the I2C hardware giving you more control over each
+   * transaction.
+   *
+   * @param dataToSend   Buffer of data to send as part of the transaction.
+   * @param sendSize     Number of bytes to send as part of the transaction.
+   * @param dataReceived Buffer to read data into.
+   * @param receiveSize  Number of bytes to read from the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  public synchronized boolean transaction(byte[] dataToSend, int sendSize,
+                                          byte[] dataReceived, int receiveSize) {
+    if (dataToSend.length < sendSize) {
+      throw new IllegalArgumentException("dataToSend is too small, must be at least " + sendSize);
+    }
+    if (dataReceived.length < receiveSize) {
+      throw new IllegalArgumentException(
+          "dataReceived is too small, must be at least " + receiveSize);
+    }
+    return I2CJNI.i2CTransactionB(m_port, (byte) m_deviceAddress, dataToSend,
+                                  (byte) sendSize, dataReceived, (byte) receiveSize) < 0;
+  }
+
+  /**
+   * Generic transaction.
+   *
+   * <p>This is a lower-level interface to the I2C hardware giving you more control over each
+   * transaction.
+   *
+   * @param dataToSend   Buffer of data to send as part of the transaction.
+   * @param sendSize     Number of bytes to send as part of the transaction.
+   * @param dataReceived Buffer to read data into.
+   * @param receiveSize  Number of bytes to read from the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  @SuppressWarnings({"PMD.CyclomaticComplexity", "ByteBufferBackingArray"})
+  public synchronized boolean transaction(ByteBuffer dataToSend, int sendSize,
+                                          ByteBuffer dataReceived, int receiveSize) {
+    if (dataToSend.hasArray() && dataReceived.hasArray()) {
+      return transaction(dataToSend.array(), sendSize, dataReceived.array(), receiveSize);
+    }
+    if (!dataToSend.isDirect()) {
+      throw new IllegalArgumentException("dataToSend must be a direct buffer");
+    }
+    if (dataToSend.capacity() < sendSize) {
+      throw new IllegalArgumentException("dataToSend is too small, must be at least " + sendSize);
+    }
+    if (!dataReceived.isDirect()) {
+      throw new IllegalArgumentException("dataReceived must be a direct buffer");
+    }
+    if (dataReceived.capacity() < receiveSize) {
+      throw new IllegalArgumentException(
+          "dataReceived is too small, must be at least " + receiveSize);
+    }
+
+    return I2CJNI.i2CTransaction(m_port, (byte) m_deviceAddress, dataToSend,
+                                 (byte) sendSize, dataReceived, (byte) receiveSize) < 0;
+  }
+
+  /**
+   * Attempt to address a device on the I2C bus.
+   *
+   * <p>This allows you to figure out if there is a device on the I2C bus that responds to the
+   * address specified in the constructor.
+   *
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  public boolean addressOnly() {
+    return transaction(new byte[0], (byte) 0, new byte[0], (byte) 0);
+  }
+
+  /**
+   * Execute a write transaction with the device.
+   *
+   * <p>Write a single byte to a register on a device and wait until the transaction is complete.
+   *
+   * @param registerAddress The address of the register on the device to be written.
+   * @param data            The byte to write to the register on the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  public synchronized boolean write(int registerAddress, int data) {
+    byte[] buffer = new byte[2];
+    buffer[0] = (byte) registerAddress;
+    buffer[1] = (byte) data;
+    return I2CJNI.i2CWriteB(m_port, (byte) m_deviceAddress, buffer,
+                            (byte) buffer.length) < 0;
+  }
+
+  /**
+   * Execute a write transaction with the device.
+   *
+   * <p>Write multiple bytes to a register on a device and wait until the transaction is complete.
+   *
+   * @param data The data to write to the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  public synchronized boolean writeBulk(byte[] data) {
+    return writeBulk(data, data.length);
+  }
+
+  /**
+   * Execute a write transaction with the device.
+   *
+   * <p>Write multiple bytes to a register on a device and wait until the transaction is complete.
+   *
+   * @param data The data to write to the device.
+   * @param size The number of data bytes to write.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  public synchronized boolean writeBulk(byte[] data, int size) {
+    if (data.length < size) {
+      throw new IllegalArgumentException(
+          "buffer is too small, must be at least " + size);
+    }
+    return I2CJNI.i2CWriteB(m_port, (byte) m_deviceAddress, data, (byte) size) < 0;
+  }
+
+  /**
+   * Execute a write transaction with the device.
+   *
+   * <p>Write multiple bytes to a register on a device and wait until the transaction is complete.
+   *
+   * @param data The data to write to the device.
+   * @param size The number of data bytes to write.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  @SuppressWarnings("ByteBufferBackingArray")
+  public synchronized boolean writeBulk(ByteBuffer data, int size) {
+    if (data.hasArray()) {
+      return writeBulk(data.array(), size);
+    }
+    if (!data.isDirect()) {
+      throw new IllegalArgumentException("must be a direct buffer");
+    }
+    if (data.capacity() < size) {
+      throw new IllegalArgumentException(
+          "buffer is too small, must be at least " + size);
+    }
+
+    return I2CJNI.i2CWrite(m_port, (byte) m_deviceAddress, data, (byte) size) < 0;
+  }
+
+  /**
+   * Execute a read transaction with the device.
+   *
+   * <p>Read bytes from a device. Most I2C devices will auto-increment the register pointer
+   * internally allowing you to read consecutive registers on a device in a single transaction.
+   *
+   * @param registerAddress The register to read first in the transaction.
+   * @param count           The number of bytes to read in the transaction.
+   * @param buffer          A pointer to the array of bytes to store the data read from the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  public boolean read(int registerAddress, int count, byte[] buffer) {
+    requireNonNull(buffer, "Null return buffer was given");
+
+    if (count < 1) {
+      throw new BoundaryException("Value must be at least 1, " + count + " given");
+    }
+    if (buffer.length < count) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + count);
+    }
+
+    byte[] registerAddressArray = new byte[1];
+    registerAddressArray[0] = (byte) registerAddress;
+
+    return transaction(registerAddressArray, registerAddressArray.length, buffer, count);
+  }
+
+  private ByteBuffer m_readDataToSendBuffer;
+
+  /**
+   * Execute a read transaction with the device.
+   *
+   * <p>Read bytes from a device. Most I2C devices will auto-increment the register pointer
+   * internally allowing you to read consecutive registers on a device in a single transaction.
+   *
+   * @param registerAddress The register to read first in the transaction.
+   * @param count           The number of bytes to read in the transaction.
+   * @param buffer          A buffer to store the data read from the device.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  @SuppressWarnings("ByteBufferBackingArray")
+  public boolean read(int registerAddress, int count, ByteBuffer buffer) {
+    if (count < 1) {
+      throw new BoundaryException("Value must be at least 1, " + count + " given");
+    }
+
+    if (buffer.hasArray()) {
+      return read(registerAddress, count, buffer.array());
+    }
+
+    if (!buffer.isDirect()) {
+      throw new IllegalArgumentException("must be a direct buffer");
+    }
+    if (buffer.capacity() < count) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + count);
+    }
+
+    synchronized (this) {
+      if (m_readDataToSendBuffer == null) {
+        m_readDataToSendBuffer = ByteBuffer.allocateDirect(1);
+      }
+      m_readDataToSendBuffer.put(0, (byte) registerAddress);
+
+      return transaction(m_readDataToSendBuffer, 1, buffer, count);
+    }
+  }
+
+  /**
+   * Execute a read only transaction with the device.
+   *
+   * <p>Read bytes from a device. This method does not write any data to prompt the device.
+   *
+   * @param buffer A pointer to the array of bytes to store the data read from the device.
+   * @param count  The number of bytes to read in the transaction.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  public boolean readOnly(byte[] buffer, int count) {
+    requireNonNull(buffer, "Null return buffer was given");
+    if (count < 1) {
+      throw new BoundaryException("Value must be at least 1, " + count + " given");
+    }
+    if (buffer.length < count) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + count);
+    }
+
+    return I2CJNI.i2CReadB(m_port, (byte) m_deviceAddress, buffer,
+                           (byte) count) < 0;
+  }
+
+  /**
+   * Execute a read only transaction with the device.
+   *
+   * <p>Read bytes from a device. This method does not write any data to prompt the device.
+   *
+   * @param buffer A pointer to the array of bytes to store the data read from the device.
+   * @param count  The number of bytes to read in the transaction.
+   * @return Transfer Aborted... false for success, true for aborted.
+   */
+  @SuppressWarnings("ByteBufferBackingArray")
+  public boolean readOnly(ByteBuffer buffer, int count) {
+    if (count < 1) {
+      throw new BoundaryException("Value must be at least 1, " + count
+          + " given");
+    }
+
+    if (buffer.hasArray()) {
+      return readOnly(buffer.array(), count);
+    }
+
+    if (!buffer.isDirect()) {
+      throw new IllegalArgumentException("must be a direct buffer");
+    }
+    if (buffer.capacity() < count) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + count);
+    }
+
+    return I2CJNI.i2CRead(m_port, (byte) m_deviceAddress, buffer, (byte) count)
+        < 0;
+  }
+
+  /*
+   * Send a broadcast write to all devices on the I2C bus.
+   *
+   * <p>This is not currently implemented!
+   *
+   * @param registerAddress The register to write on all devices on the bus.
+   * @param data            The value to write to the devices.
+   */
+  // public void broadcast(int registerAddress, int data) {
+  // }
+
+  /**
+   * Verify that a device's registers contain expected values.
+   *
+   * <p>Most devices will have a set of registers that contain a known value that can be used to
+   * identify them. This allows an I2C device driver to easily verify that the device contains the
+   * expected value.
+   *
+   * @param registerAddress The base register to start reading from the device.
+   * @param count           The size of the field to be verified.
+   * @param expected        A buffer containing the values expected from the device.
+   * @return true if the sensor was verified to be connected
+   * @pre The device must support and be configured to use register auto-increment.
+   */
+  public boolean verifySensor(int registerAddress, int count,
+                              byte[] expected) {
+    // TODO: Make use of all 7 read bytes
+    byte[] dataToSend = new byte[1];
+
+    byte[] deviceData = new byte[4];
+    for (int i = 0; i < count; i += 4) {
+      int toRead = count - i < 4 ? count - i : 4;
+      // Read the chunk of data. Return false if the sensor does not
+      // respond.
+      dataToSend[0] = (byte) (registerAddress + i);
+      if (transaction(dataToSend, 1, deviceData, toRead)) {
+        return false;
+      }
+
+      for (byte j = 0; j < toRead; j++) {
+        if (deviceData[j] != expected[i + j]) {
+          return false;
+        }
+      }
+    }
+    return true;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptHandlerFunction.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptHandlerFunction.java
new file mode 100644
index 0000000..6fd807b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptHandlerFunction.java
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.InterruptJNI.InterruptJNIHandlerFunction;
+
+
+/**
+ * It is recommended that you use this class in conjunction with classes from {@link
+ * java.util.concurrent.atomic} as these objects are all thread safe.
+ *
+ * @param <T> The type of the parameter that should be returned to the the method {@link
+ *            #interruptFired(int, Object)}
+ */
+public abstract class InterruptHandlerFunction<T> {
+  /**
+   * The entry point for the interrupt. When the interrupt fires the {@link #apply(int, Object)}
+   * method is called. The outer class is provided as an interface to allow the implementer to pass
+   * a generic object to the interrupt fired method.
+   */
+  private class Function implements InterruptJNIHandlerFunction {
+    @SuppressWarnings("unchecked")
+    @Override
+    public void apply(int interruptAssertedMask, Object param) {
+      interruptFired(interruptAssertedMask, (T) param);
+    }
+  }
+
+  final Function m_function = new Function();
+
+  /**
+   * This method is run every time an interrupt is fired.
+   *
+   * @param interruptAssertedMask Interrupt Mask
+   * @param param                 The parameter provided by overriding the {@link
+   *                              #overridableParameter()} method.
+   */
+  public abstract void interruptFired(int interruptAssertedMask, T param);
+
+
+  /**
+   * Override this method if you would like to pass a specific parameter to the {@link
+   * #interruptFired(int, Object)} when it is fired by the interrupt. This method is called once
+   * when {@link InterruptableSensorBase#requestInterrupts(InterruptHandlerFunction)} is run.
+   *
+   * @return The object that should be passed to the interrupt when it runs
+   */
+  public T overridableParameter() {
+    return null;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java
new file mode 100644
index 0000000..cc10fe1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/InterruptableSensorBase.java
@@ -0,0 +1,249 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.InterruptJNI;
+import edu.wpi.first.hal.util.AllocationException;
+
+
+/**
+ * Base for sensors to be used with interrupts.
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public abstract class InterruptableSensorBase extends SendableBase {
+  @SuppressWarnings("JavadocMethod")
+  public enum WaitResult {
+    kTimeout(0x0), kRisingEdge(0x1), kFallingEdge(0x100), kBoth(0x101);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    WaitResult(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * The interrupt resource.
+   */
+  protected int m_interrupt = InterruptJNI.HalInvalidHandle;
+
+  /**
+   * Flags if the interrupt being allocated is synchronous.
+   */
+  protected boolean m_isSynchronousInterrupt;
+
+  /**
+   * Create a new InterrupatableSensorBase.
+   */
+  public InterruptableSensorBase() {
+    m_interrupt = 0;
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    if (m_interrupt != 0) {
+      cancelInterrupts();
+    }
+  }
+
+  /**
+   * If this is an analog trigger.
+   *
+   * @return true if this is an analog trigger.
+   */
+  public abstract int getAnalogTriggerTypeForRouting();
+
+  /**
+   * The channel routing number.
+   *
+   * @return channel routing number
+   */
+  public abstract int getPortHandleForRouting();
+
+  /**
+   * Request one of the 8 interrupts asynchronously on this digital input.
+   *
+   * @param handler The {@link InterruptHandlerFunction} that contains the method {@link
+   *                InterruptHandlerFunction#interruptFired(int, Object)} that will be called
+   *                whenever there is an interrupt on this device. Request interrupts in synchronous
+   *                mode where the user program interrupt handler will be called when an interrupt
+   *                occurs. The default is interrupt on rising edges only.
+   */
+  public void requestInterrupts(InterruptHandlerFunction<?> handler) {
+    if (m_interrupt != 0) {
+      throw new AllocationException("The interrupt has already been allocated");
+    }
+
+    allocateInterrupts(false);
+
+    assert m_interrupt != 0;
+
+    InterruptJNI.requestInterrupts(m_interrupt, getPortHandleForRouting(),
+        getAnalogTriggerTypeForRouting());
+    setUpSourceEdge(true, false);
+    InterruptJNI.attachInterruptHandler(m_interrupt, handler.m_function,
+        handler.overridableParameter());
+  }
+
+  /**
+   * Request one of the 8 interrupts synchronously on this digital input. Request interrupts in
+   * synchronous mode where the user program will have to explicitly wait for the interrupt to occur
+   * using {@link #waitForInterrupt}. The default is interrupt on rising edges only.
+   */
+  public void requestInterrupts() {
+    if (m_interrupt != 0) {
+      throw new AllocationException("The interrupt has already been allocated");
+    }
+
+    allocateInterrupts(true);
+
+    assert m_interrupt != 0;
+
+    InterruptJNI.requestInterrupts(m_interrupt, getPortHandleForRouting(),
+        getAnalogTriggerTypeForRouting());
+    setUpSourceEdge(true, false);
+
+  }
+
+  /**
+   * Allocate the interrupt.
+   *
+   * @param watcher true if the interrupt should be in synchronous mode where the user program will
+   *                have to explicitly wait for the interrupt to occur.
+   */
+  protected void allocateInterrupts(boolean watcher) {
+    m_isSynchronousInterrupt = watcher;
+
+    m_interrupt = InterruptJNI.initializeInterrupts(watcher);
+  }
+
+  /**
+   * Cancel interrupts on this device. This deallocates all the chipobject structures and disables
+   * any interrupts.
+   */
+  public void cancelInterrupts() {
+    if (m_interrupt == 0) {
+      throw new IllegalStateException("The interrupt is not allocated.");
+    }
+    InterruptJNI.cleanInterrupts(m_interrupt);
+    m_interrupt = 0;
+  }
+
+  /**
+   * In synchronous mode, wait for the defined interrupt to occur.
+   *
+   * @param timeout        Timeout in seconds
+   * @param ignorePrevious If true, ignore interrupts that happened before waitForInterrupt was
+   *                       called.
+   * @return Result of the wait.
+   */
+  public WaitResult waitForInterrupt(double timeout, boolean ignorePrevious) {
+    if (m_interrupt == 0) {
+      throw new IllegalStateException("The interrupt is not allocated.");
+    }
+    int result = InterruptJNI.waitForInterrupt(m_interrupt, timeout, ignorePrevious);
+
+    // Rising edge result is the interrupt bit set in the byte 0xFF
+    // Falling edge result is the interrupt bit set in the byte 0xFF00
+    // Set any bit set to be true for that edge, and AND the 2 results
+    // together to match the existing enum for all interrupts
+    int rising = ((result & 0xFF) != 0) ? 0x1 : 0x0;
+    int falling = ((result & 0xFF00) != 0) ? 0x0100 : 0x0;
+    result = rising | falling;
+
+    for (WaitResult mode : WaitResult.values()) {
+      if (mode.value == result) {
+        return mode;
+      }
+    }
+    return null;
+  }
+
+  /**
+   * In synchronous mode, wait for the defined interrupt to occur.
+   *
+   * @param timeout Timeout in seconds
+   * @return Result of the wait.
+   */
+  public WaitResult waitForInterrupt(double timeout) {
+    return waitForInterrupt(timeout, true);
+  }
+
+  /**
+   * Enable interrupts to occur on this input. Interrupts are disabled when the RequestInterrupt
+   * call is made. This gives time to do the setup of the other options before starting to field
+   * interrupts.
+   */
+  public void enableInterrupts() {
+    if (m_interrupt == 0) {
+      throw new IllegalStateException("The interrupt is not allocated.");
+    }
+    if (m_isSynchronousInterrupt) {
+      throw new IllegalStateException("You do not need to enable synchronous interrupts");
+    }
+    InterruptJNI.enableInterrupts(m_interrupt);
+  }
+
+  /**
+   * Disable Interrupts without without deallocating structures.
+   */
+  public void disableInterrupts() {
+    if (m_interrupt == 0) {
+      throw new IllegalStateException("The interrupt is not allocated.");
+    }
+    if (m_isSynchronousInterrupt) {
+      throw new IllegalStateException("You can not disable synchronous interrupts");
+    }
+    InterruptJNI.disableInterrupts(m_interrupt);
+  }
+
+  /**
+   * Return the timestamp for the rising interrupt that occurred most recently. This is in the same
+   * time domain as getClock(). The rising-edge interrupt should be enabled with {@link
+   * #setUpSourceEdge}.
+   *
+   * @return Timestamp in seconds since boot.
+   */
+  public double readRisingTimestamp() {
+    if (m_interrupt == 0) {
+      throw new IllegalStateException("The interrupt is not allocated.");
+    }
+    return InterruptJNI.readInterruptRisingTimestamp(m_interrupt) * 1e-6;
+  }
+
+  /**
+   * Return the timestamp for the falling interrupt that occurred most recently. This is in the same
+   * time domain as getClock(). The falling-edge interrupt should be enabled with {@link
+   * #setUpSourceEdge}.
+   *
+   * @return Timestamp in seconds since boot.
+   */
+  public double readFallingTimestamp() {
+    if (m_interrupt == 0) {
+      throw new IllegalStateException("The interrupt is not allocated.");
+    }
+    return InterruptJNI.readInterruptFallingTimestamp(m_interrupt) * 1e-6;
+  }
+
+  /**
+   * Set which edge to trigger interrupts on.
+   *
+   * @param risingEdge  true to interrupt on rising edge
+   * @param fallingEdge true to interrupt on falling edge
+   */
+  public void setUpSourceEdge(boolean risingEdge, boolean fallingEdge) {
+    if (m_interrupt != 0) {
+      InterruptJNI.setInterruptUpSourceEdge(m_interrupt, risingEdge,
+          fallingEdge);
+    } else {
+      throw new IllegalArgumentException("You must call RequestInterrupts before setUpSourceEdge");
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobot.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobot.java
new file mode 100644
index 0000000..e72033e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobot.java
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * IterativeRobot implements the IterativeRobotBase robot program framework.
+ *
+ * <p>The IterativeRobot class is intended to be subclassed by a user creating a robot program.
+ *
+ * <p>periodic() functions from the base class are called each time a new packet is received from
+ * the driver station.
+ *
+ * @deprecated Use TimedRobot instead. It's a drop-in replacement that provides more regular
+ *     execution periods.
+ */
+@Deprecated
+public class IterativeRobot extends IterativeRobotBase {
+  private static final double kPacketPeriod = 0.02;
+
+  /**
+   * Create a new IterativeRobot.
+   */
+  public IterativeRobot() {
+    super(kPacketPeriod);
+
+    HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Iterative);
+  }
+
+  /**
+   * Provide an alternate "main loop" via startCompetition().
+   */
+  @Override
+  public void startCompetition() {
+    robotInit();
+
+    // Tell the DS that the robot is ready to be enabled
+    HAL.observeUserProgramStarting();
+
+    // Loop forever, calling the appropriate mode-dependent function
+    while (true) {
+      // Wait for new data to arrive
+      m_ds.waitForData();
+
+      loopFunc();
+    }
+  }
+}
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
new file mode 100644
index 0000000..ee13ef9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/IterativeRobotBase.java
@@ -0,0 +1,275 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+/**
+ * IterativeRobotBase implements a specific type of robot program framework, extending the RobotBase
+ * class.
+ *
+ * <p>The IterativeRobotBase class does not implement startCompetition(), so it should not be used
+ * by teams directly.
+ *
+ * <p>This class provides the following functions which are called by the main loop,
+ * startCompetition(), at the appropriate times:
+ *
+ * <p>robotInit() -- provide for initialization at robot power-on
+ *
+ * <p>init() functions -- each of the following functions is called once when the
+ * appropriate mode is entered:
+ *   - disabledInit()   -- called each and every time disabled is entered from
+ *                         another mode
+ *   - autonomousInit() -- called each and every time autonomous is entered from
+ *                         another mode
+ *   - teleopInit()     -- called each and every time teleop is entered from
+ *                         another mode
+ *   - testInit()       -- called each and every time test is entered from
+ *                         another mode
+ *
+ * <p>periodic() functions -- each of these functions is called on an interval:
+ *   - robotPeriodic()
+ *   - disabledPeriodic()
+ *   - autonomousPeriodic()
+ *   - teleopPeriodic()
+ *   - testPeriodic()
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public abstract class IterativeRobotBase extends RobotBase {
+  protected double m_period;
+
+  private enum Mode {
+    kNone,
+    kDisabled,
+    kAutonomous,
+    kTeleop,
+    kTest
+  }
+
+  private Mode m_lastMode = Mode.kNone;
+  private final Watchdog m_watchdog;
+
+  /**
+   * Constructor for IterativeRobotBase.
+   *
+   * @param period Period in seconds.
+   */
+  protected IterativeRobotBase(double period) {
+    m_period = period;
+    m_watchdog = new Watchdog(period, this::printLoopOverrunMessage);
+  }
+
+  /**
+   * Provide an alternate "main loop" via startCompetition().
+   */
+  @Override
+  public abstract void startCompetition();
+
+  /* ----------- Overridable initialization code ----------------- */
+
+  /**
+   * Robot-wide initialization code should go here.
+   *
+   * <p>Users should override this method for default Robot-wide initialization which will be called
+   * when the robot is first powered on. It will be called exactly one time.
+   *
+   * <p>Warning: the Driver Station "Robot Code" light and FMS "Robot Ready" indicators will be off
+   * until RobotInit() exits. Code in RobotInit() that waits for enable will cause the robot to
+   * 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!");
+  }
+
+  /**
+   * Initialization code for disabled mode should go here.
+   *
+   * <p>Users should override this method for initialization code which will be called each time the
+   * robot enters disabled mode.
+   */
+  public void disabledInit() {
+    System.out.println("Default disabledInit() method... Overload me!");
+  }
+
+  /**
+   * Initialization code for autonomous mode should go here.
+   *
+   * <p>Users should override this method for initialization code which will be called each time the
+   * robot enters autonomous mode.
+   */
+  public void autonomousInit() {
+    System.out.println("Default autonomousInit() method... Overload me!");
+  }
+
+  /**
+   * Initialization code for teleop mode should go here.
+   *
+   * <p>Users should override this method for initialization code which will be called each time the
+   * robot enters teleop mode.
+   */
+  public void teleopInit() {
+    System.out.println("Default teleopInit() method... Overload me!");
+  }
+
+  /**
+   * Initialization code for test mode should go here.
+   *
+   * <p>Users should override this method for initialization code which will be called each time the
+   * robot enters test mode.
+   */
+  @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
+  public void testInit() {
+    System.out.println("Default testInit() method... Overload me!");
+  }
+
+  /* ----------- Overridable periodic code ----------------- */
+
+  private boolean m_rpFirstRun = true;
+
+  /**
+   * Periodic code for all robot modes should go here.
+   */
+  public void robotPeriodic() {
+    if (m_rpFirstRun) {
+      System.out.println("Default robotPeriodic() method... Overload me!");
+      m_rpFirstRun = false;
+    }
+  }
+
+  private boolean m_dpFirstRun = true;
+
+  /**
+   * Periodic code for disabled mode should go here.
+   */
+  public void disabledPeriodic() {
+    if (m_dpFirstRun) {
+      System.out.println("Default disabledPeriodic() method... Overload me!");
+      m_dpFirstRun = false;
+    }
+  }
+
+  private boolean m_apFirstRun = true;
+
+  /**
+   * Periodic code for autonomous mode should go here.
+   */
+  public void autonomousPeriodic() {
+    if (m_apFirstRun) {
+      System.out.println("Default autonomousPeriodic() method... Overload me!");
+      m_apFirstRun = false;
+    }
+  }
+
+  private boolean m_tpFirstRun = true;
+
+  /**
+   * Periodic code for teleop mode should go here.
+   */
+  public void teleopPeriodic() {
+    if (m_tpFirstRun) {
+      System.out.println("Default teleopPeriodic() method... Overload me!");
+      m_tpFirstRun = false;
+    }
+  }
+
+  private boolean m_tmpFirstRun = true;
+
+  /**
+   * Periodic code for test mode should go here.
+   */
+  @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
+  public void testPeriodic() {
+    if (m_tmpFirstRun) {
+      System.out.println("Default testPeriodic() method... Overload me!");
+      m_tmpFirstRun = false;
+    }
+  }
+
+  protected void loopFunc() {
+    m_watchdog.reset();
+
+    // Call the appropriate function depending upon the current robot mode
+    if (isDisabled()) {
+      // 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.setEnabled(false);
+        Shuffleboard.disableActuatorWidgets();
+        disabledInit();
+        m_watchdog.addEpoch("disabledInit()");
+        m_lastMode = Mode.kDisabled;
+      }
+
+      HAL.observeUserProgramDisabled();
+      disabledPeriodic();
+      m_watchdog.addEpoch("disablePeriodic()");
+    } else if (isAutonomous()) {
+      // 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.setEnabled(false);
+        Shuffleboard.disableActuatorWidgets();
+        autonomousInit();
+        m_watchdog.addEpoch("autonomousInit()");
+        m_lastMode = Mode.kAutonomous;
+      }
+
+      HAL.observeUserProgramAutonomous();
+      autonomousPeriodic();
+      m_watchdog.addEpoch("autonomousPeriodic()");
+    } else if (isOperatorControl()) {
+      // 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.setEnabled(false);
+        Shuffleboard.disableActuatorWidgets();
+        teleopInit();
+        m_watchdog.addEpoch("teleopInit()");
+        m_lastMode = Mode.kTeleop;
+      }
+
+      HAL.observeUserProgramTeleop();
+      teleopPeriodic();
+      m_watchdog.addEpoch("teleopPeriodic()");
+    } else {
+      // 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.setEnabled(true);
+        Shuffleboard.enableActuatorWidgets();
+        testInit();
+        m_watchdog.addEpoch("testInit()");
+        m_lastMode = Mode.kTest;
+      }
+
+      HAL.observeUserProgramTest();
+      testPeriodic();
+      m_watchdog.addEpoch("testPeriodic()");
+    }
+
+    robotPeriodic();
+    m_watchdog.addEpoch("robotPeriodic()");
+    m_watchdog.disable();
+    SmartDashboard.updateValues();
+
+    LiveWindow.updateValues();
+    Shuffleboard.update();
+
+    // Warn on loop time overruns
+    if (m_watchdog.isExpired()) {
+      m_watchdog.printEpochs();
+    }
+  }
+
+  private void printLoopOverrunMessage() {
+    DriverStation.reportWarning("Loop time of " + m_period + "s overrun\n", false);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Jaguar.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Jaguar.java
new file mode 100644
index 0000000..934e70b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Jaguar.java
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * Texas Instruments / Vex Robotics Jaguar Speed Controller as a PWM device.
+ */
+public class Jaguar extends PWMSpeedController {
+  /**
+   * Constructor.
+   *
+   * @param channel The PWM channel that the Jaguar is attached to. 0-9 are on-board, 10-19 are on
+   *                the MXP port
+   */
+  public Jaguar(final int channel) {
+    super(channel);
+
+    /*
+     * Input profile defined by Luminary Micro.
+     *
+     * Full reverse ranges from 0.671325ms to 0.6972211ms Proportional reverse
+     * ranges from 0.6972211ms to 1.4482078ms Neutral ranges from 1.4482078ms to
+     * 1.5517922ms Proportional forward ranges from 1.5517922ms to 2.3027789ms
+     * Full forward ranges from 2.3027789ms to 2.328675ms
+     */
+    setBounds(2.31, 1.55, 1.507, 1.454, .697);
+    setPeriodMultiplier(PeriodMultiplier.k1X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_Jaguar, getChannel());
+    setName("Jaguar", getChannel());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java
new file mode 100644
index 0000000..bb7ef81
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Joystick.java
@@ -0,0 +1,404 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * Handle input from standard Joysticks connected to the Driver Station.
+ *
+ * <p>This class handles standard input that comes from the Driver Station. Each time a value is
+ * requested the most recent value is returned. There is a single class instance for each joystick
+ * and the mapping of ports to hardware buttons depends on the code in the Driver Station.
+ */
+public class Joystick extends GenericHID {
+  static final byte kDefaultXChannel = 0;
+  static final byte kDefaultYChannel = 1;
+  static final byte kDefaultZChannel = 2;
+  static final byte kDefaultTwistChannel = 2;
+  static final byte kDefaultThrottleChannel = 3;
+
+  @Deprecated
+  static final byte kDefaultXAxis = 0;
+  @Deprecated
+  static final byte kDefaultYAxis = 1;
+  @Deprecated
+  static final byte kDefaultZAxis = 2;
+  @Deprecated
+  static final byte kDefaultTwistAxis = 2;
+  @Deprecated
+  static final byte kDefaultThrottleAxis = 3;
+
+  /**
+   * Represents an analog axis on a joystick.
+   */
+  public enum AxisType {
+    kX(0), kY(1), kZ(2), kTwist(3), kThrottle(4);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    AxisType(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Represents a digital button on a joystick.
+   */
+  public enum ButtonType {
+    kTrigger(1), kTop(2);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    ButtonType(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Represents a digital button on a joystick.
+   */
+  private enum Button {
+    kTrigger(1), kTop(2);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    Button(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Represents an analog axis on a joystick.
+   */
+  private enum Axis {
+    kX(0), kY(1), kZ(2), kTwist(3), kThrottle(4), kNumAxes(5);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    Axis(int value) {
+      this.value = value;
+    }
+  }
+
+  private final byte[] m_axes = new byte[Axis.kNumAxes.value];
+
+  /**
+   * Construct an instance of a joystick. The joystick index is the USB port on the drivers
+   * station.
+   *
+   * @param port The port on the Driver Station that the joystick is plugged into.
+   */
+  public Joystick(final int port) {
+    super(port);
+
+    m_axes[Axis.kX.value] = kDefaultXChannel;
+    m_axes[Axis.kY.value] = kDefaultYChannel;
+    m_axes[Axis.kZ.value] = kDefaultZChannel;
+    m_axes[Axis.kTwist.value] = kDefaultTwistChannel;
+    m_axes[Axis.kThrottle.value] = kDefaultThrottleChannel;
+
+    HAL.report(tResourceType.kResourceType_Joystick, port);
+  }
+
+  /**
+   * Set the channel associated with the X axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setXChannel(int channel) {
+    m_axes[Axis.kX.value] = (byte) channel;
+  }
+
+  /**
+   * Set the channel associated with the Y axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setYChannel(int channel) {
+    m_axes[Axis.kY.value] = (byte) channel;
+  }
+
+  /**
+   * Set the channel associated with the Z axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setZChannel(int channel) {
+    m_axes[Axis.kZ.value] = (byte) channel;
+  }
+
+  /**
+   * Set the channel associated with the throttle axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setThrottleChannel(int channel) {
+    m_axes[Axis.kThrottle.value] = (byte) channel;
+  }
+
+  /**
+   * Set the channel associated with the twist axis.
+   *
+   * @param channel The channel to set the axis to.
+   */
+  public void setTwistChannel(int channel) {
+    m_axes[Axis.kTwist.value] = (byte) channel;
+  }
+
+  /**
+   * Set the channel associated with a specified axis.
+   *
+   * @deprecated    Use the more specific axis channel setter functions.
+   * @param axis    The axis to set the channel for.
+   * @param channel The channel to set the axis to.
+   */
+  @Deprecated
+  public void setAxisChannel(AxisType axis, int channel) {
+    m_axes[axis.value] = (byte) channel;
+  }
+
+  /**
+   * Get the channel currently associated with the X axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getXChannel() {
+    return m_axes[Axis.kX.value];
+  }
+
+  /**
+   * Get the channel currently associated with the Y axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getYChannel() {
+    return m_axes[Axis.kY.value];
+  }
+
+  /**
+   * Get the channel currently associated with the Z axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getZChannel() {
+    return m_axes[Axis.kZ.value];
+  }
+
+  /**
+   * Get the channel currently associated with the twist axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getTwistChannel() {
+    return m_axes[Axis.kTwist.value];
+  }
+
+  /**
+   * Get the channel currently associated with the throttle axis.
+   *
+   * @return The channel for the axis.
+   */
+  public int getThrottleChannel() {
+    return m_axes[Axis.kThrottle.value];
+  }
+
+  /**
+   * Get the channel currently associated with the specified axis.
+   *
+   * @deprecated Use the more specific axis channel getter functions.
+   * @param axis The axis to look up the channel for.
+   * @return The channel for the axis.
+   */
+  @Deprecated
+  public int getAxisChannel(AxisType axis) {
+    return m_axes[axis.value];
+  }
+
+  /**
+   * Get the X value of the joystick. This depends on the mapping of the joystick connected to the
+   * current port.
+   *
+   * @param hand Unused
+   * @return The X value of the joystick.
+   */
+  @Override
+  public final double getX(Hand hand) {
+    return getRawAxis(m_axes[Axis.kX.value]);
+  }
+
+  /**
+   * Get the Y value of the joystick. This depends on the mapping of the joystick connected to the
+   * current port.
+   *
+   * @param hand Unused
+   * @return The Y value of the joystick.
+   */
+  @Override
+  public final double getY(Hand hand) {
+    return getRawAxis(m_axes[Axis.kY.value]);
+  }
+
+  /**
+   * Get the z position of the HID.
+   *
+   * @return the z position
+   */
+  public double getZ() {
+    return getRawAxis(m_axes[Axis.kZ.value]);
+  }
+
+  /**
+   * Get the twist value of the current joystick. This depends on the mapping of the joystick
+   * connected to the current port.
+   *
+   * @return The Twist value of the joystick.
+   */
+  public double getTwist() {
+    return getRawAxis(m_axes[Axis.kTwist.value]);
+  }
+
+  /**
+   * Get the throttle value of the current joystick. This depends on the mapping of the joystick
+   * connected to the current port.
+   *
+   * @return The Throttle value of the joystick.
+   */
+  public double getThrottle() {
+    return getRawAxis(m_axes[Axis.kThrottle.value]);
+  }
+
+  /**
+   * For the current joystick, return the axis determined by the argument.
+   *
+   * <p>This is for cases where the joystick axis is returned programmatically, otherwise one of the
+   * previous functions would be preferable (for example getX()).
+   *
+   * @deprecated Use the more specific axis getter functions.
+   * @param axis The axis to read.
+   * @return The value of the axis.
+   */
+  @Deprecated
+  public double getAxis(final AxisType axis) {
+    switch (axis) {
+      case kX:
+        return getX();
+      case kY:
+        return getY();
+      case kZ:
+        return getZ();
+      case kTwist:
+        return getTwist();
+      case kThrottle:
+        return getThrottle();
+      default:
+        return 0.0;
+    }
+  }
+
+  /**
+   * Read the state of the trigger on the joystick.
+   *
+   * @return The state of the trigger.
+   */
+  public boolean getTrigger() {
+    return getRawButton(Button.kTrigger.value);
+  }
+
+  /**
+   * Whether the trigger was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getTriggerPressed() {
+    return getRawButtonPressed(Button.kTrigger.value);
+  }
+
+  /**
+   * Whether the trigger was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getTriggerReleased() {
+    return getRawButtonReleased(Button.kTrigger.value);
+  }
+
+  /**
+   * Read the state of the top button on the joystick.
+   *
+   * @return The state of the top button.
+   */
+  public boolean getTop() {
+    return getRawButton(Button.kTop.value);
+  }
+
+  /**
+   * Whether the top button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getTopPressed() {
+    return getRawButtonPressed(Button.kTop.value);
+  }
+
+  /**
+   * Whether the top button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getTopReleased() {
+    return getRawButtonReleased(Button.kTop.value);
+  }
+
+  /**
+   * Get buttons based on an enumerated type.
+   *
+   * <p>The button type will be looked up in the list of buttons and then read.
+   *
+   * @deprecated Use Button enum values instead of ButtonType.
+   * @param button The type of button to read.
+   * @return The state of the button.
+   */
+  @Deprecated
+  public boolean getButton(ButtonType button) {
+    return getRawButton(button.value);
+  }
+
+  /**
+   * Get the magnitude of the direction vector formed by the joystick's current position relative to
+   * its origin.
+   *
+   * @return The magnitude of the direction vector
+   */
+  public double getMagnitude() {
+    return Math.sqrt(Math.pow(getX(), 2) + Math.pow(getY(), 2));
+  }
+
+  /**
+   * Get the direction of the vector formed by the joystick and its origin in radians.
+   *
+   * @return The direction of the vector in radians
+   */
+  public double getDirectionRadians() {
+    return Math.atan2(getX(), -getY());
+  }
+
+  /**
+   * Get the direction of the vector formed by the joystick and its origin in degrees.
+   *
+   * @return The direction of the vector in degrees
+   */
+  public double getDirectionDegrees() {
+    return Math.toDegrees(getDirectionRadians());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/JoystickBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/JoystickBase.java
new file mode 100644
index 0000000..56d4eba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/JoystickBase.java
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * JoystickBase Interface.
+ *
+ * @deprecated Inherit directly from GenericHID instead.
+ */
+@Deprecated
+public abstract class JoystickBase extends GenericHID {
+  public JoystickBase(int port) {
+    super(port);
+  }
+
+  /**
+   * Get the z position of the HID.
+   *
+   * @param hand which hand, left or right
+   * @return the z position
+   */
+  public abstract double getZ(Hand hand);
+
+  public double getZ() {
+    return getZ(Hand.kRight);
+  }
+
+  /**
+   * Get the twist value.
+   *
+   * @return the twist value
+   */
+  public abstract double getTwist();
+
+  /**
+   * Get the throttle.
+   *
+   * @return the throttle value
+   */
+  public abstract double getThrottle();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java
new file mode 100644
index 0000000..5dd3a4f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/MotorSafety.java
@@ -0,0 +1,150 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.LinkedHashSet;
+import java.util.Set;
+
+/**
+ * This base class runs a watchdog timer and calls the subclass's StopMotor()
+ * function if the timeout expires.
+ *
+ * <p>The subclass should call feed() whenever the motor value is updated.
+ */
+public abstract class MotorSafety {
+  private static final double kDefaultSafetyExpiration = 0.1;
+
+  private double m_expiration = kDefaultSafetyExpiration;
+  private boolean m_enabled;
+  private double m_stopTime = Timer.getFPGATimestamp();
+  private final Object m_thisMutex = new Object();
+  private static final Set<MotorSafety> m_instanceList = new LinkedHashSet<>();
+  private static final Object m_listMutex = new Object();
+
+  /**
+   * MotorSafety constructor.
+   */
+  public MotorSafety() {
+    synchronized (m_listMutex) {
+      m_instanceList.add(this);
+    }
+  }
+
+  /**
+   * Feed the motor safety object.
+   *
+   * <p>Resets the timer on this object that is used to do the timeouts.
+   */
+  public void feed() {
+    synchronized (m_thisMutex) {
+      m_stopTime = Timer.getFPGATimestamp() + m_expiration;
+    }
+  }
+
+  /**
+   * Set the expiration time for the corresponding motor safety object.
+   *
+   * @param expirationTime The timeout value in seconds.
+   */
+  public void setExpiration(double expirationTime) {
+    synchronized (m_thisMutex) {
+      m_expiration = expirationTime;
+    }
+  }
+
+  /**
+   * Retrieve the timeout value for the corresponding motor safety object.
+   *
+   * @return the timeout value in seconds.
+   */
+  public double getExpiration() {
+    synchronized (m_thisMutex) {
+      return m_expiration;
+    }
+  }
+
+  /**
+   * Determine of the motor is still operating or has timed out.
+   *
+   * @return a true value if the motor is still operating normally and hasn't timed out.
+   */
+  public boolean isAlive() {
+    synchronized (m_thisMutex) {
+      return !m_enabled || m_stopTime > Timer.getFPGATimestamp();
+    }
+  }
+
+  /**
+   * Check if this motor has exceeded its timeout. This method is called periodically to determine
+   * if this motor has exceeded its timeout value. If it has, the stop method is called, and the
+   * motor is shut down until its value is updated again.
+   */
+  public void check() {
+    boolean enabled;
+    double stopTime;
+
+    synchronized (m_thisMutex) {
+      enabled = m_enabled;
+      stopTime = m_stopTime;
+    }
+
+    if (!enabled || RobotState.isDisabled() || RobotState.isTest()) {
+      return;
+    }
+
+    if (stopTime < Timer.getFPGATimestamp()) {
+      DriverStation.reportError(getDescription() + "... Output not updated often enough.", false);
+
+      stopMotor();
+    }
+  }
+
+  /**
+   * Enable/disable motor safety for this device.
+   *
+   * <p>Turn on and off the motor safety option for this PWM object.
+   *
+   * @param enabled True if motor safety is enforced for this object
+   */
+  public void setSafetyEnabled(boolean enabled) {
+    synchronized (m_thisMutex) {
+      m_enabled = enabled;
+    }
+  }
+
+  /**
+   * Return the state of the motor safety enabled flag.
+   *
+   * <p>Return if the motor safety is currently enabled for this device.
+   *
+   * @return True if motor safety is enforced for this device
+   */
+  public boolean isSafetyEnabled() {
+    synchronized (m_thisMutex) {
+      return m_enabled;
+    }
+  }
+
+  /**
+   * Check the motors to see if any have timed out.
+   *
+   * <p>This static method is called periodically to poll all the motors and stop any that have
+   * timed out.
+   */
+  public static void checkMotors() {
+    synchronized (m_listMutex) {
+      for (MotorSafety elem : m_instanceList) {
+        elem.check();
+      }
+    }
+  }
+
+  public abstract void stopMotor();
+
+  public abstract String getDescription();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/NamedSendable.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/NamedSendable.java
new file mode 100644
index 0000000..bf972c9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/NamedSendable.java
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * The interface for sendable objects that gives the sendable a default name in the Smart
+ * Dashboard.
+ * @deprecated Use Sendable directly instead
+ */
+@Deprecated
+public interface NamedSendable extends Sendable {
+  /**
+   * The name of the subtable.
+   *
+   * @return the name of the subtable of SmartDashboard that the Sendable object will use.
+   */
+  @Override
+  String getName();
+
+  @Override
+  default void setName(String name) {
+  }
+
+  @Override
+  default String getSubsystem() {
+    return "";
+  }
+
+  @Override
+  default void setSubsystem(String subsystem) {
+  }
+
+  @Override
+  default void initSendable(SendableBuilder builder) {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java
new file mode 100644
index 0000000..f166b46
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/NidecBrushless.java
@@ -0,0 +1,210 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Nidec Brushless Motor.
+ */
+public class NidecBrushless extends MotorSafety implements SpeedController, Sendable,
+    AutoCloseable {
+  private boolean m_isInverted;
+  private final DigitalOutput m_dio;
+  private final PWM m_pwm;
+  private volatile double m_speed;
+  private volatile boolean m_disabled;
+
+  private final SendableImpl m_sendableImpl;
+
+  /**
+   * Constructor.
+   *
+   * @param pwmChannel The PWM channel that the Nidec Brushless controller is attached to.
+   *                   0-9 are on-board, 10-19 are on the MXP port
+   * @param dioChannel The DIO channel that the Nidec Brushless controller is attached to.
+   *                   0-9 are on-board, 10-25 are on the MXP port
+   */
+  public NidecBrushless(final int pwmChannel, final int dioChannel) {
+    m_sendableImpl = new SendableImpl(true);
+
+    setSafetyEnabled(false);
+
+    // the dio controls the output (in PWM mode)
+    m_dio = new DigitalOutput(dioChannel);
+    addChild(m_dio);
+    m_dio.setPWMRate(15625);
+    m_dio.enablePWM(0.5);
+
+    // the pwm enables the controller
+    m_pwm = new PWM(pwmChannel);
+    addChild(m_pwm);
+
+    HAL.report(tResourceType.kResourceType_NidecBrushless, pwmChannel);
+    setName("Nidec Brushless", pwmChannel);
+  }
+
+  @Override
+  public void close() {
+    m_sendableImpl.close();
+    m_dio.close();
+    m_pwm.close();
+  }
+
+  @Override
+  public final synchronized String getName() {
+    return m_sendableImpl.getName();
+  }
+
+  @Override
+  public final synchronized void setName(String name) {
+    m_sendableImpl.setName(name);
+  }
+
+  /**
+   * Sets the name of the sensor with a channel number.
+   *
+   * @param moduleType A string that defines the module name in the label for the value
+   * @param channel    The channel number the device is plugged into
+   */
+  protected final void setName(String moduleType, int channel) {
+    m_sendableImpl.setName(moduleType, channel);
+  }
+
+  /**
+   * Sets the name of the sensor with a module and channel number.
+   *
+   * @param moduleType   A string that defines the module name in the label for the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually PWM)
+   */
+  protected final void setName(String moduleType, int moduleNumber, int channel) {
+    m_sendableImpl.setName(moduleType, moduleNumber, channel);
+  }
+
+  @Override
+  public final synchronized String getSubsystem() {
+    return m_sendableImpl.getSubsystem();
+  }
+
+  @Override
+  public final synchronized void setSubsystem(String subsystem) {
+    m_sendableImpl.setSubsystem(subsystem);
+  }
+
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  protected final void addChild(Object child) {
+    m_sendableImpl.addChild(child);
+  }
+
+  /**
+   * Set the PWM value.
+   *
+   * <p>The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the
+   * FPGA.
+   *
+   * @param speed The speed value between -1.0 and 1.0 to set.
+   */
+  @Override
+  public void set(double speed) {
+    if (!m_disabled) {
+      m_speed = speed;
+      m_dio.updateDutyCycle(0.5 + 0.5 * (m_isInverted ? -speed : speed));
+      m_pwm.setRaw(0xffff);
+    }
+
+    feed();
+  }
+
+  /**
+   * Get the recently set value of the PWM.
+   *
+   * @return The most recently set value for the PWM between -1.0 and 1.0.
+   */
+  @Override
+  public double get() {
+    return m_speed;
+  }
+
+  @Override
+  public void setInverted(boolean isInverted) {
+    m_isInverted = isInverted;
+  }
+
+  @Override
+  public boolean getInverted() {
+    return m_isInverted;
+  }
+
+  /**
+   * Write out the PID value as seen in the PIDOutput base object.
+   *
+   * @param output Write out the PWM value as was found in the PIDController
+   */
+  @Override
+  public void pidWrite(double output) {
+    set(output);
+  }
+
+  /**
+   * Stop the motor. This is called by the MotorSafety object when it has a timeout for this PWM and
+   * needs to stop it from running. Calling set() will re-enable the motor.
+   */
+  @Override
+  public void stopMotor() {
+    m_dio.updateDutyCycle(0.5);
+    m_pwm.setDisabled();
+  }
+
+  @Override
+  public String getDescription() {
+    return "Nidec " + getChannel();
+  }
+
+  /**
+   * Disable the motor.  The enable() function must be called to re-enable
+   * the motor.
+   */
+  @Override
+  public void disable() {
+    m_disabled = true;
+    m_dio.updateDutyCycle(0.5);
+    m_pwm.setDisabled();
+  }
+
+  /**
+   * Re-enable the motor after disable() has been called.  The set()
+   * function must be called to set a new motor speed.
+   */
+  public void enable() {
+    m_disabled = false;
+  }
+
+  /**
+   * Gets the channel number associated with the object.
+   *
+   * @return The channel number.
+   */
+  public int getChannel() {
+    return m_pwm.getChannel();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Nidec Brushless");
+    builder.setActuator(true);
+    builder.setSafeState(this::stopMotor);
+    builder.addDoubleProperty("Value", this::get, this::set);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
new file mode 100644
index 0000000..45b7d94
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Notifier.java
@@ -0,0 +1,198 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.concurrent.atomic.AtomicInteger;
+import java.util.concurrent.locks.ReentrantLock;
+
+import edu.wpi.first.hal.NotifierJNI;
+
+public class Notifier implements AutoCloseable {
+  // The thread waiting on the HAL alarm.
+  private Thread m_thread;
+  // The lock for the process information.
+  private final ReentrantLock m_processLock = new ReentrantLock();
+  // The C pointer to the notifier object. We don't use it directly, it is
+  // just passed to the JNI bindings.
+  private final AtomicInteger m_notifier = new AtomicInteger();
+  // The time, in microseconds, at which the corresponding handler should be
+  // called. Has the same zero as Utility.getFPGATime().
+  private double m_expirationTime;
+  // The handler passed in by the user which should be called at the
+  // appropriate interval.
+  private Runnable m_handler;
+  // Whether we are calling the handler just once or periodically.
+  private boolean m_periodic;
+  // If periodic, the period of the calling; if just once, stores how long it
+  // is until we call the handler.
+  private double m_period;
+
+  @Override
+  @SuppressWarnings("NoFinalizer")
+  protected void finalize() {
+    close();
+  }
+
+  @Override
+  public void close() {
+    int handle = m_notifier.getAndSet(0);
+    if (handle == 0) {
+      return;
+    }
+    NotifierJNI.stopNotifier(handle);
+    // Join the thread to ensure the handler has exited.
+    if (m_thread.isAlive()) {
+      try {
+        m_thread.interrupt();
+        m_thread.join();
+      } catch (InterruptedException ex) {
+        Thread.currentThread().interrupt();
+      }
+    }
+    NotifierJNI.cleanNotifier(handle);
+    m_thread = null;
+  }
+
+  /**
+   * Update the alarm hardware to reflect the next alarm.
+   *
+   * @param triggerTime the time at which the next alarm will be triggered
+   */
+  private void updateAlarm(long triggerTime) {
+    int notifier = m_notifier.get();
+    if (notifier == 0) {
+      return;
+    }
+    NotifierJNI.updateNotifierAlarm(notifier, triggerTime);
+  }
+
+  /**
+   * Update the alarm hardware to reflect the next alarm.
+   */
+  private void updateAlarm() {
+    updateAlarm((long) (m_expirationTime * 1e6));
+  }
+
+  /**
+   * Create a Notifier for timer event notification.
+   *
+   * @param run The handler that is called at the notification time which is set
+   *            using StartSingle or StartPeriodic.
+   */
+  public Notifier(Runnable run) {
+    m_handler = run;
+    m_notifier.set(NotifierJNI.initializeNotifier());
+
+    m_thread = new Thread(() -> {
+      while (!Thread.interrupted()) {
+        int notifier = m_notifier.get();
+        if (notifier == 0) {
+          break;
+        }
+        long curTime = NotifierJNI.waitForNotifierAlarm(notifier);
+        if (curTime == 0) {
+          break;
+        }
+
+        Runnable handler = null;
+        m_processLock.lock();
+        try {
+          handler = m_handler;
+          if (m_periodic) {
+            m_expirationTime += m_period;
+            updateAlarm();
+          } else {
+            // need to update the alarm to cause it to wait again
+            updateAlarm((long) -1);
+          }
+        } finally {
+          m_processLock.unlock();
+        }
+
+        if (handler != null) {
+          handler.run();
+        }
+      }
+    });
+    m_thread.setName("Notifier");
+    m_thread.setDaemon(true);
+    m_thread.setUncaughtExceptionHandler((thread, error) -> {
+      Throwable cause = error.getCause();
+      if (cause != null) {
+        error = cause;
+      }
+      DriverStation.reportError("Unhandled exception: " + error.toString(), error.getStackTrace());
+      DriverStation.reportError(
+          "The loopFunc() method (or methods called by it) should have handled "
+              + "the exception above.", false);
+    });
+    m_thread.start();
+  }
+
+  /**
+   * Change the handler function.
+   *
+   * @param handler Handler
+   */
+  public void setHandler(Runnable handler) {
+    m_processLock.lock();
+    try {
+      m_handler = handler;
+    } finally {
+      m_processLock.unlock();
+    }
+  }
+
+  /**
+   * Register for single event notification. A timer event is queued for a single
+   * event after the specified delay.
+   *
+   * @param delay Seconds to wait before the handler is called.
+   */
+  public void startSingle(double delay) {
+    m_processLock.lock();
+    try {
+      m_periodic = false;
+      m_period = delay;
+      m_expirationTime = RobotController.getFPGATime() * 1e-6 + delay;
+      updateAlarm();
+    } finally {
+      m_processLock.unlock();
+    }
+  }
+
+  /**
+   * Register for periodic event notification. A timer event is queued for
+   * periodic event notification. Each time the interrupt occurs, the event will
+   * be immediately requeued for the same time interval.
+   *
+   * @param period Period in seconds to call the handler starting one period after
+   *               the call to this method.
+   */
+  public void startPeriodic(double period) {
+    m_processLock.lock();
+    try {
+      m_periodic = true;
+      m_period = period;
+      m_expirationTime = RobotController.getFPGATime() * 1e-6 + period;
+      updateAlarm();
+    } finally {
+      m_processLock.unlock();
+    }
+  }
+
+  /**
+   * Stop timer events from occurring. Stop any repeating timer events from
+   * occurring. This will also remove any single notification events from the
+   * queue. If a timer-based call to the registered handler is in progress, this
+   * function will block until the handler call is complete.
+   */
+  public void stop() {
+    NotifierJNI.cancelNotifierAlarm(m_notifier.get());
+  }
+}
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
new file mode 100644
index 0000000..780a5c2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDBase.java
@@ -0,0 +1,828 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.concurrent.locks.ReentrantLock;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.util.BoundaryException;
+import edu.wpi.first.wpilibj.filters.LinearDigitalFilter;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Class implements a PID Control Loop.
+ *
+ * <p>Creates a separate thread which reads the given PIDSource and takes care of the integral
+ * calculations, as well as writing the given PIDOutput.
+ *
+ * <p>This feedback controller runs in discrete time, so time deltas are not used in the integral
+ * and derivative calculations. Therefore, the sample rate affects the controller's behavior for a
+ * given set of PID constants.
+ */
+@SuppressWarnings("PMD.TooManyFields")
+public class PIDBase extends SendableBase implements PIDInterface, PIDOutput {
+  public static final double kDefaultPeriod = 0.05;
+  private static int instances;
+
+  // Factor for "proportional" control
+  @SuppressWarnings("MemberName")
+  private double m_P;
+
+  // Factor for "integral" control
+  @SuppressWarnings("MemberName")
+  private double m_I;
+
+  // Factor for "derivative" control
+  @SuppressWarnings("MemberName")
+  private double m_D;
+
+  // Factor for "feed forward" control
+  @SuppressWarnings("MemberName")
+  private double m_F;
+
+  // |maximum output|
+  private double m_maximumOutput = 1.0;
+
+  // |minimum output|
+  private double m_minimumOutput = -1.0;
+
+  // Maximum input - limit setpoint to this
+  private double m_maximumInput;
+
+  // Minimum input - limit setpoint to this
+  private double m_minimumInput;
+
+  // Input range - difference between maximum and minimum
+  private double m_inputRange;
+
+  // Do the endpoints wrap around? (e.g., absolute encoder)
+  private boolean m_continuous;
+
+  // Is the PID controller enabled
+  protected boolean m_enabled;
+
+  // The prior error (used to compute velocity)
+  private double m_prevError;
+
+  // The sum of the errors for use in the integral calc
+  private double m_totalError;
+
+  // The tolerance object used to check if on target
+  private Tolerance m_tolerance;
+
+  private double m_setpoint;
+  private double m_prevSetpoint;
+  @SuppressWarnings("PMD.UnusedPrivateField")
+  private double m_error;
+  private double m_result;
+
+  private PIDSource m_origSource;
+  private LinearDigitalFilter m_filter;
+
+  protected ReentrantLock m_thisMutex = new ReentrantLock();
+
+  // Ensures when disable() is called, pidWrite() won't run if calculate()
+  // is already running at that time.
+  protected ReentrantLock m_pidWriteMutex = new ReentrantLock();
+
+  protected PIDSource m_pidInput;
+  protected PIDOutput m_pidOutput;
+  protected Timer m_setpointTimer;
+
+  /**
+   * Tolerance is the type of tolerance used to specify if the PID controller is on target.
+   *
+   * <p>The various implementations of this class such as PercentageTolerance and AbsoluteTolerance
+   * specify types of tolerance specifications to use.
+   */
+  public interface Tolerance {
+    boolean onTarget();
+  }
+
+  /**
+   * Used internally for when Tolerance hasn't been set.
+   */
+  public static class NullTolerance implements Tolerance {
+    @Override
+    public boolean onTarget() {
+      throw new IllegalStateException("No tolerance value set when calling onTarget().");
+    }
+  }
+
+  public class PercentageTolerance implements Tolerance {
+    private final double m_percentage;
+
+    PercentageTolerance(double value) {
+      m_percentage = value;
+    }
+
+    @Override
+    public boolean onTarget() {
+      return Math.abs(getError()) < m_percentage / 100 * m_inputRange;
+    }
+  }
+
+  public class AbsoluteTolerance implements Tolerance {
+    private final double m_value;
+
+    AbsoluteTolerance(double value) {
+      m_value = value;
+    }
+
+    @Override
+    public boolean onTarget() {
+      return Math.abs(getError()) < m_value;
+    }
+  }
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D, and F.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param Kf     the feed forward term
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output percentage
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDBase(double Kp, double Ki, double Kd, double Kf, PIDSource source,
+                 PIDOutput output) {
+    super(false);
+    requireNonNull(source, "Null PIDSource was given");
+    requireNonNull(output, "Null PIDOutput was given");
+
+    m_setpointTimer = new Timer();
+    m_setpointTimer.start();
+
+    m_P = Kp;
+    m_I = Ki;
+    m_D = Kd;
+    m_F = Kf;
+
+    // Save original source
+    m_origSource = source;
+
+    // Create LinearDigitalFilter with original source as its source argument
+    m_filter = LinearDigitalFilter.movingAverage(m_origSource, 1);
+    m_pidInput = m_filter;
+
+    m_pidOutput = output;
+
+    instances++;
+    HAL.report(tResourceType.kResourceType_PIDController, instances);
+    m_tolerance = new NullTolerance();
+    setName("PIDController", instances);
+  }
+
+  /**
+   * Allocate a PID object with the given constants for P, I, and D.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source the PIDSource object that is used to get values
+   * @param output the PIDOutput object that is set to the output percentage
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDBase(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) {
+    this(Kp, Ki, Kd, 0.0, source, output);
+  }
+
+  /**
+   * Read the input, calculate the output accordingly, and write to the output. This should only be
+   * called by the PIDTask and is created during initialization.
+   */
+  @SuppressWarnings({"LocalVariableName", "PMD.ExcessiveMethodLength", "PMD.NPathComplexity"})
+  protected void calculate() {
+    if (m_origSource == null || m_pidOutput == null) {
+      return;
+    }
+
+    boolean enabled;
+
+    m_thisMutex.lock();
+    try {
+      enabled = m_enabled;
+    } finally {
+      m_thisMutex.unlock();
+    }
+
+    if (enabled) {
+      double input;
+
+      // Storage for function inputs
+      PIDSourceType pidSourceType;
+      double P;
+      double I;
+      double D;
+      double feedForward = calculateFeedForward();
+      double minimumOutput;
+      double maximumOutput;
+
+      // Storage for function input-outputs
+      double prevError;
+      double error;
+      double totalError;
+
+      m_thisMutex.lock();
+      try {
+        input = m_pidInput.pidGet();
+
+        pidSourceType = m_pidInput.getPIDSourceType();
+        P = m_P;
+        I = m_I;
+        D = m_D;
+        minimumOutput = m_minimumOutput;
+        maximumOutput = m_maximumOutput;
+
+        prevError = m_prevError;
+        error = getContinuousError(m_setpoint - input);
+        totalError = m_totalError;
+      } finally {
+        m_thisMutex.unlock();
+      }
+
+      // Storage for function outputs
+      double result;
+
+      if (pidSourceType.equals(PIDSourceType.kRate)) {
+        if (P != 0) {
+          totalError = clamp(totalError + error, minimumOutput / P,
+              maximumOutput / P);
+        }
+
+        result = P * totalError + D * error + feedForward;
+      } else {
+        if (I != 0) {
+          totalError = clamp(totalError + error, minimumOutput / I,
+              maximumOutput / I);
+        }
+
+        result = P * error + I * totalError + D * (error - prevError)
+            + feedForward;
+      }
+
+      result = clamp(result, minimumOutput, maximumOutput);
+
+      // Ensures m_enabled check and pidWrite() call occur atomically
+      m_pidWriteMutex.lock();
+      try {
+        m_thisMutex.lock();
+        try {
+          if (m_enabled) {
+            // Don't block other PIDController operations on pidWrite()
+            m_thisMutex.unlock();
+
+            m_pidOutput.pidWrite(result);
+          }
+        } finally {
+          if (m_thisMutex.isHeldByCurrentThread()) {
+            m_thisMutex.unlock();
+          }
+        }
+      } finally {
+        m_pidWriteMutex.unlock();
+      }
+
+      m_thisMutex.lock();
+      try {
+        m_prevError = error;
+        m_error = error;
+        m_totalError = totalError;
+        m_result = result;
+      } finally {
+        m_thisMutex.unlock();
+      }
+    }
+  }
+
+  /**
+   * Calculate the feed forward term.
+   *
+   * <p>Both of the provided feed forward calculations are velocity feed forwards. If a different
+   * feed forward calculation is desired, the user can override this function and provide his or
+   * her own. This function  does no synchronization because the PIDController class only calls it
+   * in synchronized code, so be careful if calling it oneself.
+   *
+   * <p>If a velocity PID controller is being used, the F term should be set to 1 over the maximum
+   * setpoint for the output. If a position PID controller is being used, the F term should be set
+   * to 1 over the maximum speed for the output measured in setpoint units per this controller's
+   * update period (see the default period in this class's constructor).
+   */
+  protected double calculateFeedForward() {
+    if (m_pidInput.getPIDSourceType().equals(PIDSourceType.kRate)) {
+      return m_F * getSetpoint();
+    } else {
+      double temp = m_F * getDeltaSetpoint();
+      m_prevSetpoint = m_setpoint;
+      m_setpointTimer.reset();
+      return temp;
+    }
+  }
+
+  /**
+   * Set the PID Controller gain parameters. Set the proportional, integral, and differential
+   * coefficients.
+   *
+   * @param p Proportional coefficient
+   * @param i Integral coefficient
+   * @param d Differential coefficient
+   */
+  @Override
+  @SuppressWarnings("ParameterName")
+  public void setPID(double p, double i, double d) {
+    m_thisMutex.lock();
+    try {
+      m_P = p;
+      m_I = i;
+      m_D = d;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the PID Controller gain parameters. Set the proportional, integral, and differential
+   * coefficients.
+   *
+   * @param p Proportional coefficient
+   * @param i Integral coefficient
+   * @param d Differential coefficient
+   * @param f Feed forward coefficient
+   */
+  @SuppressWarnings("ParameterName")
+  public void setPID(double p, double i, double d, double f) {
+    m_thisMutex.lock();
+    try {
+      m_P = p;
+      m_I = i;
+      m_D = d;
+      m_F = f;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the Proportional coefficient of the PID controller gain.
+   *
+   * @param p Proportional coefficient
+   */
+  @SuppressWarnings("ParameterName")
+  public void setP(double p) {
+    m_thisMutex.lock();
+    try {
+      m_P = p;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the Integral coefficient of the PID controller gain.
+   *
+   * @param i Integral coefficient
+   */
+  @SuppressWarnings("ParameterName")
+  public void setI(double i) {
+    m_thisMutex.lock();
+    try {
+      m_I = i;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the Differential coefficient of the PID controller gain.
+   *
+   * @param d differential coefficient
+   */
+  @SuppressWarnings("ParameterName")
+  public void setD(double d) {
+    m_thisMutex.lock();
+    try {
+      m_D = d;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the Feed forward coefficient of the PID controller gain.
+   *
+   * @param f feed forward coefficient
+   */
+  @SuppressWarnings("ParameterName")
+  public void setF(double f) {
+    m_thisMutex.lock();
+    try {
+      m_F = f;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Get the Proportional coefficient.
+   *
+   * @return proportional coefficient
+   */
+  @Override
+  public double getP() {
+    m_thisMutex.lock();
+    try {
+      return m_P;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Get the Integral coefficient.
+   *
+   * @return integral coefficient
+   */
+  @Override
+  public double getI() {
+    m_thisMutex.lock();
+    try {
+      return m_I;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Get the Differential coefficient.
+   *
+   * @return differential coefficient
+   */
+  @Override
+  public double getD() {
+    m_thisMutex.lock();
+    try {
+      return m_D;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Get the Feed forward coefficient.
+   *
+   * @return feed forward coefficient
+   */
+  public double getF() {
+    m_thisMutex.lock();
+    try {
+      return m_F;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Return the current PID result This is always centered on zero and constrained the the max and
+   * min outs.
+   *
+   * @return the latest calculated output
+   */
+  public double get() {
+    m_thisMutex.lock();
+    try {
+      return m_result;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the PID controller to consider the input to be continuous, Rather then using the max and
+   * min input range as constraints, it considers them to be the same point and automatically
+   * calculates the shortest route to the setpoint.
+   *
+   * @param continuous Set to true turns on continuous, false turns off continuous
+   */
+  public void setContinuous(boolean continuous) {
+    if (continuous && m_inputRange <= 0) {
+      throw new IllegalStateException("No input range set when calling setContinuous().");
+    }
+    m_thisMutex.lock();
+    try {
+      m_continuous = continuous;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the PID controller to consider the input to be continuous, Rather then using the max and
+   * min input range as constraints, it considers them to be the same point and automatically
+   * calculates the shortest route to the setpoint.
+   */
+  public void setContinuous() {
+    setContinuous(true);
+  }
+
+  /**
+   * Sets the maximum and minimum values expected from the input and setpoint.
+   *
+   * @param minimumInput the minimum value expected from the input
+   * @param maximumInput the maximum value expected from the input
+   */
+  public void setInputRange(double minimumInput, double maximumInput) {
+    m_thisMutex.lock();
+    try {
+      if (minimumInput > maximumInput) {
+        throw new BoundaryException("Lower bound is greater than upper bound");
+      }
+      m_minimumInput = minimumInput;
+      m_maximumInput = maximumInput;
+      m_inputRange = maximumInput - minimumInput;
+    } finally {
+      m_thisMutex.unlock();
+    }
+
+    setSetpoint(m_setpoint);
+  }
+
+  /**
+   * Sets the minimum and maximum values to write.
+   *
+   * @param minimumOutput the minimum percentage to write to the output
+   * @param maximumOutput the maximum percentage to write to the output
+   */
+  public void setOutputRange(double minimumOutput, double maximumOutput) {
+    m_thisMutex.lock();
+    try {
+      if (minimumOutput > maximumOutput) {
+        throw new BoundaryException("Lower bound is greater than upper bound");
+      }
+      m_minimumOutput = minimumOutput;
+      m_maximumOutput = maximumOutput;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the setpoint for the PIDController.
+   *
+   * @param setpoint the desired setpoint
+   */
+  @Override
+  public void setSetpoint(double setpoint) {
+    m_thisMutex.lock();
+    try {
+      if (m_maximumInput > m_minimumInput) {
+        if (setpoint > m_maximumInput) {
+          m_setpoint = m_maximumInput;
+        } else if (setpoint < m_minimumInput) {
+          m_setpoint = m_minimumInput;
+        } else {
+          m_setpoint = setpoint;
+        }
+      } else {
+        m_setpoint = setpoint;
+      }
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Returns the current setpoint of the PIDController.
+   *
+   * @return the current setpoint
+   */
+  @Override
+  public double getSetpoint() {
+    m_thisMutex.lock();
+    try {
+      return m_setpoint;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Returns the change in setpoint over time of the PIDController.
+   *
+   * @return the change in setpoint over time
+   */
+  public double getDeltaSetpoint() {
+    m_thisMutex.lock();
+    try {
+      return (m_setpoint - m_prevSetpoint) / m_setpointTimer.get();
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Returns the current difference of the input from the setpoint.
+   *
+   * @return the current error
+   */
+  @Override
+  public double getError() {
+    m_thisMutex.lock();
+    try {
+      return getContinuousError(getSetpoint() - m_pidInput.pidGet());
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Returns the current difference of the error over the past few iterations. You can specify the
+   * number of iterations to average with setToleranceBuffer() (defaults to 1). getAvgError() is
+   * used for the onTarget() function.
+   *
+   * @deprecated Use getError(), which is now already filtered.
+   * @return     the current average of the error
+   */
+  @Deprecated
+  public double getAvgError() {
+    m_thisMutex.lock();
+    try {
+      return getError();
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Sets what type of input the PID controller will use.
+   *
+   * @param pidSource the type of input
+   */
+  void setPIDSourceType(PIDSourceType pidSource) {
+    m_pidInput.setPIDSourceType(pidSource);
+  }
+
+  /**
+   * Returns the type of input the PID controller is using.
+   *
+   * @return the PID controller input type
+   */
+  PIDSourceType getPIDSourceType() {
+    return m_pidInput.getPIDSourceType();
+  }
+
+  /**
+   * Set the PID tolerance using a Tolerance object. Tolerance can be specified as a percentage of
+   * the range or as an absolute value. The Tolerance object encapsulates those options in an
+   * object. Use it by creating the type of tolerance that you want to use: setTolerance(new
+   * PIDController.AbsoluteTolerance(0.1))
+   *
+   * @deprecated      Use setPercentTolerance() instead.
+   * @param tolerance A tolerance object of the right type, e.g. PercentTolerance or
+   *                  AbsoluteTolerance
+   */
+  @Deprecated
+  public void setTolerance(Tolerance tolerance) {
+    m_tolerance = tolerance;
+  }
+
+  /**
+   * Set the absolute error which is considered tolerable for use with OnTarget.
+   *
+   * @param absvalue absolute error which is tolerable in the units of the input object
+   */
+  public void setAbsoluteTolerance(double absvalue) {
+    m_thisMutex.lock();
+    try {
+      m_tolerance = new AbsoluteTolerance(absvalue);
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the percentage error which is considered tolerable for use with OnTarget. (Input of 15.0 =
+   * 15 percent)
+   *
+   * @param percentage percent error which is tolerable
+   */
+  public void setPercentTolerance(double percentage) {
+    m_thisMutex.lock();
+    try {
+      m_tolerance = new PercentageTolerance(percentage);
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the number of previous error samples to average for tolerancing. When determining whether a
+   * mechanism is on target, the user may want to use a rolling average of previous measurements
+   * instead of a precise position or velocity. This is useful for noisy sensors which return a few
+   * erroneous measurements when the mechanism is on target. However, the mechanism will not
+   * register as on target for at least the specified bufLength cycles.
+   *
+   * @deprecated      Use a LinearDigitalFilter as the input.
+   * @param bufLength Number of previous cycles to average.
+   */
+  @Deprecated
+  public void setToleranceBuffer(int bufLength) {
+    m_thisMutex.lock();
+    try {
+      m_filter = LinearDigitalFilter.movingAverage(m_origSource, bufLength);
+      m_pidInput = m_filter;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Return true if the error is within the percentage of the total input range, determined by
+   * setTolerance. This assumes that the maximum and minimum input were set using setInput.
+   *
+   * @return true if the error is less than the tolerance
+   */
+  public boolean onTarget() {
+    m_thisMutex.lock();
+    try {
+      return m_tolerance.onTarget();
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Reset the previous error, the integral term, and disable the controller.
+   */
+  @Override
+  public void reset() {
+    m_thisMutex.lock();
+    try {
+      m_prevError = 0;
+      m_totalError = 0;
+      m_result = 0;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Passes the output directly to setSetpoint().
+   *
+   * <p>PIDControllers can be nested by passing a PIDController as another PIDController's output.
+   * In that case, the output of the parent controller becomes the input (i.e., the reference) of
+   * the child.
+   *
+   * <p>It is the caller's responsibility to put the data into a valid form for setSetpoint().
+   */
+  @Override
+  public void pidWrite(double output) {
+    setSetpoint(output);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("PIDController");
+    builder.setSafeState(this::reset);
+    builder.addDoubleProperty("p", this::getP, this::setP);
+    builder.addDoubleProperty("i", this::getI, this::setI);
+    builder.addDoubleProperty("d", this::getD, this::setD);
+    builder.addDoubleProperty("f", this::getF, this::setF);
+    builder.addDoubleProperty("setpoint", this::getSetpoint, this::setSetpoint);
+  }
+
+  /**
+   * Wraps error around for continuous inputs. The original error is returned if continuous mode is
+   * disabled. This is an unsynchronized function.
+   *
+   * @param error The current error of the PID controller.
+   * @return Error for continuous inputs.
+   */
+  protected double getContinuousError(double error) {
+    if (m_continuous && m_inputRange > 0) {
+      error %= m_inputRange;
+      if (Math.abs(error) > m_inputRange / 2) {
+        if (error > 0) {
+          return error - m_inputRange;
+        } else {
+          return error + m_inputRange;
+        }
+      }
+    }
+
+    return error;
+  }
+
+  private static double clamp(double value, double low, double high) {
+    return Math.max(low, Math.min(value, high));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java
new file mode 100644
index 0000000..da4118f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDController.java
@@ -0,0 +1,181 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Class implements a PID Control Loop.
+ *
+ * <p>Creates a separate thread which reads the given PIDSource and takes care of the integral
+ * calculations, as well as writing the given PIDOutput.
+ *
+ * <p>This feedback controller runs in discrete time, so time deltas are not used in the integral
+ * and derivative calculations. Therefore, the sample rate affects the controller's behavior for a
+ * given set of PID constants.
+ */
+public class PIDController extends PIDBase implements Controller {
+  Notifier m_controlLoop = new Notifier(this::calculate);
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D, and F.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param Kf     the feed forward term
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output percentage
+   * @param period the loop time for doing calculations in seconds.
+   *               This particularly affects calculations of
+   *               the integral and differential terms.
+   *               The default is 0.05 (50ms).
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source,
+                       PIDOutput output, double period) {
+    super(Kp, Ki, Kd, Kf, source, output);
+    m_controlLoop.startPeriodic(period);
+  }
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D and period.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source the PIDSource object that is used to get values
+   * @param output the PIDOutput object that is set to the output percentage
+   * @param period the loop time for doing calculations in seconds.
+   *               This particularly affects calculations of
+   *               the integral and differential terms.
+   *               The default is 0.05 (50ms).
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output,
+                       double period) {
+    this(Kp, Ki, Kd, 0.0, source, output, period);
+  }
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D, using a 50ms period.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output percentage
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDController(double Kp, double Ki, double Kd, PIDSource source, PIDOutput output) {
+    this(Kp, Ki, Kd, source, output, kDefaultPeriod);
+  }
+
+  /**
+   * Allocate a PID object with the given constants for P, I, D, using a 50ms period.
+   *
+   * @param Kp     the proportional coefficient
+   * @param Ki     the integral coefficient
+   * @param Kd     the derivative coefficient
+   * @param Kf     the feed forward term
+   * @param source The PIDSource object that is used to get values
+   * @param output The PIDOutput object that is set to the output percentage
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDController(double Kp, double Ki, double Kd, double Kf, PIDSource source,
+                       PIDOutput output) {
+    this(Kp, Ki, Kd, Kf, source, output, kDefaultPeriod);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    m_controlLoop.close();
+    m_thisMutex.lock();
+    try {
+      m_pidOutput = null;
+      m_pidInput = null;
+      m_controlLoop = null;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Begin running the PIDController.
+   */
+  @Override
+  public void enable() {
+    m_thisMutex.lock();
+    try {
+      m_enabled = true;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Stop running the PIDController, this sets the output to zero before stopping.
+   */
+  @Override
+  public void disable() {
+    // Ensures m_enabled check and pidWrite() call occur atomically
+    m_pidWriteMutex.lock();
+    try {
+      m_thisMutex.lock();
+      try {
+        m_enabled = false;
+      } finally {
+        m_thisMutex.unlock();
+      }
+
+      m_pidOutput.pidWrite(0);
+    } finally {
+      m_pidWriteMutex.unlock();
+    }
+  }
+
+  /**
+   * Set the enabled state of the PIDController.
+   */
+  public void setEnabled(boolean enable) {
+    if (enable) {
+      enable();
+    } else {
+      disable();
+    }
+  }
+
+  /**
+   * Return true if PIDController is enabled.
+   */
+  public boolean isEnabled() {
+    m_thisMutex.lock();
+    try {
+      return m_enabled;
+    } finally {
+      m_thisMutex.unlock();
+    }
+  }
+
+  /**
+   * Reset the previous error, the integral term, and disable the controller.
+   */
+  @Override
+  public void reset() {
+    disable();
+
+    super.reset();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    super.initSendable(builder);
+    builder.addBooleanProperty("enabled", this::isEnabled, this::setEnabled);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java
new file mode 100644
index 0000000..fd91ec8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDInterface.java
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+@SuppressWarnings("SummaryJavadoc")
+public interface PIDInterface {
+  @SuppressWarnings("ParameterName")
+  void setPID(double p, double i, double d);
+
+  double getP();
+
+  double getI();
+
+  double getD();
+
+  void setSetpoint(double setpoint);
+
+  double getSetpoint();
+
+  double getError();
+
+  void reset();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java
new file mode 100644
index 0000000..0ef9403
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDOutput.java
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * This interface allows PIDController to write it's results to its output.
+ */
+@FunctionalInterface
+public interface PIDOutput {
+  /**
+   * Set the output to the value calculated by PIDController.
+   *
+   * @param output the value calculated by PIDController
+   */
+  void pidWrite(double output);
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSource.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSource.java
new file mode 100644
index 0000000..841a232
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSource.java
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * This interface allows for PIDController to automatically read from this object.
+ */
+public interface PIDSource {
+  /**
+   * Set which parameter of the device you are using as a process control variable.
+   *
+   * @param pidSource An enum to select the parameter.
+   */
+  void setPIDSourceType(PIDSourceType pidSource);
+
+  /**
+   * Get which parameter of the device you are using as a process control variable.
+   *
+   * @return the currently selected PID source parameter
+   */
+  PIDSourceType getPIDSourceType();
+
+  /**
+   * Get the result to use in PIDController.
+   *
+   * @return the result to use in PIDController
+   */
+  double pidGet();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java
new file mode 100644
index 0000000..31aa79a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PIDSourceType.java
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * A description for the type of output value to provide to a PIDController.
+ */
+public enum PIDSourceType {
+  kDisplacement,
+  kRate
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java
new file mode 100644
index 0000000..d59a413
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWM.java
@@ -0,0 +1,317 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.PWMConfigDataResult;
+import edu.wpi.first.hal.PWMJNI;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Class implements the PWM generation in the FPGA.
+ *
+ * <p>The values supplied as arguments for PWM outputs range from -1.0 to 1.0. They are mapped to
+ * the hardware dependent values, in this case 0-2000 for the FPGA. Changes are immediately sent to
+ * the FPGA, and the update occurs at the next FPGA cycle (5.005ms). There is no delay.
+ *
+ * <p>As of revision 0.1.10 of the FPGA, the FPGA interprets the 0-2000 values as follows: - 2000 =
+ * maximum pulse width - 1999 to 1001 = linear scaling from "full forward" to "center" - 1000 =
+ * center value - 999 to 2 = linear scaling from "center" to "full reverse" - 1 = minimum pulse
+ * width (currently .5ms) - 0 = disabled (i.e. PWM output is held low)
+ */
+public class PWM extends MotorSafety implements Sendable, AutoCloseable {
+  /**
+   * Represents the amount to multiply the minimum servo-pulse pwm period by.
+   */
+  public enum PeriodMultiplier {
+    /**
+     * Period Multiplier: don't skip pulses. PWM pulses occur every 5.005 ms
+     */
+    k1X,
+    /**
+     * Period Multiplier: skip every other pulse. PWM pulses occur every 10.010 ms
+     */
+    k2X,
+    /**
+     * Period Multiplier: skip three out of four pulses. PWM pulses occur every 20.020 ms
+     */
+    k4X
+  }
+
+  private final int m_channel;
+  private int m_handle;
+
+  private final SendableImpl m_sendableImpl;
+
+  /**
+   * Allocate a PWM given a channel.
+   *
+   * @param channel The PWM channel number. 0-9 are on-board, 10-19 are on the MXP port
+   */
+  public PWM(final int channel) {
+    m_sendableImpl = new SendableImpl(true);
+
+    SensorUtil.checkPWMChannel(channel);
+    m_channel = channel;
+
+    m_handle = PWMJNI.initializePWMPort(HAL.getPort((byte) channel));
+
+    setDisabled();
+
+    PWMJNI.setPWMEliminateDeadband(m_handle, false);
+
+    HAL.report(tResourceType.kResourceType_PWM, channel);
+    setName("PWM", channel);
+
+    setSafetyEnabled(false);
+  }
+
+  /**
+   * Free the resource associated with the PWM channel and set the value to 0.
+   */
+  @Override
+  public void close() {
+    m_sendableImpl.close();
+
+    if (m_handle == 0) {
+      return;
+    }
+    setDisabled();
+    PWMJNI.freePWMPort(m_handle);
+    m_handle = 0;
+  }
+
+  @Override
+  public final synchronized String getName() {
+    return m_sendableImpl.getName();
+  }
+
+  @Override
+  public final synchronized void setName(String name) {
+    m_sendableImpl.setName(name);
+  }
+
+  /**
+   * Sets the name of the sensor with a channel number.
+   *
+   * @param moduleType A string that defines the module name in the label for the value
+   * @param channel    The channel number the device is plugged into
+   */
+  protected final void setName(String moduleType, int channel) {
+    m_sendableImpl.setName(moduleType, channel);
+  }
+
+  /**
+   * Sets the name of the sensor with a module and channel number.
+   *
+   * @param moduleType   A string that defines the module name in the label for the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually PWM)
+   */
+  protected final void setName(String moduleType, int moduleNumber, int channel) {
+    m_sendableImpl.setName(moduleType, moduleNumber, channel);
+  }
+
+  @Override
+  public final synchronized String getSubsystem() {
+    return m_sendableImpl.getSubsystem();
+  }
+
+  @Override
+  public final synchronized void setSubsystem(String subsystem) {
+    m_sendableImpl.setSubsystem(subsystem);
+  }
+
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  protected final void addChild(Object child) {
+    m_sendableImpl.addChild(child);
+  }
+
+  @Override
+  public void stopMotor() {
+    setDisabled();
+  }
+
+  @Override
+  public String getDescription() {
+    return "PWM " + getChannel();
+  }
+
+  /**
+   * Optionally eliminate the deadband from a speed controller.
+   *
+   * @param eliminateDeadband If true, set the motor curve on the Jaguar to eliminate the deadband
+   *                          in the middle of the range. Otherwise, keep the full range without
+   *                          modifying any values.
+   */
+  public void enableDeadbandElimination(boolean eliminateDeadband) {
+    PWMJNI.setPWMEliminateDeadband(m_handle, eliminateDeadband);
+  }
+
+  /**
+   * Set the bounds on the PWM pulse widths. This sets the bounds on the PWM values for a particular
+   * type of controller. The values determine the upper and lower speeds as well as the deadband
+   * bracket.
+   *
+   * @param max         The max PWM pulse width in ms
+   * @param deadbandMax The high end of the deadband range pulse width in ms
+   * @param center      The center (off) pulse width in ms
+   * @param deadbandMin The low end of the deadband pulse width in ms
+   * @param min         The minimum pulse width in ms
+   */
+  public void setBounds(double max, double deadbandMax, double center, double deadbandMin,
+                           double min) {
+    PWMJNI.setPWMConfig(m_handle, max, deadbandMax, center, deadbandMin, min);
+  }
+
+  /**
+   * Gets the bounds on the PWM pulse widths. This Gets the bounds on the PWM values for a
+   * particular type of controller. The values determine the upper and lower speeds as well
+   * as the deadband bracket.
+   */
+  public PWMConfigDataResult getRawBounds() {
+    return PWMJNI.getPWMConfigRaw(m_handle);
+  }
+
+  /**
+   * Gets the channel number associated with the PWM Object.
+   *
+   * @return The channel number.
+   */
+  public int getChannel() {
+    return m_channel;
+  }
+
+  /**
+   * Set the PWM value based on a position.
+   *
+   * <p>This is intended to be used by servos.
+   *
+   * @param pos The position to set the servo between 0.0 and 1.0.
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinNegativePwm() called.
+   */
+  public void setPosition(double pos) {
+    PWMJNI.setPWMPosition(m_handle, pos);
+  }
+
+  /**
+   * Get the PWM value in terms of a position.
+   *
+   * <p>This is intended to be used by servos.
+   *
+   * @return The position the servo is set to between 0.0 and 1.0.
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinNegativePwm() called.
+   */
+  public double getPosition() {
+    return PWMJNI.getPWMPosition(m_handle);
+  }
+
+  /**
+   * Set the PWM value based on a speed.
+   *
+   * <p>This is intended to be used by speed controllers.
+   *
+   * @param speed The speed to set the speed controller between -1.0 and 1.0.
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinPositivePwm() called.
+   * @pre SetCenterPwm() called.
+   * @pre SetMaxNegativePwm() called.
+   * @pre SetMinNegativePwm() called.
+   */
+  public void setSpeed(double speed) {
+    PWMJNI.setPWMSpeed(m_handle, speed);
+  }
+
+  /**
+   * Get the PWM value in terms of speed.
+   *
+   * <p>This is intended to be used by speed controllers.
+   *
+   * @return The most recently set speed between -1.0 and 1.0.
+   * @pre SetMaxPositivePwm() called.
+   * @pre SetMinPositivePwm() called.
+   * @pre SetMaxNegativePwm() called.
+   * @pre SetMinNegativePwm() called.
+   */
+  public double getSpeed() {
+    return PWMJNI.getPWMSpeed(m_handle);
+  }
+
+  /**
+   * Set the PWM value directly to the hardware.
+   *
+   * <p>Write a raw value to a PWM channel.
+   *
+   * @param value Raw PWM value. Range 0 - 255.
+   */
+  public void setRaw(int value) {
+    PWMJNI.setPWMRaw(m_handle, (short) value);
+  }
+
+  /**
+   * Get the PWM value directly from the hardware.
+   *
+   * <p>Read a raw value from a PWM channel.
+   *
+   * @return Raw PWM control value. Range: 0 - 255.
+   */
+  public int getRaw() {
+    return PWMJNI.getPWMRaw(m_handle);
+  }
+
+  /**
+   * Temporarily disables the PWM output. The next set call will reenable
+   * the output.
+   */
+  public void setDisabled() {
+    PWMJNI.setPWMDisabled(m_handle);
+  }
+
+  /**
+   * Slow down the PWM signal for old devices.
+   *
+   * @param mult The period multiplier to apply to this channel
+   */
+  public void setPeriodMultiplier(PeriodMultiplier mult) {
+    switch (mult) {
+      case k4X:
+        // Squelch 3 out of 4 outputs
+        PWMJNI.setPWMPeriodScale(m_handle, 3);
+        break;
+      case k2X:
+        // Squelch 1 out of 2 outputs
+        PWMJNI.setPWMPeriodScale(m_handle, 1);
+        break;
+      case k1X:
+        // Don't squelch any outputs
+        PWMJNI.setPWMPeriodScale(m_handle, 0);
+        break;
+      default:
+        // Cannot hit this, limited by PeriodMultiplier enum
+    }
+  }
+
+  protected void setZeroLatch() {
+    PWMJNI.latchPWMZero(m_handle);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("PWM");
+    builder.setActuator(true);
+    builder.setSafeState(this::setDisabled);
+    builder.addDoubleProperty("Value", this::getRaw, value -> setRaw((int) value));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java
new file mode 100644
index 0000000..0a33423
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMSpeedController.java
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Common base class for all PWM Speed Controllers.
+ */
+public abstract class PWMSpeedController extends PWM implements SpeedController {
+  private boolean m_isInverted;
+
+  /**
+   * Constructor.
+   *
+   * @param channel The PWM channel that the controller is attached to. 0-9 are on-board, 10-19 are
+   *                on the MXP port
+   */
+  protected PWMSpeedController(int channel) {
+    super(channel);
+  }
+
+  @Override
+  public String getDescription() {
+    return "PWM " + getChannel();
+  }
+
+  /**
+   * Set the PWM value.
+   *
+   * <p>The PWM value is set using a range of -1.0 to 1.0, appropriately scaling the value for the
+   * FPGA.
+   *
+   * @param speed The speed value between -1.0 and 1.0 to set.
+   */
+  @Override
+  public void set(double speed) {
+    setSpeed(m_isInverted ? -speed : speed);
+    feed();
+  }
+
+  /**
+   * Get the recently set value of the PWM.
+   *
+   * @return The most recently set value for the PWM between -1.0 and 1.0.
+   */
+  @Override
+  public double get() {
+    return getSpeed();
+  }
+
+  @Override
+  public void setInverted(boolean isInverted) {
+    m_isInverted = isInverted;
+  }
+
+  @Override
+  public boolean getInverted() {
+    return m_isInverted;
+  }
+
+  @Override
+  public void disable() {
+    setDisabled();
+  }
+
+  /**
+   * Write out the PID value as seen in the PIDOutput base object.
+   *
+   * @param output Write out the PWM value as was found in the PIDController
+   */
+  @Override
+  public void pidWrite(double output) {
+    set(output);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Speed Controller");
+    builder.setActuator(true);
+    builder.setSafeState(this::setDisabled);
+    builder.addDoubleProperty("Value", this::getSpeed, this::setSpeed);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMTalonSRX.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMTalonSRX.java
new file mode 100644
index 0000000..2b42ed4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMTalonSRX.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * Cross the Road Electronics (CTRE) Talon SRX Speed Controller with PWM control.
+ */
+public class PWMTalonSRX extends PWMSpeedController {
+  /**
+   * Constructor for a PWMTalonSRX connected via PWM.
+   *
+   * <p>Note that the PWMTalonSRX uses the following bounds for PWM values. These values should work
+   * reasonably well for most controllers, but if users experience issues such as asymmetric
+   * behavior around the deadband or inability to saturate the controller in either direction,
+   * calibration is recommended. The calibration procedure can be found in the TalonSRX User Manual
+   * available from CTRE.
+   *
+   * <p>- 2.0004ms = full "forward" - 1.52ms = the "high end" of the deadband range - 1.50ms =
+   * center
+   * of the deadband range (off) - 1.48ms = the "low end" of the deadband range - .997ms = full
+   * "reverse"
+   *
+   * @param channel The PWM channel that the PWMTalonSRX is attached to. 0-9 are on-board, 10-19 are
+   *                on the MXP port
+   */
+  public PWMTalonSRX(final int channel) {
+    super(channel);
+
+    setBounds(2.004, 1.52, 1.50, 1.48, .997);
+    setPeriodMultiplier(PeriodMultiplier.k1X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_PWMTalonSRX, getChannel());
+    setName("PWMTalonSRX", getChannel());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMVictorSPX.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMVictorSPX.java
new file mode 100644
index 0000000..f1acb43
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PWMVictorSPX.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * Cross the Road Electronics (CTRE) Victor SPX Speed Controller with PWM control.
+ */
+public class PWMVictorSPX extends PWMSpeedController {
+  /**
+   * Constructor for a PWMVictorSPX connected via PWM.
+   *
+   * <p>Note that the PWMVictorSPX uses the following bounds for PWM values. These values should
+   *  work reasonably well for most controllers, but if users experience issues such as asymmetric
+   * behavior around the deadband or inability to saturate the controller in either direction,
+   * calibration is recommended. The calibration procedure can be found in the VictorSPX User
+   * Manual available from CTRE.
+   *
+   * <p>- 2.0004ms = full "forward" - 1.52ms = the "high end" of the deadband range - 1.50ms =
+   * center
+   * of the deadband range (off) - 1.48ms = the "low end" of the deadband range - .997ms = full
+   * "reverse"
+   *
+   * @param channel The PWM channel that the PWMVictorSPX is attached to. 0-9 are on-board, 10-19
+   *                are on the MXP port
+   */
+  public PWMVictorSPX(final int channel) {
+    super(channel);
+
+    setBounds(2.004, 1.52, 1.50, 1.48, .997);
+    setPeriodMultiplier(PeriodMultiplier.k1X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_PWMVictorSPX, getChannel());
+    setName("PWMVictorSPX", getChannel());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java
new file mode 100644
index 0000000..dd175eb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/PowerDistributionPanel.java
@@ -0,0 +1,124 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.PDPJNI;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Class for getting voltage, current, temperature, power and energy from the Power Distribution
+ * Panel over CAN.
+ */
+public class PowerDistributionPanel extends SendableBase  {
+  private final int m_handle;
+
+  /**
+   * Constructor.
+   *
+   * @param module The CAN ID of the PDP
+   */
+  public PowerDistributionPanel(int module) {
+    SensorUtil.checkPDPModule(module);
+    m_handle = PDPJNI.initializePDP(module);
+
+    HAL.report(tResourceType.kResourceType_PDP, module);
+    setName("PowerDistributionPanel", module);
+  }
+
+  /**
+   * Constructor.  Uses the default CAN ID (0).
+   */
+  public PowerDistributionPanel() {
+    this(0);
+  }
+
+  /**
+   * Query the input voltage of the PDP.
+   *
+   * @return The voltage of the PDP in volts
+   */
+  public double getVoltage() {
+    return PDPJNI.getPDPVoltage(m_handle);
+  }
+
+  /**
+   * Query the temperature of the PDP.
+   *
+   * @return The temperature of the PDP in degrees Celsius
+   */
+  public double getTemperature() {
+    return PDPJNI.getPDPTemperature(m_handle);
+  }
+
+  /**
+   * Query the current of a single channel of the PDP.
+   *
+   * @return The current of one of the PDP channels (channels 0-15) in Amperes
+   */
+  public double getCurrent(int channel) {
+    double current = PDPJNI.getPDPChannelCurrent((byte) channel, m_handle);
+
+    SensorUtil.checkPDPChannel(channel);
+
+    return current;
+  }
+
+  /**
+   * Query the current of all monitored PDP channels (0-15).
+   *
+   * @return The current of all the channels in Amperes
+   */
+  public double getTotalCurrent() {
+    return PDPJNI.getPDPTotalCurrent(m_handle);
+  }
+
+  /**
+   * Query the total power drawn from the monitored PDP channels.
+   *
+   * @return the total power in Watts
+   */
+  public double getTotalPower() {
+    return PDPJNI.getPDPTotalPower(m_handle);
+  }
+
+  /**
+   * Query the total energy drawn from the monitored PDP channels.
+   *
+   * @return the total energy in Joules
+   */
+  public double getTotalEnergy() {
+    return PDPJNI.getPDPTotalEnergy(m_handle);
+  }
+
+  /**
+   * Reset the total energy to 0.
+   */
+  public void resetTotalEnergy() {
+    PDPJNI.resetPDPTotalEnergy(m_handle);
+  }
+
+  /**
+   * Clear all PDP sticky faults.
+   */
+  public void clearStickyFaults() {
+    PDPJNI.clearPDPStickyFaults(m_handle);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("PowerDistributionPanel");
+    for (int i = 0; i < SensorUtil.kPDPChannels; ++i) {
+      final int chan = i;
+      builder.addDoubleProperty("Chan" + i, () -> getCurrent(chan), null);
+    }
+    builder.addDoubleProperty("Voltage", this::getVoltage, null);
+    builder.addDoubleProperty("TotalCurrent", this::getTotalCurrent, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java
new file mode 100644
index 0000000..45d9e0e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Preferences.java
@@ -0,0 +1,259 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Vector;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.networktables.EntryListenerFlags;
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * The preferences class provides a relatively simple way to save important values to the roboRIO to
+ * access the next time the roboRIO is booted.
+ *
+ * <p> This class loads and saves from a file inside the roboRIO. The user can not access the file
+ * directly, but may modify values at specific fields which will then be automatically saved to the
+ * file by the NetworkTables server. </p>
+ *
+ * <p> This class is thread safe. </p>
+ *
+ * <p> This will also interact with {@link NetworkTable} by creating a table called "Preferences"
+ * with all the key-value pairs. </p>
+ */
+public final class Preferences {
+  /**
+   * The Preferences table name.
+   */
+  private static final String TABLE_NAME = "Preferences";
+  /**
+   * The singleton instance.
+   */
+  private static Preferences instance;
+  /**
+   * The network table.
+   */
+  private final NetworkTable m_table;
+
+  /**
+   * Returns the preferences instance.
+   *
+   * @return the preferences instance
+   */
+  public static synchronized Preferences getInstance() {
+    if (instance == null) {
+      instance = new Preferences();
+    }
+    return instance;
+  }
+
+  /**
+   * Creates a preference class.
+   */
+  private Preferences() {
+    m_table = NetworkTableInstance.getDefault().getTable(TABLE_NAME);
+    m_table.getEntry(".type").setString("RobotPreferences");
+    // Listener to set all Preferences values to persistent
+    // (for backwards compatibility with old dashboards).
+    m_table.addEntryListener(
+        (table, key, entry, value, flags) -> entry.setPersistent(),
+        EntryListenerFlags.kImmediate | EntryListenerFlags.kNew);
+    HAL.report(tResourceType.kResourceType_Preferences, 0);
+  }
+
+  /**
+   * Gets the vector of keys.
+   * @return a vector of the keys
+   */
+  @SuppressWarnings({"PMD.LooseCoupling", "PMD.UseArrayListInsteadOfVector"})
+  public Vector<String> getKeys() {
+    return new Vector<>(m_table.getKeys());
+  }
+
+  /**
+   * Puts the given string into the preferences table.
+   *
+   * @param key   the key
+   * @param value the value
+   * @throws NullPointerException if value is null
+   */
+  public void putString(String key, String value) {
+    requireNonNull(value, "Provided value was null");
+
+    NetworkTableEntry entry = m_table.getEntry(key);
+    entry.setString(value);
+    entry.setPersistent();
+  }
+
+  /**
+   * Puts the given int into the preferences table.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  public void putInt(String key, int value) {
+    NetworkTableEntry entry = m_table.getEntry(key);
+    entry.setDouble(value);
+    entry.setPersistent();
+  }
+
+  /**
+   * Puts the given double into the preferences table.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  public void putDouble(String key, double value) {
+    NetworkTableEntry entry = m_table.getEntry(key);
+    entry.setDouble(value);
+    entry.setPersistent();
+  }
+
+  /**
+   * Puts the given float into the preferences table.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  public void putFloat(String key, float value) {
+    NetworkTableEntry entry = m_table.getEntry(key);
+    entry.setDouble(value);
+    entry.setPersistent();
+  }
+
+  /**
+   * Puts the given boolean into the preferences table.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  public void putBoolean(String key, boolean value) {
+    NetworkTableEntry entry = m_table.getEntry(key);
+    entry.setBoolean(value);
+    entry.setPersistent();
+  }
+
+  /**
+   * Puts the given long into the preferences table.
+   *
+   * @param key   the key
+   * @param value the value
+   */
+  public void putLong(String key, long value) {
+    NetworkTableEntry entry = m_table.getEntry(key);
+    entry.setDouble(value);
+    entry.setPersistent();
+  }
+
+  /**
+   * Returns whether or not there is a key with the given name.
+   *
+   * @param key the key
+   * @return if there is a value at the given key
+   */
+  public boolean containsKey(String key) {
+    return m_table.containsKey(key);
+  }
+
+  /**
+   * Remove a preference.
+   *
+   * @param key the key
+   */
+  public void remove(String key) {
+    m_table.delete(key);
+  }
+
+  /**
+   * Remove all preferences.
+   */
+  public void removeAll() {
+    for (String key : m_table.getKeys()) {
+      if (!".type".equals(key)) {
+        remove(key);
+      }
+    }
+  }
+
+  /**
+   * Returns the string at the given key. If this table does not have a value for that position,
+   * then the given backup value will be returned.
+   *
+   * @param key    the key
+   * @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) {
+    return m_table.getEntry(key).getString(backup);
+  }
+
+  /**
+   * Returns the int at the given key. If this table does not have a value for that position, then
+   * the given backup value will be returned.
+   *
+   * @param key    the key
+   * @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) {
+    return (int) m_table.getEntry(key).getDouble(backup);
+  }
+
+  /**
+   * Returns the double at the given key. If this table does not have a value for that position,
+   * then the given backup value will be returned.
+   *
+   * @param key    the key
+   * @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) {
+    return m_table.getEntry(key).getDouble(backup);
+  }
+
+  /**
+   * Returns the boolean at the given key. If this table does not have a value for that position,
+   * then the given backup value will be returned.
+   *
+   * @param key    the key
+   * @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) {
+    return m_table.getEntry(key).getBoolean(backup);
+  }
+
+  /**
+   * Returns the float at the given key. If this table does not have a value for that position, then
+   * the given backup value will be returned.
+   *
+   * @param key    the key
+   * @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) {
+    return (float) m_table.getEntry(key).getDouble(backup);
+  }
+
+  /**
+   * Returns the long at the given key. If this table does not have a value for that position, then
+   * the given backup value will be returned.
+   *
+   * @param key    the key
+   * @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) {
+    return (long) m_table.getEntry(key).getDouble(backup);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java
new file mode 100644
index 0000000..549a681
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Relay.java
@@ -0,0 +1,368 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Optional;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.RelayJNI;
+import edu.wpi.first.hal.util.UncleanStatusException;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Class for VEX Robotics Spike style relay outputs. Relays are intended to be connected to Spikes
+ * or similar relays. The relay channels controls a pair of channels that are either both off, one
+ * on, the other on, or both on. This translates into two Spike outputs at 0v, one at 12v and one
+ * at 0v, one at 0v and the other at 12v, or two Spike outputs at 12V. This allows off, full
+ * forward, or full reverse control of motors without variable speed. It also allows the two
+ * channels (forward and reverse) to be used independently for something that does not care about
+ * voltage polarity (like a solenoid).
+ */
+public class Relay extends MotorSafety implements Sendable, AutoCloseable {
+  /**
+   * This class represents errors in trying to set relay values contradictory to the direction to
+   * which the relay is set.
+   */
+  public static class InvalidValueException extends RuntimeException {
+    /**
+     * Create a new exception with the given message.
+     *
+     * @param message the message to pass with the exception
+     */
+    public InvalidValueException(String message) {
+      super(message);
+    }
+  }
+
+  /**
+   * The state to drive a Relay to.
+   */
+  public enum Value {
+    kOff("Off"),
+    kOn("On"),
+    kForward("Forward"),
+    kReverse("Reverse");
+
+    private final String m_prettyValue;
+
+    Value(String prettyValue) {
+      m_prettyValue = prettyValue;
+    }
+
+    public String getPrettyValue() {
+      return m_prettyValue;
+    }
+
+    public static Optional<Value> getValueOf(String value) {
+      return Arrays.stream(Value.values()).filter(v -> v.m_prettyValue.equals(value)).findFirst();
+    }
+  }
+
+  /**
+   * The Direction(s) that a relay is configured to operate in.
+   */
+  public enum Direction {
+    /**
+     * direction: both directions are valid.
+     */
+
+    kBoth,
+    /**
+     * direction: Only forward is valid.
+     */
+    kForward,
+    /**
+     * direction: only reverse is valid.
+     */
+    kReverse
+  }
+
+  private final int m_channel;
+
+  private int m_forwardHandle;
+  private int m_reverseHandle;
+
+  private Direction m_direction;
+
+  private final SendableImpl m_sendableImpl;
+
+  /**
+   * Common relay initialization method. This code is common to all Relay constructors and
+   * initializes the relay and reserves all resources that need to be locked. Initially the relay is
+   * set to both lines at 0v.
+   */
+  private void initRelay() {
+    SensorUtil.checkRelayChannel(m_channel);
+
+    int portHandle = HAL.getPort((byte) m_channel);
+    if (m_direction == Direction.kBoth || m_direction == Direction.kForward) {
+      m_forwardHandle = RelayJNI.initializeRelayPort(portHandle, true);
+      HAL.report(tResourceType.kResourceType_Relay, m_channel);
+    }
+    if (m_direction == Direction.kBoth || m_direction == Direction.kReverse) {
+      m_reverseHandle = RelayJNI.initializeRelayPort(portHandle, false);
+      HAL.report(tResourceType.kResourceType_Relay, m_channel + 128);
+    }
+
+    setSafetyEnabled(false);
+
+    setName("Relay", m_channel);
+  }
+
+  /**
+   * Relay constructor given a channel.
+   *
+   * @param channel The channel number for this relay (0 - 3).
+   * @param direction The direction that the Relay object will control.
+   */
+  public Relay(final int channel, Direction direction) {
+    m_sendableImpl = new SendableImpl(true);
+
+    m_channel = channel;
+    m_direction = requireNonNull(direction, "Null Direction was given");
+    initRelay();
+    set(Value.kOff);
+  }
+
+  /**
+   * Relay constructor given a channel, allowing both directions.
+   *
+   * @param channel The channel number for this relay (0 - 3).
+   */
+  public Relay(final int channel) {
+    this(channel, Direction.kBoth);
+  }
+
+  @Override
+  public void close() {
+    m_sendableImpl.close();
+    freeRelay();
+  }
+
+  private void freeRelay() {
+    try {
+      RelayJNI.setRelay(m_forwardHandle, false);
+    } catch (UncleanStatusException ignored) {
+      // do nothing. Ignore
+    }
+    try {
+      RelayJNI.setRelay(m_reverseHandle, false);
+    } catch (UncleanStatusException ignored) {
+      // do nothing. Ignore
+    }
+
+    RelayJNI.freeRelayPort(m_forwardHandle);
+    RelayJNI.freeRelayPort(m_reverseHandle);
+
+    m_forwardHandle = 0;
+    m_reverseHandle = 0;
+  }
+
+  @Override
+  public final synchronized String getName() {
+    return m_sendableImpl.getName();
+  }
+
+  @Override
+  public final synchronized void setName(String name) {
+    m_sendableImpl.setName(name);
+  }
+
+  /**
+   * Sets the name of the sensor with a channel number.
+   *
+   * @param moduleType A string that defines the module name in the label for the value
+   * @param channel    The channel number the device is plugged into
+   */
+  protected final void setName(String moduleType, int channel) {
+    m_sendableImpl.setName(moduleType, channel);
+  }
+
+  /**
+   * Sets the name of the sensor with a module and channel number.
+   *
+   * @param moduleType   A string that defines the module name in the label for the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually PWM)
+   */
+  protected final void setName(String moduleType, int moduleNumber, int channel) {
+    m_sendableImpl.setName(moduleType, moduleNumber, channel);
+  }
+
+  @Override
+  public final synchronized String getSubsystem() {
+    return m_sendableImpl.getSubsystem();
+  }
+
+  @Override
+  public final synchronized void setSubsystem(String subsystem) {
+    m_sendableImpl.setSubsystem(subsystem);
+  }
+
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  protected final void addChild(Object child) {
+    m_sendableImpl.addChild(child);
+  }
+
+  /**
+   * Set the relay state.
+   *
+   * <p>Valid values depend on which directions of the relay are controlled by the object.
+   *
+   * <p>When set to kBothDirections, the relay can be set to any of the four states: 0v-0v, 12v-0v,
+   * 0v-12v, 12v-12v
+   *
+   * <p>When set to kForwardOnly or kReverseOnly, you can specify the constant for the direction or
+   * you can simply specify kOff and kOn. Using only kOff and kOn is recommended.
+   *
+   * @param value The state to set the relay.
+   */
+  @SuppressWarnings("PMD.CyclomaticComplexity")
+  public void set(Value value) {
+    switch (value) {
+      case kOff:
+        if (m_direction == Direction.kBoth || m_direction == Direction.kForward) {
+          RelayJNI.setRelay(m_forwardHandle, false);
+        }
+        if (m_direction == Direction.kBoth || m_direction == Direction.kReverse) {
+          RelayJNI.setRelay(m_reverseHandle, false);
+        }
+        break;
+      case kOn:
+        if (m_direction == Direction.kBoth || m_direction == Direction.kForward) {
+          RelayJNI.setRelay(m_forwardHandle, true);
+        }
+        if (m_direction == Direction.kBoth || m_direction == Direction.kReverse) {
+          RelayJNI.setRelay(m_reverseHandle, true);
+        }
+        break;
+      case kForward:
+        if (m_direction == Direction.kReverse) {
+          throw new InvalidValueException("A relay configured for reverse cannot be set to "
+              + "forward");
+        }
+        if (m_direction == Direction.kBoth || m_direction == Direction.kForward) {
+          RelayJNI.setRelay(m_forwardHandle, true);
+        }
+        if (m_direction == Direction.kBoth) {
+          RelayJNI.setRelay(m_reverseHandle, false);
+        }
+        break;
+      case kReverse:
+        if (m_direction == Direction.kForward) {
+          throw new InvalidValueException("A relay configured for forward cannot be set to "
+              + "reverse");
+        }
+        if (m_direction == Direction.kBoth) {
+          RelayJNI.setRelay(m_forwardHandle, false);
+        }
+        if (m_direction == Direction.kBoth || m_direction == Direction.kReverse) {
+          RelayJNI.setRelay(m_reverseHandle, true);
+        }
+        break;
+      default:
+        // Cannot hit this, limited by Value enum
+    }
+  }
+
+  /**
+   * Get the Relay State.
+   *
+   * <p>Gets the current state of the relay.
+   *
+   * <p>When set to kForwardOnly or kReverseOnly, value is returned as kOn/kOff not
+   * kForward/kReverse (per the recommendation in Set)
+   *
+   * @return The current state of the relay as a Relay::Value
+   */
+  public Value get() {
+    if (m_direction == Direction.kForward) {
+      if (RelayJNI.getRelay(m_forwardHandle)) {
+        return Value.kOn;
+      } else {
+        return Value.kOff;
+      }
+    } else if (m_direction == Direction.kReverse) {
+      if (RelayJNI.getRelay(m_reverseHandle)) {
+        return Value.kOn;
+      } else {
+        return Value.kOff;
+      }
+    } else {
+      if (RelayJNI.getRelay(m_forwardHandle)) {
+        if (RelayJNI.getRelay(m_reverseHandle)) {
+          return Value.kOn;
+        } else {
+          return Value.kForward;
+        }
+      } else {
+        if (RelayJNI.getRelay(m_reverseHandle)) {
+          return Value.kReverse;
+        } else {
+          return Value.kOff;
+        }
+      }
+    }
+  }
+
+  /**
+   * Get the channel number.
+   *
+   * @return The channel number.
+   */
+  public int getChannel() {
+    return m_channel;
+  }
+
+  @Override
+  public void stopMotor() {
+    set(Value.kOff);
+  }
+
+  @Override
+  public String getDescription() {
+    return "Relay ID " + getChannel();
+  }
+
+  /**
+   * Set the Relay Direction.
+   *
+   * <p>Changes which values the relay can be set to depending on which direction is used
+   *
+   * <p>Valid inputs are kBothDirections, kForwardOnly, and kReverseOnly
+   *
+   * @param direction The direction for the relay to operate in
+   */
+  public void setDirection(Direction direction) {
+    requireNonNull(direction, "Null Direction was given");
+    if (m_direction == direction) {
+      return;
+    }
+
+    freeRelay();
+    m_direction = direction;
+    initRelay();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Relay");
+    builder.setActuator(true);
+    builder.setSafeState(() -> set(Value.kOff));
+    builder.addStringProperty("Value", () -> get().getPrettyValue(),
+        value -> set(Value.getValueOf(value).orElse(Value.kOff)));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Resource.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Resource.java
new file mode 100644
index 0000000..39a0eac
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Resource.java
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.util.AllocationException;
+import edu.wpi.first.hal.util.CheckedAllocationException;
+
+/**
+ * Track resources in the program. The Resource class is a convenient way of keeping track of
+ * allocated arbitrary resources in the program. Resources are just indices that have an lower and
+ * upper bound that are tracked by this class. In the library they are used for tracking allocation
+ * of hardware channels but this is purely arbitrary. The resource class does not do any actual
+ * allocation, but simply tracks if a given index is currently in use.
+ *
+ * <p><b>WARNING:</b> this should only be statically allocated. When the program loads into memory
+ * all the static constructors are called. At that time a linked list of all the "Resources" is
+ * created. Then when the program actually starts - in the Robot constructor, all resources are
+ * initialized. This ensures that the program is restartable in memory without having to
+ * unload/reload.
+ */
+public final class Resource {
+  private static Resource resourceList;
+  private final boolean[] m_numAllocated;
+  private final int m_size;
+  private final Resource m_nextResource;
+
+  /**
+   * Clears all allocated resources.
+   */
+  public static void restartProgram() {
+    for (Resource r = Resource.resourceList; r != null; r = r.m_nextResource) {
+      for (int i = 0; i < r.m_size; i++) {
+        r.m_numAllocated[i] = false;
+      }
+    }
+  }
+
+  /**
+   * Allocate storage for a new instance of Resource. Allocate a bool array of values that will get
+   * initialized to indicate that no resources have been allocated yet. The indices of the
+   * resources are 0..size-1.
+   *
+   * @param size The number of blocks to allocate
+   */
+  public Resource(final int size) {
+    m_size = size;
+    m_numAllocated = new boolean[size];
+    for (int i = 0; i < size; i++) {
+      m_numAllocated[i] = false;
+    }
+    m_nextResource = Resource.resourceList;
+    Resource.resourceList = this;
+  }
+
+  /**
+   * Allocate a resource. When a resource is requested, mark it allocated. In this case, a free
+   * resource value within the range is located and returned after it is marked allocated.
+   *
+   * @return The index of the allocated block.
+   * @throws CheckedAllocationException If there are no resources available to be allocated.
+   */
+  public int allocate() throws CheckedAllocationException {
+    for (int i = 0; i < m_size; i++) {
+      if (!m_numAllocated[i]) {
+        m_numAllocated[i] = true;
+        return i;
+      }
+    }
+    throw new CheckedAllocationException("No available resources");
+  }
+
+  /**
+   * Allocate a specific resource value. The user requests a specific resource value, i.e. channel
+   * number and it is verified unallocated, then returned.
+   *
+   * @param index The resource to allocate
+   * @return The index of the allocated block
+   * @throws CheckedAllocationException If there are no resources available to be allocated.
+   */
+  public int allocate(final int index) throws CheckedAllocationException {
+    if (index >= m_size || index < 0) {
+      throw new CheckedAllocationException("Index " + index + " out of range");
+    }
+    if (m_numAllocated[index]) {
+      throw new CheckedAllocationException("Resource at index " + index + " already allocated");
+    }
+    m_numAllocated[index] = true;
+    return index;
+  }
+
+  /**
+   * Free an allocated resource. After a resource is no longer needed, for example a destructor is
+   * called for a channel assignment class, Free will release the resource value so it can be reused
+   * somewhere else in the program.
+   *
+   * @param index The index of the resource to free.
+   */
+  public void free(final int index) {
+    if (!m_numAllocated[index]) {
+      throw new AllocationException("No resource available to be freed");
+    }
+    m_numAllocated[index] = false;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java
new file mode 100644
index 0000000..44c03a3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotBase.java
@@ -0,0 +1,285 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.io.File;
+import java.io.IOException;
+import java.io.OutputStream;
+import java.nio.charset.StandardCharsets;
+import java.nio.file.Files;
+import java.util.function.Supplier;
+
+import edu.wpi.cscore.CameraServerJNI;
+import edu.wpi.first.cameraserver.CameraServerShared;
+import edu.wpi.first.cameraserver.CameraServerSharedStore;
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.HALUtil;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
+import edu.wpi.first.wpilibj.util.WPILibVersion;
+
+/**
+ * Implement a Robot Program framework. The RobotBase class is intended to be subclassed by a user
+ * creating a robot program. Overridden autonomous() and operatorControl() methods are called at the
+ * appropriate time as the match proceeds. In the current implementation, the Autonomous code will
+ * run to completion before the OperatorControl code could start. In the future the Autonomous code
+ * might be spawned as a task, then killed at the end of the Autonomous period.
+ */
+public abstract class RobotBase implements AutoCloseable {
+  /**
+   * The ID of the main Java thread.
+   */
+  // This is usually 1, but it is best to make sure
+  public static final long MAIN_THREAD_ID = Thread.currentThread().getId();
+
+  private static void setupCameraServerShared() {
+    CameraServerShared shared = new CameraServerShared() {
+
+      @Override
+      public void reportVideoServer(int id) {
+        HAL.report(tResourceType.kResourceType_PCVideoServer, id);
+      }
+
+      @Override
+      public void reportUsbCamera(int id) {
+        HAL.report(tResourceType.kResourceType_UsbCamera, id);
+      }
+
+      @Override
+      public void reportDriverStationError(String error) {
+        DriverStation.reportError(error, true);
+      }
+
+      @Override
+      public void reportAxisCamera(int id) {
+        HAL.report(tResourceType.kResourceType_AxisCamera, id);
+      }
+
+      @Override
+      public Long getRobotMainThreadId() {
+        return MAIN_THREAD_ID;
+      }
+    };
+
+    CameraServerSharedStore.setCameraServerShared(shared);
+  }
+
+  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
+   * completion before Autonomous is entered.
+   *
+   * <p>This must be used to ensure that the communications code starts. In the future it would be
+   * nice
+   * to put this code into it's own task that loads on boot so ensure that it runs.
+   */
+  protected RobotBase() {
+    NetworkTableInstance inst = NetworkTableInstance.getDefault();
+    setupCameraServerShared();
+    inst.setNetworkIdentity("Robot");
+    inst.startServer("/home/lvuser/networktables.ini");
+    m_ds = DriverStation.getInstance();
+    inst.getTable("LiveWindow").getSubTable(".status").getEntry("LW Enabled").setBoolean(false);
+
+    LiveWindow.setEnabled(false);
+    Shuffleboard.disableActuatorWidgets();
+  }
+
+  @Deprecated
+  public void free() {
+  }
+
+  @Override
+  public void close() {
+  }
+
+  /**
+   * Get if the robot is a simulation.
+   *
+   * @return If the robot is running in simulation.
+   */
+  public static boolean isSimulation() {
+    return !isReal();
+  }
+
+  /**
+   * Get if the robot is real.
+   *
+   * @return If the robot is running in the real world.
+   */
+  public static boolean isReal() {
+    return HALUtil.getHALRuntimeType() == 0;
+  }
+
+  /**
+   * Determine if the Robot is currently disabled.
+   *
+   * @return True if the Robot is currently disabled by the field controls.
+   */
+  public boolean isDisabled() {
+    return m_ds.isDisabled();
+  }
+
+  /**
+   * Determine if the Robot is currently enabled.
+   *
+   * @return True if the Robot is currently enabled by the field controls.
+   */
+  public boolean isEnabled() {
+    return m_ds.isEnabled();
+  }
+
+  /**
+   * Determine if the robot is currently in Autonomous mode as determined by the field
+   * controls.
+   *
+   * @return True if the robot is currently operating Autonomously.
+   */
+  public boolean isAutonomous() {
+    return m_ds.isAutonomous();
+  }
+
+  /**
+   * Determine if the robot is currently in Test mode as determined by the driver
+   * station.
+   *
+   * @return True if the robot is currently operating in Test mode.
+   */
+  public boolean isTest() {
+    return m_ds.isTest();
+  }
+
+  /**
+   * Determine if the robot is currently in Operator Control mode as determined by the field
+   * controls.
+   *
+   * @return True if the robot is currently operating in Tele-Op mode.
+   */
+  public boolean isOperatorControl() {
+    return m_ds.isOperatorControl();
+  }
+
+  /**
+   * Indicates if new data is available from the driver station.
+   *
+   * @return Has new data arrived over the network since the last time this function was called?
+   */
+  public boolean isNewDataAvailable() {
+    return m_ds.isNewControlData();
+  }
+
+  /**
+   * Provide an alternate "main loop" via startCompetition().
+   */
+  public abstract void startCompetition();
+
+  @SuppressWarnings("JavadocMethod")
+  public static boolean getBooleanProperty(String name, boolean defaultValue) {
+    String propVal = System.getProperty(name);
+    if (propVal == null) {
+      return defaultValue;
+    }
+    if ("false".equalsIgnoreCase(propVal)) {
+      return false;
+    } else if ("true".equalsIgnoreCase(propVal)) {
+      return true;
+    } else {
+      throw new IllegalStateException(propVal);
+    }
+  }
+
+  /**
+   * Starting point for the applications.
+   */
+  @SuppressWarnings({"PMD.AvoidInstantiatingObjectsInLoops", "PMD.AvoidCatchingThrowable",
+                     "PMD.CyclomaticComplexity", "PMD.NPathComplexity"})
+  public static <T extends RobotBase> void startRobot(Supplier<T> robotSupplier) {
+    if (!HAL.initialize(500, 0)) {
+      throw new IllegalStateException("Failed to initialize. Terminating");
+    }
+
+    // Call a CameraServer JNI function to force OpenCV native library loading
+    // Needed because all the OpenCV JNI functions don't have built in loading
+    CameraServerJNI.enumerateSinks();
+
+    HAL.report(tResourceType.kResourceType_Language, tInstances.kLanguage_Java);
+
+    System.out.println("********** Robot program starting **********");
+
+    T robot;
+    try {
+      robot = robotSupplier.get();
+    } catch (Throwable throwable) {
+      Throwable cause = throwable.getCause();
+      if (cause != null) {
+        throwable = cause;
+      }
+      String robotName = "Unknown";
+      StackTraceElement[] elements = throwable.getStackTrace();
+      if (elements.length > 0) {
+        robotName = elements[0].getClassName();
+      }
+      DriverStation.reportError("Unhandled exception instantiating robot " + robotName + " "
+          + throwable.toString(), elements);
+      DriverStation.reportWarning("Robots should not quit, but yours did!", false);
+      DriverStation.reportError("Could not instantiate robot " + robotName + "!", false);
+      System.exit(1);
+      return;
+    }
+
+    if (isReal()) {
+      try {
+        final File file = new File("/tmp/frc_versions/FRC_Lib_Version.ini");
+
+        if (file.exists()) {
+          file.delete();
+        }
+
+        file.createNewFile();
+
+        try (OutputStream output = Files.newOutputStream(file.toPath())) {
+          output.write("Java ".getBytes(StandardCharsets.UTF_8));
+          output.write(WPILibVersion.Version.getBytes(StandardCharsets.UTF_8));
+        }
+
+      } catch (IOException ex) {
+        DriverStation.reportError("Could not write FRC_Lib_Version.ini: " + ex.toString(),
+                ex.getStackTrace());
+      }
+    }
+
+    boolean errorOnExit = false;
+    try {
+      robot.startCompetition();
+    } catch (Throwable throwable) {
+      Throwable cause = throwable.getCause();
+      if (cause != null) {
+        throwable = cause;
+      }
+      DriverStation.reportError("Unhandled exception: " + throwable.toString(),
+          throwable.getStackTrace());
+      errorOnExit = true;
+    } finally {
+      // startCompetition never returns unless exception occurs....
+      DriverStation.reportWarning("Robots should not quit, but yours did!", false);
+      if (errorOnExit) {
+        DriverStation.reportError(
+            "The startCompetition() method (or methods called by it) should have "
+                + "handled the exception above.", false);
+      } else {
+        DriverStation.reportError("Unexpected return from startCompetition() method.", false);
+      }
+    }
+    System.exit(1);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java
new file mode 100644
index 0000000..0623812
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotController.java
@@ -0,0 +1,232 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.HALUtil;
+import edu.wpi.first.hal.PowerJNI;
+import edu.wpi.first.hal.can.CANJNI;
+import edu.wpi.first.hal.can.CANStatus;
+
+/**
+ * Contains functions for roboRIO functionality.
+ */
+public final class RobotController {
+  private RobotController() {
+    throw new UnsupportedOperationException("This is a utility class!");
+  }
+
+  /**
+   * Return the FPGA Version number. For now, expect this to be the current
+   * year.
+   *
+   * @return FPGA Version number.
+   */
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public static int getFPGAVersion() {
+    return HALUtil.getFPGAVersion();
+  }
+
+  /**
+   * Return the FPGA Revision number. The format of the revision is 3 numbers. The 12 most
+   * significant bits are the Major Revision. the next 8 bits are the Minor Revision. The 12 least
+   * significant bits are the Build Number.
+   *
+   * @return FPGA Revision number.
+   */
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public static long getFPGARevision() {
+    return (long) HALUtil.getFPGARevision();
+  }
+
+  /**
+   * Read the microsecond timer from the FPGA.
+   *
+   * @return The current time in microseconds according to the FPGA.
+   */
+  public static long getFPGATime() {
+    return HALUtil.getFPGATime();
+  }
+
+  /**
+   * Get the state of the "USER" button on the roboRIO.
+   *
+   * @return true if the button is currently pressed down
+   */
+  public static boolean getUserButton() {
+    return HALUtil.getFPGAButton();
+  }
+
+  /**
+   * Read the battery voltage.
+   *
+   * @return The battery voltage in Volts.
+   */
+  public static double getBatteryVoltage() {
+    return PowerJNI.getVinVoltage();
+  }
+
+  /**
+   * Gets a value indicating whether the FPGA outputs are enabled. The outputs may be disabled if
+   * the robot is disabled or e-stopped, the watchdog has expired, or if the roboRIO browns out.
+   *
+   * @return True if the FPGA outputs are enabled.
+   */
+  public static boolean isSysActive() {
+    return HAL.getSystemActive();
+  }
+
+  /**
+   * Check if the system is browned out.
+   *
+   * @return True if the system is browned out
+   */
+  public static boolean isBrownedOut() {
+    return HAL.getBrownedOut();
+  }
+
+  /**
+   * Get the input voltage to the robot controller.
+   *
+   * @return The controller input voltage value in Volts
+   */
+  public static double getInputVoltage() {
+    return PowerJNI.getVinVoltage();
+  }
+
+  /**
+   * Get the input current to the robot controller.
+   *
+   * @return The controller input current value in Amps
+   */
+  public static double getInputCurrent() {
+    return PowerJNI.getVinCurrent();
+  }
+
+  /**
+   * Get the voltage of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail voltage value in Volts
+   */
+  public static double getVoltage3V3() {
+    return PowerJNI.getUserVoltage3V3();
+  }
+
+  /**
+   * Get the current output of the 3.3V rail.
+   *
+   * @return The controller 3.3V rail output current value in Volts
+   */
+  public static double getCurrent3V3() {
+    return PowerJNI.getUserCurrent3V3();
+  }
+
+  /**
+   * Get the enabled state of the 3.3V rail. The rail may be disabled due to a controller brownout,
+   * a short circuit on the rail, or controller over-voltage.
+   *
+   * @return The controller 3.3V rail enabled value
+   */
+  public static boolean getEnabled3V3() {
+    return PowerJNI.getUserActive3V3();
+  }
+
+  /**
+   * Get the count of the total current faults on the 3.3V rail since the controller has booted.
+   *
+   * @return The number of faults
+   */
+  public static int getFaultCount3V3() {
+    return PowerJNI.getUserCurrentFaults3V3();
+  }
+
+  /**
+   * Get the voltage of the 5V rail.
+   *
+   * @return The controller 5V rail voltage value in Volts
+   */
+  public static double getVoltage5V() {
+    return PowerJNI.getUserVoltage5V();
+  }
+
+  /**
+   * Get the current output of the 5V rail.
+   *
+   * @return The controller 5V rail output current value in Amps
+   */
+  public static double getCurrent5V() {
+    return PowerJNI.getUserCurrent5V();
+  }
+
+  /**
+   * Get the enabled state of the 5V rail. The rail may be disabled due to a controller brownout, a
+   * short circuit on the rail, or controller over-voltage.
+   *
+   * @return The controller 5V rail enabled value
+   */
+  public static boolean getEnabled5V() {
+    return PowerJNI.getUserActive5V();
+  }
+
+  /**
+   * Get the count of the total current faults on the 5V rail since the controller has booted.
+   *
+   * @return The number of faults
+   */
+  public static int getFaultCount5V() {
+    return PowerJNI.getUserCurrentFaults5V();
+  }
+
+  /**
+   * Get the voltage of the 6V rail.
+   *
+   * @return The controller 6V rail voltage value in Volts
+   */
+  public static double getVoltage6V() {
+    return PowerJNI.getUserVoltage6V();
+  }
+
+  /**
+   * Get the current output of the 6V rail.
+   *
+   * @return The controller 6V rail output current value in Amps
+   */
+  public static double getCurrent6V() {
+    return PowerJNI.getUserCurrent6V();
+  }
+
+  /**
+   * Get the enabled state of the 6V rail. The rail may be disabled due to a controller brownout, a
+   * short circuit on the rail, or controller over-voltage.
+   *
+   * @return The controller 6V rail enabled value
+   */
+  public static boolean getEnabled6V() {
+    return PowerJNI.getUserActive6V();
+  }
+
+  /**
+   * Get the count of the total current faults on the 6V rail since the controller has booted.
+   *
+   * @return The number of faults
+   */
+  public static int getFaultCount6V() {
+    return PowerJNI.getUserCurrentFaults6V();
+  }
+
+  /**
+   * Get the current status of the CAN bus.
+   *
+   * @return The status of the CAN bus
+   */
+  public static CANStatus getCANStatus() {
+    CANStatus status = new CANStatus();
+    CANJNI.GetCANStatus(status);
+    return status;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java
new file mode 100644
index 0000000..6f020fd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotDrive.java
@@ -0,0 +1,723 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Utility class for handling Robot drive based on a definition of the motor configuration. The
+ * robot drive class handles basic driving for a robot. Currently, 2 and 4 motor tank and mecanum
+ * drive trains are supported. In the future other drive types like swerve might be implemented.
+ * Motor channel numbers are supplied on creation of the class. Those are used for either the drive
+ * function (intended for hand created drive code, such as autonomous) or with the Tank/Arcade
+ * functions intended to be used for Operator Control driving.
+ *
+ * @deprecated Use {@link edu.wpi.first.wpilibj.drive.DifferentialDrive}
+ *             or {@link edu.wpi.first.wpilibj.drive.MecanumDrive} classes instead.
+ */
+@Deprecated
+@SuppressWarnings({"PMD.GodClass", "PMD.TooManyMethods"})
+public class RobotDrive extends MotorSafety implements AutoCloseable {
+  /**
+   * The location of a motor on the robot for the purpose of driving.
+   */
+  public enum MotorType {
+    kFrontLeft(0), kFrontRight(1), kRearLeft(2), kRearRight(3);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    MotorType(int value) {
+      this.value = value;
+    }
+  }
+
+  public static final double kDefaultExpirationTime = 0.1;
+  public static final double kDefaultSensitivity = 0.5;
+  public static final double kDefaultMaxOutput = 1.0;
+  protected static final int kMaxNumberOfMotors = 4;
+  protected double m_sensitivity;
+  protected double m_maxOutput;
+  protected SpeedController m_frontLeftMotor;
+  protected SpeedController m_frontRightMotor;
+  protected SpeedController m_rearLeftMotor;
+  protected SpeedController m_rearRightMotor;
+  protected boolean m_allocatedSpeedControllers;
+  protected static boolean kArcadeRatioCurve_Reported;
+  protected static boolean kTank_Reported;
+  protected static boolean kArcadeStandard_Reported;
+  protected static boolean kMecanumCartesian_Reported;
+  protected static boolean kMecanumPolar_Reported;
+
+  /**
+   * Constructor for RobotDrive with 2 motors specified with channel numbers. Set up parameters for
+   * a two wheel drive system where the left and right motor pwm channels are specified in the call.
+   * This call assumes Talons for controlling the motors.
+   *
+   * @param leftMotorChannel  The PWM channel number that drives the left motor.
+   * @param rightMotorChannel The PWM channel number that drives the right motor.
+   */
+  public RobotDrive(final int leftMotorChannel, final int rightMotorChannel) {
+    m_sensitivity = kDefaultSensitivity;
+    m_maxOutput = kDefaultMaxOutput;
+    m_frontLeftMotor = null;
+    m_rearLeftMotor = new Talon(leftMotorChannel);
+    m_frontRightMotor = null;
+    m_rearRightMotor = new Talon(rightMotorChannel);
+    m_allocatedSpeedControllers = true;
+    setSafetyEnabled(true);
+    drive(0, 0);
+  }
+
+  /**
+   * Constructor for RobotDrive with 4 motors specified with channel numbers. Set up parameters for
+   * a four wheel drive system where all four motor pwm channels are specified in the call. This
+   * call assumes Talons for controlling the motors.
+   *
+   * @param frontLeftMotor  Front left motor channel number
+   * @param rearLeftMotor   Rear Left motor channel number
+   * @param frontRightMotor Front right motor channel number
+   * @param rearRightMotor  Rear Right motor channel number
+   */
+  public RobotDrive(final int frontLeftMotor, final int rearLeftMotor, final int frontRightMotor,
+                    final int rearRightMotor) {
+    m_sensitivity = kDefaultSensitivity;
+    m_maxOutput = kDefaultMaxOutput;
+    m_rearLeftMotor = new Talon(rearLeftMotor);
+    m_rearRightMotor = new Talon(rearRightMotor);
+    m_frontLeftMotor = new Talon(frontLeftMotor);
+    m_frontRightMotor = new Talon(frontRightMotor);
+    m_allocatedSpeedControllers = true;
+    setSafetyEnabled(true);
+    drive(0, 0);
+  }
+
+  /**
+   * Constructor for RobotDrive with 2 motors specified as SpeedController objects. The
+   * SpeedController version of the constructor enables programs to use the RobotDrive classes with
+   * subclasses of the SpeedController objects, for example, versions with ramping or reshaping of
+   * the curve to suit motor bias or dead-band elimination.
+   *
+   * @param leftMotor  The left SpeedController object used to drive the robot.
+   * @param rightMotor the right SpeedController object used to drive the robot.
+   */
+  public RobotDrive(SpeedController leftMotor, SpeedController rightMotor) {
+    requireNonNull(leftMotor, "Provided left motor was null");
+    requireNonNull(rightMotor, "Provided right motor was null");
+
+    m_frontLeftMotor = null;
+    m_rearLeftMotor = leftMotor;
+    m_frontRightMotor = null;
+    m_rearRightMotor = rightMotor;
+    m_sensitivity = kDefaultSensitivity;
+    m_maxOutput = kDefaultMaxOutput;
+    m_allocatedSpeedControllers = false;
+    setSafetyEnabled(true);
+    drive(0, 0);
+  }
+
+  /**
+   * Constructor for RobotDrive with 4 motors specified as SpeedController objects. Speed controller
+   * input version of RobotDrive (see previous comments).
+   *
+   * @param frontLeftMotor  The front left SpeedController object used to drive the robot
+   * @param rearLeftMotor   The back left SpeedController object used to drive the robot.
+   * @param frontRightMotor The front right SpeedController object used to drive the robot.
+   * @param rearRightMotor  The back right SpeedController object used to drive the robot.
+   */
+  public RobotDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor,
+                    SpeedController frontRightMotor, SpeedController rearRightMotor) {
+    m_frontLeftMotor = requireNonNull(frontLeftMotor, "frontLeftMotor cannot be null");
+    m_rearLeftMotor = requireNonNull(rearLeftMotor, "rearLeftMotor cannot be null");
+    m_frontRightMotor = requireNonNull(frontRightMotor, "frontRightMotor cannot be null");
+    m_rearRightMotor = requireNonNull(rearRightMotor, "rearRightMotor cannot be null");
+    m_sensitivity = kDefaultSensitivity;
+    m_maxOutput = kDefaultMaxOutput;
+    m_allocatedSpeedControllers = false;
+    setSafetyEnabled(true);
+    drive(0, 0);
+  }
+
+  /**
+   * Drive the motors at "outputMagnitude" and "curve". Both outputMagnitude and curve are -1.0 to
+   * +1.0 values, where 0.0 represents stopped and not turning. {@literal curve < 0 will turn left
+   * and curve > 0} will turn right.
+   *
+   * <p>The algorithm for steering provides a constant turn radius for any normal speed range, both
+   * forward and backward. Increasing sensitivity causes sharper turns for fixed values of curve.
+   *
+   * <p>This function will most likely be used in an autonomous routine.
+   *
+   * @param outputMagnitude The speed setting for the outside wheel in a turn, forward or backwards,
+   *                        +1 to -1.
+   * @param curve           The rate of turn, constant for different forward speeds. Set {@literal
+   *                        curve < 0 for left turn or curve > 0 for right turn.} Set curve =
+   *                        e^(-r/w) to get a turn radius r for wheelbase w of your robot.
+   *                        Conversely, turn radius r = -ln(curve)*w for a given value of curve and
+   *                        wheelbase w.
+   */
+  public void drive(double outputMagnitude, double curve) {
+    final double leftOutput;
+    final double rightOutput;
+
+    if (!kArcadeRatioCurve_Reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
+          tInstances.kRobotDrive_ArcadeRatioCurve);
+      kArcadeRatioCurve_Reported = true;
+    }
+    if (curve < 0) {
+      double value = Math.log(-curve);
+      double ratio = (value - m_sensitivity) / (value + m_sensitivity);
+      if (ratio == 0) {
+        ratio = .0000000001;
+      }
+      leftOutput = outputMagnitude / ratio;
+      rightOutput = outputMagnitude;
+    } else if (curve > 0) {
+      double value = Math.log(curve);
+      double ratio = (value - m_sensitivity) / (value + m_sensitivity);
+      if (ratio == 0) {
+        ratio = .0000000001;
+      }
+      leftOutput = outputMagnitude;
+      rightOutput = outputMagnitude / ratio;
+    } else {
+      leftOutput = outputMagnitude;
+      rightOutput = outputMagnitude;
+    }
+    setLeftRightMotorOutputs(leftOutput, rightOutput);
+  }
+
+  /**
+   * Provide tank steering using the stored robot configuration. drive the robot using two joystick
+   * inputs. The Y-axis will be selected from each Joystick object. The calculated values will be
+   * squared to decrease sensitivity at low speeds.
+   *
+   * @param leftStick  The joystick to control the left side of the robot.
+   * @param rightStick The joystick to control the right side of the robot.
+   */
+  public void tankDrive(GenericHID leftStick, GenericHID rightStick) {
+    requireNonNull(leftStick, "Provided left stick was null");
+    requireNonNull(rightStick, "Provided right stick was null");
+
+    tankDrive(leftStick.getY(), rightStick.getY(), true);
+  }
+
+  /**
+   * Provide tank steering using the stored robot configuration. drive the robot using two joystick
+   * inputs. The Y-axis will be selected from each Joystick object.
+   *
+   * @param leftStick     The joystick to control the left side of the robot.
+   * @param rightStick    The joystick to control the right side of the robot.
+   * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
+   */
+  public void tankDrive(GenericHID leftStick, GenericHID rightStick, boolean squaredInputs) {
+    requireNonNull(leftStick, "Provided left stick was null");
+    requireNonNull(rightStick, "Provided right stick was null");
+
+    tankDrive(leftStick.getY(), rightStick.getY(), squaredInputs);
+  }
+
+  /**
+   * Provide tank steering using the stored robot configuration. This function lets you pick the
+   * axis to be used on each Joystick object for the left and right sides of the robot. The
+   * calculated values will be squared to decrease sensitivity at low speeds.
+   *
+   * @param leftStick  The Joystick object to use for the left side of the robot.
+   * @param leftAxis   The axis to select on the left side Joystick object.
+   * @param rightStick The Joystick object to use for the right side of the robot.
+   * @param rightAxis  The axis to select on the right side Joystick object.
+   */
+  public void tankDrive(GenericHID leftStick, final int leftAxis, GenericHID rightStick,
+                        final int rightAxis) {
+    requireNonNull(leftStick, "Provided left stick was null");
+    requireNonNull(rightStick, "Provided right stick was null");
+
+    tankDrive(leftStick.getRawAxis(leftAxis), rightStick.getRawAxis(rightAxis), true);
+  }
+
+  /**
+   * Provide tank steering using the stored robot configuration. This function lets you pick the
+   * axis to be used on each Joystick object for the left and right sides of the robot.
+   *
+   * @param leftStick     The Joystick object to use for the left side of the robot.
+   * @param leftAxis      The axis to select on the left side Joystick object.
+   * @param rightStick    The Joystick object to use for the right side of the robot.
+   * @param rightAxis     The axis to select on the right side Joystick object.
+   * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
+   */
+  public void tankDrive(GenericHID leftStick, final int leftAxis, GenericHID rightStick,
+                        final int rightAxis, boolean squaredInputs) {
+    requireNonNull(leftStick, "Provided left stick was null");
+    requireNonNull(rightStick, "Provided right stick was null");
+
+    tankDrive(leftStick.getRawAxis(leftAxis), rightStick.getRawAxis(rightAxis), squaredInputs);
+  }
+
+  /**
+   * Provide tank steering using the stored robot configuration. This function lets you directly
+   * provide joystick values from any source.
+   *
+   * @param leftValue     The value of the left stick.
+   * @param rightValue    The value of the right stick.
+   * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
+   */
+  public void tankDrive(double leftValue, double rightValue, boolean squaredInputs) {
+    if (!kTank_Reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
+          tInstances.kRobotDrive_Tank);
+      kTank_Reported = true;
+    }
+
+    leftValue = limit(leftValue);
+    rightValue = limit(rightValue);
+
+    // square the inputs (while preserving the sign) to increase fine control
+    // while permitting full power
+    if (squaredInputs) {
+      leftValue = Math.copySign(leftValue * leftValue, leftValue);
+      rightValue = Math.copySign(rightValue * rightValue, rightValue);
+    }
+    setLeftRightMotorOutputs(leftValue, rightValue);
+  }
+
+  /**
+   * Provide tank steering using the stored robot configuration. This function lets you directly
+   * provide joystick values from any source. The calculated values will be squared to decrease
+   * sensitivity at low speeds.
+   *
+   * @param leftValue  The value of the left stick.
+   * @param rightValue The value of the right stick.
+   */
+  public void tankDrive(double leftValue, double rightValue) {
+    tankDrive(leftValue, rightValue, true);
+  }
+
+  /**
+   * Arcade drive implements single stick driving. Given a single Joystick, the class assumes the Y
+   * axis for the move value and the X axis for the rotate value. (Should add more information here
+   * regarding the way that arcade drive works.)
+   *
+   * @param stick         The joystick to use for Arcade single-stick driving. The Y-axis will be
+   *                      selected for forwards/backwards and the X-axis will be selected for
+   *                      rotation rate.
+   * @param squaredInputs If true, the sensitivity will be decreased for small values
+   */
+  public void arcadeDrive(GenericHID stick, boolean squaredInputs) {
+    // simply call the full-featured arcadeDrive with the appropriate values
+    arcadeDrive(stick.getY(), stick.getX(), squaredInputs);
+  }
+
+  /**
+   * Arcade drive implements single stick driving. Given a single Joystick, the class assumes the Y
+   * axis for the move value and the X axis for the rotate value. (Should add more information here
+   * regarding the way that arcade drive works.) The calculated values will be squared to decrease
+   * sensitivity at low speeds.
+   *
+   * @param stick The joystick to use for Arcade single-stick driving. The Y-axis will be selected
+   *              for forwards/backwards and the X-axis will be selected for rotation rate.
+   */
+  public void arcadeDrive(GenericHID stick) {
+    arcadeDrive(stick, true);
+  }
+
+  /**
+   * Arcade drive implements single stick driving. Given two joystick instances and two axis,
+   * compute the values to send to either two or four motors.
+   *
+   * @param moveStick     The Joystick object that represents the forward/backward direction
+   * @param moveAxis      The axis on the moveStick object to use for forwards/backwards (typically
+   *                      Y_AXIS)
+   * @param rotateStick   The Joystick object that represents the rotation value
+   * @param rotateAxis    The axis on the rotation object to use for the rotate right/left
+   *                      (typically X_AXIS)
+   * @param squaredInputs Setting this parameter to true decreases the sensitivity at lower speeds
+   */
+  public void arcadeDrive(GenericHID moveStick, final int moveAxis, GenericHID rotateStick,
+                          final int rotateAxis, boolean squaredInputs) {
+    double moveValue = moveStick.getRawAxis(moveAxis);
+    double rotateValue = rotateStick.getRawAxis(rotateAxis);
+
+    arcadeDrive(moveValue, rotateValue, squaredInputs);
+  }
+
+  /**
+   * Arcade drive implements single stick driving. Given two joystick instances and two axis,
+   * compute the values to send to either two or four motors. The calculated values will be
+   * squared to decrease sensitivity at low speeds.
+   *
+   * @param moveStick   The Joystick object that represents the forward/backward direction
+   * @param moveAxis    The axis on the moveStick object to use for forwards/backwards (typically
+   *                    Y_AXIS)
+   * @param rotateStick The Joystick object that represents the rotation value
+   * @param rotateAxis  The axis on the rotation object to use for the rotate right/left (typically
+   *                    X_AXIS)
+   */
+  public void arcadeDrive(GenericHID moveStick, final int moveAxis, GenericHID rotateStick,
+                          final int rotateAxis) {
+    arcadeDrive(moveStick, moveAxis, rotateStick, rotateAxis, true);
+  }
+
+  /**
+   * Arcade drive implements single stick driving. This function lets you directly provide
+   * joystick values from any source.
+   *
+   * @param moveValue     The value to use for forwards/backwards
+   * @param rotateValue   The value to use for the rotate right/left
+   * @param squaredInputs If set, decreases the sensitivity at low speeds
+   */
+  public void arcadeDrive(double moveValue, double rotateValue, boolean squaredInputs) {
+    // local variables to hold the computed PWM values for the motors
+    if (!kArcadeStandard_Reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
+          tInstances.kRobotDrive_ArcadeStandard);
+      kArcadeStandard_Reported = true;
+    }
+
+    double leftMotorSpeed;
+    double rightMotorSpeed;
+
+    moveValue = limit(moveValue);
+    rotateValue = limit(rotateValue);
+
+    // square the inputs (while preserving the sign) to increase fine control
+    // while permitting full power
+    if (squaredInputs) {
+      // square the inputs (while preserving the sign) to increase fine control
+      // while permitting full power
+      moveValue = Math.copySign(moveValue * moveValue, moveValue);
+      rotateValue = Math.copySign(rotateValue * rotateValue, rotateValue);
+    }
+
+    if (moveValue > 0.0) {
+      if (rotateValue > 0.0) {
+        leftMotorSpeed = moveValue - rotateValue;
+        rightMotorSpeed = Math.max(moveValue, rotateValue);
+      } else {
+        leftMotorSpeed = Math.max(moveValue, -rotateValue);
+        rightMotorSpeed = moveValue + rotateValue;
+      }
+    } else {
+      if (rotateValue > 0.0) {
+        leftMotorSpeed = -Math.max(-moveValue, rotateValue);
+        rightMotorSpeed = moveValue + rotateValue;
+      } else {
+        leftMotorSpeed = moveValue - rotateValue;
+        rightMotorSpeed = -Math.max(-moveValue, -rotateValue);
+      }
+    }
+
+    setLeftRightMotorOutputs(leftMotorSpeed, rightMotorSpeed);
+  }
+
+  /**
+   * Arcade drive implements single stick driving. This function lets you directly provide
+   * joystick values from any source. The calculated values will be squared to decrease
+   * sensitivity at low speeds.
+   *
+   * @param moveValue   The value to use for forwards/backwards
+   * @param rotateValue The value to use for the rotate right/left
+   */
+  public void arcadeDrive(double moveValue, double rotateValue) {
+    arcadeDrive(moveValue, rotateValue, true);
+  }
+
+  /**
+   * Drive method for Mecanum wheeled robots.
+   *
+   * <p>A method for driving with Mecanum wheeled robots. There are 4 wheels on the robot, arranged
+   * so that the front and back wheels are toed in 45 degrees. When looking at the wheels from the
+   * top, the roller axles should form an X across the robot.
+   *
+   * <p>This is designed to be directly driven by joystick axes.
+   *
+   * @param x         The speed that the robot should drive in the X direction. [-1.0..1.0]
+   * @param y         The speed that the robot should drive in the Y direction. This input is
+   *                  inverted to match the forward == -1.0 that joysticks produce. [-1.0..1.0]
+   * @param rotation  The rate of rotation for the robot that is completely independent of the
+   *                  translation. [-1.0..1.0]
+   * @param gyroAngle The current angle reading from the gyro. Use this to implement field-oriented
+   *                  controls.
+   */
+  @SuppressWarnings("ParameterName")
+  public void mecanumDrive_Cartesian(double x, double y, double rotation, double gyroAngle) {
+    if (!kMecanumCartesian_Reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
+          tInstances.kRobotDrive_MecanumCartesian);
+      kMecanumCartesian_Reported = true;
+    }
+    @SuppressWarnings("LocalVariableName")
+    double xIn = x;
+    @SuppressWarnings("LocalVariableName")
+    double yIn = y;
+    // Negate y for the joystick.
+    yIn = -yIn;
+    // Compensate for gyro angle.
+    double[] rotated = rotateVector(xIn, yIn, gyroAngle);
+    xIn = rotated[0];
+    yIn = rotated[1];
+
+    double[] wheelSpeeds = new double[kMaxNumberOfMotors];
+    wheelSpeeds[MotorType.kFrontLeft.value] = xIn + yIn + rotation;
+    wheelSpeeds[MotorType.kFrontRight.value] = -xIn + yIn - rotation;
+    wheelSpeeds[MotorType.kRearLeft.value] = -xIn + yIn + rotation;
+    wheelSpeeds[MotorType.kRearRight.value] = xIn + yIn - rotation;
+
+    normalize(wheelSpeeds);
+    m_frontLeftMotor.set(wheelSpeeds[MotorType.kFrontLeft.value] * m_maxOutput);
+    m_frontRightMotor.set(wheelSpeeds[MotorType.kFrontRight.value] * m_maxOutput);
+    m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft.value] * m_maxOutput);
+    m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput);
+
+    feed();
+  }
+
+  /**
+   * Drive method for Mecanum wheeled robots.
+   *
+   * <p>A method for driving with Mecanum wheeled robots. There are 4 wheels on the robot, arranged
+   * so that the front and back wheels are toed in 45 degrees. When looking at the wheels from the
+   * top, the roller axles should form an X across the robot.
+   *
+   * @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
+   * @param direction The angle the robot should drive in degrees. The direction and magnitude
+   *                  are independent of the rotation rate. [-180.0..180.0]
+   * @param rotation  The rate of rotation for the robot that is completely independent of the
+   *                  magnitude or direction. [-1.0..1.0]
+   */
+  public void mecanumDrive_Polar(double magnitude, double direction, double rotation) {
+    if (!kMecanumPolar_Reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, getNumMotors(),
+          tInstances.kRobotDrive_MecanumPolar);
+      kMecanumPolar_Reported = true;
+    }
+    // Normalized for full power along the Cartesian axes.
+    magnitude = limit(magnitude) * Math.sqrt(2.0);
+    // The rollers are at 45 degree angles.
+    double dirInRad = (direction + 45.0) * Math.PI / 180.0;
+    double cosD = Math.cos(dirInRad);
+    double sinD = Math.sin(dirInRad);
+
+    double[] wheelSpeeds = new double[kMaxNumberOfMotors];
+    wheelSpeeds[MotorType.kFrontLeft.value] = sinD * magnitude + rotation;
+    wheelSpeeds[MotorType.kFrontRight.value] = cosD * magnitude - rotation;
+    wheelSpeeds[MotorType.kRearLeft.value] = cosD * magnitude + rotation;
+    wheelSpeeds[MotorType.kRearRight.value] = sinD * magnitude - rotation;
+
+    normalize(wheelSpeeds);
+
+    m_frontLeftMotor.set(wheelSpeeds[MotorType.kFrontLeft.value] * m_maxOutput);
+    m_frontRightMotor.set(wheelSpeeds[MotorType.kFrontRight.value] * m_maxOutput);
+    m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft.value] * m_maxOutput);
+    m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput);
+
+    feed();
+  }
+
+  /**
+   * Holonomic Drive method for Mecanum wheeled robots.
+   *
+   * <p>This is an alias to mecanumDrive_Polar() for backward compatibility
+   *
+   * @param magnitude The speed that the robot should drive in a given direction. [-1.0..1.0]
+   * @param direction The direction the robot should drive. The direction and maginitude are
+   *                  independent of the rotation rate.
+   * @param rotation  The rate of rotation for the robot that is completely independent of the
+   *                  magnitute or direction. [-1.0..1.0]
+   */
+  void holonomicDrive(double magnitude, double direction, double rotation) {
+    mecanumDrive_Polar(magnitude, direction, rotation);
+  }
+
+  /**
+   * Set the speed of the right and left motors. This is used once an appropriate drive setup
+   * function is called such as twoWheelDrive(). The motors are set to "leftSpeed" and
+   * "rightSpeed" and includes flipping the direction of one side for opposing motors.
+   *
+   * @param leftOutput  The speed to send to the left side of the robot.
+   * @param rightOutput The speed to send to the right side of the robot.
+   */
+  public void setLeftRightMotorOutputs(double leftOutput, double rightOutput) {
+    requireNonNull(m_rearLeftMotor, "Provided left motor was null");
+    requireNonNull(m_rearRightMotor, "Provided right motor was null");
+
+    if (m_frontLeftMotor != null) {
+      m_frontLeftMotor.set(limit(leftOutput) * m_maxOutput);
+    }
+    m_rearLeftMotor.set(limit(leftOutput) * m_maxOutput);
+
+    if (m_frontRightMotor != null) {
+      m_frontRightMotor.set(-limit(rightOutput) * m_maxOutput);
+    }
+    m_rearRightMotor.set(-limit(rightOutput) * m_maxOutput);
+
+    feed();
+  }
+
+  /**
+   * Limit motor values to the -1.0 to +1.0 range.
+   */
+  protected static double limit(double number) {
+    if (number > 1.0) {
+      return 1.0;
+    }
+    if (number < -1.0) {
+      return -1.0;
+    }
+    return number;
+  }
+
+  /**
+   * Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
+   */
+  protected static void normalize(double[] wheelSpeeds) {
+    double maxMagnitude = Math.abs(wheelSpeeds[0]);
+    for (int i = 1; i < kMaxNumberOfMotors; i++) {
+      double temp = Math.abs(wheelSpeeds[i]);
+      if (maxMagnitude < temp) {
+        maxMagnitude = temp;
+      }
+    }
+    if (maxMagnitude > 1.0) {
+      for (int i = 0; i < kMaxNumberOfMotors; i++) {
+        wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+      }
+    }
+  }
+
+  /**
+   * Rotate a vector in Cartesian space.
+   */
+  @SuppressWarnings("ParameterName")
+  protected static double[] rotateVector(double x, double y, double angle) {
+    double cosA = Math.cos(angle * (Math.PI / 180.0));
+    double sinA = Math.sin(angle * (Math.PI / 180.0));
+    double[] out = new double[2];
+    out[0] = x * cosA - y * sinA;
+    out[1] = x * sinA + y * cosA;
+    return out;
+  }
+
+  /**
+   * Invert a motor direction. This is used when a motor should run in the opposite direction as the
+   * drive code would normally run it. Motors that are direct drive would be inverted, the drive
+   * code assumes that the motors are geared with one reversal.
+   *
+   * @param motor      The motor index to invert.
+   * @param isInverted True if the motor should be inverted when operated.
+   */
+  public void setInvertedMotor(MotorType motor, boolean isInverted) {
+    switch (motor) {
+      case kFrontLeft:
+        m_frontLeftMotor.setInverted(isInverted);
+        break;
+      case kFrontRight:
+        m_frontRightMotor.setInverted(isInverted);
+        break;
+      case kRearLeft:
+        m_rearLeftMotor.setInverted(isInverted);
+        break;
+      case kRearRight:
+        m_rearRightMotor.setInverted(isInverted);
+        break;
+      default:
+        throw new IllegalArgumentException("Illegal motor type: " + motor);
+    }
+  }
+
+  /**
+   * Set the turning sensitivity.
+   *
+   * <p>This only impacts the drive() entry-point.
+   *
+   * @param sensitivity Effectively sets the turning sensitivity (or turn radius for a given value)
+   */
+  public void setSensitivity(double sensitivity) {
+    m_sensitivity = sensitivity;
+  }
+
+  /**
+   * Configure the scaling factor for using RobotDrive with motor controllers in a mode other than
+   * PercentVbus.
+   *
+   * @param maxOutput Multiplied with the output percentage computed by the drive functions.
+   */
+  public void setMaxOutput(double maxOutput) {
+    m_maxOutput = maxOutput;
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  /**
+   * Free the speed controllers if they were allocated locally.
+   */
+  @Override
+  public void close() {
+    if (m_allocatedSpeedControllers) {
+      if (m_frontLeftMotor != null) {
+        ((PWM) m_frontLeftMotor).close();
+      }
+      if (m_frontRightMotor != null) {
+        ((PWM) m_frontRightMotor).close();
+      }
+      if (m_rearLeftMotor != null) {
+        ((PWM) m_rearLeftMotor).close();
+      }
+      if (m_rearRightMotor != null) {
+        ((PWM) m_rearRightMotor).close();
+      }
+    }
+  }
+
+  @Override
+  public String getDescription() {
+    return "Robot Drive";
+  }
+
+  @Override
+  public void stopMotor() {
+    if (m_frontLeftMotor != null) {
+      m_frontLeftMotor.stopMotor();
+    }
+    if (m_frontRightMotor != null) {
+      m_frontRightMotor.stopMotor();
+    }
+    if (m_rearLeftMotor != null) {
+      m_rearLeftMotor.stopMotor();
+    }
+    if (m_rearRightMotor != null) {
+      m_rearRightMotor.stopMotor();
+    }
+
+    feed();
+  }
+
+  protected int getNumMotors() {
+    int motors = 0;
+    if (m_frontLeftMotor != null) {
+      motors++;
+    }
+    if (m_frontRightMotor != null) {
+      motors++;
+    }
+    if (m_rearLeftMotor != null) {
+      motors++;
+    }
+    if (m_rearRightMotor != null) {
+      motors++;
+    }
+    return motors;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java
new file mode 100644
index 0000000..0f384ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/RobotState.java
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+@SuppressWarnings("JavadocMethod")
+public final class RobotState {
+  public static boolean isDisabled() {
+    return DriverStation.getInstance().isDisabled();
+  }
+
+  public static boolean isEnabled() {
+    return DriverStation.getInstance().isEnabled();
+  }
+
+  public static boolean isOperatorControl() {
+    return DriverStation.getInstance().isOperatorControl();
+  }
+
+  public static boolean isAutonomous() {
+    return DriverStation.getInstance().isAutonomous();
+  }
+
+  public static boolean isTest() {
+    return DriverStation.getInstance().isTest();
+  }
+
+  private RobotState() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SD540.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SD540.java
new file mode 100644
index 0000000..8f9ce0d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SD540.java
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * Mindsensors SD540 Speed Controller.
+ */
+public class SD540 extends PWMSpeedController {
+  /**
+   * Common initialization code called by all constructors.
+   *
+   * <p>Note that the SD540 uses the following bounds for PWM values. These values should work
+   * reasonably well for most controllers, but if users experience issues such as asymmetric
+   * behavior around the deadband or inability to saturate the controller in either direction,
+   * calibration is recommended. The calibration procedure can be found in the SD540 User Manual
+   * available from Mindsensors.
+   *
+   * <p>- 2.05ms = full "forward" - 1.55ms = the "high end" of the deadband range - 1.50ms = center
+   * of the deadband range (off) - 1.44ms = the "low end" of the deadband range - .94ms = full
+   * "reverse"
+   */
+  protected void initSD540() {
+    setBounds(2.05, 1.55, 1.50, 1.44, .94);
+    setPeriodMultiplier(PeriodMultiplier.k1X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_MindsensorsSD540, getChannel());
+    setName("SD540", getChannel());
+  }
+
+  /**
+   * Constructor.
+   *
+   * @param channel The PWM channel that the SD540 is attached to. 0-9 are on-board, 10-19 are on
+   *                the MXP port
+   */
+  public SD540(final int channel) {
+    super(channel);
+    initSD540();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java
new file mode 100644
index 0000000..70b9d82
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SPI.java
@@ -0,0 +1,804 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.nio.ByteBuffer;
+import java.nio.ByteOrder;
+import java.nio.IntBuffer;
+
+import edu.wpi.first.hal.AccumulatorResult;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.SPIJNI;
+
+/**
+ * Represents a SPI bus port.
+ */
+@SuppressWarnings({"PMD.CyclomaticComplexity", "PMD.TooManyMethods"})
+public class SPI implements AutoCloseable {
+  public enum Port {
+    kOnboardCS0(0), kOnboardCS1(1), kOnboardCS2(2), kOnboardCS3(3), kMXP(4);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    Port(int value) {
+      this.value = value;
+    }
+  }
+
+  private static int devices;
+
+  private int m_port;
+  private int m_msbFirst;
+  private int m_clockIdleHigh;
+  private int m_sampleOnTrailing;
+
+  /**
+   * Constructor.
+   *
+   * @param port the physical SPI port
+   */
+  public SPI(Port port) {
+    m_port = (byte) port.value;
+    devices++;
+
+    SPIJNI.spiInitialize(m_port);
+
+    HAL.report(tResourceType.kResourceType_SPI, devices);
+  }
+
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  @Override
+  public void close() {
+    if (m_accum != null) {
+      m_accum.close();
+      m_accum = null;
+    }
+    SPIJNI.spiClose(m_port);
+  }
+
+  /**
+   * Configure the rate of the generated clock signal. The default value is 500,000 Hz. The maximum
+   * value is 4,000,000 Hz.
+   *
+   * @param hz The clock rate in Hertz.
+   */
+  public final void setClockRate(int hz) {
+    SPIJNI.spiSetSpeed(m_port, hz);
+  }
+
+  /**
+   * Configure the order that bits are sent and received on the wire to be most significant bit
+   * first.
+   */
+  public final void setMSBFirst() {
+    m_msbFirst = 1;
+    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  }
+
+  /**
+   * Configure the order that bits are sent and received on the wire to be least significant bit
+   * first.
+   */
+  public final void setLSBFirst() {
+    m_msbFirst = 0;
+    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  }
+
+  /**
+   * Configure the clock output line to be active low. This is sometimes called clock polarity high
+   * or clock idle high.
+   */
+  public final void setClockActiveLow() {
+    m_clockIdleHigh = 1;
+    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  }
+
+  /**
+   * Configure the clock output line to be active high. This is sometimes called clock polarity low
+   * or clock idle low.
+   */
+  public final void setClockActiveHigh() {
+    m_clockIdleHigh = 0;
+    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  }
+
+  /**
+   * Configure that the data is stable on the leading edge and the data changes on the trailing
+   * edge.
+   */
+  public final void setSampleDataOnLeadingEdge() {
+    m_sampleOnTrailing = 0;
+    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  }
+
+  /**
+   * Configure that the data is stable on the trailing edge and the data changes on the leading
+   * edge.
+   */
+  public final void setSampleDataOnTrailingEdge() {
+    m_sampleOnTrailing = 1;
+    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  }
+
+  /**
+   * Configure that the data is stable on the falling edge and the data changes on the rising edge.
+   * Note this gets reversed is setClockActiveLow is set.
+   * @deprecated use {@link #setSampleDataOnTrailingEdge()} in most cases.
+   */
+  @Deprecated
+  public final void setSampleDataOnFalling() {
+    m_sampleOnTrailing = 1;
+    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  }
+
+  /**
+   * Configure that the data is stable on the rising edge and the data changes on the falling edge.
+   * Note this gets reversed is setClockActiveLow is set.
+   * @deprecated use {@link #setSampleDataOnLeadingEdge()} in most cases.
+   */
+  @Deprecated
+  public final void setSampleDataOnRising() {
+    m_sampleOnTrailing = 0;
+    SPIJNI.spiSetOpts(m_port, m_msbFirst, m_sampleOnTrailing, m_clockIdleHigh);
+  }
+
+
+
+  /**
+   * Configure the chip select line to be active high.
+   */
+  public final void setChipSelectActiveHigh() {
+    SPIJNI.spiSetChipSelectActiveHigh(m_port);
+  }
+
+  /**
+   * Configure the chip select line to be active low.
+   */
+  public final void setChipSelectActiveLow() {
+    SPIJNI.spiSetChipSelectActiveLow(m_port);
+  }
+
+  /**
+   * Write data to the slave device. Blocks until there is space in the output FIFO.
+   *
+   * <p>If not running in output only mode, also saves the data received on the MISO input during
+   * the transfer into the receive FIFO.
+   */
+  public int write(byte[] dataToSend, int size) {
+    if (dataToSend.length < size) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + size);
+    }
+    return SPIJNI.spiWriteB(m_port, dataToSend, (byte) size);
+  }
+
+  /**
+   * Write data to the slave device. Blocks until there is space in the output FIFO.
+   *
+   * <p>If not running in output only mode, also saves the data received on the MISO input during
+   * the transfer into the receive FIFO.
+   *
+   * @param dataToSend The buffer containing the data to send.
+   */
+  @SuppressWarnings("ByteBufferBackingArray")
+  public int write(ByteBuffer dataToSend, int size) {
+    if (dataToSend.hasArray()) {
+      return write(dataToSend.array(), size);
+    }
+    if (!dataToSend.isDirect()) {
+      throw new IllegalArgumentException("must be a direct buffer");
+    }
+    if (dataToSend.capacity() < size) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + size);
+    }
+    return SPIJNI.spiWrite(m_port, dataToSend, (byte) size);
+  }
+
+  /**
+   * Read a word from the receive FIFO.
+   *
+   * <p>Waits for the current transfer to complete if the receive FIFO is empty.
+   *
+   * <p>If the receive FIFO is empty, there is no active transfer, and initiate is false, errors.
+   *
+   * @param initiate If true, this function pushes "0" into the transmit buffer and initiates a
+   *                 transfer. If false, this function assumes that data is already in the receive
+   *                 FIFO from a previous write.
+   */
+  public int read(boolean initiate, byte[] dataReceived, int size) {
+    if (dataReceived.length < size) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + size);
+    }
+    return SPIJNI.spiReadB(m_port, initiate, dataReceived, (byte) size);
+  }
+
+  /**
+   * Read a word from the receive FIFO.
+   *
+   * <p>Waits for the current transfer to complete if the receive FIFO is empty.
+   *
+   * <p>If the receive FIFO is empty, there is no active transfer, and initiate is false, errors.
+   *
+   * @param initiate     If true, this function pushes "0" into the transmit buffer and initiates
+   *                     a transfer. If false, this function assumes that data is already in the
+   *                     receive FIFO from a previous write.
+   * @param dataReceived The buffer to be filled with the received data.
+   * @param size         The length of the transaction, in bytes
+   */
+  @SuppressWarnings("ByteBufferBackingArray")
+  public int read(boolean initiate, ByteBuffer dataReceived, int size) {
+    if (dataReceived.hasArray()) {
+      return read(initiate, dataReceived.array(), size);
+    }
+    if (!dataReceived.isDirect()) {
+      throw new IllegalArgumentException("must be a direct buffer");
+    }
+    if (dataReceived.capacity() < size) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + size);
+    }
+    return SPIJNI.spiRead(m_port, initiate, dataReceived, (byte) size);
+  }
+
+  /**
+   * Perform a simultaneous read/write transaction with the device.
+   *
+   * @param dataToSend   The data to be written out to the device
+   * @param dataReceived Buffer to receive data from the device
+   * @param size         The length of the transaction, in bytes
+   */
+  public int transaction(byte[] dataToSend, byte[] dataReceived, int size) {
+    if (dataToSend.length < size) {
+      throw new IllegalArgumentException("dataToSend is too small, must be at least " + size);
+    }
+    if (dataReceived.length < size) {
+      throw new IllegalArgumentException("dataReceived is too small, must be at least " + size);
+    }
+    return SPIJNI.spiTransactionB(m_port, dataToSend, dataReceived, (byte) size);
+  }
+
+  /**
+   * Perform a simultaneous read/write transaction with the device.
+   *
+   * @param dataToSend   The data to be written out to the device.
+   * @param dataReceived Buffer to receive data from the device.
+   * @param size         The length of the transaction, in bytes
+   */
+  @SuppressWarnings({"PMD.CyclomaticComplexity", "ByteBufferBackingArray"})
+  public int transaction(ByteBuffer dataToSend, ByteBuffer dataReceived, int size) {
+    if (dataToSend.hasArray() && dataReceived.hasArray()) {
+      return transaction(dataToSend.array(), dataReceived.array(), size);
+    }
+    if (!dataToSend.isDirect()) {
+      throw new IllegalArgumentException("dataToSend must be a direct buffer");
+    }
+    if (dataToSend.capacity() < size) {
+      throw new IllegalArgumentException("dataToSend is too small, must be at least " + size);
+    }
+    if (!dataReceived.isDirect()) {
+      throw new IllegalArgumentException("dataReceived must be a direct buffer");
+    }
+    if (dataReceived.capacity() < size) {
+      throw new IllegalArgumentException("dataReceived is too small, must be at least " + size);
+    }
+    return SPIJNI.spiTransaction(m_port, dataToSend, dataReceived, (byte) size);
+  }
+
+  /**
+   * Initialize automatic SPI transfer engine.
+   *
+   * <p>Only a single engine is available, and use of it blocks use of all other
+   * chip select usage on the same physical SPI port while it is running.
+   *
+   * @param bufferSize buffer size in bytes
+   */
+  public void initAuto(int bufferSize) {
+    SPIJNI.spiInitAuto(m_port, bufferSize);
+  }
+
+  /**
+   * Frees the automatic SPI transfer engine.
+   */
+  public void freeAuto() {
+    SPIJNI.spiFreeAuto(m_port);
+  }
+
+  /**
+   * Set the data to be transmitted by the engine.
+   *
+   * <p>Up to 16 bytes are configurable, and may be followed by up to 127 zero
+   * bytes.
+   *
+   * @param dataToSend data to send (maximum 16 bytes)
+   * @param zeroSize number of zeros to send after the data
+   */
+  public void setAutoTransmitData(byte[] dataToSend, int zeroSize) {
+    SPIJNI.spiSetAutoTransmitData(m_port, dataToSend, zeroSize);
+  }
+
+  /**
+   * Start running the automatic SPI transfer engine at a periodic rate.
+   *
+   * <p>{@link #initAuto(int)} and {@link #setAutoTransmitData(byte[], int)} must
+   * be called before calling this function.
+   *
+   * @param period period between transfers, in seconds (us resolution)
+   */
+  public void startAutoRate(double period) {
+    SPIJNI.spiStartAutoRate(m_port, period);
+  }
+
+  /**
+   * Start running the automatic SPI transfer engine when a trigger occurs.
+   *
+   * <p>{@link #initAuto(int)} and {@link #setAutoTransmitData(byte[], int)} must
+   * be called before calling this function.
+   *
+   * @param source digital source for the trigger (may be an analog trigger)
+   * @param rising trigger on the rising edge
+   * @param falling trigger on the falling edge
+   */
+  public void startAutoTrigger(DigitalSource source, boolean rising, boolean falling) {
+    SPIJNI.spiStartAutoTrigger(m_port, source.getPortHandleForRouting(),
+                               source.getAnalogTriggerTypeForRouting(), rising, falling);
+  }
+
+  /**
+   * Stop running the automatic SPI transfer engine.
+   */
+  public void stopAuto() {
+    SPIJNI.spiStopAuto(m_port);
+  }
+
+  /**
+   * Force the engine to make a single transfer.
+   */
+  public void forceAutoRead() {
+    SPIJNI.spiForceAutoRead(m_port);
+  }
+
+  /**
+   * Read data that has been transferred by the automatic SPI transfer engine.
+   *
+   * <p>Transfers may be made a byte at a time, so it's necessary for the caller
+   * to handle cases where an entire transfer has not been completed.
+   *
+   * <p>Each received data sequence consists of a timestamp followed by the
+   * received data bytes, one byte per word (in the least significant byte).
+   * The length of each received data sequence is the same as the combined
+   * size of the data and zeroSize set in setAutoTransmitData().
+   *
+   * <p>Blocks until numToRead words have been read or timeout expires.
+   * May be called with numToRead=0 to retrieve how many words are available.
+   *
+   * @param buffer buffer where read words are stored
+   * @param numToRead number of words to read
+   * @param timeout timeout in seconds (ms resolution)
+   * @return Number of words remaining to be read
+   */
+  public int readAutoReceivedData(ByteBuffer buffer, int numToRead, double timeout) {
+    if (!buffer.isDirect()) {
+      throw new IllegalArgumentException("must be a direct buffer");
+    }
+    if (buffer.capacity() < numToRead * 4) {
+      throw new IllegalArgumentException("buffer is too small, must be at least "
+          + (numToRead * 4));
+    }
+    return SPIJNI.spiReadAutoReceivedData(m_port, buffer, numToRead, timeout);
+  }
+
+  /**
+   * Read data that has been transferred by the automatic SPI transfer engine.
+   *
+   * <p>Transfers may be made a byte at a time, so it's necessary for the caller
+   * to handle cases where an entire transfer has not been completed.
+   *
+   * <p>Each received data sequence consists of a timestamp followed by the
+   * received data bytes, one byte per word (in the least significant byte).
+   * The length of each received data sequence is the same as the combined
+   * size of the data and zeroSize set in setAutoTransmitData().
+   *
+   * <p>Blocks until numToRead words have been read or timeout expires.
+   * May be called with numToRead=0 to retrieve how many words are available.
+   *
+   * @param buffer array where read words are stored
+   * @param numToRead number of words to read
+   * @param timeout timeout in seconds (ms resolution)
+   * @return Number of words remaining to be read
+   */
+  public int readAutoReceivedData(int[] buffer, int numToRead, double timeout) {
+    if (buffer.length < numToRead) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + numToRead);
+    }
+    return SPIJNI.spiReadAutoReceivedData(m_port, buffer, numToRead, timeout);
+  }
+
+  /**
+   * Get the number of bytes dropped by the automatic SPI transfer engine due
+   * to the receive buffer being full.
+   *
+   * @return Number of bytes dropped
+   */
+  public int getAutoDroppedCount() {
+    return SPIJNI.spiGetAutoDroppedCount(m_port);
+  }
+
+  private static final int kAccumulateDepth = 2048;
+
+  @SuppressWarnings("PMD.TooManyFields")
+  private static class Accumulator implements AutoCloseable {
+    Accumulator(int port, int xferSize, int validMask, int validValue, int dataShift,
+                int dataSize, boolean isSigned, boolean bigEndian) {
+      m_notifier = new Notifier(this::update);
+      m_buf = ByteBuffer.allocateDirect((xferSize + 1) * kAccumulateDepth * 4)
+          .order(ByteOrder.nativeOrder());
+      m_intBuf = m_buf.asIntBuffer();
+      m_xferSize = xferSize + 1;  // +1 for timestamp
+      m_validMask = validMask;
+      m_validValue = validValue;
+      m_dataShift = dataShift;
+      m_dataMax = 1 << dataSize;
+      m_dataMsbMask = 1 << (dataSize - 1);
+      m_isSigned = isSigned;
+      m_bigEndian = bigEndian;
+      m_port = port;
+    }
+
+    @Override
+    public void close() {
+      m_notifier.close();
+    }
+
+    final Notifier m_notifier;
+    final ByteBuffer m_buf;
+    final IntBuffer m_intBuf;
+    final Object m_mutex = new Object();
+
+    long m_value;
+    int m_count;
+    int m_lastValue;
+    long m_lastTimestamp;
+    double m_integratedValue;
+
+    int m_center;
+    int m_deadband;
+    double m_integratedCenter;
+
+    final int m_validMask;
+    final int m_validValue;
+    final int m_dataMax;        // one more than max data value
+    final int m_dataMsbMask;    // data field MSB mask (for signed)
+    final int m_dataShift;      // data field shift right amount, in bits
+    final int m_xferSize;       // SPI transfer size, in bytes
+    final boolean m_isSigned;   // is data field signed?
+    final boolean m_bigEndian;  // is response big endian?
+    final int m_port;
+
+    @SuppressWarnings({"PMD.CyclomaticComplexity", "PMD.NPathComplexity"})
+    void update() {
+      synchronized (m_mutex) {
+        boolean done = false;
+        while (!done) {
+          done = true;
+
+          // get amount of data available
+          int numToRead = SPIJNI.spiReadAutoReceivedData(m_port, m_buf, 0, 0);
+
+          // only get whole responses
+          numToRead -= numToRead % m_xferSize;
+          if (numToRead > m_xferSize * kAccumulateDepth) {
+            numToRead = m_xferSize * kAccumulateDepth;
+            done = false;
+          }
+          if (numToRead == 0) {
+            return;  // no samples
+          }
+
+          // read buffered data
+          SPIJNI.spiReadAutoReceivedData(m_port, m_buf, numToRead, 0);
+
+          // loop over all responses
+          for (int off = 0; off < numToRead; off += m_xferSize) {
+            // get timestamp from first word
+            long timestamp = m_intBuf.get(off) & 0xffffffffL;
+
+            // convert from bytes
+            int resp = 0;
+            if (m_bigEndian) {
+              for (int i = 1; i < m_xferSize; ++i) {
+                resp <<= 8;
+                resp |= m_intBuf.get(off + i) & 0xff;
+              }
+            } else {
+              for (int i = m_xferSize - 1; i >= 1; --i) {
+                resp <<= 8;
+                resp |= m_intBuf.get(off + i) & 0xff;
+              }
+            }
+
+            // process response
+            if ((resp & m_validMask) == m_validValue) {
+              // valid sensor data; extract data field
+              int data = resp >> m_dataShift;
+              data &= m_dataMax - 1;
+              // 2s complement conversion if signed MSB is set
+              if (m_isSigned && (data & m_dataMsbMask) != 0) {
+                data -= m_dataMax;
+              }
+              // center offset
+              int dataNoCenter = data;
+              data -= m_center;
+              // only accumulate if outside deadband
+              if (data < -m_deadband || data > m_deadband) {
+                m_value += data;
+                if (m_count != 0) {
+                  // timestamps use the 1us FPGA clock; also handle rollover
+                  if (timestamp >= m_lastTimestamp) {
+                    m_integratedValue += dataNoCenter * (timestamp - m_lastTimestamp)
+                        * 1e-6 - m_integratedCenter;
+                  } else {
+                    m_integratedValue += dataNoCenter * ((1L << 32) - m_lastTimestamp + timestamp)
+                        * 1e-6 - m_integratedCenter;
+                  }
+                }
+              }
+              ++m_count;
+              m_lastValue = data;
+            } else {
+              // no data from the sensor; just clear the last value
+              m_lastValue = 0;
+            }
+            m_lastTimestamp = timestamp;
+          }
+        }
+      }
+    }
+  }
+
+  private Accumulator m_accum;
+
+  /**
+   * Initialize the accumulator.
+   *
+   * @param period     Time between reads
+   * @param cmd        SPI command to send to request data
+   * @param xferSize   SPI transfer size, in bytes
+   * @param validMask  Mask to apply to received data for validity checking
+   * @param validValue After validMask is applied, required matching value for validity checking
+   * @param dataShift  Bit shift to apply to received data to get actual data value
+   * @param dataSize   Size (in bits) of data field
+   * @param isSigned   Is data field signed?
+   * @param bigEndian  Is device big endian?
+   */
+  public void initAccumulator(double period, int cmd, int xferSize,
+                              int validMask, int validValue,
+                              int dataShift, int dataSize,
+                              boolean isSigned, boolean bigEndian) {
+    initAuto(xferSize * 2048);
+    byte[] cmdBytes = new byte[] {0, 0, 0, 0};
+    if (bigEndian) {
+      for (int i = xferSize - 1; i >= 0; --i) {
+        cmdBytes[i] = (byte) (cmd & 0xff);
+        cmd >>= 8;
+      }
+    } else {
+      cmdBytes[0] = (byte) (cmd & 0xff);
+      cmd >>= 8;
+      cmdBytes[1] = (byte) (cmd & 0xff);
+      cmd >>= 8;
+      cmdBytes[2] = (byte) (cmd & 0xff);
+      cmd >>= 8;
+      cmdBytes[3] = (byte) (cmd & 0xff);
+    }
+    setAutoTransmitData(cmdBytes, xferSize - 4);
+    startAutoRate(period);
+
+    m_accum = new Accumulator(m_port, xferSize, validMask, validValue, dataShift, dataSize,
+                              isSigned, bigEndian);
+    m_accum.m_notifier.startPeriodic(period * 1024);
+  }
+
+  /**
+   * Frees the accumulator.
+   */
+  public void freeAccumulator() {
+    if (m_accum != null) {
+      m_accum.close();
+      m_accum = null;
+    }
+    freeAuto();
+  }
+
+  /**
+   * Resets the accumulator to zero.
+   */
+  public void resetAccumulator() {
+    if (m_accum == null) {
+      return;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.m_value = 0;
+      m_accum.m_count = 0;
+      m_accum.m_lastValue = 0;
+      m_accum.m_lastTimestamp = 0;
+      m_accum.m_integratedValue = 0;
+    }
+  }
+
+  /**
+   * Set the center value of the accumulator.
+   *
+   * <p>The center value is subtracted from each value before it is added to the accumulator. This
+   * is used for the center value of devices like gyros and accelerometers to make integration work
+   * and to take the device offset into account when integrating.
+   */
+  public void setAccumulatorCenter(int center) {
+    if (m_accum == null) {
+      return;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.m_center = center;
+    }
+  }
+
+  /**
+   * Set the accumulator's deadband.
+   */
+  public void setAccumulatorDeadband(int deadband) {
+    if (m_accum == null) {
+      return;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.m_deadband = deadband;
+    }
+  }
+
+  /**
+   * Read the last value read by the accumulator engine.
+   */
+  public int getAccumulatorLastValue() {
+    if (m_accum == null) {
+      return 0;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.update();
+      return m_accum.m_lastValue;
+    }
+  }
+
+  /**
+   * Read the accumulated value.
+   *
+   * @return The 64-bit value accumulated since the last Reset().
+   */
+  public long getAccumulatorValue() {
+    if (m_accum == null) {
+      return 0;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.update();
+      return m_accum.m_value;
+    }
+  }
+
+  /**
+   * Read the number of accumulated values.
+   *
+   * <p>Read the count of the accumulated values since the accumulator was last Reset().
+   *
+   * @return The number of times samples from the channel were accumulated.
+   */
+  public int getAccumulatorCount() {
+    if (m_accum == null) {
+      return 0;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.update();
+      return m_accum.m_count;
+    }
+  }
+
+  /**
+   * Read the average of the accumulated value.
+   *
+   * @return The accumulated average value (value / count).
+   */
+  public double getAccumulatorAverage() {
+    if (m_accum == null) {
+      return 0;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.update();
+      if (m_accum.m_count == 0) {
+        return 0.0;
+      }
+      return ((double) m_accum.m_value) / m_accum.m_count;
+    }
+  }
+
+  /**
+   * Read the accumulated value and the number of accumulated values atomically.
+   *
+   * <p>This function reads the value and count atomically. This can be used for averaging.
+   *
+   * @param result AccumulatorResult object to store the results in.
+   */
+  public void getAccumulatorOutput(AccumulatorResult result) {
+    if (result == null) {
+      throw new IllegalArgumentException("Null parameter `result'");
+    }
+    if (m_accum == null) {
+      result.value = 0;
+      result.count = 0;
+      return;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.update();
+      result.value = m_accum.m_value;
+      result.count = m_accum.m_count;
+    }
+  }
+
+  /**
+   * Set the center value of the accumulator integrator.
+   *
+   * <p>The center value is subtracted from each value*dt before it is added to the
+   * integrated value. This is used for the center value of devices like gyros
+   * and accelerometers to take the device offset into account when integrating.
+   */
+  public void setAccumulatorIntegratedCenter(double center) {
+    if (m_accum == null) {
+      return;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.m_integratedCenter = center;
+    }
+  }
+
+  /**
+   * Read the integrated value.  This is the sum of (each value * time between
+   * values).
+   *
+   * @return The integrated value accumulated since the last Reset().
+   */
+  public double getAccumulatorIntegratedValue() {
+    if (m_accum == null) {
+      return 0;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.update();
+      return m_accum.m_integratedValue;
+    }
+  }
+
+  /**
+   * Read the average of the integrated value.  This is the sum of (each value
+   * times the time between values), divided by the count.
+   *
+   * @return The average of the integrated value accumulated since the last
+   *         Reset().
+   */
+  public double getAccumulatorIntegratedAverage() {
+    if (m_accum == null) {
+      return 0;
+    }
+    synchronized (m_accum.m_mutex) {
+      m_accum.update();
+      if (m_accum.m_count <= 1) {
+        return 0.0;
+      }
+      // count-1 due to not integrating the first value received
+      return m_accum.m_integratedValue / (m_accum.m_count - 1);
+    }
+  }
+}
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
new file mode 100644
index 0000000..6c13013
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SampleRobot.java
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
+
+/**
+ * A simple robot base class that knows the standard FRC competition states (disabled, autonomous,
+ * or operator controlled).
+ *
+ * <p>You can build a simple robot program off of this by overriding the robotinit(), disabled(),
+ * autonomous() and operatorControl() methods. The startCompetition() method will calls these
+ * methods (sometimes repeatedly). depending on the state of the competition.
+ *
+ * <p>Alternatively you can override the robotMain() method and manage all aspects of the robot
+ * yourself.
+ *
+ * @deprecated WARNING: While it may look like a good choice to use for your code if you're
+ *     inexperienced, don't. Unless you know what you are doing, complex code will
+ *     be much more difficult under this system. Use TimedRobot or Command-Based
+ *     instead.
+ */
+@Deprecated
+public class SampleRobot extends RobotBase {
+  private boolean m_robotMainOverridden = true;
+
+  /**
+   * Create a new SampleRobot.
+   */
+  public SampleRobot() {
+    HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Simple);
+  }
+
+  /**
+   * Robot-wide initialization code should go here.
+   *
+   * <p>Users should override this method for default Robot-wide initialization which will be called
+   * when the robot is first powered on. It will be called exactly one time.
+   *
+   * <p>Warning: the Driver Station "Robot Code" light and FMS "Robot Ready" indicators will be off
+   * until RobotInit() exits. Code in RobotInit() that waits for enable will cause the robot to
+   * never indicate that the code is ready, causing the robot to be bypassed in a match.
+   */
+  protected void robotInit() {
+    System.out.println("Default robotInit() method running, consider providing your own");
+  }
+
+  /**
+   * Disabled should go here. Users should overload this method to run code that should run while
+   * the field is disabled.
+   *
+   * <p>Called once each time the robot enters the disabled state.
+   */
+  protected void disabled() {
+    System.out.println("Default disabled() method running, consider providing your own");
+  }
+
+  /**
+   * Autonomous should go here. Users should add autonomous code to this method that should run
+   * while the field is in the autonomous period.
+   *
+   * <p>Called once each time the robot enters the autonomous state.
+   */
+  public void autonomous() {
+    System.out.println("Default autonomous() method running, consider providing your own");
+  }
+
+  /**
+   * Operator control (tele-operated) code should go here. Users should add Operator Control code to
+   * this method that should run while the field is in the Operator Control (tele-operated) period.
+   *
+   * <p>Called once each time the robot enters the operator-controlled state.
+   */
+  public void operatorControl() {
+    System.out.println("Default operatorControl() method running, consider providing your own");
+  }
+
+  /**
+   * Test code should go here. Users should add test code to this method that should run while the
+   * robot is in test mode.
+   */
+  @SuppressWarnings("PMD.JUnit4TestShouldUseTestAnnotation")
+  public void test() {
+    System.out.println("Default test() method running, consider providing your own");
+  }
+
+  /**
+   * Robot main program for free-form programs.
+   *
+   * <p>This should be overridden by user subclasses if the intent is to not use the autonomous()
+   * and operatorControl() methods. In that case, the program is responsible for sensing when to run
+   * the autonomous and operator control functions in their program.
+   *
+   * <p>This method will be called immediately after the constructor is called. If it has not been
+   * overridden by a user subclass (i.e. the default version runs), then the robotInit(),
+   * disabled(), autonomous() and operatorControl() methods will be called.
+   */
+  public void robotMain() {
+    m_robotMainOverridden = false;
+  }
+
+  /**
+   * Start a competition. This code tracks the order of the field starting to ensure that everything
+   * happens in the right order. Repeatedly run the correct method, either Autonomous or
+   * OperatorControl when the robot is enabled. After running the correct method, wait for some
+   * state to change, either the other mode starts or the robot is disabled. Then go back and wait
+   * for the robot to be enabled again.
+   */
+  @SuppressWarnings("PMD.CyclomaticComplexity")
+  @Override
+  public void startCompetition() {
+    robotInit();
+
+    // Tell the DS that the robot is ready to be enabled
+    HAL.observeUserProgramStarting();
+
+    robotMain();
+
+    if (!m_robotMainOverridden) {
+      while (true) {
+        if (isDisabled()) {
+          m_ds.InDisabled(true);
+          disabled();
+          m_ds.InDisabled(false);
+          while (isDisabled()) {
+            Timer.delay(0.01);
+          }
+        } else if (isAutonomous()) {
+          m_ds.InAutonomous(true);
+          autonomous();
+          m_ds.InAutonomous(false);
+          while (isAutonomous() && !isDisabled()) {
+            Timer.delay(0.01);
+          }
+        } else if (isTest()) {
+          LiveWindow.setEnabled(true);
+          Shuffleboard.enableActuatorWidgets();
+          m_ds.InTest(true);
+          test();
+          m_ds.InTest(false);
+          while (isTest() && isEnabled()) {
+            Timer.delay(0.01);
+          }
+          LiveWindow.setEnabled(false);
+          Shuffleboard.disableActuatorWidgets();
+        } else {
+          m_ds.InOperatorControl(true);
+          operatorControl();
+          m_ds.InOperatorControl(false);
+          while (isOperatorControl() && !isDisabled()) {
+            Timer.delay(0.01);
+          }
+        }
+      } /* while loop */
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Sendable.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Sendable.java
new file mode 100644
index 0000000..76eb03c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Sendable.java
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+
+/**
+ * The base interface for objects that can be sent over the network through network tables.
+ */
+public interface Sendable {
+  /**
+   * Gets the name of this {@link Sendable} object.
+   *
+   * @return Name
+   */
+  String getName();
+
+  /**
+   * Sets the name of this {@link Sendable} object.
+   *
+   * @param name name
+   */
+  void setName(String name);
+
+  /**
+   * Sets both the subsystem name and device name of this {@link Sendable} object.
+   *
+   * @param subsystem subsystem name
+   * @param name device name
+   */
+  default void setName(String subsystem, String name) {
+    setSubsystem(subsystem);
+    setName(name);
+  }
+
+  /**
+   * Gets the subsystem name of this {@link Sendable} object.
+   *
+   * @return Subsystem name
+   */
+  String getSubsystem();
+
+  /**
+   * Sets the subsystem name of this {@link Sendable} object.
+   *
+   * @param subsystem subsystem name
+   */
+  void setSubsystem(String subsystem);
+
+  /**
+   * Initializes this {@link Sendable} object.
+   *
+   * @param builder sendable builder
+   */
+  void initSendable(SendableBuilder builder);
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableBase.java
new file mode 100644
index 0000000..b663ed5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableBase.java
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+
+/**
+ * Base class for all sensors. Stores most recent status information as well as containing utility
+ * functions for checking channels and error processing.
+ */
+public abstract class SendableBase implements Sendable, AutoCloseable {
+  private String m_name = "";
+  private String m_subsystem = "Ungrouped";
+
+  /**
+   * Creates an instance of the sensor base.
+   */
+  public SendableBase() {
+    this(true);
+  }
+
+  /**
+   * Creates an instance of the sensor base.
+   *
+   * @param addLiveWindow if true, add this Sendable to LiveWindow
+   */
+  public SendableBase(boolean addLiveWindow) {
+    if (addLiveWindow) {
+      LiveWindow.add(this);
+    }
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  @Override
+  public void close() {
+    LiveWindow.remove(this);
+  }
+
+  @Override
+  public final synchronized String getName() {
+    return m_name;
+  }
+
+  @Override
+  public final synchronized void setName(String name) {
+    m_name = name;
+  }
+
+  /**
+   * Sets the name of the sensor with a channel number.
+   *
+   * @param moduleType A string that defines the module name in the label for the value
+   * @param channel    The channel number the device is plugged into
+   */
+  protected final void setName(String moduleType, int channel) {
+    setName(moduleType + "[" + channel + "]");
+  }
+
+  /**
+   * Sets the name of the sensor with a module and channel number.
+   *
+   * @param moduleType   A string that defines the module name in the label for the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually PWM)
+   */
+  protected final void setName(String moduleType, int moduleNumber, int channel) {
+    setName(moduleType + "[" + moduleNumber + "," + channel + "]");
+  }
+
+  @Override
+  public final synchronized String getSubsystem() {
+    return m_subsystem;
+  }
+
+  @Override
+  public final synchronized void setSubsystem(String subsystem) {
+    m_subsystem = subsystem;
+  }
+
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  protected final void addChild(Object child) {
+    LiveWindow.addChild(this, child);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableImpl.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableImpl.java
new file mode 100644
index 0000000..0fa2e74
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SendableImpl.java
@@ -0,0 +1,101 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * The base interface for objects that can be sent over the network through network tables.
+ */
+public class SendableImpl implements Sendable, AutoCloseable {
+  private String m_name = "";
+  private String m_subsystem = "Ungrouped";
+
+  /**
+   * Creates an instance of the sensor base.
+   */
+  public SendableImpl() {
+    this(true);
+  }
+
+  /**
+   * Creates an instance of the sensor base.
+   *
+   * @param addLiveWindow if true, add this Sendable to LiveWindow
+   */
+  public SendableImpl(boolean addLiveWindow) {
+    if (addLiveWindow) {
+      LiveWindow.add(this);
+    }
+  }
+
+  @Deprecated
+  public void free() {
+    close();
+  }
+
+  @Override
+  public void close() {
+    LiveWindow.remove(this);
+  }
+
+  @Override
+  public synchronized String getName() {
+    return m_name;
+  }
+
+  @Override
+  public synchronized void setName(String name) {
+    m_name = name;
+  }
+
+  /**
+   * Sets the name of the sensor with a channel number.
+   *
+   * @param moduleType A string that defines the module name in the label for the value
+   * @param channel    The channel number the device is plugged into
+   */
+  public void setName(String moduleType, int channel) {
+    setName(moduleType + "[" + channel + "]");
+  }
+
+  /**
+   * Sets the name of the sensor with a module and channel number.
+   *
+   * @param moduleType   A string that defines the module name in the label for the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually PWM)
+   */
+  public void setName(String moduleType, int moduleNumber, int channel) {
+    setName(moduleType + "[" + moduleNumber + "," + channel + "]");
+  }
+
+  @Override
+  public synchronized String getSubsystem() {
+    return m_subsystem;
+  }
+
+  @Override
+  public synchronized void setSubsystem(String subsystem) {
+    m_subsystem = subsystem;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+  }
+
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  public void addChild(Object child) {
+    LiveWindow.addChild(this, child);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java
new file mode 100644
index 0000000..4f2b8b5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SensorUtil.java
@@ -0,0 +1,236 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.AnalogJNI;
+import edu.wpi.first.hal.ConstantsJNI;
+import edu.wpi.first.hal.DIOJNI;
+import edu.wpi.first.hal.PDPJNI;
+import edu.wpi.first.hal.PWMJNI;
+import edu.wpi.first.hal.PortsJNI;
+import edu.wpi.first.hal.RelayJNI;
+import edu.wpi.first.hal.SolenoidJNI;
+
+/**
+ * Stores most recent status information as well as containing utility functions for checking
+ * channels and error processing.
+ */
+public final class SensorUtil {
+  /**
+   * Ticks per microsecond.
+   */
+  public static final int kSystemClockTicksPerMicrosecond
+      = ConstantsJNI.getSystemClockTicksPerMicrosecond();
+
+  /**
+   * Number of digital channels per roboRIO.
+   */
+  public static final int kDigitalChannels = PortsJNI.getNumDigitalChannels();
+
+  /**
+   * Number of analog input channels per roboRIO.
+   */
+  public static final int kAnalogInputChannels = PortsJNI.getNumAnalogInputs();
+
+  /**
+   * Number of analog output channels per roboRIO.
+   */
+  public static final int kAnalogOutputChannels = PortsJNI.getNumAnalogOutputs();
+
+  /**
+   * Number of solenoid channels per module.
+   */
+  public static final int kSolenoidChannels = PortsJNI.getNumSolenoidChannels();
+
+  /**
+   * Number of PWM channels per roboRIO.
+   */
+  public static final int kPwmChannels = PortsJNI.getNumPWMChannels();
+
+  /**
+   * Number of relay channels per roboRIO.
+   */
+  public static final int kRelayChannels = PortsJNI.getNumRelayHeaders();
+
+  /**
+   * Number of power distribution channels per PDP.
+   */
+  public static final int kPDPChannels = PortsJNI.getNumPDPChannels();
+
+  /**
+   * Number of power distribution modules per PDP.
+   */
+  public static final int kPDPModules = PortsJNI.getNumPDPModules();
+
+  /**
+   * Number of PCM Modules.
+   */
+  public static final int kPCMModules = PortsJNI.getNumPCMModules();
+
+  /**
+   * Verify that the solenoid module is correct.
+   *
+   * @param moduleNumber The solenoid module module number to check.
+   */
+  public static void checkSolenoidModule(final int moduleNumber) {
+    if (!SolenoidJNI.checkSolenoidModule(moduleNumber)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested solenoid module is out of range. Minimum: 0, Maximum: ")
+        .append(kPCMModules)
+        .append(", Requested: ")
+        .append(moduleNumber);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Check that the digital channel number is valid. Verify that the channel number is one of the
+   * legal channel numbers. Channel numbers are 0-based.
+   *
+   * @param channel The channel number to check.
+   */
+  public static void checkDigitalChannel(final int channel) {
+    if (!DIOJNI.checkDIOChannel(channel)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested DIO channel is out of range. Minimum: 0, Maximum: ")
+        .append(kDigitalChannels)
+        .append(", Requested: ")
+        .append(channel);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Check that the digital channel number is valid. Verify that the channel number is one of the
+   * legal channel numbers. Channel numbers are 0-based.
+   *
+   * @param channel The channel number to check.
+   */
+  public static void checkRelayChannel(final int channel) {
+    if (!RelayJNI.checkRelayChannel(channel)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested relay channel is out of range. Minimum: 0, Maximum: ")
+        .append(kRelayChannels)
+        .append(", Requested: ")
+        .append(channel);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Check that the digital channel number is valid. Verify that the channel number is one of the
+   * legal channel numbers. Channel numbers are 0-based.
+   *
+   * @param channel The channel number to check.
+   */
+  public static void checkPWMChannel(final int channel) {
+    if (!PWMJNI.checkPWMChannel(channel)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested PWM channel is out of range. Minimum: 0, Maximum: ")
+        .append(kPwmChannels)
+        .append(", Requested: ")
+        .append(channel);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Check that the analog input number is value. Verify that the analog input number is one of the
+   * legal channel numbers. Channel numbers are 0-based.
+   *
+   * @param channel The channel number to check.
+   */
+  public static void checkAnalogInputChannel(final int channel) {
+    if (!AnalogJNI.checkAnalogInputChannel(channel)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested analog input channel is out of range. Minimum: 0, Maximum: ")
+        .append(kAnalogInputChannels)
+        .append(", Requested: ")
+        .append(channel);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Check that the analog input number is value. Verify that the analog input number is one of the
+   * legal channel numbers. Channel numbers are 0-based.
+   *
+   * @param channel The channel number to check.
+   */
+  public static void checkAnalogOutputChannel(final int channel) {
+    if (!AnalogJNI.checkAnalogOutputChannel(channel)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested analog output channel is out of range. Minimum: 0, Maximum: ")
+        .append(kAnalogOutputChannels)
+        .append(", Requested: ")
+        .append(channel);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Verify that the solenoid channel number is within limits. Channel numbers are 0-based.
+   *
+   * @param channel The channel number to check.
+   */
+  public static void checkSolenoidChannel(final int channel) {
+    if (!SolenoidJNI.checkSolenoidChannel(channel)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested solenoid channel is out of range. Minimum: 0, Maximum: ")
+        .append(kSolenoidChannels)
+        .append(", Requested: ")
+        .append(channel);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Verify that the power distribution channel number is within limits. Channel numbers are
+   * 0-based.
+   *
+   * @param channel The channel number to check.
+   */
+  public static void checkPDPChannel(final int channel) {
+    if (!PDPJNI.checkPDPChannel(channel)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested PDP channel is out of range. Minimum: 0, Maximum: ")
+        .append(kPDPChannels)
+        .append(", Requested: ")
+        .append(channel);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Verify that the PDP module number is within limits. module numbers are 0-based.
+   *
+   * @param module The module number to check.
+   */
+  public static void checkPDPModule(final int module) {
+    if (!PDPJNI.checkPDPModule(module)) {
+      StringBuilder buf = new StringBuilder();
+      buf.append("Requested PDP module is out of range. Minimum: 0, Maximum: ")
+        .append(kPDPModules)
+        .append(", Requested: ")
+        .append(module);
+      throw new IndexOutOfBoundsException(buf.toString());
+    }
+  }
+
+  /**
+   * Get the number of the default solenoid module.
+   *
+   * @return The number of the default solenoid module.
+   */
+  public static int getDefaultSolenoidModule() {
+    return 0;
+  }
+
+  private SensorUtil() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java
new file mode 100644
index 0000000..019a490
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SerialPort.java
@@ -0,0 +1,394 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.io.UnsupportedEncodingException;
+import java.nio.charset.StandardCharsets;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.SerialPortJNI;
+
+/**
+ * Driver for the RS-232 serial port on the roboRIO.
+ *
+ * <p>The current implementation uses the VISA formatted I/O mode. This means that all traffic goes
+ * through the formatted buffers. This allows the intermingled use of print(), readString(), and the
+ * raw buffer accessors read() and write().
+ *
+ * <p>More information can be found in the NI-VISA User Manual here: http://www.ni
+ * .com/pdf/manuals/370423a.pdf and the NI-VISA Programmer's Reference Manual here:
+ * http://www.ni.com/pdf/manuals/370132c.pdf
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public class SerialPort implements AutoCloseable {
+  private byte m_port;
+
+  public enum Port {
+    kOnboard(0), kMXP(1), kUSB(2), kUSB1(2), kUSB2(3);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    Port(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Represents the parity to use for serial communications.
+   */
+  public enum Parity {
+    kNone(0), kOdd(1), kEven(2), kMark(3), kSpace(4);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    Parity(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Represents the number of stop bits to use for Serial Communication.
+   */
+  public enum StopBits {
+    kOne(10), kOnePointFive(15), kTwo(20);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    StopBits(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Represents what type of flow control to use for serial communication.
+   */
+  public enum FlowControl {
+    kNone(0), kXonXoff(1), kRtsCts(2), kDtsDsr(4);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    FlowControl(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Represents which type of buffer mode to use when writing to a serial m_port.
+   */
+  public enum WriteBufferMode {
+    kFlushOnAccess(1), kFlushWhenFull(2);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    WriteBufferMode(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Create an instance of a Serial Port class.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   * @param port     The Serial port to use
+   * @param portName The direct portName to use
+   * @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
+   * @param parity   Select the type of parity checking to use.
+   * @param stopBits The number of stop bits to use as defined by the enum StopBits.
+   * @deprecated     Will be removed for 2019
+   */
+  @Deprecated
+  public SerialPort(final int baudRate, String portName, Port port, final int dataBits,
+                    Parity parity, StopBits stopBits) {
+    m_port = (byte) port.value;
+
+    SerialPortJNI.serialInitializePortDirect(m_port, portName);
+    SerialPortJNI.serialSetBaudRate(m_port, baudRate);
+    SerialPortJNI.serialSetDataBits(m_port, (byte) dataBits);
+    SerialPortJNI.serialSetParity(m_port, (byte) parity.value);
+    SerialPortJNI.serialSetStopBits(m_port, (byte) stopBits.value);
+
+    // Set the default read buffer size to 1 to return bytes immediately
+    setReadBufferSize(1);
+
+    // Set the default timeout to 5 seconds.
+    setTimeout(5.0);
+
+    // Don't wait until the buffer is full to transmit.
+    setWriteBufferMode(WriteBufferMode.kFlushOnAccess);
+
+    disableTermination();
+
+    HAL.report(tResourceType.kResourceType_SerialPort, 0);
+  }
+
+  /**
+   * Create an instance of a Serial Port class.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   * @param port     The Serial port to use
+   * @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
+   * @param parity   Select the type of parity checking to use.
+   * @param stopBits The number of stop bits to use as defined by the enum StopBits.
+   */
+  public SerialPort(final int baudRate, Port port, final int dataBits, Parity parity,
+                    StopBits stopBits) {
+    m_port = (byte) port.value;
+
+    SerialPortJNI.serialInitializePort(m_port);
+    SerialPortJNI.serialSetBaudRate(m_port, baudRate);
+    SerialPortJNI.serialSetDataBits(m_port, (byte) dataBits);
+    SerialPortJNI.serialSetParity(m_port, (byte) parity.value);
+    SerialPortJNI.serialSetStopBits(m_port, (byte) stopBits.value);
+
+    // Set the default read buffer size to 1 to return bytes immediately
+    setReadBufferSize(1);
+
+    // Set the default timeout to 5 seconds.
+    setTimeout(5.0);
+
+    // Don't wait until the buffer is full to transmit.
+    setWriteBufferMode(WriteBufferMode.kFlushOnAccess);
+
+    disableTermination();
+
+    HAL.report(tResourceType.kResourceType_SerialPort, 0);
+  }
+
+  /**
+   * Create an instance of a Serial Port class. Defaults to one stop bit.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   * @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
+   * @param parity   Select the type of parity checking to use.
+   */
+  public SerialPort(final int baudRate, Port port, final int dataBits, Parity parity) {
+    this(baudRate, port, dataBits, parity, StopBits.kOne);
+  }
+
+  /**
+   * Create an instance of a Serial Port class. Defaults to no parity and one stop bit.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   * @param dataBits The number of data bits per transfer. Valid values are between 5 and 8 bits.
+   */
+  public SerialPort(final int baudRate, Port port, final int dataBits) {
+    this(baudRate, port, dataBits, Parity.kNone, StopBits.kOne);
+  }
+
+  /**
+   * Create an instance of a Serial Port class. Defaults to 8 databits, no parity, and one stop
+   * bit.
+   *
+   * @param baudRate The baud rate to configure the serial port.
+   */
+  public SerialPort(final int baudRate, Port port) {
+    this(baudRate, port, 8, Parity.kNone, StopBits.kOne);
+  }
+
+  @Override
+  public void close() {
+    SerialPortJNI.serialClose(m_port);
+  }
+
+  /**
+   * Set the type of flow control to enable on this port.
+   *
+   * <p>By default, flow control is disabled.
+   *
+   * @param flowControl the FlowControl m_value to use
+   */
+  public void setFlowControl(FlowControl flowControl) {
+    SerialPortJNI.serialSetFlowControl(m_port, (byte) flowControl.value);
+  }
+
+  /**
+   * Enable termination and specify the termination character.
+   *
+   * <p>Termination is currently only implemented for receive. When the the terminator is received,
+   * the read() or readString() will return fewer bytes than requested, stopping after the
+   * terminator.
+   *
+   * @param terminator The character to use for termination.
+   */
+  public void enableTermination(char terminator) {
+    SerialPortJNI.serialEnableTermination(m_port, terminator);
+  }
+
+  /**
+   * Enable termination with the default terminator '\n'
+   *
+   * <p>Termination is currently only implemented for receive. When the the terminator is received,
+   * the read() or readString() will return fewer bytes than requested, stopping after the
+   * terminator.
+   *
+   * <p>The default terminator is '\n'
+   */
+  public void enableTermination() {
+    enableTermination('\n');
+  }
+
+  /**
+   * Disable termination behavior.
+   */
+  public void disableTermination() {
+    SerialPortJNI.serialDisableTermination(m_port);
+  }
+
+  /**
+   * Get the number of bytes currently available to read from the serial port.
+   *
+   * @return The number of bytes available to read.
+   */
+  public int getBytesReceived() {
+    return SerialPortJNI.serialGetBytesReceived(m_port);
+  }
+
+  /**
+   * Read a string out of the buffer. Reads the entire contents of the buffer
+   *
+   * @return The read string
+   */
+  public String readString() {
+    return readString(getBytesReceived());
+  }
+
+  /**
+   * Read a string out of the buffer. Reads the entire contents of the buffer
+   *
+   * @param count the number of characters to read into the string
+   * @return The read string
+   */
+  public String readString(int count) {
+    byte[] out = read(count);
+    try {
+      return new String(out, 0, out.length, "US-ASCII");
+    } catch (UnsupportedEncodingException ex) {
+      ex.printStackTrace();
+      return "";
+    }
+  }
+
+  /**
+   * Read raw bytes out of the buffer.
+   *
+   * @param count The maximum number of bytes to read.
+   * @return An array of the read bytes
+   */
+  public byte[] read(final int count) {
+    byte[] dataReceivedBuffer = new byte[count];
+    int gotten = SerialPortJNI.serialRead(m_port, dataReceivedBuffer, count);
+    if (gotten == count) {
+      return dataReceivedBuffer;
+    }
+    byte[] retVal = new byte[gotten];
+    System.arraycopy(dataReceivedBuffer, 0, retVal, 0, gotten);
+    return retVal;
+  }
+
+  /**
+   * Write raw bytes to the serial port.
+   *
+   * @param buffer The buffer of bytes to write.
+   * @param count  The maximum number of bytes to write.
+   * @return The number of bytes actually written into the port.
+   */
+  public int write(byte[] buffer, int count) {
+    if (buffer.length < count) {
+      throw new IllegalArgumentException("buffer is too small, must be at least " + count);
+    }
+    return SerialPortJNI.serialWrite(m_port, buffer, count);
+  }
+
+  /**
+   * Write a string to the serial port.
+   *
+   * @param data The string to write to the serial port.
+   * @return The number of bytes actually written into the port.
+   */
+  public int writeString(String data) {
+    return write(data.getBytes(StandardCharsets.UTF_8), data.length());
+  }
+
+  /**
+   * Configure the timeout of the serial m_port.
+   *
+   * <p>This defines the timeout for transactions with the hardware. It will affect reads if less
+   * bytes are available than the read buffer size (defaults to 1) and very large writes.
+   *
+   * @param timeout The number of seconds to to wait for I/O.
+   */
+  public void setTimeout(double timeout) {
+    SerialPortJNI.serialSetTimeout(m_port, timeout);
+  }
+
+  /**
+   * Specify the size of the input buffer.
+   *
+   * <p>Specify the amount of data that can be stored before data from the device is returned to
+   * Read. If you want data that is received to be returned immediately, set this to 1.
+   *
+   * <p>It the buffer is not filled before the read timeout expires, all data that has been received
+   * so far will be returned.
+   *
+   * @param size The read buffer size.
+   */
+  public void setReadBufferSize(int size) {
+    SerialPortJNI.serialSetReadBufferSize(m_port, size);
+  }
+
+  /**
+   * Specify the size of the output buffer.
+   *
+   * <p>Specify the amount of data that can be stored before being transmitted to the device.
+   *
+   * @param size The write buffer size.
+   */
+  public void setWriteBufferSize(int size) {
+    SerialPortJNI.serialSetWriteBufferSize(m_port, size);
+  }
+
+  /**
+   * Specify the flushing behavior of the output buffer.
+   *
+   * <p>When set to kFlushOnAccess, data is synchronously written to the serial port after each
+   * call to either print() or write().
+   *
+   * <p>When set to kFlushWhenFull, data will only be written to the serial port when the buffer
+   * is full or when flush() is called.
+   *
+   * @param mode The write buffer mode.
+   */
+  public void setWriteBufferMode(WriteBufferMode mode) {
+    SerialPortJNI.serialSetWriteMode(m_port, (byte) mode.value);
+  }
+
+  /**
+   * Force the output buffer to be written to the port.
+   *
+   * <p>This is used when setWriteBufferMode() is set to kFlushWhenFull to force a flush before the
+   * buffer is full.
+   */
+  public void flush() {
+    SerialPortJNI.serialFlush(m_port);
+  }
+
+  /**
+   * Reset the serial port driver to a known state.
+   *
+   * <p>Empty the transmit and receive buffers in the device and formatted I/O.
+   */
+  public void reset() {
+    SerialPortJNI.serialClear(m_port);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java
new file mode 100644
index 0000000..1abe6bb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Servo.java
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Standard hobby style servo.
+ *
+ * <p>The range parameters default to the appropriate values for the Hitec HS-322HD servo provided
+ * in the FIRST Kit of Parts in 2008.
+ */
+public class Servo extends PWM {
+  private static final double kMaxServoAngle = 180.0;
+  private static final double kMinServoAngle = 0.0;
+
+  protected static final double kDefaultMaxServoPWM = 2.4;
+  protected static final double kDefaultMinServoPWM = .6;
+
+  /**
+   * Constructor.<br>
+   *
+   * <p>By default {@value #kDefaultMaxServoPWM} ms is used as the maxPWM value<br> By default
+   * {@value #kDefaultMinServoPWM} ms is used as the minPWM value<br>
+   *
+   * @param channel The PWM channel to which the servo is attached. 0-9 are on-board, 10-19 are on
+   *                the MXP port
+   */
+  public Servo(final int channel) {
+    super(channel);
+    setBounds(kDefaultMaxServoPWM, 0, 0, 0, kDefaultMinServoPWM);
+    setPeriodMultiplier(PeriodMultiplier.k4X);
+
+    HAL.report(tResourceType.kResourceType_Servo, getChannel());
+    setName("Servo", getChannel());
+  }
+
+
+  /**
+   * Set the servo position.
+   *
+   * <p>Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
+   *
+   * @param value Position from 0.0 to 1.0.
+   */
+  public void set(double value) {
+    setPosition(value);
+  }
+
+  /**
+   * Get the servo position.
+   *
+   * <p>Servo values range from 0.0 to 1.0 corresponding to the range of full left to full right.
+   *
+   * @return Position from 0.0 to 1.0.
+   */
+  public double get() {
+    return getPosition();
+  }
+
+  /**
+   * Set the servo angle.
+   *
+   * <p>Assume that the servo angle is linear with respect to the PWM value (big assumption, need to
+   * test).
+   *
+   * <p>Servo angles that are out of the supported range of the servo simply "saturate" in that
+   * direction In other words, if the servo has a range of (X degrees to Y degrees) than angles of
+   * less than X result in an angle of X being set and angles of more than Y degrees result in an
+   * angle of Y being set.
+   *
+   * @param degrees The angle in degrees to set the servo.
+   */
+  public void setAngle(double degrees) {
+    if (degrees < kMinServoAngle) {
+      degrees = kMinServoAngle;
+    } else if (degrees > kMaxServoAngle) {
+      degrees = kMaxServoAngle;
+    }
+
+    setPosition(((degrees - kMinServoAngle)) / getServoAngleRange());
+  }
+
+  /**
+   * Get the servo angle.
+   *
+   * <p>Assume that the servo angle is linear with respect to the PWM value (big assumption, need to
+   * test).
+   *
+   * @return The angle in degrees to which the servo is set.
+   */
+  public double getAngle() {
+    return getPosition() * getServoAngleRange() + kMinServoAngle;
+  }
+
+  private double getServoAngleRange() {
+    return kMaxServoAngle - kMinServoAngle;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Servo");
+    builder.addDoubleProperty("Value", this::get, this::set);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java
new file mode 100644
index 0000000..014ec10
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Solenoid.java
@@ -0,0 +1,122 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.SolenoidJNI;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Solenoid class for running high voltage Digital Output on the PCM.
+ *
+ * <p>The Solenoid class is typically used for pneumatic solenoids, but could be used for any
+ * device within the current spec of the PCM.
+ */
+public class Solenoid extends SolenoidBase {
+  private final int m_channel; // The channel to control.
+  private int m_solenoidHandle;
+
+  /**
+   * Constructor using the default PCM ID (defaults to 0).
+   *
+   * @param channel The channel on the PCM to control (0..7).
+   */
+  public Solenoid(final int channel) {
+    this(SensorUtil.getDefaultSolenoidModule(), channel);
+  }
+
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber The CAN ID of the PCM the solenoid is attached to.
+   * @param channel      The channel on the PCM to control (0..7).
+   */
+  public Solenoid(final int moduleNumber, final int channel) {
+    super(moduleNumber);
+    m_channel = channel;
+
+    SensorUtil.checkSolenoidModule(m_moduleNumber);
+    SensorUtil.checkSolenoidChannel(m_channel);
+
+    int portHandle = HAL.getPortWithModule((byte) m_moduleNumber, (byte) m_channel);
+    m_solenoidHandle = SolenoidJNI.initializeSolenoidPort(portHandle);
+
+    HAL.report(tResourceType.kResourceType_Solenoid, m_channel, m_moduleNumber);
+    setName("Solenoid", m_moduleNumber, m_channel);
+  }
+
+  @Override
+  public void close() {
+    super.close();
+    SolenoidJNI.freeSolenoidPort(m_solenoidHandle);
+    m_solenoidHandle = 0;
+  }
+
+  /**
+   * Set the value of a solenoid.
+   *
+   * @param on True will turn the solenoid output on. False will turn the solenoid output off.
+   */
+  public void set(boolean on) {
+    SolenoidJNI.setSolenoid(m_solenoidHandle, on);
+  }
+
+  /**
+   * Read the current value of the solenoid.
+   *
+   * @return True if the solenoid output is on or false if the solenoid output is off.
+   */
+  public boolean get() {
+    return SolenoidJNI.getSolenoid(m_solenoidHandle);
+  }
+
+  /**
+   * Check if solenoid is blacklisted. If a solenoid is shorted, it is added to the blacklist and
+   * disabled until power cycle, or until faults are cleared.
+   *
+   * @return If solenoid is disabled due to short.
+   * @see #clearAllPCMStickyFaults()
+   */
+  public boolean isBlackListed() {
+    int value = getPCMSolenoidBlackList() & (1 << m_channel);
+    return value != 0;
+  }
+
+  /**
+   * Set the pulse duration in the PCM. This is used in conjunction with
+   * the startPulse method to allow the PCM to control the timing of a pulse.
+   * The timing can be controlled in 0.01 second increments.
+   *
+   * @param durationSeconds The duration of the pulse, from 0.01 to 2.55 seconds.
+   *
+   * @see #startPulse()
+   */
+  public void setPulseDuration(double durationSeconds) {
+    long durationMS = (long) (durationSeconds * 1000);
+    SolenoidJNI.setOneShotDuration(m_solenoidHandle, durationMS);
+  }
+
+  /**
+   * Trigger the PCM to generate a pulse of the duration set in
+   * setPulseDuration.
+   *
+   * @see #setPulseDuration(double)
+   */
+  public void startPulse() {
+    SolenoidJNI.fireOneShot(m_solenoidHandle);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Solenoid");
+    builder.setActuator(true);
+    builder.setSafeState(() -> set(false));
+    builder.addBooleanProperty("Value", this::get, this::set);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SolenoidBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SolenoidBase.java
new file mode 100644
index 0000000..59c6c3d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SolenoidBase.java
@@ -0,0 +1,141 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.SolenoidJNI;
+
+/**
+ * SolenoidBase class is the common base class for the {@link Solenoid} and {@link DoubleSolenoid}
+ * classes.
+ */
+public abstract class SolenoidBase extends SendableBase {
+  protected final int m_moduleNumber; // The number of the solenoid module being used.
+
+  /**
+   * Constructor.
+   *
+   * @param moduleNumber The PCM CAN ID
+   */
+  public SolenoidBase(final int moduleNumber) {
+    m_moduleNumber = moduleNumber;
+  }
+
+  /**
+   * Read all 8 solenoids from the specified module as a single byte.
+   *
+   * @param moduleNumber the module number to read
+   * @return The current value of all 8 solenoids on the module.
+   */
+  public static int getAll(int moduleNumber) {
+    return SolenoidJNI.getAllSolenoids(moduleNumber);
+  }
+
+  /**
+   * Read all 8 solenoids from the module used by this solenoid as a single byte.
+   *
+   * @return The current value of all 8 solenoids on this module.
+   */
+  public int getAll() {
+    return SolenoidBase.getAll(m_moduleNumber);
+  }
+
+  /**
+   * Reads complete solenoid blacklist for all 8 solenoids as a single byte. If a solenoid is
+   * shorted, it is added to the blacklist and disabled until power cycle, or until faults are
+   * cleared.
+   *
+   * @param moduleNumber the module number to read
+   * @return The solenoid blacklist of all 8 solenoids on the module.
+   * @see #clearAllPCMStickyFaults()
+   */
+  public static int getPCMSolenoidBlackList(int moduleNumber) {
+    return SolenoidJNI.getPCMSolenoidBlackList(moduleNumber);
+  }
+
+  /**
+   * Reads complete solenoid blacklist for all 8 solenoids as a single byte. If a solenoid is
+   * shorted, it is added to the blacklist and disabled until power cycle, or until faults are
+   * cleared.
+   *
+   * @return The solenoid blacklist of all 8 solenoids on the module.
+   * @see #clearAllPCMStickyFaults()
+   */
+  public int getPCMSolenoidBlackList() {
+    return SolenoidBase.getPCMSolenoidBlackList(m_moduleNumber);
+  }
+
+  /**
+   * If true, the common highside solenoid voltage rail is too low, most likely a solenoid channel
+   * is shorted.
+   *
+   * @param moduleNumber the module number to read
+   * @return true if PCM sticky fault is set
+   */
+  public static boolean getPCMSolenoidVoltageStickyFault(int moduleNumber) {
+    return SolenoidJNI.getPCMSolenoidVoltageStickyFault(moduleNumber);
+  }
+
+  /**
+   * If true, the common highside solenoid voltage rail is too low, most likely a solenoid channel
+   * is shorted.
+   *
+   * @return true if PCM sticky fault is set
+   */
+  public boolean getPCMSolenoidVoltageStickyFault() {
+    return SolenoidBase.getPCMSolenoidVoltageStickyFault(m_moduleNumber);
+  }
+
+  /**
+   * The common highside solenoid voltage rail is too low, most likely a solenoid channel is
+   * shorted.
+   *
+   * @param moduleNumber the module number to read
+   * @return true if PCM is in fault state.
+   */
+  public static boolean getPCMSolenoidVoltageFault(int moduleNumber) {
+    return SolenoidJNI.getPCMSolenoidVoltageFault(moduleNumber);
+  }
+
+  /**
+   * The common highside solenoid voltage rail is too low, most likely a solenoid channel is
+   * shorted.
+   *
+   * @return true if PCM is in fault state.
+   */
+  public boolean getPCMSolenoidVoltageFault() {
+    return SolenoidBase.getPCMSolenoidVoltageFault(m_moduleNumber);
+  }
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * <p>If a sticky fault is set, then it will be persistently cleared. Compressor drive maybe
+   * momentarily disable while flags are being cleared. Care should be taken to not call this too
+   * frequently, otherwise normal compressor functionality may be prevented.
+   *
+   * <p>If no sticky faults are set then this call will have no effect.
+   *
+   * @param moduleNumber the module number to read
+   */
+  public static void clearAllPCMStickyFaults(int moduleNumber) {
+    SolenoidJNI.clearAllPCMStickyFaults(moduleNumber);
+  }
+
+  /**
+   * Clear ALL sticky faults inside PCM that Compressor is wired to.
+   *
+   * <p>If a sticky fault is set, then it will be persistently cleared. Compressor drive maybe
+   * momentarily disable while flags are being cleared. Care should be taken to not call this too
+   * frequently, otherwise normal compressor functionality may be prevented.
+   *
+   * <p>If no sticky faults are set then this call will have no effect.
+   */
+  public void clearAllPCMStickyFaults() {
+    SolenoidBase.clearAllPCMStickyFaults(m_moduleNumber);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Spark.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Spark.java
new file mode 100644
index 0000000..aa7953a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Spark.java
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * REV Robotics SPARK Speed Controller.
+ */
+public class Spark extends PWMSpeedController {
+  /**
+   * Common initialization code called by all constructors.
+   *
+   * <p>Note that the SPARK uses the following bounds for PWM values. These values should work
+   * reasonably well for most controllers, but if users experience issues such as asymmetric
+   * behavior around the deadband or inability to saturate the controller in either direction,
+   * calibration is recommended. The calibration procedure can be found in the Spark User Manual
+   * available from REV Robotics.
+   *
+   * <p>- 2.003ms = full "forward" - 1.55ms = the "high end" of the deadband range - 1.50ms =
+   * center of the deadband range (off) - 1.46ms = the "low end" of the deadband range - .999ms =
+   * full "reverse"
+   */
+  protected void initSpark() {
+    setBounds(2.003, 1.55, 1.50, 1.46, .999);
+    setPeriodMultiplier(PeriodMultiplier.k1X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_RevSPARK, getChannel());
+    setName("Spark", getChannel());
+  }
+
+  /**
+   * Constructor.
+   *
+   * @param channel The PWM channel that the SPARK is attached to. 0-9 are on-board, 10-19 are on
+   *                the MXP port
+   */
+  public Spark(final int channel) {
+    super(channel);
+    initSpark();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java
new file mode 100644
index 0000000..b90d19f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedController.java
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+/**
+ * Interface for speed controlling devices.
+ */
+public interface SpeedController extends PIDOutput {
+  /**
+   * Common interface for setting the speed of a speed controller.
+   *
+   * @param speed The speed to set. Value should be between -1.0 and 1.0.
+   */
+  void set(double speed);
+
+  /**
+   * Common interface for getting the current set speed of a speed controller.
+   *
+   * @return The current set speed. Value is between -1.0 and 1.0.
+   */
+  double get();
+
+  /**
+   * Common interface for inverting direction of a speed controller.
+   *
+   * @param isInverted The state of inversion true is inverted.
+   */
+  void setInverted(boolean isInverted);
+
+  /**
+   * Common interface for returning if a speed controller is in the inverted state or not.
+   *
+   * @return isInverted The state of the inversion true is inverted.
+   */
+  boolean getInverted();
+
+  /**
+   * Disable the speed controller.
+   */
+  void disable();
+
+  /**
+   * Stops motor movement. Motor can be moved again by calling set without having to re-enable the
+   * motor.
+   */
+  void stopMotor();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java
new file mode 100644
index 0000000..9158bb3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/SpeedControllerGroup.java
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Allows multiple {@link SpeedController} objects to be linked together.
+ */
+public class SpeedControllerGroup extends SendableBase implements SpeedController {
+  private boolean m_isInverted;
+  private final SpeedController[] m_speedControllers;
+  private static int instances;
+
+  /**
+   * Create a new SpeedControllerGroup with the provided SpeedControllers.
+   *
+   * @param speedControllers The SpeedControllers to add
+   */
+  @SuppressWarnings("PMD.AvoidArrayLoops")
+  public SpeedControllerGroup(SpeedController speedController,
+                              SpeedController... speedControllers) {
+    m_speedControllers = new SpeedController[speedControllers.length + 1];
+    m_speedControllers[0] = speedController;
+    addChild(speedController);
+    for (int i = 0; i < speedControllers.length; i++) {
+      m_speedControllers[i + 1] = speedControllers[i];
+      addChild(speedControllers[i]);
+    }
+    instances++;
+    setName("SpeedControllerGroup", instances);
+  }
+
+  @Override
+  public void set(double speed) {
+    for (SpeedController speedController : m_speedControllers) {
+      speedController.set(m_isInverted ? -speed : speed);
+    }
+  }
+
+  @Override
+  public double get() {
+    if (m_speedControllers.length > 0) {
+      return m_speedControllers[0].get() * (m_isInverted ? -1 : 1);
+    }
+    return 0.0;
+  }
+
+  @Override
+  public void setInverted(boolean isInverted) {
+    m_isInverted = isInverted;
+  }
+
+  @Override
+  public boolean getInverted() {
+    return m_isInverted;
+  }
+
+  @Override
+  public void disable() {
+    for (SpeedController speedController : m_speedControllers) {
+      speedController.disable();
+    }
+  }
+
+  @Override
+  public void stopMotor() {
+    for (SpeedController speedController : m_speedControllers) {
+      speedController.stopMotor();
+    }
+  }
+
+  @Override
+  public void pidWrite(double output) {
+    set(output);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Speed Controller");
+    builder.setActuator(true);
+    builder.setSafeState(this::stopMotor);
+    builder.addDoubleProperty("Value", this::get, this::set);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Talon.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Talon.java
new file mode 100644
index 0000000..334d9e3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Talon.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * Cross the Road Electronics (CTRE) Talon and Talon SR Speed Controller.
+ */
+public class Talon extends PWMSpeedController {
+  /**
+   * Constructor for a Talon (original or Talon SR).
+   *
+   * <p>Note that the Talon uses the following bounds for PWM values. These values should work
+   * reasonably well for most controllers, but if users experience issues such as asymmetric
+   * behavior around the deadband or inability to saturate the controller in either direction,
+   * calibration is recommended. The calibration procedure can be found in the Talon User Manual
+   * available from CTRE.
+   *
+   * <p>- 2.037ms = full "forward" - 1.539ms = the "high end" of the deadband range - 1.513ms =
+   * center of the deadband range (off) - 1.487ms = the "low end" of the deadband range - .989ms
+   * = full "reverse"
+   *
+   * @param channel The PWM channel that the Talon is attached to. 0-9 are on-board, 10-19 are on
+   *                the MXP port
+   */
+  public Talon(final int channel) {
+    super(channel);
+
+    setBounds(2.037, 1.539, 1.513, 1.487, .989);
+    setPeriodMultiplier(PeriodMultiplier.k1X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_Talon, getChannel());
+    setName("Talon", getChannel());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Threads.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Threads.java
new file mode 100644
index 0000000..7b49d4d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Threads.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.ThreadsJNI;
+
+public final class Threads {
+  /**
+  * Get the thread priority for the current thread.
+  * @return The current thread priority. Scaled 1-99.
+  */
+  public static int getCurrentThreadPriority() {
+    return ThreadsJNI.getCurrentThreadPriority();
+  }
+
+  /**
+  * Get if the current thread is realtime.
+  * @return If the current thread is realtime
+  */
+  public static boolean getCurrentThreadIsRealTime() {
+    return ThreadsJNI.getCurrentThreadIsRealTime();
+  }
+
+  /**
+  * Sets the thread priority for the current thread.
+  *
+  * @param realTime Set to true to set a realtime priority, false for standard
+  *     priority
+  * @param priority Priority to set the thread to. Scaled 1-99, with 1 being
+  *     highest. On RoboRIO, priority is ignored for non realtime setting
+  *
+  * @return The success state of setting the priority
+  */
+  public static boolean setCurrentThreadPriority(boolean realTime, int priority) {
+    return ThreadsJNI.setCurrentThreadPriority(realTime, priority);
+  }
+
+  private Threads() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
new file mode 100644
index 0000000..9575bf1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/TimedRobot.java
@@ -0,0 +1,99 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.NotifierJNI;
+
+/**
+ * TimedRobot implements the IterativeRobotBase robot program framework.
+ *
+ * <p>The TimedRobot class is intended to be subclassed by a user creating a robot program.
+ *
+ * <p>periodic() functions from the base class are called on an interval by a Notifier instance.
+ */
+public class TimedRobot extends IterativeRobotBase {
+  public static final double kDefaultPeriod = 0.02;
+
+  // The C pointer to the notifier object. We don't use it directly, it is
+  // just passed to the JNI bindings.
+  private final int m_notifier = NotifierJNI.initializeNotifier();
+
+  // The absolute expiration time
+  private double m_expirationTime;
+
+  /**
+   * Constructor for TimedRobot.
+   */
+  protected TimedRobot() {
+    this(kDefaultPeriod);
+  }
+
+  /**
+   * Constructor for TimedRobot.
+   *
+   * @param period Period in seconds.
+   */
+  protected TimedRobot(double period) {
+    super(period);
+
+    HAL.report(tResourceType.kResourceType_Framework, tInstances.kFramework_Timed);
+  }
+
+  @Override
+  @SuppressWarnings("NoFinalizer")
+  protected void finalize() {
+    NotifierJNI.stopNotifier(m_notifier);
+    NotifierJNI.cleanNotifier(m_notifier);
+  }
+
+  /**
+   * Provide an alternate "main loop" via startCompetition().
+   */
+  @Override
+  @SuppressWarnings("UnsafeFinalization")
+  public void startCompetition() {
+    robotInit();
+
+    // Tell the DS that the robot is ready to be enabled
+    HAL.observeUserProgramStarting();
+
+    m_expirationTime = RobotController.getFPGATime() * 1e-6 + m_period;
+    updateAlarm();
+
+    // Loop forever, calling the appropriate mode-dependent function
+    while (true) {
+      long curTime = NotifierJNI.waitForNotifierAlarm(m_notifier);
+      if (curTime == 0) {
+        break;
+      }
+
+      m_expirationTime += m_period;
+      updateAlarm();
+
+      loopFunc();
+    }
+  }
+
+  /**
+   * Get time period between calls to Periodic() functions.
+   */
+  public double getPeriod() {
+    return m_period;
+  }
+
+  /**
+   * Update the alarm hardware to reflect the next alarm.
+   */
+  @SuppressWarnings("UnsafeFinalization")
+  private void updateAlarm() {
+    NotifierJNI.updateNotifierAlarm(m_notifier, (long) (m_expirationTime * 1e6));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
new file mode 100644
index 0000000..a4c553e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Timer.java
@@ -0,0 +1,125 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+public class Timer {
+  /**
+   * Return the system clock time in seconds. Return the time from the FPGA hardware clock in
+   * seconds since the FPGA started.
+   *
+   * @return Robot running time in seconds.
+   */
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public static double getFPGATimestamp() {
+    return RobotController.getFPGATime() / 1000000.0;
+  }
+
+  /**
+   * Return the approximate match time. The FMS does not send an official match time to the robots,
+   * but does send an approximate match time. The value will count down the time remaining in the
+   * current period (auto or teleop). Warning: This is not an official time (so it cannot be used to
+   * dispute ref calls or guarantee that a function will trigger before the match ends) The
+   * Practice Match function of the DS approximates the behaviour seen on the field.
+   *
+   * @return Time remaining in current match period (auto or teleop) in seconds
+   */
+  public static double getMatchTime() {
+    return DriverStation.getInstance().getMatchTime();
+  }
+
+  /**
+   * Pause the thread for a specified time. Pause the execution of the thread for a specified period
+   * of time given in seconds. Motors will continue to run at their last assigned values, and
+   * sensors will continue to update. Only the task containing the wait will pause until the wait
+   * time is expired.
+   *
+   * @param seconds Length of time to pause
+   */
+  public static void delay(final double seconds) {
+    try {
+      Thread.sleep((long) (seconds * 1e3));
+    } catch (final InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+  }
+
+  private double m_startTime;
+  private double m_accumulatedTime;
+  private boolean m_running;
+
+  @SuppressWarnings("JavadocMethod")
+  public Timer() {
+    reset();
+  }
+
+  private double getMsClock() {
+    return RobotController.getFPGATime() / 1000.0;
+  }
+
+  /**
+   * Get the current time from the timer. If the clock is running it is derived from the current
+   * system clock the start time stored in the timer class. If the clock is not running, then return
+   * the time when it was last stopped.
+   *
+   * @return Current time value for this timer in seconds
+   */
+  public synchronized double get() {
+    if (m_running) {
+      return m_accumulatedTime + (getMsClock() - m_startTime) / 1000.0;
+    } else {
+      return m_accumulatedTime;
+    }
+  }
+
+  /**
+   * Reset the timer by setting the time to 0. Make the timer startTime the current time so new
+   * requests will be relative now
+   */
+  public synchronized void reset() {
+    m_accumulatedTime = 0;
+    m_startTime = getMsClock();
+  }
+
+  /**
+   * Start the timer running. Just set the running flag to true indicating that all time requests
+   * should be relative to the system clock.
+   */
+  public synchronized void start() {
+    m_startTime = getMsClock();
+    m_running = true;
+  }
+
+  /**
+   * Stop the timer. This computes the time as of now and clears the running flag, causing all
+   * subsequent time requests to be read from the accumulated time rather than looking at the system
+   * clock.
+   */
+  public synchronized void stop() {
+    final double temp = get();
+    m_accumulatedTime = temp;
+    m_running = false;
+  }
+
+  /**
+   * Check if the period specified has passed and if it has, advance the start time by that period.
+   * This is useful to decide if it's time to do periodic work without drifting later by the time it
+   * took to get around to checking.
+   *
+   * @param period The period to check for (in seconds).
+   * @return If the period has passed.
+   */
+  public synchronized boolean hasPeriodPassed(double period) {
+    if (get() > period) {
+      // Advance the start time by the period.
+      // Don't set it to the current time... we want to avoid drift.
+      m_startTime += period * 1000;
+      return true;
+    }
+    return false;
+  }
+}
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
new file mode 100644
index 0000000..b42dfdf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Ultrasonic.java
@@ -0,0 +1,398 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.ArrayList;
+import java.util.List;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * Ultrasonic rangefinder class. The Ultrasonic rangefinder measures absolute distance based on the
+ * round-trip time of a ping generated by the controller. These sensors use two transducers, a
+ * speaker and a microphone both tuned to the ultrasonic range. A common ultrasonic sensor, the
+ * Daventech SRF04 requires a short pulse to be generated on a digital channel. This causes the
+ * chirp to be emitted. A second line becomes high as the ping is transmitted and goes low when the
+ * echo is received. The time that the line is high determines the round trip distance (time of
+ * flight).
+ */
+public class Ultrasonic extends SendableBase implements PIDSource {
+  /**
+   * The units to return when PIDGet is called.
+   */
+  public enum Unit {
+    /**
+     * Use inches for PIDGet.
+     */
+    kInches,
+    /**
+     * Use millimeters for PIDGet.
+     */
+    kMillimeters
+  }
+
+  // Time (sec) for the ping trigger pulse.
+  private static final double kPingTime = 10 * 1e-6;
+  private static final double kSpeedOfSoundInchesPerSec = 1130.0 * 12.0;
+  // ultrasonic sensor list
+  private static final List<Ultrasonic> m_sensors = new ArrayList<>();
+  // automatic round robin mode
+  private static boolean m_automaticEnabled;
+  private DigitalInput m_echoChannel;
+  private DigitalOutput m_pingChannel;
+  private boolean m_allocatedChannels;
+  private boolean m_enabled;
+  private Counter m_counter;
+  // task doing the round-robin automatic sensing
+  private static Thread m_task;
+  private Unit m_units;
+  private static int m_instances;
+  protected PIDSourceType m_pidSource = PIDSourceType.kDisplacement;
+
+  /**
+   * Background task that goes through the list of ultrasonic sensors and pings each one in turn.
+   * The counter is configured to read the timing of the returned echo pulse.
+   *
+   * <p><b>DANGER WILL ROBINSON, DANGER WILL ROBINSON:</b> This code runs as a task and assumes that
+   * none of the ultrasonic sensors will change while it's running. If one does, then this will
+   * certainly break. Make sure to disable automatic mode before changing anything with the
+   * sensors!!
+   */
+  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;
+          }
+          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
+      }
+    }
+  }
+
+  /**
+   * Initialize the Ultrasonic Sensor. This is the common code that initializes the ultrasonic
+   * sensor given that there are two digital I/O channels allocated. If the system was running in
+   * automatic mode (round robin) when the new sensor is added, it is stopped, the sensor is added,
+   * then automatic mode is restored.
+   */
+  private synchronized void initialize() {
+    if (m_task == null) {
+      m_task = new UltrasonicChecker();
+    }
+    final boolean originalMode = m_automaticEnabled;
+    setAutomaticMode(false); // kill task when adding a new sensor
+    m_sensors.add(this);
+
+    m_counter = new Counter(m_echoChannel); // set up counter for this
+    addChild(m_counter);
+    // sensor
+    m_counter.setMaxPeriod(1.0);
+    m_counter.setSemiPeriodMode(true);
+    m_counter.reset();
+    m_enabled = true; // make it available for round robin scheduling
+    setAutomaticMode(originalMode);
+
+    m_instances++;
+    HAL.report(tResourceType.kResourceType_Ultrasonic, m_instances);
+    setName("Ultrasonic", m_echoChannel.getChannel());
+  }
+
+  /**
+   * Create an instance of the Ultrasonic Sensor. This is designed to supchannel the Daventech SRF04
+   * and Vex ultrasonic sensors.
+   *
+   * @param pingChannel The digital output channel that sends the pulse to initiate the sensor
+   *                    sending the ping.
+   * @param echoChannel The digital input channel that receives the echo. The length of time that
+   *                    the echo is high represents the round trip time of the ping, and the
+   *                    distance.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  public Ultrasonic(final int pingChannel, final int echoChannel, Unit units) {
+    m_pingChannel = new DigitalOutput(pingChannel);
+    m_echoChannel = new DigitalInput(echoChannel);
+    addChild(m_pingChannel);
+    addChild(m_echoChannel);
+    m_allocatedChannels = true;
+    m_units = units;
+    initialize();
+  }
+
+  /**
+   * Create an instance of the Ultrasonic Sensor. This is designed to supchannel the Daventech SRF04
+   * and Vex ultrasonic sensors. Default unit is inches.
+   *
+   * @param pingChannel The digital output channel that sends the pulse to initiate the sensor
+   *                    sending the ping.
+   * @param echoChannel The digital input channel that receives the echo. The length of time that
+   *                    the echo is high represents the round trip time of the ping, and the
+   *                    distance.
+   */
+  public Ultrasonic(final int pingChannel, final int echoChannel) {
+    this(pingChannel, echoChannel, Unit.kInches);
+  }
+
+  /**
+   * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a
+   * DigitalOutput for the ping channel.
+   *
+   * @param pingChannel The digital output object that starts the sensor doing a ping. Requires a
+   *                    10uS pulse to start.
+   * @param echoChannel The digital input object that times the return pulse to determine the
+   *                    range.
+   * @param units       The units returned in either kInches or kMilliMeters
+   */
+  public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel, Unit units) {
+    requireNonNull(pingChannel, "Provided ping channel was null");
+    requireNonNull(echoChannel, "Provided echo channel was null");
+
+    m_allocatedChannels = false;
+    m_pingChannel = pingChannel;
+    m_echoChannel = echoChannel;
+    m_units = units;
+    initialize();
+  }
+
+  /**
+   * Create an instance of an Ultrasonic Sensor from a DigitalInput for the echo channel and a
+   * DigitalOutput for the ping channel. Default unit is inches.
+   *
+   * @param pingChannel The digital output object that starts the sensor doing a ping. Requires a
+   *                    10uS pulse to start.
+   * @param echoChannel The digital input object that times the return pulse to determine the
+   *                    range.
+   */
+  public Ultrasonic(DigitalOutput pingChannel, DigitalInput echoChannel) {
+    this(pingChannel, echoChannel, Unit.kInches);
+  }
+
+  /**
+   * Destructor for the ultrasonic sensor. Delete the instance of the ultrasonic sensor by freeing
+   * the allocated digital channels. If the system was in automatic mode (round robin), then it is
+   * stopped, then started again after this sensor is removed (provided this wasn't the last
+   * sensor).
+   */
+  @Override
+  public synchronized void close() {
+    super.close();
+    final boolean wasAutomaticMode = m_automaticEnabled;
+    setAutomaticMode(false);
+    if (m_allocatedChannels) {
+      if (m_pingChannel != null) {
+        m_pingChannel.close();
+      }
+      if (m_echoChannel != null) {
+        m_echoChannel.close();
+      }
+    }
+
+    if (m_counter != null) {
+      m_counter.close();
+      m_counter = null;
+    }
+
+    m_pingChannel = null;
+    m_echoChannel = null;
+    synchronized (m_sensors) {
+      m_sensors.remove(this);
+    }
+    if (!m_sensors.isEmpty() && wasAutomaticMode) {
+      setAutomaticMode(true);
+    }
+  }
+
+  /**
+   * Turn Automatic mode on/off. When in Automatic mode, all sensors will fire in round robin,
+   * waiting a set time between each sensor.
+   *
+   * @param enabling Set to true if round robin scheduling should start for all the ultrasonic
+   *                 sensors. This scheduling method assures that the sensors are non-interfering
+   *                 because no two sensors fire at the same time. If another scheduling algorithm
+   *                 is preferred, it can be implemented by pinging the sensors manually and waiting
+   *                 for the results to come back.
+   */
+  public void setAutomaticMode(boolean enabling) {
+    if (enabling == m_automaticEnabled) {
+      return; // ignore the case of no change
+    }
+    m_automaticEnabled = enabling;
+
+    if (enabling) {
+      /* Clear all the counters so no data is valid. No synchronization is
+       * needed because the background task is stopped.
+       */
+      for (Ultrasonic u : m_sensors) {
+        u.m_counter.reset();
+      }
+
+      // Start round robin task
+      m_task.start();
+    } else {
+      // Wait for background task to stop running
+      try {
+        m_task.join();
+      } catch (InterruptedException ex) {
+        Thread.currentThread().interrupt();
+        ex.printStackTrace();
+      }
+
+      /* Clear all the counters (data now invalid) since automatic mode is
+       * disabled. No synchronization is needed because the background task is
+       * stopped.
+       */
+      for (Ultrasonic u : m_sensors) {
+        u.m_counter.reset();
+      }
+    }
+  }
+
+  /**
+   * Single ping to ultrasonic sensor. Send out a single ping to the ultrasonic sensor. This only
+   * works if automatic (round robin) mode is disabled. A single ping is sent out, and the counter
+   * should count the semi-period when it comes in. The counter is reset to make the current value
+   * invalid.
+   */
+  public void ping() {
+    setAutomaticMode(false); // turn off automatic round robin if pinging
+    // single sensor
+    m_counter.reset(); // reset the counter to zero (invalid data now)
+    // do the ping to start getting a single range
+    m_pingChannel.pulse(kPingTime);
+  }
+
+  /**
+   * Check if there is a valid range measurement. The ranges are accumulated in a counter that will
+   * increment on each edge of the echo (return) signal. If the count is not at least 2, then the
+   * range has not yet been measured, and is invalid.
+   *
+   * @return true if the range is valid
+   */
+  public boolean isRangeValid() {
+    return m_counter.get() > 1;
+  }
+
+  /**
+   * Get the range in inches from the ultrasonic sensor. If there is no valid value yet, i.e. at
+   * least one measurement hasn't completed, then return 0.
+   *
+   * @return double Range in inches of the target returned from the ultrasonic sensor.
+   */
+  public double getRangeInches() {
+    if (isRangeValid()) {
+      return m_counter.getPeriod() * kSpeedOfSoundInchesPerSec / 2.0;
+    } else {
+      return 0;
+    }
+  }
+
+  /**
+   * Get the range in millimeters from the ultrasonic sensor. If there is no valid value yet, i.e.
+   * at least one measurement hasn't completed, then return 0.
+   *
+   * @return double Range in millimeters of the target returned by the ultrasonic sensor.
+   */
+  public double getRangeMM() {
+    return getRangeInches() * 25.4;
+  }
+
+  @Override
+  public void setPIDSourceType(PIDSourceType pidSource) {
+    if (!pidSource.equals(PIDSourceType.kDisplacement)) {
+      throw new IllegalArgumentException("Only displacement PID is allowed for ultrasonics.");
+    }
+    m_pidSource = pidSource;
+  }
+
+  @Override
+  public PIDSourceType getPIDSourceType() {
+    return m_pidSource;
+  }
+
+  /**
+   * Get the range in the current DistanceUnit for the PIDSource base object.
+   *
+   * @return The range in DistanceUnit
+   */
+  @Override
+  public double pidGet() {
+    switch (m_units) {
+      case kInches:
+        return getRangeInches();
+      case kMillimeters:
+        return getRangeMM();
+      default:
+        return 0.0;
+    }
+  }
+
+  /**
+   * Set the current DistanceUnit that should be used for the PIDSource base object.
+   *
+   * @param units The DistanceUnit that should be used.
+   */
+  public void setDistanceUnits(Unit units) {
+    m_units = units;
+  }
+
+  /**
+   * Get the current DistanceUnit that is used for the PIDSource base object.
+   *
+   * @return The type of DistanceUnit that is being used.
+   */
+  public Unit getDistanceUnits() {
+    return m_units;
+  }
+
+  /**
+   * Is the ultrasonic enabled.
+   *
+   * @return true if the ultrasonic is enabled
+   */
+  public boolean isEnabled() {
+    return m_enabled;
+  }
+
+  /**
+   * Set if the ultrasonic is enabled.
+   *
+   * @param enable set to true to enable the ultrasonic
+   */
+  public void setEnabled(boolean enable) {
+    m_enabled = enable;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Ultrasonic");
+    builder.addDoubleProperty("Value", this::getRangeInches, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Utility.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Utility.java
new file mode 100644
index 0000000..47035b4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Utility.java
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.HALUtil;
+
+/**
+ * Contains global utility functions.
+ * @deprecated Use RobotController class instead
+ */
+@Deprecated
+public final class Utility {
+  private Utility() {
+  }
+
+  /**
+   * Return the FPGA Version number. For now, expect this to be 2009.
+   *
+   * @return FPGA Version number.
+   * @deprecated Use RobotController.getFPGAVersion()
+   */
+  @SuppressWarnings("AbbreviationAsWordInName")
+  @Deprecated
+  int getFPGAVersion() {
+    return HALUtil.getFPGAVersion();
+  }
+
+  /**
+   * Return the FPGA Revision number. The format of the revision is 3 numbers. The 12 most
+   * significant bits are the Major Revision. the next 8 bits are the Minor Revision. The 12 least
+   * significant bits are the Build Number.
+   *
+   * @return FPGA Revision number.
+   * @deprecated Use RobotController.getFPGARevision()
+   */
+  @SuppressWarnings("AbbreviationAsWordInName")
+  @Deprecated
+  long getFPGARevision() {
+    return (long) HALUtil.getFPGARevision();
+  }
+
+  /**
+   * Read the microsecond timer from the FPGA.
+   *
+   * @return The current time in microseconds according to the FPGA.
+   * @deprecated Use RobotController.getFPGATime()
+   */
+  @Deprecated
+  @SuppressWarnings("AbbreviationAsWordInName")
+  public static long getFPGATime() {
+    return HALUtil.getFPGATime();
+  }
+
+  /**
+   * Get the state of the "USER" button on the roboRIO.
+   *
+   * @return true if the button is currently pressed down
+   * @deprecated Use RobotController.getUserButton()
+   */
+  @Deprecated
+  public static boolean getUserButton() {
+    return HALUtil.getFPGAButton();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Victor.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Victor.java
new file mode 100644
index 0000000..b1aeeab
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Victor.java
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * VEX Robotics Victor 888 Speed Controller The Vex Robotics Victor 884 Speed Controller can also
+ * be used with this class but may need to be calibrated per the Victor 884 user manual.
+ */
+public class Victor extends PWMSpeedController {
+  /**
+   * Constructor.
+   *
+   * <p>Note that the Victor uses the following bounds for PWM values. These values were determined
+   * empirically and optimized for the Victor 888. These values should work reasonably well for
+   * Victor 884 controllers also but if users experience issues such as asymmetric behaviour around
+   * the deadband or inability to saturate the controller in either direction, calibration is
+   * recommended. The calibration procedure can be found in the Victor 884 User Manual available
+   * from VEX Robotics: http://content.vexrobotics.com/docs/ifi-v884-users-manual-9-25-06.pdf
+   *
+   * <p>- 2.027ms = full "forward" - 1.525ms = the "high end" of the deadband range - 1.507ms =
+   * center of the deadband range (off) - 1.49ms = the "low end" of the deadband range - 1.026ms =
+   * full "reverse"
+   *
+   * @param channel The PWM channel that the Victor is attached to. 0-9 are
+   *        on-board, 10-19 are on the MXP port
+   */
+  public Victor(final int channel) {
+    super(channel);
+
+    setBounds(2.027, 1.525, 1.507, 1.49, 1.026);
+    setPeriodMultiplier(PeriodMultiplier.k2X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_Victor, getChannel());
+    setName("Victor", getChannel());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/VictorSP.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/VictorSP.java
new file mode 100644
index 0000000..3de2a0a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/VictorSP.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * VEX Robotics Victor SP Speed Controller.
+ */
+public class VictorSP extends PWMSpeedController {
+  /**
+   * Constructor.
+   *
+   * <p>Note that the VictorSP uses the following bounds for PWM values. These values should work
+   * reasonably well for most controllers, but if users experience issues such as asymmetric
+   * behavior around the deadband or inability to saturate the controller in either direction,
+   * calibration is recommended. The calibration procedure can be found in the VictorSP User Manual
+   * available from CTRE.
+   *
+   * <p>- 2.004ms = full "forward" - 1.52ms = the "high end" of the deadband range - 1.50ms =
+   * center of the deadband range (off) - 1.48ms = the "low end" of the deadband range - .997ms =
+   * full "reverse"
+   *
+   * @param channel The PWM channel that the VictorSP is attached to. 0-9 are
+   *        on-board, 10-19 are on the MXP port
+   */
+  public VictorSP(final int channel) {
+    super(channel);
+
+    setBounds(2.004, 1.52, 1.50, 1.48, .997);
+    setPeriodMultiplier(PeriodMultiplier.k1X);
+    setSpeed(0.0);
+    setZeroLatch();
+
+    HAL.report(tResourceType.kResourceType_VictorSP, getChannel());
+    setName("VictorSP", getChannel());
+  }
+}
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
new file mode 100644
index 0000000..7ff8937
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/Watchdog.java
@@ -0,0 +1,292 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.io.Closeable;
+import java.util.HashMap;
+import java.util.Map;
+import java.util.PriorityQueue;
+import java.util.concurrent.TimeUnit;
+import java.util.concurrent.locks.Condition;
+import java.util.concurrent.locks.ReentrantLock;
+
+/**
+ * A class that's a wrapper around a watchdog timer.
+ *
+ * <p>When the timer expires, a message is printed to the console and an optional user-provided
+ * callback is invoked.
+ *
+ * <p>The watchdog is initialized disabled, so the user needs to call enable() before use.
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public class Watchdog implements Closeable, Comparable<Watchdog> {
+  // Used for timeout print rate-limiting
+  private static final long kMinPrintPeriod = 1000000; // us
+
+  private long m_startTime; // us
+  private long m_timeout; // us
+  private long m_expirationTime; // us
+  private final Runnable m_callback;
+  private long m_lastTimeoutPrintTime; // us
+  private long m_lastEpochsPrintTime; // us
+
+  @SuppressWarnings("PMD.UseConcurrentHashMap")
+  private final Map<String, Long> m_epochs = new HashMap<>();
+  boolean m_isExpired;
+
+  boolean m_suppressTimeoutMessage;
+
+  static {
+    startDaemonThread(() -> schedulerFunc());
+  }
+
+  private static final PriorityQueue<Watchdog> m_watchdogs = new PriorityQueue<>();
+  private static ReentrantLock m_queueMutex = new ReentrantLock();
+  private static Condition m_schedulerWaiter = m_queueMutex.newCondition();
+
+  /**
+   * Watchdog constructor.
+   *
+   * @param timeout  The watchdog's timeout in seconds with microsecond resolution.
+   * @param callback This function is called when the timeout expires.
+   */
+  public Watchdog(double timeout, Runnable callback) {
+    m_timeout = (long) (timeout * 1.0e6);
+    m_callback = callback;
+  }
+
+  @Override
+  public void close() {
+    disable();
+  }
+
+  @Override
+  public int compareTo(Watchdog rhs) {
+    // Elements with sooner expiration times are sorted as lesser. The head of
+    // Java's PriorityQueue is the least element.
+    if (m_expirationTime < rhs.m_expirationTime) {
+      return -1;
+    } else if (m_expirationTime > rhs.m_expirationTime) {
+      return 1;
+    } else {
+      return 0;
+    }
+  }
+
+  /**
+   * Returns the time in seconds since the watchdog was last fed.
+   */
+  public double getTime() {
+    return (RobotController.getFPGATime() - m_startTime) / 1.0e6;
+  }
+
+  /**
+   * Sets the watchdog's timeout.
+   *
+   * @param timeout The watchdog's timeout in seconds with microsecond
+   *                resolution.
+   */
+  public void setTimeout(double timeout) {
+    m_startTime = RobotController.getFPGATime();
+    m_epochs.clear();
+
+    m_queueMutex.lock();
+    try {
+      m_timeout = (long) (timeout * 1.0e6);
+      m_isExpired = false;
+
+      m_watchdogs.remove(this);
+      m_expirationTime = m_startTime + m_timeout;
+      m_watchdogs.add(this);
+      m_schedulerWaiter.signalAll();
+    } finally {
+      m_queueMutex.unlock();
+    }
+  }
+
+  /**
+   * Returns the watchdog's timeout in seconds.
+   */
+  public double getTimeout() {
+    m_queueMutex.lock();
+    try {
+      return m_timeout / 1.0e6;
+    } finally {
+      m_queueMutex.unlock();
+    }
+  }
+
+  /**
+   * Returns true if the watchdog timer has expired.
+   */
+  public boolean isExpired() {
+    m_queueMutex.lock();
+    try {
+      return m_isExpired;
+    } finally {
+      m_queueMutex.unlock();
+    }
+  }
+
+  /**
+   * Adds time since last epoch to the list printed by printEpochs().
+   *
+   * <p>Epochs are a way to partition the time elapsed so that when overruns occur, one can
+   * determine which parts of an operation consumed the most time.
+   *
+   * @param epochName The name to associate with the epoch.
+   */
+  public void addEpoch(String epochName) {
+    long currentTime = RobotController.getFPGATime();
+    m_epochs.put(epochName, currentTime - m_startTime);
+    m_startTime = currentTime;
+  }
+
+  /**
+   * Prints list of epochs added so far and their times.
+   */
+  public void printEpochs() {
+    long now = RobotController.getFPGATime();
+    if (now  - m_lastEpochsPrintTime > kMinPrintPeriod) {
+      m_lastEpochsPrintTime = now;
+      m_epochs.forEach((key, value) -> {
+        System.out.format("\t%s: %.6fs\n", key, value / 1.0e6);
+      });
+    }
+  }
+
+  /**
+   * Resets the watchdog timer.
+   *
+   * <p>This also enables the timer if it was previously disabled.
+   */
+  public void reset() {
+    enable();
+  }
+
+  /**
+   * Enables the watchdog timer.
+   */
+  public void enable() {
+    m_startTime = RobotController.getFPGATime();
+    m_epochs.clear();
+
+    m_queueMutex.lock();
+    try {
+      m_isExpired = false;
+
+      m_watchdogs.remove(this);
+      m_expirationTime = m_startTime + m_timeout;
+      m_watchdogs.add(this);
+      m_schedulerWaiter.signalAll();
+    } finally {
+      m_queueMutex.unlock();
+    }
+  }
+
+  /**
+   * Disables the watchdog timer.
+   */
+  public void disable() {
+    m_queueMutex.lock();
+    try {
+      m_isExpired = false;
+
+      m_watchdogs.remove(this);
+      m_schedulerWaiter.signalAll();
+    } finally {
+      m_queueMutex.unlock();
+    }
+  }
+
+  /**
+   * Enable or disable suppression of the generic timeout message.
+   *
+   * <p>This may be desirable if the user-provided callback already prints a more specific message.
+   *
+   * @param suppress Whether to suppress generic timeout message.
+   */
+  public void suppressTimeoutMessage(boolean suppress) {
+    m_suppressTimeoutMessage = suppress;
+  }
+
+  private static Thread startDaemonThread(Runnable target) {
+    Thread inst = new Thread(target);
+    inst.setDaemon(true);
+    inst.start();
+    return inst;
+  }
+
+
+  private static void schedulerFunc() {
+    m_queueMutex.lock();
+
+    try {
+      while (true) {
+        if (m_watchdogs.size() > 0) {
+          boolean timedOut = !awaitUntil(m_schedulerWaiter, m_watchdogs.peek().m_expirationTime);
+          if (timedOut) {
+            if (m_watchdogs.size() == 0 || m_watchdogs.peek().m_expirationTime
+                > RobotController.getFPGATime()) {
+              continue;
+            }
+
+            // If the condition variable timed out, that means a Watchdog timeout
+            // has occurred, so call its timeout function.
+            Watchdog watchdog = m_watchdogs.poll();
+
+            long now = RobotController.getFPGATime();
+            if (now  - watchdog.m_lastTimeoutPrintTime > kMinPrintPeriod) {
+              watchdog.m_lastTimeoutPrintTime = now;
+              if (!watchdog.m_suppressTimeoutMessage) {
+                System.out.format("Watchdog not fed within %.6fs\n", watchdog.m_timeout / 1.0e6);
+              }
+            }
+
+            // Set expiration flag before calling the callback so any
+            // manipulation of the flag in the callback (e.g., calling
+            // Disable()) isn't clobbered.
+            watchdog.m_isExpired = true;
+
+            m_queueMutex.unlock();
+            watchdog.m_callback.run();
+            m_queueMutex.lock();
+          }
+          // Otherwise, a Watchdog removed itself from the queue (it notifies
+          // the scheduler of this) or a spurious wakeup occurred, so just
+          // rewait with the soonest watchdog timeout.
+        } else {
+          while (m_watchdogs.size() == 0) {
+            m_schedulerWaiter.awaitUninterruptibly();
+          }
+        }
+      }
+    } finally {
+      m_queueMutex.unlock();
+    }
+  }
+
+  /**
+   * Wrapper emulating functionality of C++'s std::condition_variable::wait_until().
+   *
+   * @param cond The condition variable on which to wait.
+   * @param time The time at which to stop waiting.
+   * @return False if the deadline has elapsed upon return, else true.
+   */
+  private static boolean awaitUntil(Condition cond, long time) {
+    long delta = time - RobotController.getFPGATime();
+    try {
+      return cond.await(delta, TimeUnit.MICROSECONDS);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+      ex.printStackTrace();
+    }
+
+    return true;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java
new file mode 100644
index 0000000..79d80e6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/XboxController.java
@@ -0,0 +1,345 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+
+/**
+ * Handle input from Xbox 360 or Xbox One controllers connected to the Driver Station.
+ *
+ * <p>This class handles Xbox input that comes from the Driver Station. Each time a value is
+ * requested the most recent value is returned. There is a single class instance for each controller
+ * and the mapping of ports to hardware buttons depends on the code in the Driver Station.
+ */
+public class XboxController extends GenericHID {
+  /**
+   * Represents a digital button on an XboxController.
+   */
+  private enum Button {
+    kBumperLeft(5),
+    kBumperRight(6),
+    kStickLeft(9),
+    kStickRight(10),
+    kA(1),
+    kB(2),
+    kX(3),
+    kY(4),
+    kBack(7),
+    kStart(8);
+
+    @SuppressWarnings({"MemberName", "PMD.SingularField"})
+    private final int value;
+
+    Button(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * Construct an instance of a joystick. The joystick index is the USB port on the drivers
+   * station.
+   *
+   * @param port The port on the Driver Station that the joystick is plugged into.
+   */
+  public XboxController(final int port) {
+    super(port);
+
+    HAL.report(tResourceType.kResourceType_XboxController, port);
+  }
+
+  /**
+   * Get the X axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The X axis value of the controller.
+   */
+  @Override
+  public double getX(Hand hand) {
+    if (hand.equals(Hand.kLeft)) {
+      return getRawAxis(0);
+    } else {
+      return getRawAxis(4);
+    }
+  }
+
+  /**
+   * Get the Y axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The Y axis value of the controller.
+   */
+  @Override
+  public double getY(Hand hand) {
+    if (hand.equals(Hand.kLeft)) {
+      return getRawAxis(1);
+    } else {
+      return getRawAxis(5);
+    }
+  }
+
+  /**
+   * Get the trigger axis value of the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The trigger axis value of the controller.
+   */
+  public double getTriggerAxis(Hand hand) {
+    if (hand.equals(Hand.kLeft)) {
+      return getRawAxis(2);
+    } else {
+      return getRawAxis(3);
+    }
+  }
+
+  /**
+   * Read the value of the bumper button on the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The state of the button.
+   */
+  public boolean getBumper(Hand hand) {
+    if (hand.equals(Hand.kLeft)) {
+      return getRawButton(Button.kBumperLeft.value);
+    } else {
+      return getRawButton(Button.kBumperRight.value);
+    }
+  }
+
+  /**
+   * Whether the bumper was pressed since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getBumperPressed(Hand hand) {
+    if (hand == Hand.kLeft) {
+      return getRawButtonPressed(Button.kBumperLeft.value);
+    } else {
+      return getRawButtonPressed(Button.kBumperRight.value);
+    }
+  }
+
+  /**
+   * Whether the bumper was released since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getBumperReleased(Hand hand) {
+    if (hand == Hand.kLeft) {
+      return getRawButtonReleased(Button.kBumperLeft.value);
+    } else {
+      return getRawButtonReleased(Button.kBumperRight.value);
+    }
+  }
+
+  /**
+   * Read the value of the stick button on the controller.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return The state of the button.
+   */
+  public boolean getStickButton(Hand hand) {
+    if (hand.equals(Hand.kLeft)) {
+      return getRawButton(Button.kStickLeft.value);
+    } else {
+      return getRawButton(Button.kStickRight.value);
+    }
+  }
+
+  /**
+   * Whether the stick button was pressed since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getStickButtonPressed(Hand hand) {
+    if (hand == Hand.kLeft) {
+      return getRawButtonPressed(Button.kStickLeft.value);
+    } else {
+      return getRawButtonPressed(Button.kStickRight.value);
+    }
+  }
+
+  /**
+   * Whether the stick button was released since the last check.
+   *
+   * @param hand Side of controller whose value should be returned.
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getStickButtonReleased(Hand hand) {
+    if (hand == Hand.kLeft) {
+      return getRawButtonReleased(Button.kStickLeft.value);
+    } else {
+      return getRawButtonReleased(Button.kStickRight.value);
+    }
+  }
+
+  /**
+   * Read the value of the A button on the controller.
+   *
+   * @return The state of the button.
+   */
+  public boolean getAButton() {
+    return getRawButton(Button.kA.value);
+  }
+
+  /**
+   * Whether the A button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getAButtonPressed() {
+    return getRawButtonPressed(Button.kA.value);
+  }
+
+  /**
+   * Whether the A button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getAButtonReleased() {
+    return getRawButtonReleased(Button.kA.value);
+  }
+
+  /**
+   * Read the value of the B button on the controller.
+   *
+   * @return The state of the button.
+   */
+  public boolean getBButton() {
+    return getRawButton(Button.kB.value);
+  }
+
+  /**
+   * Whether the B button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getBButtonPressed() {
+    return getRawButtonPressed(Button.kB.value);
+  }
+
+  /**
+   * Whether the B button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getBButtonReleased() {
+    return getRawButtonReleased(Button.kB.value);
+  }
+
+  /**
+   * Read the value of the X button on the controller.
+   *
+   * @return The state of the button.
+   */
+  public boolean getXButton() {
+    return getRawButton(Button.kX.value);
+  }
+
+  /**
+   * Whether the X button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getXButtonPressed() {
+    return getRawButtonPressed(Button.kX.value);
+  }
+
+  /**
+   * Whether the X button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getXButtonReleased() {
+    return getRawButtonReleased(Button.kX.value);
+  }
+
+  /**
+   * Read the value of the Y button on the controller.
+   *
+   * @return The state of the button.
+   */
+  public boolean getYButton() {
+    return getRawButton(Button.kY.value);
+  }
+
+  /**
+   * Whether the Y button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getYButtonPressed() {
+    return getRawButtonPressed(Button.kY.value);
+  }
+
+  /**
+   * Whether the Y button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getYButtonReleased() {
+    return getRawButtonReleased(Button.kY.value);
+  }
+
+  /**
+   * Read the value of the back button on the controller.
+   *
+   * @return The state of the button.
+   */
+  public boolean getBackButton() {
+    return getRawButton(Button.kBack.value);
+  }
+
+  /**
+   * Whether the back button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getBackButtonPressed() {
+    return getRawButtonPressed(Button.kBack.value);
+  }
+
+  /**
+   * Whether the back button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getBackButtonReleased() {
+    return getRawButtonReleased(Button.kBack.value);
+  }
+
+  /**
+   * Read the value of the start button on the controller.
+   *
+   * @return The state of the button.
+   */
+  public boolean getStartButton() {
+    return getRawButton(Button.kStart.value);
+  }
+
+  /**
+   * Whether the start button was pressed since the last check.
+   *
+   * @return Whether the button was pressed since the last check.
+   */
+  public boolean getStartButtonPressed() {
+    return getRawButtonPressed(Button.kStart.value);
+  }
+
+  /**
+   * Whether the start button was released since the last check.
+   *
+   * @return Whether the button was released since the last check.
+   */
+  public boolean getStartButtonReleased() {
+    return getRawButtonReleased(Button.kStart.value);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java
new file mode 100644
index 0000000..a7dc2fa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Button.java
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.buttons;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+/**
+ * This class provides an easy way to link commands to OI inputs.
+ *
+ * <p>It is very easy to link a button to a command. For instance, you could link the trigger button
+ * of a joystick to a "score" command.
+ *
+ * <p>This class represents a subclass of Trigger that is specifically aimed at buttons on an
+ * operator interface as a common use case of the more generalized Trigger objects. This is a simple
+ * wrapper around Trigger with the method names renamed to fit the Button object use.
+ */
+public abstract class Button extends Trigger {
+  /**
+   * Starts the given command whenever the button is newly pressed.
+   *
+   * @param command the command to start
+   */
+  public void whenPressed(final Command command) {
+    whenActive(command);
+  }
+
+  /**
+   * Constantly starts the given command while the button is held.
+   *
+   * {@link Command#start()} will be called repeatedly while the button is held, and will be
+   * canceled when the button is released.
+   *
+   * @param command the command to start
+   */
+  public void whileHeld(final Command command) {
+    whileActive(command);
+  }
+
+  /**
+   * Starts the command when the button is released.
+   *
+   * @param command the command to start
+   */
+  public void whenReleased(final Command command) {
+    whenInactive(command);
+  }
+
+  /**
+   * Toggles the command whenever the button is pressed (on then off then on).
+   *
+   * @param command the command to start
+   */
+  public void toggleWhenPressed(final Command command) {
+    toggleWhenActive(command);
+  }
+
+  /**
+   * Cancel the command when the button is pressed.
+   *
+   * @param command the command to start
+   */
+  public void cancelWhenPressed(final Command command) {
+    cancelWhenActive(command);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java
new file mode 100644
index 0000000..bb1eff7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/InternalButton.java
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.buttons;
+
+/**
+ * This class is intended to be used within a program. The programmer can manually set its value.
+ * Also includes a setting for whether or not it should invert its value.
+ */
+public class InternalButton extends Button {
+  private boolean m_pressed;
+  private boolean m_inverted;
+
+  /**
+   * Creates an InternalButton that is not inverted.
+   */
+  public InternalButton() {
+    this(false);
+  }
+
+  /**
+   * Creates an InternalButton which is inverted depending on the input.
+   *
+   * @param inverted if false, then this button is pressed when set to true, otherwise it is pressed
+   *                 when set to false.
+   */
+  public InternalButton(boolean inverted) {
+    m_pressed = m_inverted = inverted;
+  }
+
+  public void setInverted(boolean inverted) {
+    m_inverted = inverted;
+  }
+
+  public void setPressed(boolean pressed) {
+    m_pressed = pressed;
+  }
+
+  @Override
+  public boolean get() {
+    return m_pressed ^ m_inverted;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java
new file mode 100644
index 0000000..db0d4c6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/JoystickButton.java
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.buttons;
+
+import edu.wpi.first.wpilibj.GenericHID;
+
+/**
+ * A {@link Button} that gets its state from a {@link GenericHID}.
+ */
+public class JoystickButton extends Button {
+  private final GenericHID m_joystick;
+  private final int m_buttonNumber;
+
+  /**
+   * Create a joystick button for triggering commands.
+   *
+   * @param joystick     The GenericHID object that has the button (e.g. Joystick, KinectStick,
+   *                     etc)
+   * @param buttonNumber The button number (see {@link GenericHID#getRawButton(int) }
+   */
+  public JoystickButton(GenericHID joystick, int buttonNumber) {
+    m_joystick = joystick;
+    m_buttonNumber = buttonNumber;
+  }
+
+  /**
+   * Gets the value of the joystick button.
+   *
+   * @return The value of the joystick button
+   */
+  @Override
+  public boolean get() {
+    return m_joystick.getRawButton(m_buttonNumber);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java
new file mode 100644
index 0000000..2fa7924
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/NetworkButton.java
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.buttons;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+/**
+ * A {@link Button} that uses a {@link NetworkTable} boolean field.
+ */
+public class NetworkButton extends Button {
+  private final NetworkTableEntry m_entry;
+
+  public NetworkButton(String table, String field) {
+    this(NetworkTableInstance.getDefault().getTable(table), field);
+  }
+
+  public NetworkButton(NetworkTable table, String field) {
+    m_entry = table.getEntry(field);
+  }
+
+  @Override
+  public boolean get() {
+    return m_entry.getInstance().isConnected() && m_entry.getBoolean(false);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java
new file mode 100644
index 0000000..abf8ca7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/POVButton.java
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.buttons;
+
+import edu.wpi.first.wpilibj.GenericHID;
+
+/**
+ * A {@link Button} that gets its state from a POV on a {@link GenericHID}.
+ */
+public class POVButton extends Button {
+  private final GenericHID m_joystick;
+  private final int m_angle;
+  private final int m_povNumber;
+
+  /**
+   * Creates a POV button for triggering commands.
+   *
+   * @param joystick The GenericHID object that has the POV
+   * @param angle The desired angle in degrees (e.g. 90, 270)
+   * @param povNumber The POV number (see {@link GenericHID#getPOV(int)})
+   */
+  public POVButton(GenericHID joystick, int angle, int povNumber) {
+    m_joystick = joystick;
+    m_angle = angle;
+    m_povNumber = povNumber;
+  }
+
+  /**
+   * Creates a POV button for triggering commands.
+   * By default, acts on POV 0
+   *
+   * @param joystick The GenericHID object that has the POV
+   * @param angle The desired angle (e.g. 90, 270)
+   */
+  public POVButton(GenericHID joystick, int angle) {
+    this(joystick, angle, 0);
+  }
+
+  /**
+   * Checks whether the current value of the POV is the target angle.
+   *
+   * @return Whether the value of the POV matches the target angle
+   */
+  @Override
+  public boolean get() {
+    return m_joystick.getPOV(m_povNumber) == m_angle;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java
new file mode 100644
index 0000000..c20e62e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/buttons/Trigger.java
@@ -0,0 +1,185 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.buttons;
+
+import edu.wpi.first.wpilibj.SendableBase;
+import edu.wpi.first.wpilibj.command.Command;
+import edu.wpi.first.wpilibj.command.Scheduler;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * This class provides an easy way to link commands to inputs.
+ *
+ * <p>It is very easy to link a button to a command. For instance, you could link the trigger
+ * button of a joystick to a "score" command.
+ *
+ * <p>It is encouraged that teams write a subclass of Trigger if they want to have something unusual
+ * (for instance, if they want to react to the user holding a button while the robot is reading a
+ * certain sensor input). For this, they only have to write the {@link Trigger#get()} method to get
+ * the full functionality of the Trigger class.
+ */
+public abstract class Trigger extends SendableBase {
+  private volatile boolean m_sendablePressed;
+
+  /**
+   * Returns whether or not the trigger is active.
+   *
+   * <p>This method will be called repeatedly a command is linked to the Trigger.
+   *
+   * @return whether or not the trigger condition is active.
+   */
+  public abstract boolean get();
+
+  /**
+   * Returns whether get() return true or the internal table for SmartDashboard use is pressed.
+   *
+   * @return whether get() return true or the internal table for SmartDashboard use is pressed.
+   */
+  @SuppressWarnings("PMD.UselessParentheses")
+  private boolean grab() {
+    return get() || m_sendablePressed;
+  }
+
+  /**
+   * Starts the given command whenever the trigger just becomes active.
+   *
+   * @param command the command to start
+   */
+  public void whenActive(final Command command) {
+    new ButtonScheduler() {
+      private boolean m_pressedLast = grab();
+
+      @Override
+      public void execute() {
+        boolean pressed = grab();
+
+        if (!m_pressedLast && pressed) {
+          command.start();
+        }
+
+        m_pressedLast = pressed;
+      }
+    }.start();
+  }
+
+  /**
+   * Constantly starts the given command while the button is held.
+   *
+   * {@link Command#start()} will be called repeatedly while the trigger is active, and will be
+   * canceled when the trigger becomes inactive.
+   *
+   * @param command the command to start
+   */
+  public void whileActive(final Command command) {
+    new ButtonScheduler() {
+      private boolean m_pressedLast = grab();
+
+      @Override
+      public void execute() {
+        boolean pressed = grab();
+
+        if (pressed) {
+          command.start();
+        } else if (m_pressedLast && !pressed) {
+          command.cancel();
+        }
+
+        m_pressedLast = pressed;
+      }
+    }.start();
+  }
+
+  /**
+   * Starts the command when the trigger becomes inactive.
+   *
+   * @param command the command to start
+   */
+  public void whenInactive(final Command command) {
+    new ButtonScheduler() {
+      private boolean m_pressedLast = grab();
+
+      @Override
+      public void execute() {
+        boolean pressed = grab();
+
+        if (m_pressedLast && !pressed) {
+          command.start();
+        }
+
+        m_pressedLast = pressed;
+      }
+    }.start();
+  }
+
+  /**
+   * Toggles a command when the trigger becomes active.
+   *
+   * @param command the command to toggle
+   */
+  public void toggleWhenActive(final Command command) {
+    new ButtonScheduler() {
+      private boolean m_pressedLast = grab();
+
+      @Override
+      public void execute() {
+        boolean pressed = grab();
+
+        if (!m_pressedLast && pressed) {
+          if (command.isRunning()) {
+            command.cancel();
+          } else {
+            command.start();
+          }
+        }
+
+        m_pressedLast = pressed;
+      }
+    }.start();
+  }
+
+  /**
+   * Cancels a command when the trigger becomes active.
+   *
+   * @param command the command to cancel
+   */
+  public void cancelWhenActive(final Command command) {
+    new ButtonScheduler() {
+      private boolean m_pressedLast = grab();
+
+      @Override
+      public void execute() {
+        boolean pressed = grab();
+
+        if (!m_pressedLast && pressed) {
+          command.cancel();
+        }
+
+        m_pressedLast = pressed;
+      }
+    }.start();
+  }
+
+  /**
+   * An internal class of {@link Trigger}. The user should ignore this, it is only public to
+   * interface between packages.
+   */
+  public abstract static class ButtonScheduler {
+    public abstract void execute();
+
+    public void start() {
+      Scheduler.getInstance().addButton(this);
+    }
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Button");
+    builder.setSafeState(() -> m_sendablePressed = false);
+    builder.addBooleanProperty("pressed", this::grab, value -> m_sendablePressed = value);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Command.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Command.java
new file mode 100644
index 0000000..0033f58
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Command.java
@@ -0,0 +1,626 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import java.util.Enumeration;
+
+import edu.wpi.first.wpilibj.RobotState;
+import edu.wpi.first.wpilibj.SendableBase;
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * The Command class is at the very core of the entire command framework. Every command can be
+ * started with a call to {@link Command#start() start()}. Once a command is started it will call
+ * {@link Command#initialize() initialize()}, and then will repeatedly call {@link Command#execute()
+ * execute()} until the {@link Command#isFinished() isFinished()} returns true. Once it does, {@link
+ * Command#end() end()} will be called.
+ *
+ * <p>However, if at any point while it is running {@link Command#cancel() cancel()} is called,
+ * then the command will be stopped and {@link Command#interrupted() interrupted()} will be called.
+ *
+ * <p>If a command uses a {@link Subsystem}, then it should specify that it does so by calling the
+ * {@link Command#requires(Subsystem) requires(...)} method in its constructor. Note that a Command
+ * may have multiple requirements, and {@link Command#requires(Subsystem) requires(...)} should be
+ * called for each one.
+ *
+ * <p>If a command is running and a new command with shared requirements is started, then one of
+ * two things will happen. If the active command is interruptible, then {@link Command#cancel()
+ * cancel()} will be called and the command will be removed to make way for the new one. If the
+ * active command is not interruptible, the other one will not even be started, and the active one
+ * will continue functioning.
+ *
+ * @see Subsystem
+ * @see CommandGroup
+ * @see IllegalUseOfCommandException
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public abstract class Command extends SendableBase {
+  /**
+   * The time since this command was initialized.
+   */
+  private double m_startTime = -1;
+
+  /**
+   * The time (in seconds) before this command "times out" (or -1 if no timeout).
+   */
+  private double m_timeout = -1;
+
+  /**
+   * Whether or not this command has been initialized.
+   */
+  private boolean m_initialized;
+
+  /**
+   * The required subsystems.
+   */
+  private final Set m_requirements = new Set();
+
+  /**
+   * Whether or not it is running.
+   */
+  private boolean m_running;
+
+  /**
+   * Whether or not it is interruptible.
+   */
+  private boolean m_interruptible = true;
+
+  /**
+   * Whether or not it has been canceled.
+   */
+  private boolean m_canceled;
+
+  /**
+   * Whether or not it has been locked.
+   */
+  private boolean m_locked;
+
+  /**
+   * Whether this command should run when the robot is disabled.
+   */
+  private boolean m_runWhenDisabled;
+
+  /**
+   * Whether or not this command has completed running.
+   */
+  private boolean m_completed;
+
+  /**
+   * The {@link CommandGroup} this is in.
+   */
+  private CommandGroup m_parent;
+
+  /**
+   * Creates a new command. The name of this command will be set to its class name.
+   */
+  public Command() {
+    super(false);
+    String name = getClass().getName();
+    setName(name.substring(name.lastIndexOf('.') + 1));
+  }
+
+  /**
+   * Creates a new command with the given name.
+   *
+   * @param name the name for this command
+   * @throws IllegalArgumentException if name is null
+   */
+  public Command(String name) {
+    super(false);
+    if (name == null) {
+      throw new IllegalArgumentException("Name must not be null.");
+    }
+    setName(name);
+  }
+
+  /**
+   * Creates a new command with the given timeout and a default name. The default name is the name
+   * of the class.
+   *
+   * @param timeout the time (in seconds) before this command "times out"
+   * @throws IllegalArgumentException if given a negative timeout
+   * @see Command#isTimedOut() isTimedOut()
+   */
+  public Command(double timeout) {
+    this();
+    if (timeout < 0) {
+      throw new IllegalArgumentException("Timeout must not be negative.  Given:" + timeout);
+    }
+    m_timeout = timeout;
+  }
+
+  /**
+   * Creates a new command with the given timeout and a default name. The default name is the name
+   * of the class.
+   *
+   * @param subsystem the subsystem that this command requires
+   * @throws IllegalArgumentException if given a negative timeout
+   * @see Command#isTimedOut() isTimedOut()
+   */
+  public Command(Subsystem subsystem) {
+    this();
+    requires(subsystem);
+  }
+
+  /**
+   * Creates a new command with the given name.
+   *
+   * @param name      the name for this command
+   * @param subsystem the subsystem that this command requires
+   * @throws IllegalArgumentException if name is null
+   */
+  public Command(String name, Subsystem subsystem) {
+    this(name);
+    requires(subsystem);
+  }
+
+  /**
+   * Creates a new command with the given timeout and a default name. The default name is the name
+   * of the class.
+   *
+   * @param timeout   the time (in seconds) before this command "times out"
+   * @param subsystem the subsystem that this command requires
+   * @throws IllegalArgumentException if given a negative timeout
+   * @see Command#isTimedOut() isTimedOut()
+   */
+  public Command(double timeout, Subsystem subsystem) {
+    this(timeout);
+    requires(subsystem);
+  }
+
+  /**
+   * Creates a new command with the given name and timeout.
+   *
+   * @param name    the name of the command
+   * @param timeout the time (in seconds) before this command "times out"
+   * @throws IllegalArgumentException if given a negative timeout or name was null.
+   * @see Command#isTimedOut() isTimedOut()
+   */
+  public Command(String name, double timeout) {
+    this(name);
+    if (timeout < 0) {
+      throw new IllegalArgumentException("Timeout must not be negative.  Given:" + timeout);
+    }
+    m_timeout = timeout;
+  }
+
+  /**
+   * Creates a new command with the given name and timeout.
+   *
+   * @param name      the name of the command
+   * @param timeout   the time (in seconds) before this command "times out"
+   * @param subsystem the subsystem that this command requires
+   * @throws IllegalArgumentException if given a negative timeout
+   * @throws IllegalArgumentException if given a negative timeout or name was null.
+   * @see Command#isTimedOut() isTimedOut()
+   */
+  public Command(String name, double timeout, Subsystem subsystem) {
+    this(name, timeout);
+    requires(subsystem);
+  }
+
+  /**
+   * Sets the timeout of this command.
+   *
+   * @param seconds the timeout (in seconds)
+   * @throws IllegalArgumentException if seconds is negative
+   * @see Command#isTimedOut() isTimedOut()
+   */
+  protected final synchronized void setTimeout(double seconds) {
+    if (seconds < 0) {
+      throw new IllegalArgumentException("Seconds must be positive.  Given:" + seconds);
+    }
+    m_timeout = seconds;
+  }
+
+  /**
+   * Returns the time since this command was initialized (in seconds). This function will work even
+   * if there is no specified timeout.
+   *
+   * @return the time since this command was initialized (in seconds).
+   */
+  public final synchronized double timeSinceInitialized() {
+    return m_startTime < 0 ? 0 : Timer.getFPGATimestamp() - m_startTime;
+  }
+
+  /**
+   * This method specifies that the given {@link Subsystem} is used by this command. This method is
+   * crucial to the functioning of the Command System in general.
+   *
+   * <p>Note that the recommended way to call this method is in the constructor.
+   *
+   * @param subsystem the {@link Subsystem} required
+   * @throws IllegalArgumentException     if subsystem is null
+   * @throws IllegalUseOfCommandException if this command has started before or if it has been given
+   *                                      to a {@link CommandGroup}
+   * @see Subsystem
+   */
+  protected synchronized void requires(Subsystem subsystem) {
+    validate("Can not add new requirement to command");
+    if (subsystem != null) {
+      m_requirements.add(subsystem);
+    } else {
+      throw new IllegalArgumentException("Subsystem must not be null.");
+    }
+  }
+
+  /**
+   * Called when the command has been removed. This will call {@link Command#interrupted()
+   * interrupted()} or {@link Command#end() end()}.
+   */
+  synchronized void removed() {
+    if (m_initialized) {
+      if (isCanceled()) {
+        interrupted();
+        _interrupted();
+      } else {
+        end();
+        _end();
+      }
+    }
+    m_initialized = false;
+    m_canceled = false;
+    m_running = false;
+    m_completed = true;
+  }
+
+  /**
+   * The run method is used internally to actually run the commands.
+   *
+   * @return whether or not the command should stay within the {@link Scheduler}.
+   */
+  synchronized boolean run() {
+    if (!m_runWhenDisabled && m_parent == null && RobotState.isDisabled()) {
+      cancel();
+    }
+    if (isCanceled()) {
+      return false;
+    }
+    if (!m_initialized) {
+      m_initialized = true;
+      startTiming();
+      _initialize();
+      initialize();
+    }
+    _execute();
+    execute();
+    return !isFinished();
+  }
+
+  /**
+   * The initialize method is called the first time this Command is run after being started.
+   */
+  protected void initialize() {}
+
+  /**
+   * A shadow method called before {@link Command#initialize() initialize()}.
+   */
+  @SuppressWarnings("MethodName")
+  void _initialize() {
+  }
+
+  /**
+   * The execute method is called repeatedly until this Command either finishes or is canceled.
+   */
+  @SuppressWarnings("MethodName")
+  protected void execute() {}
+
+  /**
+   * A shadow method called before {@link Command#execute() execute()}.
+   */
+  @SuppressWarnings("MethodName")
+  void _execute() {
+  }
+
+  /**
+   * Returns whether this command is finished. If it is, then the command will be removed and {@link
+   * Command#end() end()} will be called.
+   *
+   * <p>It may be useful for a team to reference the {@link Command#isTimedOut() isTimedOut()}
+   * method for time-sensitive commands.
+   *
+   * <p>Returning false will result in the command never ending automatically. It may still be
+   * cancelled manually or interrupted by another command. Returning true will result in the
+   * command executing once and finishing immediately. We recommend using {@link InstantCommand}
+   * for this.
+   *
+   * @return whether this command is finished.
+   * @see Command#isTimedOut() isTimedOut()
+   */
+  protected abstract boolean isFinished();
+
+  /**
+   * Called when the command ended peacefully. This is where you may want to wrap up loose ends,
+   * like shutting off a motor that was being used in the command.
+   */
+  protected void end() {}
+
+  /**
+   * A shadow method called after {@link Command#end() end()}.
+   */
+  @SuppressWarnings("MethodName")
+  void _end() {
+  }
+
+  /**
+   * Called when the command ends because somebody called {@link Command#cancel() cancel()} or
+   * another command shared the same requirements as this one, and booted it out.
+   *
+   * <p>This is where you may want to wrap up loose ends, like shutting off a motor that was being
+   * used in the command.
+   *
+   * <p>Generally, it is useful to simply call the {@link Command#end() end()} method within this
+   * method, as done here.
+   */
+  protected void interrupted() {
+    end();
+  }
+
+  /**
+   * A shadow method called after {@link Command#interrupted() interrupted()}.
+   */
+  @SuppressWarnings("MethodName")
+  void _interrupted() {}
+
+  /**
+   * Called to indicate that the timer should start. This is called right before {@link
+   * Command#initialize() initialize()} is, inside the {@link Command#run() run()} method.
+   */
+  private void startTiming() {
+    m_startTime = Timer.getFPGATimestamp();
+  }
+
+  /**
+   * Returns whether or not the {@link Command#timeSinceInitialized() timeSinceInitialized()} method
+   * returns a number which is greater than or equal to the timeout for the command. If there is no
+   * timeout, this will always return false.
+   *
+   * @return whether the time has expired
+   */
+  protected synchronized boolean isTimedOut() {
+    return m_timeout != -1 && timeSinceInitialized() >= m_timeout;
+  }
+
+  /**
+   * Returns the requirements (as an {@link Enumeration Enumeration} of {@link Subsystem
+   * Subsystems}) of this command.
+   *
+   * @return the requirements (as an {@link Enumeration Enumeration} of {@link Subsystem
+   * Subsystems}) of this command
+   */
+  synchronized Enumeration getRequirements() {
+    return m_requirements.getElements();
+  }
+
+  /**
+   * Prevents further changes from being made.
+   */
+  synchronized void lockChanges() {
+    m_locked = true;
+  }
+
+  /**
+   * If changes are locked, then this will throw an {@link IllegalUseOfCommandException}.
+   *
+   * @param message the message to say (it is appended by a default message)
+   */
+  synchronized void validate(String message) {
+    if (m_locked) {
+      throw new IllegalUseOfCommandException(message
+          + " after being started or being added to a command group");
+    }
+  }
+
+  /**
+   * Sets the parent of this command. No actual change is made to the group.
+   *
+   * @param parent the parent
+   * @throws IllegalUseOfCommandException if this {@link Command} already is already in a group
+   */
+  synchronized void setParent(CommandGroup parent) {
+    if (m_parent != null) {
+      throw new IllegalUseOfCommandException(
+          "Can not give command to a command group after already being put in a command group");
+    }
+    lockChanges();
+    m_parent = parent;
+  }
+
+  /**
+   * Returns whether the command has a parent.
+   *
+   * @return true if the command has a parent.
+   */
+  synchronized boolean isParented() {
+    return m_parent != null;
+  }
+
+  /**
+   * Clears list of subsystem requirements. This is only used by
+   * {@link ConditionalCommand} so cancelling the chosen command works properly
+   * in {@link CommandGroup}.
+   */
+  protected void clearRequirements() {
+    m_requirements.clear();
+  }
+
+  /**
+   * Starts up the command. Gets the command ready to start. <p> Note that the command will
+   * eventually start, however it will not necessarily do so immediately, and may in fact be
+   * canceled before initialize is even called. </p>
+   *
+   * @throws IllegalUseOfCommandException if the command is a part of a CommandGroup
+   */
+  public synchronized void start() {
+    lockChanges();
+    if (m_parent != null) {
+      throw new IllegalUseOfCommandException(
+          "Can not start a command that is a part of a command group");
+    }
+    Scheduler.getInstance().add(this);
+    m_completed = false;
+  }
+
+  /**
+   * This is used internally to mark that the command has been started. The lifecycle of a command
+   * is:
+   *
+   * <p>startRunning() is called. run() is called (multiple times potentially) removed() is called.
+   *
+   * <p>It is very important that startRunning and removed be called in order or some assumptions of
+   * the code will be broken.
+   */
+  synchronized void startRunning() {
+    m_running = true;
+    m_startTime = -1;
+  }
+
+  /**
+   * Returns whether or not the command is running. This may return true even if the command has
+   * just been canceled, as it may not have yet called {@link Command#interrupted()}.
+   *
+   * @return whether or not the command is running
+   */
+  public synchronized boolean isRunning() {
+    return m_running;
+  }
+
+  /**
+   * This will cancel the current command. <p> This will cancel the current command eventually. It
+   * can be called multiple times. And it can be called when the command is not running. If the
+   * command is running though, then the command will be marked as canceled and eventually removed.
+   * </p> <p> A command can not be canceled if it is a part of a command group, you must cancel the
+   * command group instead. </p>
+   *
+   * @throws IllegalUseOfCommandException if this command is a part of a command group
+   */
+  public synchronized void cancel() {
+    if (m_parent != null) {
+      throw new IllegalUseOfCommandException("Can not manually cancel a command in a command "
+          + "group");
+    }
+    _cancel();
+  }
+
+  /**
+   * This works like cancel(), except that it doesn't throw an exception if it is a part of a
+   * command group. Should only be called by the parent command group.
+   */
+  @SuppressWarnings("MethodName")
+  synchronized void _cancel() {
+    if (isRunning()) {
+      m_canceled = true;
+    }
+  }
+
+  /**
+   * Returns whether or not this has been canceled.
+   *
+   * @return whether or not this has been canceled
+   */
+  public synchronized boolean isCanceled() {
+    return m_canceled;
+  }
+
+  /**
+   * Whether or not this command has completed running.
+   *
+   * @return whether or not this command has completed running.
+   */
+  public synchronized boolean isCompleted() {
+    return m_completed;
+  }
+
+  /**
+   * Returns whether or not this command can be interrupted.
+   *
+   * @return whether or not this command can be interrupted
+   */
+  public synchronized boolean isInterruptible() {
+    return m_interruptible;
+  }
+
+  /**
+   * Sets whether or not this command can be interrupted.
+   *
+   * @param interruptible whether or not this command can be interrupted
+   */
+  protected synchronized void setInterruptible(boolean interruptible) {
+    m_interruptible = interruptible;
+  }
+
+  /**
+   * Checks if the command requires the given {@link Subsystem}.
+   *
+   * @param system the system
+   * @return whether or not the subsystem is required, or false if given null
+   */
+  public synchronized boolean doesRequire(Subsystem system) {
+    return m_requirements.contains(system);
+  }
+
+  /**
+   * Returns the {@link CommandGroup} that this command is a part of. Will return null if this
+   * {@link Command} is not in a group.
+   *
+   * @return the {@link CommandGroup} that this command is a part of (or null if not in group)
+   */
+  public synchronized CommandGroup getGroup() {
+    return m_parent;
+  }
+
+  /**
+   * Sets whether or not this {@link Command} should run when the robot is disabled.
+   *
+   * <p>By default a command will not run when the robot is disabled, and will in fact be canceled.
+   *
+   * @param run whether or not this command should run when the robot is disabled
+   */
+  public void setRunWhenDisabled(boolean run) {
+    m_runWhenDisabled = run;
+  }
+
+  /**
+   * Returns whether or not this {@link Command} will run when the robot is disabled, or if it will
+   * cancel itself.
+   *
+   * @return True if this command will run when the robot is disabled.
+   */
+  public boolean willRunWhenDisabled() {
+    return m_runWhenDisabled;
+  }
+
+  /**
+   * The string representation for a {@link Command} is by default its name.
+   *
+   * @return the string representation of this object
+   */
+  @Override
+  public String toString() {
+    return getName();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Command");
+    builder.addStringProperty(".name", this::getName, null);
+    builder.addBooleanProperty("running", this::isRunning, value -> {
+      if (value) {
+        if (!isRunning()) {
+          start();
+        }
+      } else {
+        if (isRunning()) {
+          cancel();
+        }
+      }
+    });
+    builder.addBooleanProperty(".isParented", this::isParented, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java
new file mode 100644
index 0000000..53b62ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/CommandGroup.java
@@ -0,0 +1,422 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import java.util.Enumeration;
+import java.util.Vector;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * A {@link CommandGroup} is a list of commands which are executed in sequence.
+ *
+ * <p> Commands in a {@link CommandGroup} are added using the {@link
+ * CommandGroup#addSequential(Command) addSequential(...)} method and are called sequentially.
+ * {@link CommandGroup CommandGroups} are themselves {@link Command commands} and can be given to
+ * other {@link CommandGroup CommandGroups}. </p>
+ *
+ * <p> {@link CommandGroup CommandGroups} will carry all of the requirements of their {@link Command
+ * subcommands}. Additional requirements can be specified by calling {@link
+ * CommandGroup#requires(Subsystem) requires(...)} normally in the constructor. </P>
+ *
+ * <p> CommandGroups can also execute commands in parallel, simply by adding them using {@link
+ * CommandGroup#addParallel(Command) addParallel(...)}. </p>
+ *
+ * @see Command
+ * @see Subsystem
+ * @see IllegalUseOfCommandException
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public class CommandGroup extends Command {
+  /**
+   * The commands in this group (stored in entries).
+   */
+  @SuppressWarnings({"PMD.LooseCoupling", "PMD.UseArrayListInsteadOfVector"})
+  private final Vector<Entry> m_commands = new Vector<>();
+  /*
+   * Intentionally package private
+   */
+  /**
+   * The active children in this group (stored in entries).
+   */
+  @SuppressWarnings({"PMD.LooseCoupling", "PMD.UseArrayListInsteadOfVector"})
+  final Vector<Entry> m_children = new Vector<>();
+  /**
+   * The current command, -1 signifies that none have been run.
+   */
+  private int m_currentCommandIndex = -1;
+
+  /**
+   * Creates a new {@link CommandGroup CommandGroup}. The name of this command will be set to its
+   * class name.
+   */
+  public CommandGroup() {
+  }
+
+  /**
+   * Creates a new {@link CommandGroup CommandGroup} with the given name.
+   *
+   * @param name the name for this command group
+   * @throws IllegalArgumentException if name is null
+   */
+  public CommandGroup(String name) {
+    super(name);
+  }
+
+  /**
+   * Adds a new {@link Command Command} to the group. The {@link Command Command} will be started
+   * after all the previously added {@link Command Commands}.
+   *
+   * <p> Note that any requirements the given {@link Command Command} has will be added to the
+   * group. For this reason, a {@link Command Command's} requirements can not be changed after being
+   * added to a group. </p>
+   *
+   * <p> It is recommended that this method be called in the constructor. </p>
+   *
+   * @param command The {@link Command Command} to be added
+   * @throws IllegalUseOfCommandException if the group has been started before or been given to
+   *                                      another group
+   * @throws IllegalArgumentException     if command is null
+   */
+  public final synchronized void addSequential(Command command) {
+    validate("Can not add new command to command group");
+    if (command == null) {
+      throw new IllegalArgumentException("Given null command");
+    }
+
+    command.setParent(this);
+
+    m_commands.addElement(new Entry(command, Entry.IN_SEQUENCE));
+    for (Enumeration e = command.getRequirements(); e.hasMoreElements(); ) {
+      requires((Subsystem) e.nextElement());
+    }
+  }
+
+  /**
+   * Adds a new {@link Command Command} to the group with a given timeout. The {@link Command
+   * Command} will be started after all the previously added commands.
+   *
+   * <p> Once the {@link Command Command} is started, it will be run until it finishes or the time
+   * expires, whichever is sooner. Note that the given {@link Command Command} will have no
+   * knowledge that it is on a timer. </p>
+   *
+   * <p> Note that any requirements the given {@link Command Command} has will be added to the
+   * group. For this reason, a {@link Command Command's} requirements can not be changed after being
+   * added to a group. </p>
+   *
+   * <p> It is recommended that this method be called in the constructor. </p>
+   *
+   * @param command The {@link Command Command} to be added
+   * @param timeout The timeout (in seconds)
+   * @throws IllegalUseOfCommandException if the group has been started before or been given to
+   *                                      another group or if the {@link Command Command} has been
+   *                                      started before or been given to another group
+   * @throws IllegalArgumentException     if command is null or timeout is negative
+   */
+  public final synchronized void addSequential(Command command, double timeout) {
+    validate("Can not add new command to command group");
+    if (command == null) {
+      throw new IllegalArgumentException("Given null command");
+    }
+    if (timeout < 0) {
+      throw new IllegalArgumentException("Can not be given a negative timeout");
+    }
+
+    command.setParent(this);
+
+    m_commands.addElement(new Entry(command, Entry.IN_SEQUENCE, timeout));
+    for (Enumeration e = command.getRequirements(); e.hasMoreElements(); ) {
+      requires((Subsystem) e.nextElement());
+    }
+  }
+
+  /**
+   * Adds a new child {@link Command} to the group. The {@link Command} will be started after all
+   * the previously added {@link Command Commands}.
+   *
+   * <p> Instead of waiting for the child to finish, a {@link CommandGroup} will have it run at the
+   * same time as the subsequent {@link Command Commands}. The child will run until either it
+   * finishes, a new child with conflicting requirements is started, or the main sequence runs a
+   * {@link Command} with conflicting requirements. In the latter two cases, the child will be
+   * canceled even if it says it can't be interrupted. </p>
+   *
+   * <p> Note that any requirements the given {@link Command Command} has will be added to the
+   * group. For this reason, a {@link Command Command's} requirements can not be changed after being
+   * added to a group. </p>
+   *
+   * <p> It is recommended that this method be called in the constructor. </p>
+   *
+   * @param command The command to be added
+   * @throws IllegalUseOfCommandException if the group has been started before or been given to
+   *                                      another command group
+   * @throws IllegalArgumentException     if command is null
+   */
+  public final synchronized void addParallel(Command command) {
+    requireNonNull(command, "Provided command was null");
+    validate("Can not add new command to command group");
+
+    command.setParent(this);
+
+    m_commands.addElement(new Entry(command, Entry.BRANCH_CHILD));
+    for (Enumeration e = command.getRequirements(); e.hasMoreElements(); ) {
+      requires((Subsystem) e.nextElement());
+    }
+  }
+
+  /**
+   * Adds a new child {@link Command} to the group with the given timeout. The {@link Command} will
+   * be started after all the previously added {@link Command Commands}.
+   *
+   * <p> Once the {@link Command Command} is started, it will run until it finishes, is interrupted,
+   * or the time expires, whichever is sooner. Note that the given {@link Command Command} will have
+   * no knowledge that it is on a timer. </p>
+   *
+   * <p> Instead of waiting for the child to finish, a {@link CommandGroup} will have it run at the
+   * same time as the subsequent {@link Command Commands}. The child will run until either it
+   * finishes, the timeout expires, a new child with conflicting requirements is started, or the
+   * main sequence runs a {@link Command} with conflicting requirements. In the latter two cases,
+   * the child will be canceled even if it says it can't be interrupted. </p>
+   *
+   * <p> Note that any requirements the given {@link Command Command} has will be added to the
+   * group. For this reason, a {@link Command Command's} requirements can not be changed after being
+   * added to a group. </p>
+   *
+   * <p> It is recommended that this method be called in the constructor. </p>
+   *
+   * @param command The command to be added
+   * @param timeout The timeout (in seconds)
+   * @throws IllegalUseOfCommandException if the group has been started before or been given to
+   *                                      another command group
+   * @throws IllegalArgumentException     if command is null
+   */
+  public final synchronized void addParallel(Command command, double timeout) {
+    requireNonNull(command, "Provided command was null");
+    if (timeout < 0) {
+      throw new IllegalArgumentException("Can not be given a negative timeout");
+    }
+    validate("Can not add new command to command group");
+
+    command.setParent(this);
+
+    m_commands.addElement(new Entry(command, Entry.BRANCH_CHILD, timeout));
+    for (Enumeration e = command.getRequirements(); e.hasMoreElements(); ) {
+      requires((Subsystem) e.nextElement());
+    }
+  }
+
+  @Override
+  @SuppressWarnings("MethodName")
+  void _initialize() {
+    m_currentCommandIndex = -1;
+  }
+
+  @Override
+  @SuppressWarnings({"MethodName", "PMD.CyclomaticComplexity", "PMD.NPathComplexity"})
+  void _execute() {
+    Entry entry = null;
+    Command cmd = null;
+    boolean firstRun = false;
+    if (m_currentCommandIndex == -1) {
+      firstRun = true;
+      m_currentCommandIndex = 0;
+    }
+
+    while (m_currentCommandIndex < m_commands.size()) {
+      if (cmd != null) {
+        if (entry.isTimedOut()) {
+          cmd._cancel();
+        }
+        if (cmd.run()) {
+          break;
+        } else {
+          cmd.removed();
+          m_currentCommandIndex++;
+          firstRun = true;
+          cmd = null;
+          continue;
+        }
+      }
+
+      entry = m_commands.elementAt(m_currentCommandIndex);
+      cmd = null;
+
+      switch (entry.m_state) {
+        case Entry.IN_SEQUENCE:
+          cmd = entry.m_command;
+          if (firstRun) {
+            cmd.startRunning();
+            cancelConflicts(cmd);
+          }
+          firstRun = false;
+          break;
+        case Entry.BRANCH_PEER:
+          m_currentCommandIndex++;
+          entry.m_command.start();
+          break;
+        case Entry.BRANCH_CHILD:
+          m_currentCommandIndex++;
+          cancelConflicts(entry.m_command);
+          entry.m_command.startRunning();
+          m_children.addElement(entry);
+          break;
+        default:
+          break;
+      }
+    }
+
+    // Run Children
+    for (int i = 0; i < m_children.size(); i++) {
+      entry = m_children.elementAt(i);
+      Command child = entry.m_command;
+      if (entry.isTimedOut()) {
+        child._cancel();
+      }
+      if (!child.run()) {
+        child.removed();
+        m_children.removeElementAt(i--);
+      }
+    }
+  }
+
+  @Override
+  @SuppressWarnings("MethodName")
+  void _end() {
+    // Theoretically, we don't have to check this, but we do if teams override
+    // the isFinished method
+    if (m_currentCommandIndex != -1 && m_currentCommandIndex < m_commands.size()) {
+      Command cmd = m_commands.elementAt(m_currentCommandIndex).m_command;
+      cmd._cancel();
+      cmd.removed();
+    }
+
+    Enumeration children = m_children.elements();
+    while (children.hasMoreElements()) {
+      Command cmd = ((Entry) children.nextElement()).m_command;
+      cmd._cancel();
+      cmd.removed();
+    }
+    m_children.removeAllElements();
+  }
+
+  @Override
+  @SuppressWarnings("MethodName")
+  void _interrupted() {
+    _end();
+  }
+
+  /**
+   * Returns true if all the {@link Command Commands} in this group have been started and have
+   * finished.
+   *
+   * <p> Teams may override this method, although they should probably reference super.isFinished()
+   * if they do. </p>
+   *
+   * @return whether this {@link CommandGroup} is finished
+   */
+  @Override
+  protected boolean isFinished() {
+    return m_currentCommandIndex >= m_commands.size() && m_children.isEmpty();
+  }
+
+  // Can be overwritten by teams
+  @Override
+  protected void initialize() {
+  }
+
+  // Can be overwritten by teams
+  @Override
+  protected void execute() {
+  }
+
+  // Can be overwritten by teams
+  @Override
+  protected void end() {
+  }
+
+  // Can be overwritten by teams
+  @Override
+  protected void interrupted() {
+  }
+
+  /**
+   * Returns whether or not this group is interruptible. A command group will be uninterruptible if
+   * {@link CommandGroup#setInterruptible(boolean) setInterruptable(false)} was called or if it is
+   * currently running an uninterruptible command or child.
+   *
+   * @return whether or not this {@link CommandGroup} is interruptible.
+   */
+  @Override
+  public synchronized boolean isInterruptible() {
+    if (!super.isInterruptible()) {
+      return false;
+    }
+
+    if (m_currentCommandIndex != -1 && m_currentCommandIndex < m_commands.size()) {
+      Command cmd = m_commands.elementAt(m_currentCommandIndex).m_command;
+      if (!cmd.isInterruptible()) {
+        return false;
+      }
+    }
+
+    for (int i = 0; i < m_children.size(); i++) {
+      if (!m_children.elementAt(i).m_command.isInterruptible()) {
+        return false;
+      }
+    }
+
+    return true;
+  }
+
+  private void cancelConflicts(Command command) {
+    for (int i = 0; i < m_children.size(); i++) {
+      Command child = m_children.elementAt(i).m_command;
+
+      Enumeration requirements = command.getRequirements();
+
+      while (requirements.hasMoreElements()) {
+        Object requirement = requirements.nextElement();
+        if (child.doesRequire((Subsystem) requirement)) {
+          child._cancel();
+          child.removed();
+          m_children.removeElementAt(i--);
+          break;
+        }
+      }
+    }
+  }
+
+  private static class Entry {
+    private static final int IN_SEQUENCE = 0;
+    private static final int BRANCH_PEER = 1;
+    private static final int BRANCH_CHILD = 2;
+    private final Command m_command;
+    private final int m_state;
+    private final double m_timeout;
+
+    Entry(Command command, int state) {
+      m_command = command;
+      m_state = state;
+      m_timeout = -1;
+    }
+
+    Entry(Command command, int state, double timeout) {
+      m_command = command;
+      m_state = state;
+      m_timeout = timeout;
+    }
+
+    boolean isTimedOut() {
+      if (m_timeout == -1) {
+        return false;
+      } else {
+        double time = m_command.timeSinceInitialized();
+        return time != 0 && time >= m_timeout;
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java
new file mode 100644
index 0000000..626f744
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/ConditionalCommand.java
@@ -0,0 +1,175 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import java.util.Enumeration;
+
+/**
+ * A {@link ConditionalCommand} is a {@link Command} that starts one of two commands.
+ *
+ * <p>
+ * A {@link ConditionalCommand} uses m_condition to determine whether it should run m_onTrue or
+ * m_onFalse.
+ * </p>
+ *
+ * <p>
+ * A {@link ConditionalCommand} adds the proper {@link Command} to the {@link Scheduler} during
+ * {@link ConditionalCommand#initialize()} and then {@link ConditionalCommand#isFinished()} will
+ * return true once that {@link Command} has finished executing.
+ * </p>
+ *
+ * <p>
+ * If no {@link Command} is specified for m_onFalse, the occurrence of that condition will be a
+ * no-op.
+ * </p>
+ *
+ * @see Command
+ * @see Scheduler
+ */
+public abstract class ConditionalCommand extends Command {
+  /**
+   * The Command to execute if {@link ConditionalCommand#condition()} returns true.
+   */
+  private Command m_onTrue;
+
+  /**
+   * The Command to execute if {@link ConditionalCommand#condition()} returns false.
+   */
+  private Command m_onFalse;
+
+  /**
+   * Stores command chosen by condition.
+   */
+  private Command m_chosenCommand;
+
+  private void requireAll() {
+    if (m_onTrue != null) {
+      for (Enumeration e = m_onTrue.getRequirements(); e.hasMoreElements(); ) {
+        requires((Subsystem) e.nextElement());
+      }
+    }
+
+    if (m_onFalse != null) {
+      for (Enumeration e = m_onFalse.getRequirements(); e.hasMoreElements(); ) {
+        requires((Subsystem) e.nextElement());
+      }
+    }
+  }
+
+  /**
+   * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
+   *
+   * <p>Users of this constructor should also override condition().
+   *
+   * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
+   */
+  public ConditionalCommand(Command onTrue) {
+    this(onTrue, null);
+  }
+
+  /**
+   * Creates a new ConditionalCommand with given onTrue and onFalse Commands.
+   *
+   * <p>Users of this constructor should also override condition().
+   *
+   * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
+   * @param onFalse The Command to execute if {@link ConditionalCommand#condition()} returns false
+   */
+  public ConditionalCommand(Command onTrue, Command onFalse) {
+    m_onTrue = onTrue;
+    m_onFalse = onFalse;
+
+    requireAll();
+  }
+
+  /**
+   * Creates a new ConditionalCommand with given name and onTrue and onFalse Commands.
+   *
+   * <p>Users of this constructor should also override condition().
+   *
+   * @param name the name for this command group
+   * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
+   */
+  public ConditionalCommand(String name, Command onTrue) {
+    this(name, onTrue, null);
+  }
+
+  /**
+   * Creates a new ConditionalCommand with given name and onTrue and onFalse Commands.
+   *
+   * <p>Users of this constructor should also override condition().
+   *
+   * @param name the name for this command group
+   * @param onTrue The Command to execute if {@link ConditionalCommand#condition()} returns true
+   * @param onFalse The Command to execute if {@link ConditionalCommand#condition()} returns false
+   */
+  public ConditionalCommand(String name, Command onTrue, Command onFalse) {
+    super(name);
+    m_onTrue = onTrue;
+    m_onFalse = onFalse;
+
+    requireAll();
+  }
+
+  /**
+   * The Condition to test to determine which Command to run.
+   *
+   * @return true if m_onTrue should be run or false if m_onFalse should be run.
+   */
+  protected abstract boolean condition();
+
+  /**
+   * Calls {@link ConditionalCommand#condition()} and runs the proper command.
+   */
+  @Override
+  protected void _initialize() {
+    if (condition()) {
+      m_chosenCommand = m_onTrue;
+    } else {
+      m_chosenCommand = m_onFalse;
+    }
+
+    if (m_chosenCommand != null) {
+      /*
+       * This is a hack to make cancelling the chosen command inside a
+       * CommandGroup work properly
+       */
+      m_chosenCommand.clearRequirements();
+
+      m_chosenCommand.start();
+    }
+    super._initialize();
+  }
+
+  @Override
+  protected synchronized void _cancel() {
+    if (m_chosenCommand != null && m_chosenCommand.isRunning()) {
+      m_chosenCommand.cancel();
+    }
+
+    super._cancel();
+  }
+
+  @Override
+  protected boolean isFinished() {
+    if (m_chosenCommand != null) {
+      return m_chosenCommand.isCompleted();
+    } else {
+      return true;
+    }
+  }
+
+  @Override
+  protected void _interrupted() {
+    if (m_chosenCommand != null && m_chosenCommand.isRunning()) {
+      m_chosenCommand.cancel();
+    }
+
+    super._interrupted();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java
new file mode 100644
index 0000000..59f6e9c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/IllegalUseOfCommandException.java
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * This exception will be thrown if a command is used illegally. There are several ways for this to
+ * happen.
+ *
+ * <p> Basically, a command becomes "locked" after it is first started or added to a command group.
+ * </p>
+ *
+ * <p> This exception should be thrown if (after a command has been locked) its requirements change,
+ * it is put into multiple command groups, it is started from outside its command group, or it adds
+ * a new child. </p>
+ */
+public class IllegalUseOfCommandException extends RuntimeException {
+  /**
+   * Instantiates an {@link IllegalUseOfCommandException}.
+   */
+  public IllegalUseOfCommandException() {
+  }
+
+  /**
+   * Instantiates an {@link IllegalUseOfCommandException} with the given message.
+   *
+   * @param message the message
+   */
+  public IllegalUseOfCommandException(String message) {
+    super(message);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java
new file mode 100644
index 0000000..1f3c5de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/InstantCommand.java
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * This command will execute once, then finish immediately afterward.
+ *
+ * <p>Subclassing {@link InstantCommand} is shorthand for returning true from
+ * {@link Command isFinished}.
+ */
+public class InstantCommand extends Command {
+  private Runnable m_func;
+
+  public InstantCommand() {
+  }
+
+  /**
+   * Creates a new {@link InstantCommand InstantCommand} with the given name.
+   *
+   * @param name the name for this command
+   */
+  public InstantCommand(String name) {
+    super(name);
+  }
+
+  /**
+   * Creates a new {@link InstantCommand InstantCommand} with the given requirement.
+   *
+   * @param subsystem the subsystem this command requires
+   */
+  public InstantCommand(Subsystem subsystem) {
+    super(subsystem);
+  }
+
+  /**
+   * Creates a new {@link InstantCommand InstantCommand} with the given name and requirement.
+   *
+   * @param name      the name for this command
+   * @param subsystem the subsystem this command requires
+   */
+  public InstantCommand(String name, Subsystem subsystem) {
+    super(name, subsystem);
+  }
+
+  /**
+   * Creates a new {@link InstantCommand InstantCommand}.
+   *
+   * @param func the function to run when {@link Command#initialize() initialize()} is run
+   */
+  public InstantCommand(Runnable func) {
+    m_func = func;
+  }
+
+  /**
+   * Creates a new {@link InstantCommand InstantCommand}.
+   *
+   * @param name the name for this command
+   * @param func the function to run when {@link Command#initialize() initialize()} is run
+   */
+  public InstantCommand(String name, Runnable func) {
+    super(name);
+    m_func = func;
+  }
+
+  /**
+   * Creates a new {@link InstantCommand InstantCommand}.
+   *
+   * @param requirement the subsystem this command requires
+   * @param func        the function to run when {@link Command#initialize() initialize()} is run
+   */
+  public InstantCommand(Subsystem requirement, Runnable func) {
+    super(requirement);
+    m_func = func;
+  }
+
+  /**
+   * Creates a new {@link InstantCommand InstantCommand}.
+   *
+   * @param name        the name for this command
+   * @param requirement the subsystem this command requires
+   * @param func        the function to run when {@link Command#initialize() initialize()} is run
+   */
+  public InstantCommand(String name, Subsystem requirement, Runnable func) {
+    super(name, requirement);
+    m_func = func;
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return true;
+  }
+
+  /**
+   * Trigger the stored function.
+   *
+   * <p>Called just before this Command runs the first time.
+   */
+  @Override
+  protected void _initialize() {
+    super._initialize();
+    if (m_func != null) {
+      m_func.run();
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java
new file mode 100644
index 0000000..e717a47
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/LinkedListElement.java
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * An element that is in a LinkedList.
+ */
+class LinkedListElement {
+  private LinkedListElement m_next;
+  private LinkedListElement m_previous;
+  private Command m_data;
+
+  public void setData(Command newData) {
+    m_data = newData;
+  }
+
+  public Command getData() {
+    return m_data;
+  }
+
+  public LinkedListElement getNext() {
+    return m_next;
+  }
+
+  public LinkedListElement getPrevious() {
+    return m_previous;
+  }
+
+  public void add(LinkedListElement listElement) {
+    if (m_next == null) {
+      m_next = listElement;
+      m_next.m_previous = this;
+    } else {
+      m_next.m_previous = listElement;
+      listElement.m_next = m_next;
+      listElement.m_previous = this;
+      m_next = listElement;
+    }
+  }
+
+  @SuppressWarnings("PMD.EmptyIfStmt")
+  public LinkedListElement remove() {
+    if (m_previous == null && m_next == null) {
+      // no-op
+    } else if (m_next == null) {
+      m_previous.m_next = null;
+    } else if (m_previous == null) {
+      m_next.m_previous = null;
+    } else {
+      m_next.m_previous = m_previous;
+      m_previous.m_next = m_next;
+    }
+    LinkedListElement returnNext = m_next;
+    m_next = null;
+    m_previous = null;
+    return returnNext;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java
new file mode 100644
index 0000000..3d7fd98
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PIDCommand.java
@@ -0,0 +1,284 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import edu.wpi.first.wpilibj.PIDController;
+import edu.wpi.first.wpilibj.PIDOutput;
+import edu.wpi.first.wpilibj.PIDSource;
+import edu.wpi.first.wpilibj.PIDSourceType;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * This class defines a {@link Command} which interacts heavily with a PID loop.
+ *
+ * <p> It provides some convenience methods to run an internal {@link PIDController} . It will also
+ * start and stop said {@link PIDController} when the {@link PIDCommand} is first initialized and
+ * ended/interrupted. </p>
+ */
+public abstract class PIDCommand extends Command {
+  /**
+   * The internal {@link PIDController}.
+   */
+  private final PIDController m_controller;
+  /**
+   * An output which calls {@link PIDCommand#usePIDOutput(double)}.
+   */
+  private final PIDOutput m_output = this::usePIDOutput;
+  /**
+   * A source which calls {@link PIDCommand#returnPIDInput()}.
+   */
+  private final PIDSource m_source = new PIDSource() {
+    @Override
+    public void setPIDSourceType(PIDSourceType pidSource) {
+    }
+
+    @Override
+    public PIDSourceType getPIDSourceType() {
+      return PIDSourceType.kDisplacement;
+    }
+
+    @Override
+    public double pidGet() {
+      return returnPIDInput();
+    }
+  };
+
+  /**
+   * Instantiates a {@link PIDCommand} that will use the given p, i and d values.
+   *
+   * @param name the name of the command
+   * @param p    the proportional value
+   * @param i    the integral value
+   * @param d    the derivative value
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDCommand(String name, double p, double i, double d) {
+    super(name);
+    m_controller = new PIDController(p, i, d, m_source, m_output);
+  }
+
+  /**
+   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will also space
+   * the time between PID loop calculations to be equal to the given period.
+   *
+   * @param name   the name
+   * @param p      the proportional value
+   * @param i      the integral value
+   * @param d      the derivative value
+   * @param period the time (in seconds) between calculations
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDCommand(String name, double p, double i, double d, double period) {
+    super(name);
+    m_controller = new PIDController(p, i, d, m_source, m_output, period);
+  }
+
+  /**
+   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
+   * class name as its name.
+   *
+   * @param p the proportional value
+   * @param i the integral value
+   * @param d the derivative value
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDCommand(double p, double i, double d) {
+    m_controller = new PIDController(p, i, d, m_source, m_output);
+  }
+
+  /**
+   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
+   * class name as its name. It will also space the time between PID loop calculations to be equal
+   * to the given period.
+   *
+   * @param p      the proportional value
+   * @param i      the integral value
+   * @param d      the derivative value
+   * @param period the time (in seconds) between calculations
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDCommand(double p, double i, double d, double period) {
+    m_controller = new PIDController(p, i, d, m_source, m_output, period);
+  }
+
+  /**
+   * Instantiates a {@link PIDCommand} that will use the given p, i and d values.
+   *
+   * @param name      the name of the command
+   * @param p         the proportional value
+   * @param i         the integral value
+   * @param d         the derivative value
+   * @param subsystem the subsystem that this command requires
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDCommand(String name, double p, double i, double d, Subsystem subsystem) {
+    super(name, subsystem);
+    m_controller = new PIDController(p, i, d, m_source, m_output);
+  }
+
+  /**
+   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will also space
+   * the time between PID loop calculations to be equal to the given period.
+   *
+   * @param name      the name
+   * @param p         the proportional value
+   * @param i         the integral value
+   * @param d         the derivative value
+   * @param period    the time (in seconds) between calculations
+   * @param subsystem the subsystem that this command requires
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDCommand(String name, double p, double i, double d, double period,
+                    Subsystem subsystem) {
+    super(name, subsystem);
+    m_controller = new PIDController(p, i, d, m_source, m_output, period);
+  }
+
+  /**
+   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
+   * class name as its name.
+   *
+   * @param p         the proportional value
+   * @param i         the integral value
+   * @param d         the derivative value
+   * @param subsystem the subsystem that this command requires
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDCommand(double p, double i, double d, Subsystem subsystem) {
+    super(subsystem);
+    m_controller = new PIDController(p, i, d, m_source, m_output);
+  }
+
+  /**
+   * Instantiates a {@link PIDCommand} that will use the given p, i and d values. It will use the
+   * class name as its name. It will also space the time between PID loop calculations to be equal
+   * to the given period.
+   *
+   * @param p         the proportional value
+   * @param i         the integral value
+   * @param d         the derivative value
+   * @param period    the time (in seconds) between calculations
+   * @param subsystem the subsystem that this command requires
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDCommand(double p, double i, double d, double period, Subsystem subsystem) {
+    super(subsystem);
+    m_controller = new PIDController(p, i, d, m_source, m_output, period);
+  }
+
+  /**
+   * Returns the {@link PIDController} used by this {@link PIDCommand}. Use this if you would like
+   * to fine tune the pid loop.
+   *
+   * @return the {@link PIDController} used by this {@link PIDCommand}
+   */
+  protected PIDController getPIDController() {
+    return m_controller;
+  }
+
+  @Override
+  @SuppressWarnings("MethodName")
+  void _initialize() {
+    m_controller.enable();
+  }
+
+  @Override
+  @SuppressWarnings("MethodName")
+  void _end() {
+    m_controller.disable();
+  }
+
+  @Override
+  @SuppressWarnings("MethodName")
+  void _interrupted() {
+    _end();
+  }
+
+  /**
+   * Adds the given value to the setpoint. If {@link PIDCommand#setInputRange(double, double)
+   * setInputRange(...)} was used, then the bounds will still be honored by this method.
+   *
+   * @param deltaSetpoint the change in the setpoint
+   */
+  public void setSetpointRelative(double deltaSetpoint) {
+    setSetpoint(getSetpoint() + deltaSetpoint);
+  }
+
+  /**
+   * Sets the setpoint to the given value. If {@link PIDCommand#setInputRange(double, double)
+   * setInputRange(...)} was called, then the given setpoint will be trimmed to fit within the
+   * range.
+   *
+   * @param setpoint the new setpoint
+   */
+  protected void setSetpoint(double setpoint) {
+    m_controller.setSetpoint(setpoint);
+  }
+
+  /**
+   * Returns the setpoint.
+   *
+   * @return the setpoint
+   */
+  protected double getSetpoint() {
+    return m_controller.getSetpoint();
+  }
+
+  /**
+   * Returns the current position.
+   *
+   * @return the current position
+   */
+  protected double getPosition() {
+    return returnPIDInput();
+  }
+
+  /**
+   * Sets the maximum and minimum values expected from the input and setpoint.
+   *
+   * @param minimumInput the minimum value expected from the input and setpoint
+   * @param maximumInput the maximum value expected from the input and setpoint
+   */
+  protected void setInputRange(double minimumInput, double maximumInput) {
+    m_controller.setInputRange(minimumInput, maximumInput);
+  }
+
+  /**
+   * Returns the input for the pid loop.
+   *
+   * <p>It returns the input for the pid loop, so if this command was based off of a gyro, then it
+   * should return the angle of the gyro.
+   *
+   * <p>All subclasses of {@link PIDCommand} must override this method.
+   *
+   * <p>This method will be called in a different thread then the {@link Scheduler} thread.
+   *
+   * @return the value the pid loop should use as input
+   */
+  protected abstract double returnPIDInput();
+
+  /**
+   * Uses the value that the pid loop calculated. The calculated value is the "output" parameter.
+   * This method is a good time to set motor values, maybe something along the lines of
+   * <code>driveline.tankDrive(output, -output)</code>
+   *
+   * <p>All subclasses of {@link PIDCommand} must override this method.
+   *
+   * <p>This method will be called in a different thread then the {@link Scheduler} thread.
+   *
+   * @param output the value the pid loop calculated
+   */
+  protected abstract void usePIDOutput(double output);
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    m_controller.initSendable(builder);
+    super.initSendable(builder);
+    builder.setSmartDashboardType("PIDCommand");
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java
new file mode 100644
index 0000000..6465eb1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PIDSubsystem.java
@@ -0,0 +1,287 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import edu.wpi.first.wpilibj.PIDController;
+import edu.wpi.first.wpilibj.PIDOutput;
+import edu.wpi.first.wpilibj.PIDSource;
+import edu.wpi.first.wpilibj.PIDSourceType;
+
+/**
+ * This class is designed to handle the case where there is a {@link Subsystem} which uses a single
+ * {@link PIDController} almost constantly (for instance, an elevator which attempts to stay at a
+ * constant height).
+ *
+ * <p>It provides some convenience methods to run an internal {@link PIDController} . It also
+ * allows access to the internal {@link PIDController} in order to give total control to the
+ * programmer.
+ */
+public abstract class PIDSubsystem extends Subsystem {
+  /**
+   * The internal {@link PIDController}.
+   */
+  private final PIDController m_controller;
+  /**
+   * An output which calls {@link PIDCommand#usePIDOutput(double)}.
+   */
+  private final PIDOutput m_output = this::usePIDOutput;
+
+  /**
+   * A source which calls {@link PIDCommand#returnPIDInput()}.
+   */
+  private final PIDSource m_source = new PIDSource() {
+    @Override
+    public void setPIDSourceType(PIDSourceType pidSource) {
+    }
+
+    @Override
+    public PIDSourceType getPIDSourceType() {
+      return PIDSourceType.kDisplacement;
+    }
+
+    @Override
+    public double pidGet() {
+      return returnPIDInput();
+    }
+  };
+
+  /**
+   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values.
+   *
+   * @param name the name
+   * @param p    the proportional value
+   * @param i    the integral value
+   * @param d    the derivative value
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDSubsystem(String name, double p, double i, double d) {
+    super(name);
+    m_controller = new PIDController(p, i, d, m_source, m_output);
+    addChild("PIDController", m_controller);
+  }
+
+  /**
+   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values.
+   *
+   * @param name the name
+   * @param p    the proportional value
+   * @param i    the integral value
+   * @param d    the derivative value
+   * @param f    the feed forward value
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDSubsystem(String name, double p, double i, double d, double f) {
+    super(name);
+    m_controller = new PIDController(p, i, d, f, m_source, m_output);
+    addChild("PIDController", m_controller);
+  }
+
+  /**
+   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will also
+   * space the time between PID loop calculations to be equal to the given period.
+   *
+   * @param name   the name
+   * @param p      the proportional value
+   * @param i      the integral value
+   * @param d      the derivative value
+   * @param f      the feed forward value
+   * @param period the time (in seconds) between calculations
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDSubsystem(String name, double p, double i, double d, double f, double period) {
+    super(name);
+    m_controller = new PIDController(p, i, d, f, m_source, m_output, period);
+    addChild("PIDController", m_controller);
+  }
+
+  /**
+   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the
+   * class name as its name.
+   *
+   * @param p the proportional value
+   * @param i the integral value
+   * @param d the derivative value
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDSubsystem(double p, double i, double d) {
+    m_controller = new PIDController(p, i, d, m_source, m_output);
+    addChild("PIDController", m_controller);
+  }
+
+  /**
+   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the
+   * class name as its name. It will also space the time between PID loop calculations to be equal
+   * to the given period.
+   *
+   * @param p      the proportional value
+   * @param i      the integral value
+   * @param d      the derivative value
+   * @param f      the feed forward coefficient
+   * @param period the time (in seconds) between calculations
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDSubsystem(double p, double i, double d, double f, double period) {
+    m_controller = new PIDController(p, i, d, f, m_source, m_output, period);
+    addChild("PIDController", m_controller);
+  }
+
+  /**
+   * Instantiates a {@link PIDSubsystem} that will use the given p, i and d values. It will use the
+   * class name as its name. It will also space the time between PID loop calculations to be equal
+   * to the given period.
+   *
+   * @param p      the proportional value
+   * @param i      the integral value
+   * @param d      the derivative value
+   * @param period the time (in seconds) between calculations
+   */
+  @SuppressWarnings("ParameterName")
+  public PIDSubsystem(double p, double i, double d, double period) {
+    m_controller = new PIDController(p, i, d, m_source, m_output, period);
+    addChild("PIDController", m_controller);
+  }
+
+  /**
+   * Returns the {@link PIDController} used by this {@link PIDSubsystem}. Use this if you would like
+   * to fine tune the pid loop.
+   *
+   * @return the {@link PIDController} used by this {@link PIDSubsystem}
+   */
+  public PIDController getPIDController() {
+    return m_controller;
+  }
+
+
+  /**
+   * Adds the given value to the setpoint. If {@link PIDSubsystem#setInputRange(double, double)
+   * setInputRange(...)} was used, then the bounds will still be honored by this method.
+   *
+   * @param deltaSetpoint the change in the setpoint
+   */
+  public void setSetpointRelative(double deltaSetpoint) {
+    setSetpoint(getPosition() + deltaSetpoint);
+  }
+
+  /**
+   * Sets the setpoint to the given value. If {@link PIDSubsystem#setInputRange(double, double)
+   * setInputRange(...)} was called, then the given setpoint will be trimmed to fit within the
+   * range.
+   *
+   * @param setpoint the new setpoint
+   */
+  public void setSetpoint(double setpoint) {
+    m_controller.setSetpoint(setpoint);
+  }
+
+  /**
+   * Returns the setpoint.
+   *
+   * @return the setpoint
+   */
+  public double getSetpoint() {
+    return m_controller.getSetpoint();
+  }
+
+  /**
+   * Returns the current position.
+   *
+   * @return the current position
+   */
+  public double getPosition() {
+    return returnPIDInput();
+  }
+
+  /**
+   * Sets the maximum and minimum values expected from the input.
+   *
+   * @param minimumInput the minimum value expected from the input
+   * @param maximumInput the maximum value expected from the output
+   */
+  public void setInputRange(double minimumInput, double maximumInput) {
+    m_controller.setInputRange(minimumInput, maximumInput);
+  }
+
+  /**
+   * Sets the maximum and minimum values to write.
+   *
+   * @param minimumOutput the minimum value to write to the output
+   * @param maximumOutput the maximum value to write to the output
+   */
+  public void setOutputRange(double minimumOutput, double maximumOutput) {
+    m_controller.setOutputRange(minimumOutput, maximumOutput);
+  }
+
+  /**
+   * Set the absolute error which is considered tolerable for use with OnTarget. The value is in the
+   * same range as the PIDInput values.
+   *
+   * @param t the absolute tolerance
+   */
+  @SuppressWarnings("ParameterName")
+  public void setAbsoluteTolerance(double t) {
+    m_controller.setAbsoluteTolerance(t);
+  }
+
+  /**
+   * Set the percentage error which is considered tolerable for use with OnTarget. (Value of 15.0 ==
+   * 15 percent).
+   *
+   * @param p the percent tolerance
+   */
+  @SuppressWarnings("ParameterName")
+  public void setPercentTolerance(double p) {
+    m_controller.setPercentTolerance(p);
+  }
+
+  /**
+   * Return true if the error is within the percentage of the total input range, determined by
+   * setTolerance. This assumes that the maximum and minimum input were set using setInput.
+   *
+   * @return true if the error is less than the tolerance
+   */
+  public boolean onTarget() {
+    return m_controller.onTarget();
+  }
+
+  /**
+   * Returns the input for the pid loop.
+   *
+   * <p>It returns the input for the pid loop, so if this Subsystem was based off of a gyro, then
+   * it should return the angle of the gyro.
+   *
+   * <p>All subclasses of {@link PIDSubsystem} must override this method.
+   *
+   * @return the value the pid loop should use as input
+   */
+  protected abstract double returnPIDInput();
+
+  /**
+   * Uses the value that the pid loop calculated. The calculated value is the "output" parameter.
+   * This method is a good time to set motor values, maybe something along the lines of
+   * <code>driveline.tankDrive(output, -output)</code>.
+   *
+   * <p>All subclasses of {@link PIDSubsystem} must override this method.
+   *
+   * @param output the value the pid loop calculated
+   */
+  protected abstract void usePIDOutput(double output);
+
+  /**
+   * Enables the internal {@link PIDController}.
+   */
+  public void enable() {
+    m_controller.enable();
+  }
+
+  /**
+   * Disables the internal {@link PIDController}.
+   */
+  public void disable() {
+    m_controller.disable();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java
new file mode 100644
index 0000000..6199c6d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/PrintCommand.java
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * A {@link PrintCommand} is a command which prints out a string when it is initialized, and then
+ * immediately finishes. It is useful if you want a {@link CommandGroup} to print out a string when
+ * it reaches a certain point.
+ */
+public class PrintCommand extends InstantCommand {
+  /**
+   * The message to print out.
+   */
+  private final String m_message;
+
+  /**
+   * Instantiates a {@link PrintCommand} which will print the given message when it is run.
+   *
+   * @param message the message to print
+   */
+  public PrintCommand(String message) {
+    super("Print(\"" + message + "\"");
+    m_message = message;
+  }
+
+  @Override
+  protected void initialize() {
+    System.out.println(m_message);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java
new file mode 100644
index 0000000..8302e22
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Scheduler.java
@@ -0,0 +1,353 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import java.util.Enumeration;
+import java.util.Hashtable;
+import java.util.Vector;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.wpilibj.SendableBase;
+import edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * The {@link Scheduler} is a singleton which holds the top-level running commands. It is in charge
+ * of both calling the command's {@link Command#run() run()} method and to make sure that there are
+ * no two commands with conflicting requirements running.
+ *
+ * <p> It is fine if teams wish to take control of the {@link Scheduler} themselves, all that needs
+ * to be done is to call {@link Scheduler#getInstance() Scheduler.getInstance()}.{@link
+ * Scheduler#run() run()} often to have {@link Command Commands} function correctly. However, this
+ * is already done for you if you use the CommandBased Robot template. </p>
+ *
+ * @see Command
+ */
+public final class Scheduler extends SendableBase {
+  /**
+   * The Singleton Instance.
+   */
+  private static Scheduler instance;
+
+  /**
+   * Returns the {@link Scheduler}, creating it if one does not exist.
+   *
+   * @return the {@link Scheduler}
+   */
+  public static synchronized Scheduler getInstance() {
+    if (instance == null) {
+      instance = new Scheduler();
+    }
+    return instance;
+  }
+
+  /**
+   * A hashtable of active {@link Command Commands} to their {@link LinkedListElement}.
+   */
+  @SuppressWarnings("PMD.LooseCoupling")
+  private final Hashtable<Command, LinkedListElement> m_commandTable = new Hashtable<>();
+  /**
+   * The {@link Set} of all {@link Subsystem Subsystems}.
+   */
+  private final Set m_subsystems = new Set();
+  /**
+   * The first {@link Command} in the list.
+   */
+  private LinkedListElement m_firstCommand;
+  /**
+   * The last {@link Command} in the list.
+   */
+  private LinkedListElement m_lastCommand;
+  /**
+   * Whether or not we are currently adding a command.
+   */
+  private boolean m_adding;
+  /**
+   * Whether or not we are currently disabled.
+   */
+  private boolean m_disabled;
+  /**
+   * A list of all {@link Command Commands} which need to be added.
+   */
+  @SuppressWarnings({"PMD.LooseCoupling", "PMD.UseArrayListInsteadOfVector"})
+  private final Vector<Command> m_additions = new Vector<>();
+  private NetworkTableEntry m_namesEntry;
+  private NetworkTableEntry m_idsEntry;
+  private NetworkTableEntry m_cancelEntry;
+  /**
+   * A list of all {@link edu.wpi.first.wpilibj.buttons.Trigger.ButtonScheduler Buttons}. It is
+   * created lazily.
+   */
+  @SuppressWarnings("PMD.LooseCoupling")
+  private Vector<ButtonScheduler> m_buttons;
+  private boolean m_runningCommandsChanged;
+
+  /**
+   * Instantiates a {@link Scheduler}.
+   */
+  private Scheduler() {
+    HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand_Scheduler);
+    setName("Scheduler");
+  }
+
+  /**
+   * Adds the command to the {@link Scheduler}. This will not add the {@link Command} immediately,
+   * but will instead wait for the proper time in the {@link Scheduler#run()} loop before doing so.
+   * The command returns immediately and does nothing if given null.
+   *
+   * <p> Adding a {@link Command} to the {@link Scheduler} involves the {@link Scheduler} removing
+   * any {@link Command} which has shared requirements. </p>
+   *
+   * @param command the command to add
+   */
+  public void add(Command command) {
+    if (command != null) {
+      m_additions.addElement(command);
+    }
+  }
+
+  /**
+   * Adds a button to the {@link Scheduler}. The {@link Scheduler} will poll the button during its
+   * {@link Scheduler#run()}.
+   *
+   * @param button the button to add
+   */
+  @SuppressWarnings("PMD.UseArrayListInsteadOfVector")
+  public void addButton(ButtonScheduler button) {
+    if (m_buttons == null) {
+      m_buttons = new Vector<>();
+    }
+    m_buttons.addElement(button);
+  }
+
+  /**
+   * Adds a command immediately to the {@link Scheduler}. This should only be called in the {@link
+   * Scheduler#run()} loop. Any command with conflicting requirements will be removed, unless it is
+   * uninterruptable. Giving <code>null</code> does nothing.
+   *
+   * @param command the {@link Command} to add
+   */
+  @SuppressWarnings({"MethodName", "PMD.CyclomaticComplexity"})
+  private void _add(Command command) {
+    if (command == null) {
+      return;
+    }
+
+    // Check to make sure no adding during adding
+    if (m_adding) {
+      System.err.println("WARNING: Can not start command from cancel method.  Ignoring:" + command);
+      return;
+    }
+
+    // Only add if not already in
+    if (!m_commandTable.containsKey(command)) {
+      // Check that the requirements can be had
+      Enumeration requirements = command.getRequirements();
+      while (requirements.hasMoreElements()) {
+        Subsystem lock = (Subsystem) requirements.nextElement();
+        if (lock.getCurrentCommand() != null && !lock.getCurrentCommand().isInterruptible()) {
+          return;
+        }
+      }
+
+      // Give it the requirements
+      m_adding = true;
+      requirements = command.getRequirements();
+      while (requirements.hasMoreElements()) {
+        Subsystem lock = (Subsystem) requirements.nextElement();
+        if (lock.getCurrentCommand() != null) {
+          lock.getCurrentCommand().cancel();
+          remove(lock.getCurrentCommand());
+        }
+        lock.setCurrentCommand(command);
+      }
+      m_adding = false;
+
+      // Add it to the list
+      LinkedListElement element = new LinkedListElement();
+      element.setData(command);
+      if (m_firstCommand == null) {
+        m_firstCommand = m_lastCommand = element;
+      } else {
+        m_lastCommand.add(element);
+        m_lastCommand = element;
+      }
+      m_commandTable.put(command, element);
+
+      m_runningCommandsChanged = true;
+
+      command.startRunning();
+    }
+  }
+
+  /**
+   * Runs a single iteration of the loop. This method should be called often in order to have a
+   * functioning {@link Command} system. The loop has five stages:
+   *
+   * <ol> <li>Poll the Buttons</li> <li>Execute/Remove the Commands</li> <li>Send values to
+   * SmartDashboard</li> <li>Add Commands</li> <li>Add Defaults</li> </ol>
+   */
+  @SuppressWarnings({"PMD.CyclomaticComplexity", "PMD.NPathComplexity"})
+  public void run() {
+    m_runningCommandsChanged = false;
+
+    if (m_disabled) {
+      return;
+    } // Don't run when m_disabled
+
+    // Get button input (going backwards preserves button priority)
+    if (m_buttons != null) {
+      for (int i = m_buttons.size() - 1; i >= 0; i--) {
+        m_buttons.elementAt(i).execute();
+      }
+    }
+
+    // Call every subsystem's periodic method
+    Enumeration subsystems = m_subsystems.getElements();
+    while (subsystems.hasMoreElements()) {
+      ((Subsystem) subsystems.nextElement()).periodic();
+    }
+
+    // Loop through the commands
+    LinkedListElement element = m_firstCommand;
+    while (element != null) {
+      Command command = element.getData();
+      element = element.getNext();
+      if (!command.run()) {
+        remove(command);
+        m_runningCommandsChanged = true;
+      }
+    }
+
+    // Add the new things
+    for (int i = 0; i < m_additions.size(); i++) {
+      _add(m_additions.elementAt(i));
+    }
+    m_additions.removeAllElements();
+
+    // Add in the defaults
+    Enumeration locks = m_subsystems.getElements();
+    while (locks.hasMoreElements()) {
+      Subsystem lock = (Subsystem) locks.nextElement();
+      if (lock.getCurrentCommand() == null) {
+        _add(lock.getDefaultCommand());
+      }
+      lock.confirmCommand();
+    }
+  }
+
+  /**
+   * Registers a {@link Subsystem} to this {@link Scheduler}, so that the {@link Scheduler} might
+   * know if a default {@link Command} needs to be run. All {@link Subsystem Subsystems} should call
+   * this.
+   *
+   * @param system the system
+   */
+  void registerSubsystem(Subsystem system) {
+    if (system != null) {
+      m_subsystems.add(system);
+    }
+  }
+
+  /**
+   * Removes the {@link Command} from the {@link Scheduler}.
+   *
+   * @param command the command to remove
+   */
+  void remove(Command command) {
+    if (command == null || !m_commandTable.containsKey(command)) {
+      return;
+    }
+    LinkedListElement element = m_commandTable.get(command);
+    m_commandTable.remove(command);
+
+    if (element.equals(m_lastCommand)) {
+      m_lastCommand = element.getPrevious();
+    }
+    if (element.equals(m_firstCommand)) {
+      m_firstCommand = element.getNext();
+    }
+    element.remove();
+
+    Enumeration requirements = command.getRequirements();
+    while (requirements.hasMoreElements()) {
+      ((Subsystem) requirements.nextElement()).setCurrentCommand(null);
+    }
+
+    command.removed();
+  }
+
+  /**
+   * Removes all commands.
+   */
+  public void removeAll() {
+    // TODO: Confirm that this works with "uninteruptible" commands
+    while (m_firstCommand != null) {
+      remove(m_firstCommand.getData());
+    }
+  }
+
+  /**
+   * Disable the command scheduler.
+   */
+  public void disable() {
+    m_disabled = true;
+  }
+
+  /**
+   * Enable the command scheduler.
+   */
+  public void enable() {
+    m_disabled = false;
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Scheduler");
+    m_namesEntry = builder.getEntry("Names");
+    m_idsEntry = builder.getEntry("Ids");
+    m_cancelEntry = builder.getEntry("Cancel");
+    builder.setUpdateTable(() -> {
+      if (m_namesEntry != null && m_idsEntry != null && m_cancelEntry != null) {
+        // Get the commands to cancel
+        double[] toCancel = m_cancelEntry.getDoubleArray(new double[0]);
+        if (toCancel.length > 0) {
+          for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
+            for (double d : toCancel) {
+              if (e.getData().hashCode() == d) {
+                e.getData().cancel();
+              }
+            }
+          }
+          m_cancelEntry.setDoubleArray(new double[0]);
+        }
+
+        if (m_runningCommandsChanged) {
+          // Set the the running commands
+          int number = 0;
+          for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
+            number++;
+          }
+          String[] commands = new String[number];
+          double[] ids = new double[number];
+          number = 0;
+          for (LinkedListElement e = m_firstCommand; e != null; e = e.getNext()) {
+            commands[number] = e.getData().getName();
+            ids[number] = e.getData().hashCode();
+            number++;
+          }
+          m_namesEntry.setStringArray(commands);
+          m_idsEntry.setDoubleArray(ids);
+        }
+      }
+    });
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Set.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Set.java
new file mode 100644
index 0000000..4b05467
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Set.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import java.util.Enumeration;
+import java.util.Vector;
+
+@SuppressWarnings("all")
+/**
+ * A set.
+ */
+class Set {
+  private Vector m_set = new Vector();
+
+  public Set() {
+  }
+
+  public void add(Object o) {
+    if (m_set.contains(o)) {
+      return;
+    }
+    m_set.addElement(o);
+  }
+
+  public void add(Set s) {
+    Enumeration stuff = s.getElements();
+    for (Enumeration e = stuff; e.hasMoreElements(); ) {
+      add(e.nextElement());
+    }
+  }
+
+  public void clear() {
+      m_set.clear();
+  }
+
+  public boolean contains(Object o) {
+    return m_set.contains(o);
+  }
+
+  public Enumeration getElements() {
+    return m_set.elements();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java
new file mode 100644
index 0000000..6dd7db8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/StartCommand.java
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * A {@link StartCommand} will call the {@link Command#start() start()} method of another command
+ * when it is initialized and will finish immediately.
+ */
+public class StartCommand extends InstantCommand {
+  /**
+   * The command to fork.
+   */
+  private final Command m_commandToFork;
+
+  /**
+   * Instantiates a {@link StartCommand} which will start the given command whenever its {@link
+   * Command#initialize() initialize()} is called.
+   *
+   * @param commandToStart the {@link Command} to start
+   */
+  public StartCommand(Command commandToStart) {
+    super("Start(" + commandToStart + ")");
+    m_commandToFork = commandToStart;
+  }
+
+  @Override
+  protected void initialize() {
+    m_commandToFork.start();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java
new file mode 100644
index 0000000..0da80c2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/Subsystem.java
@@ -0,0 +1,210 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import java.util.Collections;
+
+import edu.wpi.first.wpilibj.Sendable;
+import edu.wpi.first.wpilibj.SendableBase;
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * This class defines a major component of the robot.
+ *
+ * <p> A good example of a subsystem is the driveline, or a claw if the robot has one. </p>
+ *
+ * <p> All motors should be a part of a subsystem. For instance, all the wheel motors should be a
+ * part of some kind of "Driveline" subsystem. </p>
+ *
+ * <p> Subsystems are used within the command system as requirements for {@link Command}. Only one
+ * command which requires a subsystem can run at a time. Also, subsystems can have default commands
+ * which are started if there is no command running which requires this subsystem. </p>
+ *
+ * @see Command
+ */
+public abstract class Subsystem extends SendableBase {
+  /**
+   * Whether or not getDefaultCommand() was called.
+   */
+  private boolean m_initializedDefaultCommand;
+  /**
+   * The current command.
+   */
+  private Command m_currentCommand;
+  private boolean m_currentCommandChanged;
+
+  /**
+   * The default command.
+   */
+  private Command m_defaultCommand;
+
+  /**
+   * Creates a subsystem with the given name.
+   *
+   * @param name the name of the subsystem
+   */
+  public Subsystem(String name) {
+    setName(name, name);
+    Scheduler.getInstance().registerSubsystem(this);
+  }
+
+  /**
+   * Creates a subsystem. This will set the name to the name of the class.
+   */
+  public Subsystem() {
+    String name = getClass().getName();
+    name = name.substring(name.lastIndexOf('.') + 1);
+    setName(name, name);
+    Scheduler.getInstance().registerSubsystem(this);
+    m_currentCommandChanged = true;
+  }
+
+  /**
+   * Initialize the default command for a subsystem By default subsystems have no default command,
+   * but if they do, the default command is set with this method. It is called on all Subsystems by
+   * CommandBase in the users program after all the Subsystems are created.
+   */
+  protected abstract void initDefaultCommand();
+
+  /**
+   * When the run method of the scheduler is called this method will be called.
+   */
+  public void periodic() {
+    // Override me!
+  }
+
+  /**
+   * Sets the default command. If this is not called or is called with null, then there will be no
+   * default command for the subsystem.
+   *
+   * <p> <b>WARNING:</b> This should <b>NOT</b> be called in a constructor if the subsystem is a
+   * singleton. </p>
+   *
+   * @param command the default command (or null if there should be none)
+   * @throws IllegalUseOfCommandException if the command does not require the subsystem
+   */
+  public void setDefaultCommand(Command command) {
+    if (command == null) {
+      m_defaultCommand = null;
+    } else {
+      if (!Collections.list(command.getRequirements()).contains(this)) {
+        throw new IllegalUseOfCommandException("A default command must require the subsystem");
+      }
+      m_defaultCommand = command;
+    }
+  }
+
+  /**
+   * Returns the default command (or null if there is none).
+   *
+   * @return the default command
+   */
+  public Command getDefaultCommand() {
+    if (!m_initializedDefaultCommand) {
+      m_initializedDefaultCommand = true;
+      initDefaultCommand();
+    }
+    return m_defaultCommand;
+  }
+
+  /**
+   * Returns the default command name, or empty string is there is none.
+   *
+   * @return the default command name
+   */
+  public String getDefaultCommandName() {
+    Command defaultCommand = getDefaultCommand();
+    if (defaultCommand != null) {
+      return defaultCommand.getName();
+    } else {
+      return "";
+    }
+  }
+
+  /**
+   * Sets the current command.
+   *
+   * @param command the new current command
+   */
+  void setCurrentCommand(Command command) {
+    m_currentCommand = command;
+    m_currentCommandChanged = true;
+  }
+
+  /**
+   * Call this to alert Subsystem that the current command is actually the command. Sometimes, the
+   * {@link Subsystem} is told that it has no command while the {@link Scheduler} is going through
+   * the loop, only to be soon after given a new one. This will avoid that situation.
+   */
+  void confirmCommand() {
+    if (m_currentCommandChanged) {
+      m_currentCommandChanged = false;
+    }
+  }
+
+  /**
+   * Returns the command which currently claims this subsystem.
+   *
+   * @return the command which currently claims this subsystem
+   */
+  public Command getCurrentCommand() {
+    return m_currentCommand;
+  }
+
+  /**
+   * Returns the current command name, or empty string if no current command.
+   *
+   * @return the current command name
+   */
+  public String getCurrentCommandName() {
+    Command currentCommand = getCurrentCommand();
+    if (currentCommand != null) {
+      return currentCommand.getName();
+    } else {
+      return "";
+    }
+  }
+
+  /**
+   * Associate a {@link Sendable} with this Subsystem.
+   * Also update the child's name.
+   *
+   * @param name name to give child
+   * @param child sendable
+   */
+  public void addChild(String name, Sendable child) {
+    child.setName(getSubsystem(), name);
+    LiveWindow.add(child);
+  }
+
+  /**
+   * Associate a {@link Sendable} with this Subsystem.
+   *
+   * @param child sendable
+   */
+  public void addChild(Sendable child) {
+    child.setSubsystem(getSubsystem());
+    LiveWindow.add(child);
+  }
+
+  @Override
+  public String toString() {
+    return getSubsystem();
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("Subsystem");
+
+    builder.addBooleanProperty(".hasDefault", () -> m_defaultCommand != null, null);
+    builder.addStringProperty(".default", this::getDefaultCommandName, null);
+    builder.addBooleanProperty(".hasCommand", () -> m_currentCommand != null, null);
+    builder.addStringProperty(".command", this::getCurrentCommandName, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java
new file mode 100644
index 0000000..6c9193b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/TimedCommand.java
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * A {@link TimedCommand} will wait for a timeout before finishing.
+ * {@link TimedCommand} is used to execute a command for a given amount of time.
+ */
+public class TimedCommand extends Command {
+  /**
+   * Instantiates a TimedCommand with the given name and timeout.
+   *
+   * @param name    the name of the command
+   * @param timeout the time the command takes to run (seconds)
+   */
+  public TimedCommand(String name, double timeout) {
+    super(name, timeout);
+  }
+
+  /**
+   * Instantiates a TimedCommand with the given timeout.
+   *
+   * @param timeout the time the command takes to run (seconds)
+   */
+  public TimedCommand(double timeout) {
+    super(timeout);
+  }
+
+  /**
+   * Instantiates a TimedCommand with the given name and timeout.
+   *
+   * @param name      the name of the command
+   * @param timeout   the time the command takes to run (seconds)
+   * @param subsystem the subsystem that this command requires
+   */
+  public TimedCommand(String name, double timeout, Subsystem subsystem) {
+    super(name, timeout, subsystem);
+  }
+
+  /**
+   * Instantiates a TimedCommand with the given timeout.
+   *
+   * @param timeout   the time the command takes to run (seconds)
+   * @param subsystem the subsystem that this command requires
+   */
+  public TimedCommand(double timeout, Subsystem subsystem) {
+    super(timeout, subsystem);
+  }
+
+  /**
+  * Ends command when timed out.
+  */
+  @Override
+  protected boolean isFinished() {
+    return isTimedOut();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java
new file mode 100644
index 0000000..1af7c1f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitCommand.java
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * A {@link WaitCommand} will wait for a certain amount of time before finishing. It is useful if
+ * you want a {@link CommandGroup} to pause for a moment.
+ *
+ * @see CommandGroup
+ */
+public class WaitCommand extends TimedCommand {
+  /**
+   * Instantiates a {@link WaitCommand} with the given timeout.
+   *
+   * @param timeout the time the command takes to run (seconds)
+   */
+  public WaitCommand(double timeout) {
+    this("Wait(" + timeout + ")", timeout);
+  }
+
+  /**
+   * Instantiates a {@link WaitCommand} with the given timeout.
+   *
+   * @param name    the name of the command
+   * @param timeout the time the command takes to run (seconds)
+   */
+  public WaitCommand(String name, double timeout) {
+    super(name, timeout);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java
new file mode 100644
index 0000000..27795c0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitForChildren.java
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * This command will only finish if whatever {@link CommandGroup} it is in has no active children.
+ * If it is not a part of a {@link CommandGroup}, then it will finish immediately. If it is itself
+ * an active child, then the {@link CommandGroup} will never end.
+ *
+ * <p>This class is useful for the situation where you want to allow anything running in parallel
+ * to finish, before continuing in the main {@link CommandGroup} sequence.
+ */
+public class WaitForChildren extends Command {
+  @Override
+  protected boolean isFinished() {
+    return getGroup() == null || getGroup().m_children.isEmpty();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java
new file mode 100644
index 0000000..799fa8c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/command/WaitUntilCommand.java
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import edu.wpi.first.wpilibj.Timer;
+
+/**
+ * WaitUntilCommand - waits until an absolute game time. This will wait until the game clock reaches
+ * some value, then continue to the next command.
+ */
+public class WaitUntilCommand extends Command {
+  private final double m_time;
+
+  public WaitUntilCommand(double time) {
+    super("WaitUntil(" + time + ")");
+    m_time = time;
+  }
+
+  /**
+   * Check if we've reached the actual finish time.
+   */
+  @Override
+  public boolean isFinished() {
+    return Timer.getMatchTime() >= m_time;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java
new file mode 100644
index 0000000..9355adc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/DifferentialDrive.java
@@ -0,0 +1,427 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.drive;
+
+import java.util.StringJoiner;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.SpeedControllerGroup;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * A class for driving differential drive/skid-steer drive platforms such as the Kit of Parts drive
+ * base, "tank drive", or West Coast Drive.
+ *
+ * <p>These drive bases typically have drop-center / skid-steer with two or more wheels per side
+ * (e.g., 6WD or 8WD). This class takes a SpeedController per side. For four and
+ * six motor drivetrains, construct and pass in {@link edu.wpi.first.wpilibj.SpeedControllerGroup}
+ * instances as follows.
+ *
+ * <p>Four motor drivetrain:
+ * <pre><code>
+ * public class Robot {
+ *   Spark m_frontLeft = new Spark(1);
+ *   Spark m_rearLeft = new Spark(2);
+ *   SpeedControllerGroup m_left = new SpeedControllerGroup(m_frontLeft, m_rearLeft);
+ *
+ *   Spark m_frontRight = new Spark(3);
+ *   Spark m_rearRight = new Spark(4);
+ *   SpeedControllerGroup m_right = new SpeedControllerGroup(m_frontRight, m_rearRight);
+ *
+ *   DifferentialDrive m_drive = new DifferentialDrive(m_left, m_right);
+ * }
+ * </code></pre>
+ *
+ * <p>Six motor drivetrain:
+ * <pre><code>
+ * public class Robot {
+ *   Spark m_frontLeft = new Spark(1);
+ *   Spark m_midLeft = new Spark(2);
+ *   Spark m_rearLeft = new Spark(3);
+ *   SpeedControllerGroup m_left = new SpeedControllerGroup(m_frontLeft, m_midLeft, m_rearLeft);
+ *
+ *   Spark m_frontRight = new Spark(4);
+ *   Spark m_midRight = new Spark(5);
+ *   Spark m_rearRight = new Spark(6);
+ *   SpeedControllerGroup m_right = new SpeedControllerGroup(m_frontRight, m_midRight, m_rearRight);
+ *
+ *   DifferentialDrive m_drive = new DifferentialDrive(m_left, m_right);
+ * }
+ * </code></pre>
+ *
+ * <p>A differential drive robot has left and right wheels separated by an arbitrary width.
+ *
+ * <p>Drive base diagram:
+ * <pre>
+ * |_______|
+ * | |   | |
+ *   |   |
+ * |_|___|_|
+ * |       |
+ * </pre>
+ *
+ * <p>Each drive() function provides different inverse kinematic relations for a differential drive
+ * robot. Motor outputs for the right side are negated, so motor direction inversion by the user is
+ * usually unnecessary.
+ *
+ * <p>This library uses the NED axes convention (North-East-Down as external reference in the world
+ * frame): http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * <p>The positive X axis points ahead, the positive Y axis points right, and the positive Z axis
+ * points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is
+ * positive.
+ *
+ * <p>Inputs smaller then {@value edu.wpi.first.wpilibj.drive.RobotDriveBase#kDefaultDeadband} will
+ * be set to 0, and larger values will be scaled so that the full range is still used. This
+ * deadband value can be changed with {@link #setDeadband}.
+ *
+ * <p>RobotDrive porting guide:
+ * <br>{@link #tankDrive(double, double)} is equivalent to
+ * {@link edu.wpi.first.wpilibj.RobotDrive#tankDrive(double, double)} if a deadband of 0 is used.
+ * <br>{@link #arcadeDrive(double, double)} is equivalent to
+ * {@link edu.wpi.first.wpilibj.RobotDrive#arcadeDrive(double, double)} if a deadband of 0 is used
+ * and the the rotation input is inverted eg arcadeDrive(y, -rotation)
+ * <br>{@link #curvatureDrive(double, double, boolean)} is similar in concept to
+ * {@link edu.wpi.first.wpilibj.RobotDrive#drive(double, double)} with the addition of a quick turn
+ * mode. However, it is not designed to give exactly the same response.
+ */
+public class DifferentialDrive extends RobotDriveBase {
+  public static final double kDefaultQuickStopThreshold = 0.2;
+  public static final double kDefaultQuickStopAlpha = 0.1;
+
+  private static int instances;
+
+  private final SpeedController m_leftMotor;
+  private final SpeedController m_rightMotor;
+
+  private double m_quickStopThreshold = kDefaultQuickStopThreshold;
+  private double m_quickStopAlpha = kDefaultQuickStopAlpha;
+  private double m_quickStopAccumulator;
+  private double m_rightSideInvertMultiplier = -1.0;
+  private boolean m_reported;
+
+  /**
+   * Construct a DifferentialDrive.
+   *
+   * <p>To pass multiple motors per side, use a {@link SpeedControllerGroup}. If a motor needs to be
+   * inverted, do so before passing it in.
+   */
+  public DifferentialDrive(SpeedController leftMotor, SpeedController rightMotor) {
+    verify(leftMotor, rightMotor);
+    m_leftMotor = leftMotor;
+    m_rightMotor = rightMotor;
+    addChild(m_leftMotor);
+    addChild(m_rightMotor);
+    instances++;
+    setName("DifferentialDrive", instances);
+  }
+
+  /**
+   * Verifies that all motors are nonnull, throwing a NullPointerException if any of them are.
+   * The exception's error message will specify all null motors, e.g. {@code
+   * NullPointerException("leftMotor, rightMotor")}, to give as much information as possible to
+   * the programmer.
+   *
+   * @throws NullPointerException if any of the given motors are null
+   */
+  @SuppressWarnings("PMD.AvoidThrowingNullPointerException")
+  private void verify(SpeedController leftMotor, SpeedController rightMotor) {
+    if (leftMotor != null && rightMotor != null) {
+      return;
+    }
+    StringJoiner joiner = new StringJoiner(", ");
+    if (leftMotor == null) {
+      joiner.add("leftMotor");
+    }
+    if (rightMotor == null) {
+      joiner.add("rightMotor");
+    }
+    throw new NullPointerException(joiner.toString());
+  }
+
+  /**
+   * Arcade drive method for differential drive platform.
+   * The calculated values will be squared to decrease sensitivity at low speeds.
+   *
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                  positive.
+   */
+  @SuppressWarnings("ParameterName")
+  public void arcadeDrive(double xSpeed, double zRotation) {
+    arcadeDrive(xSpeed, zRotation, true);
+  }
+
+  /**
+   * Arcade drive method for differential drive platform.
+   *
+   * @param xSpeed        The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param zRotation     The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                      positive.
+   * @param squareInputs If set, decreases the input sensitivity at low speeds.
+   */
+  @SuppressWarnings("ParameterName")
+  public void arcadeDrive(double xSpeed, double zRotation, boolean squareInputs) {
+    if (!m_reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, 2,
+                 tInstances.kRobotDrive2_DifferentialArcade);
+      m_reported = true;
+    }
+
+    xSpeed = limit(xSpeed);
+    xSpeed = applyDeadband(xSpeed, m_deadband);
+
+    zRotation = limit(zRotation);
+    zRotation = applyDeadband(zRotation, m_deadband);
+
+    // Square the inputs (while preserving the sign) to increase fine control
+    // while permitting full power.
+    if (squareInputs) {
+      xSpeed = Math.copySign(xSpeed * xSpeed, xSpeed);
+      zRotation = Math.copySign(zRotation * zRotation, zRotation);
+    }
+
+    double leftMotorOutput;
+    double rightMotorOutput;
+
+    double maxInput = Math.copySign(Math.max(Math.abs(xSpeed), Math.abs(zRotation)), xSpeed);
+
+    if (xSpeed >= 0.0) {
+      // First quadrant, else second quadrant
+      if (zRotation >= 0.0) {
+        leftMotorOutput = maxInput;
+        rightMotorOutput = xSpeed - zRotation;
+      } else {
+        leftMotorOutput = xSpeed + zRotation;
+        rightMotorOutput = maxInput;
+      }
+    } else {
+      // Third quadrant, else fourth quadrant
+      if (zRotation >= 0.0) {
+        leftMotorOutput = xSpeed + zRotation;
+        rightMotorOutput = maxInput;
+      } else {
+        leftMotorOutput = maxInput;
+        rightMotorOutput = xSpeed - zRotation;
+      }
+    }
+
+    m_leftMotor.set(limit(leftMotorOutput) * m_maxOutput);
+    m_rightMotor.set(limit(rightMotorOutput) * m_maxOutput * m_rightSideInvertMultiplier);
+
+    feed();
+  }
+
+  /**
+   * Curvature drive method for differential drive platform.
+   *
+   * <p>The rotation argument controls the curvature of the robot's path rather than its rate of
+   * heading change. This makes the robot more controllable at high speeds. Also handles the
+   * robot's quick turn functionality - "quick turn" overrides constant-curvature turning for
+   * turn-in-place maneuvers.
+   *
+   * @param xSpeed      The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param zRotation   The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                    positive.
+   * @param isQuickTurn If set, overrides constant-curvature turning for
+   *                    turn-in-place maneuvers.
+   */
+  @SuppressWarnings({"ParameterName", "PMD.CyclomaticComplexity"})
+  public void curvatureDrive(double xSpeed, double zRotation, boolean isQuickTurn) {
+    if (!m_reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, 2,
+                 tInstances.kRobotDrive2_DifferentialCurvature);
+      m_reported = true;
+    }
+
+    xSpeed = limit(xSpeed);
+    xSpeed = applyDeadband(xSpeed, m_deadband);
+
+    zRotation = limit(zRotation);
+    zRotation = applyDeadband(zRotation, m_deadband);
+
+    double angularPower;
+    boolean overPower;
+
+    if (isQuickTurn) {
+      if (Math.abs(xSpeed) < m_quickStopThreshold) {
+        m_quickStopAccumulator = (1 - m_quickStopAlpha) * m_quickStopAccumulator
+            + m_quickStopAlpha * limit(zRotation) * 2;
+      }
+      overPower = true;
+      angularPower = zRotation;
+    } else {
+      overPower = false;
+      angularPower = Math.abs(xSpeed) * zRotation - m_quickStopAccumulator;
+
+      if (m_quickStopAccumulator > 1) {
+        m_quickStopAccumulator -= 1;
+      } else if (m_quickStopAccumulator < -1) {
+        m_quickStopAccumulator += 1;
+      } else {
+        m_quickStopAccumulator = 0.0;
+      }
+    }
+
+    double leftMotorOutput = xSpeed + angularPower;
+    double rightMotorOutput = xSpeed - angularPower;
+
+    // If rotation is overpowered, reduce both outputs to within acceptable range
+    if (overPower) {
+      if (leftMotorOutput > 1.0) {
+        rightMotorOutput -= leftMotorOutput - 1.0;
+        leftMotorOutput = 1.0;
+      } else if (rightMotorOutput > 1.0) {
+        leftMotorOutput -= rightMotorOutput - 1.0;
+        rightMotorOutput = 1.0;
+      } else if (leftMotorOutput < -1.0) {
+        rightMotorOutput -= leftMotorOutput + 1.0;
+        leftMotorOutput = -1.0;
+      } else if (rightMotorOutput < -1.0) {
+        leftMotorOutput -= rightMotorOutput + 1.0;
+        rightMotorOutput = -1.0;
+      }
+    }
+
+    // Normalize the wheel speeds
+    double maxMagnitude = Math.max(Math.abs(leftMotorOutput), Math.abs(rightMotorOutput));
+    if (maxMagnitude > 1.0) {
+      leftMotorOutput /= maxMagnitude;
+      rightMotorOutput /= maxMagnitude;
+    }
+
+    m_leftMotor.set(leftMotorOutput * m_maxOutput);
+    m_rightMotor.set(rightMotorOutput * m_maxOutput * m_rightSideInvertMultiplier);
+
+    feed();
+  }
+
+  /**
+   * Tank drive method for differential drive platform.
+   * The calculated values will be squared to decrease sensitivity at low speeds.
+   *
+   * @param leftSpeed  The robot's left side speed along the X axis [-1.0..1.0]. Forward is
+   *                   positive.
+   * @param rightSpeed The robot's right side speed along the X axis [-1.0..1.0]. Forward is
+   *                   positive.
+   */
+  public void tankDrive(double leftSpeed, double rightSpeed) {
+    tankDrive(leftSpeed, rightSpeed, true);
+  }
+
+  /**
+   * Tank drive method for differential drive platform.
+   *
+   * @param leftSpeed     The robot left side's speed along the X axis [-1.0..1.0]. Forward is
+   *                      positive.
+   * @param rightSpeed    The robot right side's speed along the X axis [-1.0..1.0]. Forward is
+   *                      positive.
+   * @param squareInputs If set, decreases the input sensitivity at low speeds.
+   */
+  public void tankDrive(double leftSpeed, double rightSpeed, boolean squareInputs) {
+    if (!m_reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, 2,
+                 tInstances.kRobotDrive2_DifferentialTank);
+      m_reported = true;
+    }
+
+    leftSpeed = limit(leftSpeed);
+    leftSpeed = applyDeadband(leftSpeed, m_deadband);
+
+    rightSpeed = limit(rightSpeed);
+    rightSpeed = applyDeadband(rightSpeed, m_deadband);
+
+    // Square the inputs (while preserving the sign) to increase fine control
+    // while permitting full power.
+    if (squareInputs) {
+      leftSpeed = Math.copySign(leftSpeed * leftSpeed, leftSpeed);
+      rightSpeed = Math.copySign(rightSpeed * rightSpeed, rightSpeed);
+    }
+
+    m_leftMotor.set(leftSpeed * m_maxOutput);
+    m_rightMotor.set(rightSpeed * m_maxOutput * m_rightSideInvertMultiplier);
+
+    feed();
+  }
+
+  /**
+   * Sets the QuickStop speed threshold in curvature drive.
+   *
+   * <p>QuickStop compensates for the robot's moment of inertia when stopping after a QuickTurn.
+   *
+   * <p>While QuickTurn is enabled, the QuickStop accumulator takes on the rotation rate value
+   * outputted by the low-pass filter when the robot's speed along the X axis is below the
+   * threshold. When QuickTurn is disabled, the accumulator's value is applied against the computed
+   * angular power request to slow the robot's rotation.
+   *
+   * @param threshold X speed below which quick stop accumulator will receive rotation rate values
+   *                  [0..1.0].
+   */
+  public void setQuickStopThreshold(double threshold) {
+    m_quickStopThreshold = threshold;
+  }
+
+  /**
+   * Sets the low-pass filter gain for QuickStop in curvature drive.
+   *
+   * <p>The low-pass filter filters incoming rotation rate commands to smooth out high frequency
+   * changes.
+   *
+   * @param alpha Low-pass filter gain [0.0..2.0]. Smaller values result in slower output changes.
+   *              Values between 1.0 and 2.0 result in output oscillation. Values below 0.0 and
+   *              above 2.0 are unstable.
+   */
+  public void setQuickStopAlpha(double alpha) {
+    m_quickStopAlpha = alpha;
+  }
+
+  /**
+   * Gets if the power sent to the right side of the drivetrain is multipled by -1.
+   *
+   * @return true if the right side is inverted
+   */
+  public boolean isRightSideInverted() {
+    return m_rightSideInvertMultiplier == -1.0;
+  }
+
+  /**
+   * Sets if the power sent to the right side of the drivetrain should be multipled by -1.
+   *
+   * @param rightSideInverted true if right side power should be multipled by -1
+   */
+  public void setRightSideInverted(boolean rightSideInverted) {
+    m_rightSideInvertMultiplier = rightSideInverted ? -1.0 : 1.0;
+  }
+
+  @Override
+  public void stopMotor() {
+    m_leftMotor.stopMotor();
+    m_rightMotor.stopMotor();
+    feed();
+  }
+
+  @Override
+  public String getDescription() {
+    return "DifferentialDrive";
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("DifferentialDrive");
+    builder.setActuator(true);
+    builder.setSafeState(this::stopMotor);
+    builder.addDoubleProperty("Left Motor Speed", m_leftMotor::get, m_leftMotor::set);
+    builder.addDoubleProperty(
+        "Right Motor Speed",
+        () -> m_rightMotor.get() * m_rightSideInvertMultiplier,
+        x -> m_rightMotor.set(x * m_rightSideInvertMultiplier));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java
new file mode 100644
index 0000000..165ba70
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/KilloughDrive.java
@@ -0,0 +1,243 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.drive;
+
+import java.util.StringJoiner;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * A class for driving Killough drive platforms.
+ *
+ * <p>Killough drives are triangular with one omni wheel on each corner.
+ *
+ * <p>Drive base diagram:
+ * <pre>
+ *  /_____\
+ * / \   / \
+ *    \ /
+ *    ---
+ * </pre>
+ *
+ * <p>Each drive() function provides different inverse kinematic relations for a Killough drive. The
+ * default wheel vectors are parallel to their respective opposite sides, but can be overridden. See
+ * the constructor for more information.
+ *
+ * <p>This library uses the NED axes convention (North-East-Down as external reference in the world
+ * frame): http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * <p>The positive X axis points ahead, the positive Y axis points right, and the positive Z axis
+ * points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is
+ * positive.
+ */
+public class KilloughDrive extends RobotDriveBase {
+  public static final double kDefaultLeftMotorAngle = 60.0;
+  public static final double kDefaultRightMotorAngle = 120.0;
+  public static final double kDefaultBackMotorAngle = 270.0;
+
+  private static int instances;
+
+  private SpeedController m_leftMotor;
+  private SpeedController m_rightMotor;
+  private SpeedController m_backMotor;
+
+  private Vector2d m_leftVec;
+  private Vector2d m_rightVec;
+  private Vector2d m_backVec;
+
+  private boolean m_reported;
+
+  /**
+   * Construct a Killough drive with the given motors and default motor angles.
+   *
+   * <p>The default motor angles make the wheels on each corner parallel to their respective
+   * opposite sides.
+   *
+   * <p>If a motor needs to be inverted, do so before passing it in.
+   *
+   * @param leftMotor  The motor on the left corner.
+   * @param rightMotor The motor on the right corner.
+   * @param backMotor  The motor on the back corner.
+   */
+  public KilloughDrive(SpeedController leftMotor, SpeedController rightMotor,
+                       SpeedController backMotor) {
+    this(leftMotor, rightMotor, backMotor, kDefaultLeftMotorAngle, kDefaultRightMotorAngle,
+        kDefaultBackMotorAngle);
+  }
+
+  /**
+   * Construct a Killough drive with the given motors.
+   *
+   * <p>Angles are measured in degrees clockwise from the positive X axis.
+   *
+   * @param leftMotor       The motor on the left corner.
+   * @param rightMotor      The motor on the right corner.
+   * @param backMotor       The motor on the back corner.
+   * @param leftMotorAngle  The angle of the left wheel's forward direction of travel.
+   * @param rightMotorAngle The angle of the right wheel's forward direction of travel.
+   * @param backMotorAngle  The angle of the back wheel's forward direction of travel.
+   */
+  public KilloughDrive(SpeedController leftMotor, SpeedController rightMotor,
+                       SpeedController backMotor, double leftMotorAngle, double rightMotorAngle,
+                       double backMotorAngle) {
+    verify(leftMotor, rightMotor, backMotor);
+    m_leftMotor = leftMotor;
+    m_rightMotor = rightMotor;
+    m_backMotor = backMotor;
+    m_leftVec = new Vector2d(Math.cos(leftMotorAngle * (Math.PI / 180.0)),
+                             Math.sin(leftMotorAngle * (Math.PI / 180.0)));
+    m_rightVec = new Vector2d(Math.cos(rightMotorAngle * (Math.PI / 180.0)),
+                              Math.sin(rightMotorAngle * (Math.PI / 180.0)));
+    m_backVec = new Vector2d(Math.cos(backMotorAngle * (Math.PI / 180.0)),
+                             Math.sin(backMotorAngle * (Math.PI / 180.0)));
+    addChild(m_leftMotor);
+    addChild(m_rightMotor);
+    addChild(m_backMotor);
+    instances++;
+    setName("KilloughDrive", instances);
+  }
+
+  /**
+   * Verifies that all motors are nonnull, throwing a NullPointerException if any of them are.
+   * The exception's error message will specify all null motors, e.g. {@code
+   * NullPointerException("leftMotor, rightMotor")}, to give as much information as possible to
+   * the programmer.
+   *
+   * @throws NullPointerException if any of the given motors are null
+   */
+  @SuppressWarnings("PMD.AvoidThrowingNullPointerException")
+  private void verify(SpeedController leftMotor, SpeedController rightMotor,
+                      SpeedController backMotor) {
+    if (leftMotor != null && rightMotor != null && backMotor != null) {
+      return;
+    }
+    StringJoiner joiner = new StringJoiner(", ");
+    if (leftMotor == null) {
+      joiner.add("leftMotor");
+    }
+    if (rightMotor == null) {
+      joiner.add("rightMotor");
+    }
+    if (backMotor == null) {
+      joiner.add("backMotor");
+    }
+    throw new NullPointerException(joiner.toString());
+  }
+
+  /**
+   * Drive method for Killough platform.
+   *
+   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
+   * from its angle or rotation rate.
+   *
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is positive.
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                  positive.
+   */
+  @SuppressWarnings("ParameterName")
+  public void driveCartesian(double ySpeed, double xSpeed, double zRotation) {
+    driveCartesian(ySpeed, xSpeed, zRotation, 0.0);
+  }
+
+  /**
+   * Drive method for Killough platform.
+   *
+   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
+   * from its angle or rotation rate.
+   *
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is positive.
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                  positive.
+   * @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use
+   *                  this to implement field-oriented controls.
+   */
+  @SuppressWarnings("ParameterName")
+  public void driveCartesian(double ySpeed, double xSpeed, double zRotation,
+                             double gyroAngle) {
+    if (!m_reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, 3,
+                 tInstances.kRobotDrive2_KilloughCartesian);
+      m_reported = true;
+    }
+
+    ySpeed = limit(ySpeed);
+    ySpeed = applyDeadband(ySpeed, m_deadband);
+
+    xSpeed = limit(xSpeed);
+    xSpeed = applyDeadband(xSpeed, m_deadband);
+
+    // Compensate for gyro angle.
+    Vector2d input = new Vector2d(ySpeed, xSpeed);
+    input.rotate(-gyroAngle);
+
+    double[] wheelSpeeds = new double[3];
+    wheelSpeeds[MotorType.kLeft.value] = input.scalarProject(m_leftVec) + zRotation;
+    wheelSpeeds[MotorType.kRight.value] = input.scalarProject(m_rightVec) + zRotation;
+    wheelSpeeds[MotorType.kBack.value] = input.scalarProject(m_backVec) + zRotation;
+
+    normalize(wheelSpeeds);
+
+    m_leftMotor.set(wheelSpeeds[MotorType.kLeft.value] * m_maxOutput);
+    m_rightMotor.set(wheelSpeeds[MotorType.kRight.value] * m_maxOutput);
+    m_backMotor.set(wheelSpeeds[MotorType.kBack.value] * m_maxOutput);
+
+    feed();
+  }
+
+  /**
+   * Drive method for Killough platform.
+   *
+   * <p>Angles are measured counter-clockwise from straight ahead. The speed at which the robot
+   * drives (translation) is independent from its angle or rotation rate.
+   *
+   * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is positive.
+   * @param angle     The angle around the Z axis at which the robot drives in degrees [-180..180].
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                  positive.
+   */
+  @SuppressWarnings("ParameterName")
+  public void drivePolar(double magnitude, double angle, double zRotation) {
+    if (!m_reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, 3,
+                 tInstances.kRobotDrive2_KilloughPolar);
+      m_reported = true;
+    }
+
+    driveCartesian(magnitude * Math.sin(angle * (Math.PI / 180.0)),
+                   magnitude * Math.cos(angle * (Math.PI / 180.0)), zRotation, 0.0);
+  }
+
+  @Override
+  public void stopMotor() {
+    m_leftMotor.stopMotor();
+    m_rightMotor.stopMotor();
+    m_backMotor.stopMotor();
+    feed();
+  }
+
+  @Override
+  public String getDescription() {
+    return "KilloughDrive";
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("KilloughDrive");
+    builder.setActuator(true);
+    builder.setSafeState(this::stopMotor);
+    builder.addDoubleProperty("Left Motor Speed", m_leftMotor::get, m_leftMotor::set);
+    builder.addDoubleProperty("Right Motor Speed", m_rightMotor::get, m_rightMotor::set);
+    builder.addDoubleProperty("Back Motor Speed", m_backMotor::get, m_backMotor::set);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java
new file mode 100644
index 0000000..acdc4d7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/MecanumDrive.java
@@ -0,0 +1,259 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.drive;
+
+import java.util.StringJoiner;
+
+import edu.wpi.first.hal.FRCNetComm.tInstances;
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * A class for driving Mecanum drive platforms.
+ *
+ * <p>Mecanum drives are rectangular with one wheel on each corner. Each wheel has rollers toed in
+ * 45 degrees toward the front or back. When looking at the wheels from the top, the roller axles
+ * should form an X across the robot. Each drive() function provides different inverse kinematic
+ * relations for a Mecanum drive robot.
+ *
+ * <p>Drive base diagram:
+ * <pre>
+ * \\_______/
+ * \\ |   | /
+ *   |   |
+ * /_|___|_\\
+ * /       \\
+ * </pre>
+ *
+ * <p>Each drive() function provides different inverse kinematic relations for a Mecanum drive
+ * robot. Motor outputs for the right side are negated, so motor direction inversion by the user is
+ * usually unnecessary.
+ *
+ * <p>This library uses the NED axes convention (North-East-Down as external reference in the world
+ * frame): http://www.nuclearprojects.com/ins/images/axis_big.png.
+ *
+ * <p>The positive X axis points ahead, the positive Y axis points right, and the positive Z axis
+ * points down. Rotations follow the right-hand rule, so clockwise rotation around the Z axis is
+ * positive.
+ *
+ * <p>Inputs smaller then {@value edu.wpi.first.wpilibj.drive.RobotDriveBase#kDefaultDeadband} will
+ * be set to 0, and larger values will be scaled so that the full range is still used. This
+ * deadband value can be changed with {@link #setDeadband}.
+ *
+ * <p>RobotDrive porting guide:
+ * <br>In MecanumDrive, the right side speed controllers are automatically inverted, while in
+ * RobotDrive, no speed controllers are automatically inverted.
+ * <br>{@link #driveCartesian(double, double, double, double)} is equivalent to
+ * {@link edu.wpi.first.wpilibj.RobotDrive#mecanumDrive_Cartesian(double, double, double, double)}
+ * if a deadband of 0 is used, and the ySpeed and gyroAngle values are inverted compared to
+ * RobotDrive (eg driveCartesian(xSpeed, -ySpeed, zRotation, -gyroAngle).
+ * <br>{@link #drivePolar(double, double, double)} is equivalent to
+ * {@link edu.wpi.first.wpilibj.RobotDrive#mecanumDrive_Polar(double, double, double)} if a
+ * deadband of 0 is used.
+ */
+public class MecanumDrive extends RobotDriveBase {
+  private static int instances;
+
+  private final SpeedController m_frontLeftMotor;
+  private final SpeedController m_rearLeftMotor;
+  private final SpeedController m_frontRightMotor;
+  private final SpeedController m_rearRightMotor;
+
+  private double m_rightSideInvertMultiplier = -1.0;
+  private boolean m_reported;
+
+  /**
+   * Construct a MecanumDrive.
+   *
+   * <p>If a motor needs to be inverted, do so before passing it in.
+   */
+  public MecanumDrive(SpeedController frontLeftMotor, SpeedController rearLeftMotor,
+                      SpeedController frontRightMotor, SpeedController rearRightMotor) {
+    verify(frontLeftMotor, rearLeftMotor, frontRightMotor, rearRightMotor);
+    m_frontLeftMotor = frontLeftMotor;
+    m_rearLeftMotor = rearLeftMotor;
+    m_frontRightMotor = frontRightMotor;
+    m_rearRightMotor = rearRightMotor;
+    addChild(m_frontLeftMotor);
+    addChild(m_rearLeftMotor);
+    addChild(m_frontRightMotor);
+    addChild(m_rearRightMotor);
+    instances++;
+    setName("MecanumDrive", instances);
+  }
+
+  /**
+   * Verifies that all motors are nonnull, throwing a NullPointerException if any of them are.
+   * The exception's error message will specify all null motors, e.g. {@code
+   * NullPointerException("frontLeftMotor, rearRightMotor")}, to give as much information as
+   * possible to the programmer.
+   *
+   * @throws NullPointerException if any of the given motors are null
+   */
+  @SuppressWarnings({"PMD.AvoidThrowingNullPointerException", "PMD.CyclomaticComplexity"})
+  private void verify(SpeedController frontLeft, SpeedController rearLeft,
+                      SpeedController frontRight, SpeedController rearRightMotor) {
+    if (frontLeft != null && rearLeft != null && frontRight != null && rearRightMotor != null) {
+      return;
+    }
+    StringJoiner joiner = new StringJoiner(", ");
+    if (frontLeft == null) {
+      joiner.add("frontLeftMotor");
+    }
+    if (rearLeft == null) {
+      joiner.add("rearLeftMotor");
+    }
+    if (frontRight == null) {
+      joiner.add("frontRightMotor");
+    }
+    if (rearRightMotor == null) {
+      joiner.add("rearRightMotor");
+    }
+    throw new NullPointerException(joiner.toString());
+  }
+
+  /**
+   * Drive method for Mecanum platform.
+   *
+   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
+   * from its angle or rotation rate.
+   *
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is positive.
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                  positive.
+   */
+  @SuppressWarnings("ParameterName")
+  public void driveCartesian(double ySpeed, double xSpeed, double zRotation) {
+    driveCartesian(ySpeed, xSpeed, zRotation, 0.0);
+  }
+
+  /**
+   * Drive method for Mecanum platform.
+   *
+   * <p>Angles are measured clockwise from the positive X axis. The robot's speed is independent
+   * from its angle or rotation rate.
+   *
+   * @param ySpeed    The robot's speed along the Y axis [-1.0..1.0]. Right is positive.
+   * @param xSpeed    The robot's speed along the X axis [-1.0..1.0]. Forward is positive.
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                  positive.
+   * @param gyroAngle The current angle reading from the gyro in degrees around the Z axis. Use
+   *                  this to implement field-oriented controls.
+   */
+  @SuppressWarnings("ParameterName")
+  public void driveCartesian(double ySpeed, double xSpeed, double zRotation, double gyroAngle) {
+    if (!m_reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, 4,
+                 tInstances.kRobotDrive2_MecanumCartesian);
+      m_reported = true;
+    }
+
+    ySpeed = limit(ySpeed);
+    ySpeed = applyDeadband(ySpeed, m_deadband);
+
+    xSpeed = limit(xSpeed);
+    xSpeed = applyDeadband(xSpeed, m_deadband);
+
+    // Compensate for gyro angle.
+    Vector2d input = new Vector2d(ySpeed, xSpeed);
+    input.rotate(-gyroAngle);
+
+    double[] wheelSpeeds = new double[4];
+    wheelSpeeds[MotorType.kFrontLeft.value] = input.x + input.y + zRotation;
+    wheelSpeeds[MotorType.kFrontRight.value] = -input.x + input.y - zRotation;
+    wheelSpeeds[MotorType.kRearLeft.value] = -input.x + input.y + zRotation;
+    wheelSpeeds[MotorType.kRearRight.value] = input.x + input.y - zRotation;
+
+    normalize(wheelSpeeds);
+
+    m_frontLeftMotor.set(wheelSpeeds[MotorType.kFrontLeft.value] * m_maxOutput);
+    m_frontRightMotor.set(wheelSpeeds[MotorType.kFrontRight.value] * m_maxOutput
+        * m_rightSideInvertMultiplier);
+    m_rearLeftMotor.set(wheelSpeeds[MotorType.kRearLeft.value] * m_maxOutput);
+    m_rearRightMotor.set(wheelSpeeds[MotorType.kRearRight.value] * m_maxOutput
+        * m_rightSideInvertMultiplier);
+
+    feed();
+  }
+
+  /**
+   * Drive method for Mecanum platform.
+   *
+   * <p>Angles are measured counter-clockwise from straight ahead. The speed at which the robot
+   * drives (translation) is independent from its angle or rotation rate.
+   *
+   * @param magnitude The robot's speed at a given angle [-1.0..1.0]. Forward is positive.
+   * @param angle     The angle around the Z axis at which the robot drives in degrees [-180..180].
+   * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. Clockwise is
+   *                  positive.
+   */
+  @SuppressWarnings("ParameterName")
+  public void drivePolar(double magnitude, double angle, double zRotation) {
+    if (!m_reported) {
+      HAL.report(tResourceType.kResourceType_RobotDrive, 4, tInstances.kRobotDrive2_MecanumPolar);
+      m_reported = true;
+    }
+
+    driveCartesian(magnitude * Math.sin(angle * (Math.PI / 180.0)),
+                   magnitude * Math.cos(angle * (Math.PI / 180.0)), zRotation, 0.0);
+  }
+
+  /**
+   * Gets if the power sent to the right side of the drivetrain is multipled by -1.
+   *
+   * @return true if the right side is inverted
+   */
+  public boolean isRightSideInverted() {
+    return m_rightSideInvertMultiplier == -1.0;
+  }
+
+  /**
+   * Sets if the power sent to the right side of the drivetrain should be multipled by -1.
+   *
+   * @param rightSideInverted true if right side power should be multipled by -1
+   */
+  public void setRightSideInverted(boolean rightSideInverted) {
+    m_rightSideInvertMultiplier = rightSideInverted ? -1.0 : 1.0;
+  }
+
+  @Override
+  public void stopMotor() {
+    m_frontLeftMotor.stopMotor();
+    m_frontRightMotor.stopMotor();
+    m_rearLeftMotor.stopMotor();
+    m_rearRightMotor.stopMotor();
+    feed();
+  }
+
+  @Override
+  public String getDescription() {
+    return "MecanumDrive";
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("MecanumDrive");
+    builder.setActuator(true);
+    builder.setSafeState(this::stopMotor);
+    builder.addDoubleProperty("Front Left Motor Speed",
+        m_frontLeftMotor::get,
+        m_frontLeftMotor::set);
+    builder.addDoubleProperty("Front Right Motor Speed",
+        () -> m_frontRightMotor.get() * m_rightSideInvertMultiplier,
+        value -> m_frontRightMotor.set(value * m_rightSideInvertMultiplier));
+    builder.addDoubleProperty("Rear Left Motor Speed",
+        m_rearLeftMotor::get,
+        m_rearLeftMotor::set);
+    builder.addDoubleProperty("Rear Right Motor Speed",
+        () -> m_rearRightMotor.get() * m_rightSideInvertMultiplier,
+        value -> m_rearRightMotor.set(value * m_rightSideInvertMultiplier));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java
new file mode 100644
index 0000000..2e47434
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/RobotDriveBase.java
@@ -0,0 +1,195 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.drive;
+
+import edu.wpi.first.wpilibj.MotorSafety;
+import edu.wpi.first.wpilibj.Sendable;
+import edu.wpi.first.wpilibj.SendableImpl;
+
+/**
+ * Common base class for drive platforms.
+ */
+public abstract class RobotDriveBase extends MotorSafety implements Sendable, AutoCloseable {
+  public static final double kDefaultDeadband = 0.02;
+  public static final double kDefaultMaxOutput = 1.0;
+
+  protected double m_deadband = kDefaultDeadband;
+  protected double m_maxOutput = kDefaultMaxOutput;
+
+  private final SendableImpl m_sendableImpl;
+
+  /**
+   * The location of a motor on the robot for the purpose of driving.
+   */
+  public enum MotorType {
+    kFrontLeft(0), kFrontRight(1), kRearLeft(2), kRearRight(3), kLeft(0),
+    kRight(1), kBack(2);
+
+    @SuppressWarnings("MemberName")
+    public final int value;
+
+    MotorType(int value) {
+      this.value = value;
+    }
+  }
+
+  /**
+   * RobotDriveBase constructor.
+   */
+  public RobotDriveBase() {
+    m_sendableImpl = new SendableImpl(true);
+
+    setSafetyEnabled(true);
+    setName("RobotDriveBase");
+  }
+
+  @Override
+  public void close() {
+    m_sendableImpl.close();
+  }
+
+  @Override
+  public final synchronized String getName() {
+    return m_sendableImpl.getName();
+  }
+
+  @Override
+  public final synchronized void setName(String name) {
+    m_sendableImpl.setName(name);
+  }
+
+  /**
+   * Sets the name of the sensor with a channel number.
+   *
+   * @param moduleType A string that defines the module name in the label for the value
+   * @param channel    The channel number the device is plugged into
+   */
+  protected final void setName(String moduleType, int channel) {
+    m_sendableImpl.setName(moduleType, channel);
+  }
+
+  /**
+   * Sets the name of the sensor with a module and channel number.
+   *
+   * @param moduleType   A string that defines the module name in the label for the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually PWM)
+   */
+  protected final void setName(String moduleType, int moduleNumber, int channel) {
+    m_sendableImpl.setName(moduleType, moduleNumber, channel);
+  }
+
+  @Override
+  public final synchronized String getSubsystem() {
+    return m_sendableImpl.getSubsystem();
+  }
+
+  @Override
+  public final synchronized void setSubsystem(String subsystem) {
+    m_sendableImpl.setSubsystem(subsystem);
+  }
+
+  /**
+   * Add a child component.
+   *
+   * @param child child component
+   */
+  protected final void addChild(Object child) {
+    m_sendableImpl.addChild(child);
+  }
+
+  /**
+   * Sets the deadband applied to the drive inputs (e.g., joystick values).
+   *
+   * <p>The default value is {@value #kDefaultDeadband}. Inputs smaller than the deadband are set to
+   * 0.0 while inputs larger than the deadband are scaled from 0.0 to 1.0. See
+   * {@link #applyDeadband}.
+   *
+   * @param deadband The deadband to set.
+   */
+  public void setDeadband(double deadband) {
+    m_deadband = deadband;
+  }
+
+  /**
+   * Configure the scaling factor for using drive methods with motor controllers in a mode other
+   * than PercentVbus or to limit the maximum output.
+   *
+   * <p>The default value is {@value #kDefaultMaxOutput}.
+   *
+   * @param maxOutput Multiplied with the output percentage computed by the drive functions.
+   */
+  public void setMaxOutput(double maxOutput) {
+    m_maxOutput = maxOutput;
+  }
+
+  /**
+   * Feed the motor safety object. Resets the timer that will stop the motors if it completes.
+   *
+   * @see MotorSafety#feed()
+   */
+  public void feedWatchdog() {
+    feed();
+  }
+
+  @Override
+  public abstract void stopMotor();
+
+  @Override
+  public abstract String getDescription();
+
+  /**
+   * Limit motor values to the -1.0 to +1.0 range.
+   */
+  protected double limit(double value) {
+    if (value > 1.0) {
+      return 1.0;
+    }
+    if (value < -1.0) {
+      return -1.0;
+    }
+    return value;
+  }
+
+  /**
+   * Returns 0.0 if the given value is within the specified range around zero. The remaining range
+   * between the deadband and 1.0 is scaled from 0.0 to 1.0.
+   *
+   * @param value    value to clip
+   * @param deadband range around zero
+   */
+  protected double applyDeadband(double value, double deadband) {
+    if (Math.abs(value) > deadband) {
+      if (value > 0.0) {
+        return (value - deadband) / (1.0 - deadband);
+      } else {
+        return (value + deadband) / (1.0 - deadband);
+      }
+    } else {
+      return 0.0;
+    }
+  }
+
+  /**
+   * Normalize all wheel speeds if the magnitude of any wheel is greater than 1.0.
+   */
+  protected void normalize(double[] wheelSpeeds) {
+    double maxMagnitude = Math.abs(wheelSpeeds[0]);
+    for (int i = 1; i < wheelSpeeds.length; i++) {
+      double temp = Math.abs(wheelSpeeds[i]);
+      if (maxMagnitude < temp) {
+        maxMagnitude = temp;
+      }
+    }
+    if (maxMagnitude > 1.0) {
+      for (int i = 0; i < wheelSpeeds.length; i++) {
+        wheelSpeeds[i] = wheelSpeeds[i] / maxMagnitude;
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java
new file mode 100644
index 0000000..2b1f839
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/drive/Vector2d.java
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.drive;
+
+/**
+ * This is a 2D vector struct that supports basic vector operations.
+ */
+@SuppressWarnings("MemberName")
+public class Vector2d {
+  public double x;
+  public double y;
+
+  public Vector2d() {}
+
+  @SuppressWarnings("ParameterName")
+  public Vector2d(double x, double y) {
+    this.x = x;
+    this.y = y;
+  }
+
+  /**
+   * Rotate a vector in Cartesian space.
+   *
+   * @param angle angle in degrees by which to rotate vector counter-clockwise.
+   */
+  public void rotate(double angle) {
+    double cosA = Math.cos(angle * (Math.PI / 180.0));
+    double sinA = Math.sin(angle * (Math.PI / 180.0));
+    double[] out = new double[2];
+    out[0] = x * cosA - y * sinA;
+    out[1] = x * sinA + y * cosA;
+    x = out[0];
+    y = out[1];
+  }
+
+  /**
+   * Returns dot product of this vector with argument.
+   *
+   * @param vec Vector with which to perform dot product.
+   */
+  public double dot(Vector2d vec) {
+    return x * vec.x + y * vec.y;
+  }
+
+  /**
+   * Returns magnitude of vector.
+   */
+  public double magnitude() {
+    return Math.sqrt(x * x + y * y);
+  }
+
+  /**
+   * Returns scalar projection of this vector onto argument.
+   *
+   * @param vec Vector onto which to project this vector.
+   */
+  public double scalarProject(Vector2d vec) {
+    return dot(vec) / vec.magnitude();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/Filter.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/Filter.java
new file mode 100644
index 0000000..26312f8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/Filter.java
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.filters;
+
+import edu.wpi.first.wpilibj.PIDSource;
+import edu.wpi.first.wpilibj.PIDSourceType;
+
+/**
+ * Superclass for filters.
+ */
+public abstract class Filter implements PIDSource {
+  private final PIDSource m_source;
+
+  public Filter(PIDSource source) {
+    m_source = source;
+  }
+
+  @Override
+  public void setPIDSourceType(PIDSourceType pidSource) {
+    m_source.setPIDSourceType(pidSource);
+  }
+
+  @Override
+  public PIDSourceType getPIDSourceType() {
+    return m_source.getPIDSourceType();
+  }
+
+  @Override
+  public abstract double pidGet();
+
+  /**
+   * Returns the current filter estimate without also inserting new data as pidGet() would do.
+   *
+   * @return The current filter estimate
+   */
+  public abstract double get();
+
+  /**
+   * Reset the filter state.
+   */
+  public abstract void reset();
+
+  /**
+   * Calls PIDGet() of source.
+   *
+   * @return Current value of source
+   */
+  protected double pidGetSource() {
+    return m_source.pidGet();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/LinearDigitalFilter.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/LinearDigitalFilter.java
new file mode 100644
index 0000000..65e84b5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/filters/LinearDigitalFilter.java
@@ -0,0 +1,192 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.filters;
+
+import java.util.Arrays;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.CircularBuffer;
+import edu.wpi.first.wpilibj.PIDSource;
+
+/**
+ * This class implements a linear, digital filter. All types of FIR and IIR filters are supported.
+ * Static factory methods are provided to create commonly used types of filters.
+ *
+ * <p>Filters are of the form: y[n] = (b0*x[n] + b1*x[n-1] + ... + bP*x[n-P]) - (a0*y[n-1] +
+ * a2*y[n-2] + ... + aQ*y[n-Q])
+ *
+ * <p>Where: y[n] is the output at time "n" x[n] is the input at time "n" y[n-1] is the output from
+ * the LAST time step ("n-1") x[n-1] is the input from the LAST time step ("n-1") b0...bP are the
+ * "feedforward" (FIR) gains a0...aQ are the "feedback" (IIR) gains IMPORTANT! Note the "-" sign in
+ * front of the feedback term! This is a common convention in signal processing.
+ *
+ * <p>What can linear filters do? Basically, they can filter, or diminish, the effects of
+ * undesirable input frequencies. High frequencies, or rapid changes, can be indicative of sensor
+ * noise or be otherwise undesirable. A "low pass" filter smooths out the signal, reducing the
+ * impact of these high frequency components.  Likewise, a "high pass" filter gets rid of
+ * slow-moving signal components, letting you detect large changes more easily.
+ *
+ * <p>Example FRC applications of filters: - Getting rid of noise from an analog sensor input (note:
+ * the roboRIO's FPGA can do this faster in hardware) - Smoothing out joystick input to prevent the
+ * wheels from slipping or the robot from tipping - Smoothing motor commands so that unnecessary
+ * strain isn't put on electrical or mechanical components - If you use clever gains, you can make a
+ * PID controller out of this class!
+ *
+ * <p>For more on filters, I highly recommend the following articles: http://en.wikipedia
+ * .org/wiki/Linear_filter http://en.wikipedia.org/wiki/Iir_filter http://en.wikipedia
+ * .org/wiki/Fir_filter
+ *
+ * <p>Note 1: PIDGet() should be called by the user on a known, regular period. You can set up a
+ * Notifier to do this (look at the WPILib PIDController class), or do it "inline" with code in a
+ * periodic function.
+ *
+ * <p>Note 2: For ALL filters, gains are necessarily a function of frequency. If you make a filter
+ * that works well for you at, say, 100Hz, you will most definitely need to adjust the gains if you
+ * then want to run it at 200Hz! Combining this with Note 1 - the impetus is on YOU as a developer
+ * to make sure PIDGet() gets called at the desired, constant frequency!
+ */
+public class LinearDigitalFilter extends Filter {
+  private static int instances;
+
+  private final CircularBuffer m_inputs;
+  private final CircularBuffer m_outputs;
+  private final double[] m_inputGains;
+  private final double[] m_outputGains;
+
+  /**
+   * Create a linear FIR or IIR filter.
+   *
+   * @param source  The PIDSource object that is used to get values
+   * @param ffGains The "feed forward" or FIR gains
+   * @param fbGains The "feed back" or IIR gains
+   */
+  public LinearDigitalFilter(PIDSource source, double[] ffGains,
+                             double[] fbGains) {
+    super(source);
+    m_inputs = new CircularBuffer(ffGains.length);
+    m_outputs = new CircularBuffer(fbGains.length);
+    m_inputGains = Arrays.copyOf(ffGains, ffGains.length);
+    m_outputGains = Arrays.copyOf(fbGains, fbGains.length);
+
+    instances++;
+    HAL.report(tResourceType.kResourceType_LinearFilter, instances);
+  }
+
+  /**
+   * Creates a one-pole IIR low-pass filter of the form: y[n] = (1-gain)*x[n] + gain*y[n-1] where
+   * gain = e^(-dt / T), T is the time constant in seconds.
+   *
+   * <p>This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  public static LinearDigitalFilter singlePoleIIR(PIDSource source,
+                                                  double timeConstant,
+                                                  double period) {
+    double gain = Math.exp(-period / timeConstant);
+    double[] ffGains = {1.0 - gain};
+    double[] fbGains = {-gain};
+
+    return new LinearDigitalFilter(source, ffGains, fbGains);
+  }
+
+  /**
+   * Creates a first-order high-pass filter of the form: y[n] = gain*x[n] + (-gain)*x[n-1] +
+   * gain*y[n-1] where gain = e^(-dt / T), T is the time constant in seconds.
+   *
+   * <p>This filter is stable for time constants greater than zero.
+   *
+   * @param source       The PIDSource object that is used to get values
+   * @param timeConstant The discrete-time time constant in seconds
+   * @param period       The period in seconds between samples taken by the user
+   */
+  public static LinearDigitalFilter highPass(PIDSource source,
+                                             double timeConstant,
+                                             double period) {
+    double gain = Math.exp(-period / timeConstant);
+    double[] ffGains = {gain, -gain};
+    double[] fbGains = {-gain};
+
+    return new LinearDigitalFilter(source, ffGains, fbGains);
+  }
+
+  /**
+   * Creates a K-tap FIR moving average filter of the form: y[n] = 1/k * (x[k] + x[k-1] + ... +
+   * x[0]).
+   *
+   * <p>This filter is always stable.
+   *
+   * @param source The PIDSource object that is used to get values
+   * @param taps   The number of samples to average over. Higher = smoother but slower
+   * @throws IllegalArgumentException if number of taps is less than 1
+   */
+  public static LinearDigitalFilter movingAverage(PIDSource source, int taps) {
+    if (taps <= 0) {
+      throw new IllegalArgumentException("Number of taps was not at least 1");
+    }
+
+    double[] ffGains = new double[taps];
+    for (int i = 0; i < ffGains.length; i++) {
+      ffGains[i] = 1.0 / taps;
+    }
+
+    double[] fbGains = new double[0];
+
+    return new LinearDigitalFilter(source, ffGains, fbGains);
+  }
+
+  @Override
+  public double get() {
+    double retVal = 0.0;
+
+    // Calculate the new value
+    for (int i = 0; i < m_inputGains.length; i++) {
+      retVal += m_inputs.get(i) * m_inputGains[i];
+    }
+    for (int i = 0; i < m_outputGains.length; i++) {
+      retVal -= m_outputs.get(i) * m_outputGains[i];
+    }
+
+    return retVal;
+  }
+
+  @Override
+  public void reset() {
+    m_inputs.clear();
+    m_outputs.clear();
+  }
+
+  /**
+   * Calculates the next value of the filter.
+   *
+   * @return The filtered value at this step
+   */
+  @Override
+  public double pidGet() {
+    double retVal = 0.0;
+
+    // Rotate the inputs
+    m_inputs.addFirst(pidGetSource());
+
+    // Calculate the new value
+    for (int i = 0; i < m_inputGains.length; i++) {
+      retVal += m_inputs.get(i) * m_inputGains[i];
+    }
+    for (int i = 0; i < m_outputGains.length; i++) {
+      retVal -= m_outputs.get(i) * m_outputGains[i];
+    }
+
+    // Rotate the outputs
+    m_outputs.addFirst(retVal);
+
+    return retVal;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java
new file mode 100644
index 0000000..81086d4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Accelerometer.java
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.interfaces;
+
+/**
+ * Interface for 3-axis accelerometers.
+ */
+public interface Accelerometer {
+  enum Range {
+    k2G, k4G, k8G, k16G
+  }
+
+  /**
+   * Common interface for setting the measuring range of an accelerometer.
+   *
+   * @param range The maximum acceleration, positive or negative, that the accelerometer will
+   *              measure. Not all accelerometers support all ranges.
+   */
+  void setRange(Range range);
+
+  /**
+   * Common interface for getting the x axis acceleration.
+   *
+   * @return The acceleration along the x axis in g-forces
+   */
+  double getX();
+
+  /**
+   * Common interface for getting the y axis acceleration.
+   *
+   * @return The acceleration along the y axis in g-forces
+   */
+  double getY();
+
+  /**
+   * Common interface for getting the z axis acceleration.
+   *
+   * @return The acceleration along the z axis in g-forces
+   */
+  double getZ();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java
new file mode 100644
index 0000000..4a5b2de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Gyro.java
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.interfaces;
+
+/**
+ * Interface for yaw rate gyros.
+ */
+public interface Gyro extends AutoCloseable {
+  /**
+   * Calibrate the gyro by running for a number of samples and computing the center value. Then use
+   * the center value as the Accumulator center value for subsequent measurements. It's important to
+   * make sure that the robot is not moving while the centering calculations are in progress, this
+   * is typically done when the robot is first turned on while it's sitting at rest before the
+   * competition starts.
+   */
+  void calibrate();
+
+  /**
+   * Reset the gyro. Resets the gyro to a heading of zero. This can be used if there is significant
+   * drift in the gyro and it needs to be recalibrated after it has been running.
+   */
+  void reset();
+
+  /**
+   * Return the actual angle in degrees that the robot is currently facing.
+   *
+   * <p>The angle is based on the current accumulator value corrected by the oversampling rate, the
+   * gyro type and the A/D calibration values. The angle is continuous, that is it will continue
+   * from 360 to 361 degrees. This allows algorithms that wouldn't want to see a discontinuity in
+   * the gyro output as it sweeps past from 360 to 0 on the second time around.
+   *
+   * <p>The angle is expected to increase as the gyro turns clockwise when looked
+   * at from the top. It needs to follow NED axis conventions in order to work
+   * properly with dependent control loops.
+   *
+   * <p>This heading is based on integration of the returned rate from the gyro.
+   *
+   * @return the current heading of the robot in degrees.
+   */
+  double getAngle();
+
+  /**
+   * Return the rate of rotation of the gyro.
+   *
+   * <p>The rate is based on the most recent reading of the gyro analog value
+   *
+   * <p>The rate is expected to be positive as the gyro turns clockwise when looked
+   * at from the top. It needs to follow NED axis conventions in order to work
+   * properly with dependent control loops.
+   *
+   * @return the current rate in degrees per second
+   */
+  double getRate();
+
+  /**
+   * Free the resources used by the gyro.
+   */
+  @Deprecated
+  void free();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Potentiometer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Potentiometer.java
new file mode 100644
index 0000000..ea5c1e6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/interfaces/Potentiometer.java
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.interfaces;
+
+import edu.wpi.first.wpilibj.PIDSource;
+
+/**
+ * Interface for a Potentiometer.
+ */
+public interface Potentiometer extends PIDSource {
+  double get();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java
new file mode 100644
index 0000000..1cdb4ab
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindow.java
@@ -0,0 +1,296 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.livewindow;
+
+import java.util.HashMap;
+import java.util.Map;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.Sendable;
+import edu.wpi.first.wpilibj.command.Scheduler;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
+
+
+/**
+ * The LiveWindow class is the public interface for putting sensors and actuators on the
+ * LiveWindow.
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public class LiveWindow {
+  private static class Component {
+    Component(Sendable sendable, Sendable parent) {
+      m_sendable = sendable;
+      m_parent = parent;
+    }
+
+    final Sendable m_sendable;
+    Sendable m_parent;
+    final SendableBuilderImpl m_builder = new SendableBuilderImpl();
+    boolean m_firstTime = true;
+    boolean m_telemetryEnabled = true;
+  }
+
+  @SuppressWarnings("PMD.UseConcurrentHashMap")
+  private static final Map<Object, Component> components = new HashMap<>();
+  private static final NetworkTable liveWindowTable =
+      NetworkTableInstance.getDefault().getTable("LiveWindow");
+  private static final NetworkTable statusTable = liveWindowTable.getSubTable(".status");
+  private static final NetworkTableEntry enabledEntry = statusTable.getEntry("LW Enabled");
+  private static boolean startLiveWindow;
+  private static boolean liveWindowEnabled;
+  private static boolean telemetryEnabled = true;
+
+  private LiveWindow() {
+    throw new UnsupportedOperationException("This is a utility class!");
+  }
+
+  public static synchronized boolean isEnabled() {
+    return liveWindowEnabled;
+  }
+
+  /**
+   * Set the enabled state of LiveWindow. If it's being enabled, turn off the scheduler and remove
+   * all the commands from the queue and enable all the components registered for LiveWindow. If
+   * it's being disabled, stop all the registered components and reenable the scheduler. TODO: add
+   * code to disable PID loops when enabling LiveWindow. The commands should reenable the PID loops
+   * themselves when they get rescheduled. This prevents arms from starting to move around, etc.
+   * after a period of adjusting them in LiveWindow mode.
+   */
+  public static synchronized void setEnabled(boolean enabled) {
+    if (liveWindowEnabled != enabled) {
+      startLiveWindow = enabled;
+      liveWindowEnabled = enabled;
+      updateValues(); // Force table generation now to make sure everything is defined
+      Scheduler scheduler = Scheduler.getInstance();
+      if (enabled) {
+        System.out.println("Starting live window mode.");
+        scheduler.disable();
+        scheduler.removeAll();
+      } else {
+        System.out.println("stopping live window mode.");
+        for (Component component : components.values()) {
+          component.m_builder.stopLiveWindowMode();
+        }
+        scheduler.enable();
+      }
+      enabledEntry.setBoolean(enabled);
+    }
+  }
+
+  /**
+   * The run method is called repeatedly to keep the values refreshed on the screen in test mode.
+   * @deprecated No longer required
+   */
+  @Deprecated
+  public static void run() {
+    updateValues();
+  }
+
+  /**
+   * Add a Sensor associated with the subsystem and with call it by the given name.
+   *
+   * @param subsystem The subsystem this component is part of.
+   * @param name      The name of this component.
+   * @param component A LiveWindowSendable component that represents a sensor.
+   * @deprecated Use {@link Sendable#setName(String, String)} instead.
+   */
+  @Deprecated
+  public static synchronized void addSensor(String subsystem, String name, Sendable component) {
+    add(component);
+    component.setName(subsystem, name);
+  }
+
+  /**
+   * Add Sensor to LiveWindow. The components are shown with the type and channel like this: Gyro[1]
+   * for a gyro object connected to the first analog channel.
+   *
+   * @param moduleType A string indicating the type of the module used in the naming (above)
+   * @param channel    The channel number the device is connected to
+   * @param component  A reference to the object being added
+   * @deprecated Use {@link edu.wpi.first.wpilibj.SendableBase#setName(String, int)} instead.
+   */
+  @Deprecated
+  public static void addSensor(String moduleType, int channel, Sendable component) {
+    add(component);
+    component.setName("Ungrouped", moduleType + "[" + channel + "]");
+  }
+
+  /**
+   * Add an Actuator associated with the subsystem and with call it by the given name.
+   *
+   * @param subsystem The subsystem this component is part of.
+   * @param name      The name of this component.
+   * @param component A LiveWindowSendable component that represents a actuator.
+   * @deprecated Use {@link Sendable#setName(String, String)} instead.
+   */
+  @Deprecated
+  public static synchronized void addActuator(String subsystem, String name, Sendable component) {
+    add(component);
+    component.setName(subsystem, name);
+  }
+
+  /**
+   * Add Actuator to LiveWindow. The components are shown with the module type, slot and channel
+   * like this: Servo[1,2] for a servo object connected to the first digital module and PWM port 2.
+   *
+   * @param moduleType A string that defines the module name in the label for the value
+   * @param channel    The channel number the device is plugged into (usually PWM)
+   * @param component  The reference to the object being added
+   * @deprecated Use {@link edu.wpi.first.wpilibj.SendableBase#setName(String, int)} instead.
+   */
+  @Deprecated
+  public static void addActuator(String moduleType, int channel, Sendable component) {
+    add(component);
+    component.setName("Ungrouped", moduleType + "[" + channel + "]");
+  }
+
+  /**
+   * Add Actuator to LiveWindow. The components are shown with the module type, slot and channel
+   * like this: Servo[1,2] for a servo object connected to the first digital module and PWM port 2.
+   *
+   * @param moduleType   A string that defines the module name in the label for the value
+   * @param moduleNumber The number of the particular module type
+   * @param channel      The channel number the device is plugged into (usually PWM)
+   * @param component    The reference to the object being added
+   * @deprecated Use {@link edu.wpi.first.wpilibj.SendableBase#setName(String, int, int)} instead.
+   */
+  @Deprecated
+  public static void addActuator(String moduleType, int moduleNumber, int channel,
+                                 Sendable component) {
+    add(component);
+    component.setName("Ungrouped", moduleType + "[" + moduleNumber + "," + channel + "]");
+  }
+
+  /**
+   * Add a component to the LiveWindow.
+   *
+   * @param sendable component to add
+   */
+  public static synchronized void add(Sendable sendable) {
+    components.putIfAbsent(sendable, new Component(sendable, null));
+  }
+
+  /**
+   * Add a child component to a component.
+   *
+   * @param parent parent component
+   * @param child child component
+   */
+  public static synchronized void addChild(Sendable parent, Object child) {
+    Component component = components.get(child);
+    if (component == null) {
+      component = new Component(null, parent);
+      components.put(child, component);
+    } else {
+      component.m_parent = parent;
+    }
+    component.m_telemetryEnabled = false;
+  }
+
+  /**
+   * Remove a component from the LiveWindow.
+   *
+   * @param sendable component to remove
+   */
+  public static synchronized void remove(Sendable sendable) {
+    Component component = components.remove(sendable);
+    if (component != null && isEnabled()) {
+      component.m_builder.stopLiveWindowMode();
+    }
+  }
+
+  /**
+   * Enable telemetry for a single component.
+   *
+   * @param sendable component
+   */
+  public static synchronized void enableTelemetry(Sendable sendable) {
+    // Re-enable global setting in case disableAllTelemetry() was called.
+    telemetryEnabled = true;
+    Component component = components.get(sendable);
+    if (component != null) {
+      component.m_telemetryEnabled = true;
+    }
+  }
+
+  /**
+   * Disable telemetry for a single component.
+   *
+   * @param sendable component
+   */
+  public static synchronized void disableTelemetry(Sendable sendable) {
+    Component component = components.get(sendable);
+    if (component != null) {
+      component.m_telemetryEnabled = false;
+    }
+  }
+
+  /**
+   * Disable ALL telemetry.
+   */
+  public static synchronized void disableAllTelemetry() {
+    telemetryEnabled = false;
+    for (Component component : components.values()) {
+      component.m_telemetryEnabled = false;
+    }
+  }
+
+  /**
+   * Tell all the sensors to update (send) their values.
+   *
+   * <p>Actuators are handled through callbacks on their value changing from the
+   * SmartDashboard widgets.
+   */
+  @SuppressWarnings("PMD.CyclomaticComplexity")
+  public static synchronized void updateValues() {
+    // Only do this if either LiveWindow mode or telemetry is enabled.
+    if (!liveWindowEnabled && !telemetryEnabled) {
+      return;
+    }
+
+    for (Component component : components.values()) {
+      if (component.m_sendable != null && component.m_parent == null
+          && (liveWindowEnabled || component.m_telemetryEnabled)) {
+        if (component.m_firstTime) {
+          // By holding off creating the NetworkTable entries, it allows the
+          // components to be redefined. This allows default sensor and actuator
+          // values to be created that are replaced with the custom names from
+          // users calling setName.
+          String name = component.m_sendable.getName();
+          if (name.isEmpty()) {
+            continue;
+          }
+          String subsystem = component.m_sendable.getSubsystem();
+          NetworkTable ssTable = liveWindowTable.getSubTable(subsystem);
+          NetworkTable table;
+          // Treat name==subsystem as top level of subsystem
+          if (name.equals(subsystem)) {
+            table = ssTable;
+          } else {
+            table = ssTable.getSubTable(name);
+          }
+          table.getEntry(".name").setString(name);
+          component.m_builder.setTable(table);
+          component.m_sendable.initSendable(component.m_builder);
+          ssTable.getEntry(".type").setString("LW Subsystem");
+
+          component.m_firstTime = false;
+        }
+
+        if (startLiveWindow) {
+          component.m_builder.startLiveWindowMode();
+        }
+        component.m_builder.updateTable();
+      }
+    }
+
+    startLiveWindow = false;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.java
new file mode 100644
index 0000000..85d88c3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/livewindow/LiveWindowSendable.java
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.livewindow;
+
+import edu.wpi.first.wpilibj.Sendable;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * Live Window Sendable is a special type of object sendable to the live window.
+ * @deprecated Use Sendable directly instead
+ */
+@Deprecated
+public interface LiveWindowSendable extends Sendable {
+  /**
+   * Update the table for this sendable object with the latest values.
+   */
+  void updateTable();
+
+  /**
+   * Start having this sendable object automatically respond to value changes reflect the value on
+   * the table.
+   */
+  void startLiveWindowMode();
+
+  /**
+   * Stop having this sendable object automatically respond to value changes.
+   */
+  void stopLiveWindowMode();
+
+  @Override
+  default String getName() {
+    return "";
+  }
+
+  @Override
+  default void setName(String name) {
+  }
+
+  @Override
+  default String getSubsystem() {
+    return "";
+  }
+
+  @Override
+  default void setSubsystem(String subsystem) {
+  }
+
+  @Override
+  default void initSendable(SendableBuilder builder) {
+    builder.setUpdateTable(this::updateTable);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/package.html b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/package.html
new file mode 100644
index 0000000..d11ae27
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/package.html
@@ -0,0 +1,30 @@
+<!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.01 Transitional//EN">
+<html>
+  <head>
+    <title>
+      WPI Robotics library
+    </title>
+    <meta http-equiv="Content-Type" content="text/html; charset=utf-8">
+  </head>
+  <body>
+    The WPI Robotics library (WPILibJ) is a set of Java classes that interfaces
+    to the hardware in the FRC control system and your robot. There are classes
+    to handle sensors, motors, the driver station, and a number of other
+    utility functions like timing and field management. The library is designed
+    to:
+    <ul>
+      <li>Deal with all the low level interfacing to these components so you
+      can concentrate on solving this year's "robot problem". This is a
+      philosophical decision to let you focus on the higher-level design of
+      your robot rather than deal with the details of the processor and the
+      operating system.
+      </li>
+      <li>Understand everything at all levels by making the full source code of
+      the library available. You can study (and modify) the algorithms used by
+      the gyro class for oversampling and integration of the input signal or
+      just ask the class for the current robot heading. You can work at any
+      level.
+      </li>
+    </ul>
+  </body>
+</html>
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInLayouts.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInLayouts.java
new file mode 100644
index 0000000..27c3e8c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInLayouts.java
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+/**
+ * The types of layouts bundled with Shuffleboard.
+ *
+ * <pre>{@code
+ * ShuffleboardLayout myList = Shuffleboard.getTab("My Tab")
+ *   .getLayout(BuiltinLayouts.kList, "My List");
+ * }</pre>
+ */
+public enum BuiltInLayouts implements LayoutType {
+  /**
+   * 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>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Label position</td><td>String</td><td>"BOTTOM"</td>
+   * <td>The position of component labels inside the grid. One of
+   * {@code ["TOP", "LEFT", "BOTTOM", "RIGHT", "HIDDEN"}</td></tr>
+   * </table>
+   */
+  kList("List Layout"),
+
+  /**
+   * Groups components in an <i>n</i> x <i>m</i> grid. Grid layouts default to 3x3.
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Number of columns</td><td>Number</td><td>3</td><td>Must be in the range [1,15]</td>
+   * </tr>
+   * <tr><td>Number of rows</td><td>Number</td><td>3</td><td>Must be in the range [1,15]</td></tr>
+   * <tr>
+   * <td>Label position</td>
+   * <td>String</td>
+   * <td>"BOTTOM"</td>
+   * <td>The position of component labels inside the grid.
+   * One of {@code ["TOP", "LEFT", "BOTTOM", "RIGHT", "HIDDEN"}</td>
+   * </tr>
+   * </table>
+   */
+  kGrid("Grid Layout"),
+  ;
+
+  private final String m_layoutName;
+
+  BuiltInLayouts(String layoutName) {
+    m_layoutName = layoutName;
+  }
+
+  @Override
+  public String getLayoutName() {
+    return m_layoutName;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java
new file mode 100644
index 0000000..14742e5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/BuiltInWidgets.java
@@ -0,0 +1,399 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import edu.wpi.first.wpilibj.interfaces.Accelerometer.Range;
+
+/**
+ * The types of the widgets bundled with Shuffleboard.
+ *
+ * <p>For example, setting a number to be displayed with a slider:
+ * <pre>{@code
+ * NetworkTableEntry example = Shuffleboard.getTab("My Tab")
+ *   .add("My Number", 0)
+ *   .withWidget(BuiltInWidgets.kNumberSlider)
+ *   .withProperties(Map.of("min", 0, "max", 1))
+ *   .getEntry();
+ * }</pre>
+ *
+ * <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.
+ */
+public enum BuiltInWidgets implements WidgetType {
+  /**
+   * Displays a value with a simple text field.
+   * <br>Supported types:
+   * <ul>
+   * <li>String</li>
+   * <li>Number</li>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kTextView("Text View"),
+  /**
+   * Displays a number with a controllable slider.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1.0</td><td>The minimum value of the slider</td></tr>
+   * <tr><td>Max</td><td>Number</td><td>1.0</td><td>The maximum value of the slider</td></tr>
+   * <tr><td>Block increment</td><td>Number</td><td>0.0625</td>
+   * <td>How much to move the slider by with the arrow keys</td></tr>
+   * </table>
+   */
+  kNumberSlider("Number Slider"),
+  /**
+   * Displays a number with a view-only bar.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1.0</td><td>The minimum value of the bar</td></tr>
+   * <tr><td>Max</td><td>Number</td><td>1.0</td><td>The maximum value of the bar</td></tr>
+   * <tr><td>Center</td><td>Number</td><td>0</td><td>The center ("zero") value of the bar</td></tr>
+   * </table>
+   */
+  kNumberBar("Number Bar"),
+  /**
+   * Displays a number with a view-only dial. Displayed values are rounded to the nearest integer.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>0</td><td>The minimum value of the dial</td></tr>
+   * <tr><td>Max</td><td>Number</td><td>100</td><td>The maximum value of the dial</td></tr>
+   * <tr><td>Show value</td><td>Boolean</td><td>true</td>
+   * <td>Whether or not to show the value as text</td></tr>
+   * </table>
+   */
+  kDial("Simple Dial"),
+  /**
+   * 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 points to a minimum. Making the widget
+   * smaller also helps with performance, but may cause the graph to become difficult to read.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * <li>Number array</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Visible time</td><td>Number</td><td>30</td>
+   * <td>How long, in seconds, should past data be visible for</td></tr>
+   * </table>
+   */
+  kGraph("Graph"),
+  /**
+   * Displays a boolean value as a large colored box.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Color when true</td><td>Color</td><td>"green"</td>
+   * <td>Can be specified as a string ({@code "#00FF00"}) or a rgba integer ({@code 0x00FF0000})
+   * </td></tr>
+   * <tr><td>Color when false</td><td>Color</td><td>"red"</td>
+   * <td>Can be specified as a string or a number</td></tr>
+   * </table>
+   */
+  kBooleanBox("Boolean Box"),
+  /**
+   * Displays a boolean with a large interactive toggle button.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kToggleButton("Toggle Button"),
+  /**
+   * Displays a boolean with a fixed-size toggle switch.
+   * <br>Supported types:
+   * <ul>
+   * <li>Boolean</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kToggleSwitch("Toggle Switch"),
+  /**
+   * Displays an analog input or a raw number with a number bar.
+   * <br>Supported types:
+   * <ul>
+   * <li>Number</li>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogInput}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>0</td><td>The minimum value of the bar</td></tr>
+   * <tr><td>Max</td><td>Number</td><td>5</td><td>The maximum value of the bar</td></tr>
+   * <tr><td>Center</td><td>Number</td><td>0</td><td>The center ("zero") value of the bar</td></tr>
+   * <tr><td>Orientation</td><td>String</td><td>"HORIZONTAL"</td>
+   * <td>The orientation of the bar. One of {@code ["HORIZONTAL", "VERTICAL"]}</td></tr>
+   * <tr><td>Number of tick marks</td><td>Number</td><td>5</td>
+   * <td>The number of discrete ticks on the bar</td></tr>
+   * </table>
+   */
+  kVoltageView("Voltage View"),
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.PowerDistributionPanel PowerDistributionPanel}.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.PowerDistributionPanel}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show voltage and current values</td><td>Boolean</td><td>true</td>
+   * <td>Whether or not to display the voltage and current draw</td></tr>
+   * </table>
+   */
+  kPowerDistributionPanel("PDP"),
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser SendableChooser} with
+   * a dropdown combo box with a list of options.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kComboBoxChooser("ComboBox Chooser"),
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser SendableChooser} with
+   * a toggle button for each available option.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.smartdashboard.SendableChooser}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kSplitButtonChooser("Split Button Chooser"),
+  /**
+   * Displays an {@link edu.wpi.first.wpilibj.Encoder} displaying its speed, total travelled
+   * distance, and its distance per tick.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.Encoder}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kEncoder("Encoder"),
+  /**
+   * Displays a {@link edu.wpi.first.wpilibj.SpeedController SpeedController}. The speed controller
+   * will be controllable from the dashboard when test mode is enabled, but will otherwise be
+   * view-only.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.PWMSpeedController}</li>
+   * <li>{@link edu.wpi.first.wpilibj.DMC60}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Jaguar}</li>
+   * <li>{@link edu.wpi.first.wpilibj.PWMTalonSRX}</li>
+   * <li>{@link edu.wpi.first.wpilibj.PWMVictorSPX}</li>
+   * <li>{@link edu.wpi.first.wpilibj.SD540}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Spark}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Talon}</li>
+   * <li>{@link edu.wpi.first.wpilibj.Victor}</li>
+   * <li>{@link edu.wpi.first.wpilibj.VictorSP}</li>
+   * <li>{@link edu.wpi.first.wpilibj.SpeedControllerGroup}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Orientation</td><td>String</td><td>"HORIZONTAL"</td>
+   * <td>One of {@code ["HORIZONTAL", "VERTICAL"]}</td></tr>
+   * </table>
+   */
+  kSpeedController("Speed Controller"),
+  /**
+   * Displays a command with a toggle button. Pressing the button will start the command, and the
+   * button will automatically release when the command completes.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.command.Command}</li>
+   * <li>{@link edu.wpi.first.wpilibj.command.CommandGroup}</li>
+   * <li>Any custom subclass of {@code Command} or {@code CommandGroup}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kCommand("Command"),
+  /**
+   * Displays a PID command with a checkbox and an editor for the PIDF constants. Selecting the
+   * checkbox will start the command, and the checkbox will automatically deselect when the command
+   * completes.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.command.PIDCommand}</li>
+   * <li>Any custom subclass of {@code PIDCommand}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kPIDCommand("PID Command"),
+  /**
+   * Displays a PID controller with an editor for the PIDF constants and a toggle switch for
+   * enabling and disabling the controller.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.PIDController}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kPIDController("PID Controller"),
+  /**
+   * Displays an accelerometer with a number bar displaying the magnitude of the acceleration and
+   * text displaying the exact value.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogAccelerometer}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Min</td><td>Number</td><td>-1</td>
+   * <td>The minimum acceleration value to display</td></tr>
+   * <tr><td>Max</td><td>Number</td><td>1</td>
+   * <td>The maximum acceleration value to display</td></tr>
+   * <tr><td>Show text</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide the acceleration values</td></tr>
+   * <tr><td>Precision</td><td>Number</td><td>2</td>
+   * <td>How many numbers to display after the decimal point</td></tr>
+   * <tr><td>Show tick marks</td><td>Boolean</td><td>false</td>
+   * <td>Show or hide the tick marks on the number bars</td></tr>
+   * </table>
+   */
+  kAccelerometer("Accelerometer"),
+  /**
+   * Displays a 3-axis accelerometer with a number bar for each axis' accleration.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.ADXL345_I2C}</li>
+   * <li>{@link edu.wpi.first.wpilibj.ADXL345_SPI}</li>
+   * <li>{@link edu.wpi.first.wpilibj.ADXL362}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Range</td><td>{@link Range}</td><td>k16G</td><td>The accelerometer range</td></tr>
+   * <tr><td>Show value</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide the acceleration values</td></tr>
+   * <tr><td>Precision</td><td>Number</td><td>2</td>
+   * <td>How many numbers to display after the decimal point</td></tr>
+   * <tr><td>Show tick marks</td><td>Boolean</td><td>false</td>
+   * <td>Show or hide the tick marks on the number bars</td></tr>
+   * </table>
+   */
+  k3AxisAccelerometer("3-Axis Accelerometer"),
+  /**
+   * Displays a gyro with a dial from 0 to 360 degrees.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.ADXRS450_Gyro}</li>
+   * <li>{@link edu.wpi.first.wpilibj.AnalogGyro}</li>
+   * <li>Any custom subclass of {@code GyroBase} (such as a MXP gyro)</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Major tick spacing</td><td>Number</td><td>45</td><td>Degrees</td></tr>
+   * <tr><td>Starting angle</td><td>Number</td><td>180</td>
+   * <td>How far to rotate the entire dial, in degrees</td></tr>
+   * <tr><td>Show tick mark ring</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  kGyro("Gyro"),
+  /**
+   * Displays a relay with toggle buttons for each supported mode (off, on, forward, reverse).
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.Relay}</li>
+   * </ul>
+   * <br>This widget has no custom properties.
+   */
+  kRelay("Relay"),
+  /**
+   * 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 drivebase. The widget will be
+   * controllable if the robot is in test mode.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.drive.DifferentialDrive}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Number of wheels</td><td>Number</td><td>4</td><td>Must be a positive even integer
+   * </td></tr>
+   * <tr><td>Wheel diameter</td><td>Number</td><td>80</td><td>Pixels</td></tr>
+   * <tr><td>Show velocity vectors</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  kDifferentialDrive("Differential Drivebase"),
+  /**
+   * 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 widget will be controllable if the robot is
+   * in test mode.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.first.wpilibj.drive.MecanumDrive}</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show velocity vectors</td><td>Boolean</td><td>true</td></tr>
+   * </table>
+   */
+  kMecanumDrive("Mecanum Drivebase"),
+  /**
+   * Displays a camera stream.
+   * <br>Supported types:
+   * <ul>
+   * <li>{@link edu.wpi.cscore.VideoSource} (as long as it is streaming on an MJPEG server)</li>
+   * </ul>
+   * <br>Custom properties:
+   * <table>
+   * <tr><th>Name</th><th>Type</th><th>Default Value</th><th>Notes</th></tr>
+   * <tr><td>Show crosshair</td><td>Boolean</td><td>true</td>
+   * <td>Show or hide a crosshair on the image</td></tr>
+   * <tr><td>Crosshair color</td><td>Color</td><td>"white"</td>
+   * <td>Can be a string or a rgba integer</td></tr>
+   * <tr><td>Show controls</td><td>Boolean</td><td>true</td><td>Show or hide the stream controls
+   * </td></tr>
+   * <tr><td>Rotation</td><td>String</td><td>"NONE"</td>
+   * <td>Rotates the displayed image. One of {@code ["NONE", "QUARTER_CW", "QUARTER_CCW", "HALF"]}
+   * </td></tr>
+   * </table>
+   */
+  kCameraStream("Camera Stream"),
+  ;
+
+  private final String m_widgetName;
+
+  BuiltInWidgets(String widgetName) {
+    this.m_widgetName = widgetName;
+  }
+
+  @Override
+  public String getWidgetName() {
+    return m_widgetName;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ComplexWidget.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ComplexWidget.java
new file mode 100644
index 0000000..d56fde8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ComplexWidget.java
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.wpilibj.Sendable;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
+
+/**
+ * A Shuffleboard widget that handles a {@link Sendable} object such as a speed controller or
+ * sensor.
+ */
+public final class ComplexWidget extends ShuffleboardWidget<ComplexWidget> {
+  private final Sendable m_sendable;
+  private SendableBuilderImpl m_builder;
+
+  ComplexWidget(ShuffleboardContainer parent, String title, Sendable sendable) {
+    super(parent, title);
+    m_sendable = sendable;
+  }
+
+  @Override
+  public void buildInto(NetworkTable parentTable, NetworkTable metaTable) {
+    buildMetadata(metaTable);
+    if (m_builder == null) {
+      m_builder = new SendableBuilderImpl();
+      m_builder.setTable(parentTable.getSubTable(getTitle()));
+      m_sendable.initSendable(m_builder);
+      m_builder.startListeners();
+    }
+    m_builder.updateTable();
+  }
+
+  /**
+   * Enables user control of this widget in the Shuffleboard application. This method is
+   * package-private to prevent users from enabling control themselves. Has no effect if the
+   * sendable is not marked as an actuator with {@link SendableBuilder#setActuator}.
+   */
+  void enableIfActuator() {
+    if (m_builder.isActuator()) {
+      m_builder.startLiveWindowMode();
+    }
+  }
+
+  /**
+   * Disables user control of this widget in the Shuffleboard application. This method is
+   * package-private to prevent users from enabling control themselves. Has no effect if the
+   * sendable is not marked as an actuator with {@link SendableBuilder#setActuator}.
+   */
+  void disableIfActuator() {
+    if (m_builder.isActuator()) {
+      m_builder.stopLiveWindowMode();
+    }
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java
new file mode 100644
index 0000000..9cb63a0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ContainerHelper.java
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import java.util.ArrayList;
+import java.util.HashSet;
+import java.util.LinkedHashMap;
+import java.util.List;
+import java.util.Map;
+import java.util.NoSuchElementException;
+import java.util.Objects;
+import java.util.Set;
+
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.wpilibj.Sendable;
+
+/**
+ * A helper class for Shuffleboard containers to handle common child operations.
+ */
+final class ContainerHelper {
+  private final ShuffleboardContainer m_container;
+  private final Set<String> m_usedTitles = new HashSet<>();
+  private final List<ShuffleboardComponent<?>> m_components = new ArrayList<>();
+  private final Map<String, ShuffleboardLayout> m_layouts = new LinkedHashMap<>();
+
+  ContainerHelper(ShuffleboardContainer container) {
+    m_container = container;
+  }
+
+  List<ShuffleboardComponent<?>> getComponents() {
+    return m_components;
+  }
+
+  ShuffleboardLayout getLayout(String title, String type) {
+    if (!m_layouts.containsKey(title)) {
+      ShuffleboardLayout layout = new ShuffleboardLayout(m_container, type, title);
+      m_components.add(layout);
+      m_layouts.put(title, layout);
+    }
+    return m_layouts.get(title);
+  }
+
+  ShuffleboardLayout getLayout(String title) {
+    ShuffleboardLayout layout = m_layouts.get(title);
+    if (layout == null) {
+      throw new NoSuchElementException("No layout has been defined with the title '" + title + "'");
+    }
+    return layout;
+  }
+
+  ComplexWidget add(String title, Sendable sendable) {
+    checkTitle(title);
+    ComplexWidget widget = new ComplexWidget(m_container, title, sendable);
+    m_components.add(widget);
+    return widget;
+  }
+
+  ComplexWidget add(Sendable sendable) throws IllegalArgumentException {
+    if (sendable.getName() == null || sendable.getName().isEmpty()) {
+      throw new IllegalArgumentException("Sendable must have a name");
+    }
+    return add(sendable.getName(), sendable);
+  }
+
+  SimpleWidget add(String title, Object defaultValue) {
+    Objects.requireNonNull(title, "Title cannot be null");
+    Objects.requireNonNull(defaultValue, "Default value cannot be null");
+    checkTitle(title);
+    checkNtType(defaultValue);
+
+    SimpleWidget widget = new SimpleWidget(m_container, title);
+    m_components.add(widget);
+    widget.getEntry().setDefaultValue(defaultValue);
+    return widget;
+  }
+
+  private static void checkNtType(Object data) {
+    if (!NetworkTableEntry.isValidDataType(data)) {
+      throw new IllegalArgumentException(
+          "Cannot add data of type " + data.getClass().getName() + " to Shuffleboard");
+    }
+  }
+
+  private void checkTitle(String title) {
+    if (m_usedTitles.contains(title)) {
+      throw new IllegalArgumentException("Title is already in use: " + title);
+    }
+    m_usedTitles.add(title);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/EventImportance.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/EventImportance.java
new file mode 100644
index 0000000..08f9712
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/EventImportance.java
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+/**
+ * The importance of an event marker in Shuffleboard.  The exact meaning of each importance level is
+ * up for interpretation on a team-to-team basis, but users should follow the general guidelines
+ * of the various importance levels.  The examples given are for reference and may be ignored or
+ * considered to be more or less important from team to team.
+ */
+public enum EventImportance {
+  // Maintainer note: this enum is mirrored in WPILibC and in Shuffleboard
+  // Modifying the enum or enum strings requires a corresponding change to the C++ enum
+  // and the enum in Shuffleboard
+
+  /**
+   * A trivial event such as a change in command state.
+   */
+  kTrivial("TRIVIAL"),
+
+  /**
+   * A low importance event such as acquisition of a game piece.
+   */
+  kLow("LOW"),
+
+  /**
+   * A "normal" importance event, such as a transition from autonomous mode to teleoperated control.
+   */
+  kNormal("NORMAL"),
+
+  /**
+   * A high-importance event such as scoring a game piece.
+   */
+  kHigh("HIGH"),
+
+  /**
+   * A critically important event such as a brownout, component failure, or software deadlock.
+   */
+  kCritical("CRITICAL");
+
+  private final String m_simpleName;
+
+  EventImportance(String simpleName) {
+    m_simpleName = simpleName;
+  }
+
+  public String getSimpleName() {
+    return m_simpleName;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/LayoutType.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/LayoutType.java
new file mode 100644
index 0000000..2d7b565
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/LayoutType.java
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+/**
+ * Represents the type of a layout in Shuffleboard. Using this is preferred over specifying raw
+ * strings, to avoid typos and having to know or look up the exact string name for a desired layout.
+ *
+ * @see BuiltInWidgets the built-in widget types
+ */
+public interface LayoutType {
+  /**
+   * Gets the string type of the layout as defined by that layout in Shuffleboard.
+   */
+  String getLayoutName();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/RecordingController.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/RecordingController.java
new file mode 100644
index 0000000..9f04274
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/RecordingController.java
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.DriverStation;
+
+/**
+ * Controls Shuffleboard recordings via NetworkTables.
+ */
+final class RecordingController {
+  private static final String kRecordingTableName = "/Shuffleboard/.recording/";
+  private static final String kRecordingControlKey = kRecordingTableName + "RecordData";
+  private static final String kRecordingFileNameFormatKey = kRecordingTableName + "FileNameFormat";
+  private static final String kEventMarkerTableName = kRecordingTableName + "events";
+
+  private final NetworkTableEntry m_recordingControlEntry;
+  private final NetworkTableEntry m_recordingFileNameFormatEntry;
+  private final NetworkTable m_eventsTable;
+
+  RecordingController(NetworkTableInstance ntInstance) {
+    m_recordingControlEntry = ntInstance.getEntry(kRecordingControlKey);
+    m_recordingFileNameFormatEntry = ntInstance.getEntry(kRecordingFileNameFormatKey);
+    m_eventsTable = ntInstance.getTable(kEventMarkerTableName);
+  }
+
+  public void startRecording() {
+    m_recordingControlEntry.setBoolean(true);
+  }
+
+  public void stopRecording() {
+    m_recordingControlEntry.setBoolean(false);
+  }
+
+  public void setRecordingFileNameFormat(String format) {
+    m_recordingFileNameFormatEntry.setString(format);
+  }
+
+  public void clearRecordingFileNameFormat() {
+    m_recordingFileNameFormatEntry.delete();
+  }
+
+  public void addEventMarker(String name, String description, EventImportance importance) {
+    if (name == null || name.isEmpty()) {
+      DriverStation.reportError(
+          "Shuffleboard event name was not specified", true);
+      return;
+    }
+
+    if (importance == null) {
+      DriverStation.reportError(
+          "Shuffleboard event importance was null", true);
+      return;
+    }
+
+    String eventDescription = description == null ? "" : description;
+
+    m_eventsTable.getSubTable(name)
+        .getEntry("Info")
+        .setStringArray(new String[]{eventDescription, importance.getSimpleName()});
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java
new file mode 100644
index 0000000..7aa93ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SendableCameraWrapper.java
@@ -0,0 +1,57 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import java.util.Map;
+import java.util.WeakHashMap;
+
+import edu.wpi.cscore.VideoSource;
+import edu.wpi.first.wpilibj.Sendable;
+import edu.wpi.first.wpilibj.SendableBase;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * A wrapper to make video sources sendable and usable from Shuffleboard.
+ */
+public final class SendableCameraWrapper extends SendableBase {
+  private static final String kProtocol = "camera_server://";
+
+  private static Map<VideoSource, SendableCameraWrapper> m_wrappers = new WeakHashMap<>();
+
+  private final String m_uri;
+
+  /**
+   * Creates a new sendable wrapper. Private constructor to avoid direct instantiation with
+   * multiple wrappers floating around for the same camera.
+   *
+   * @param source the source to wrap
+   */
+  private SendableCameraWrapper(VideoSource source) {
+    super(false);
+    String name = source.getName();
+    setName(name);
+    m_uri = kProtocol + name;
+  }
+
+  /**
+   * Gets a sendable wrapper object for the given video source, creating the wrapper if one does
+   * not already exist for the source.
+   *
+   * @param source the video source to wrap
+   * @return a sendable wrapper object for the video source, usable in Shuffleboard via
+   * {@link ShuffleboardTab#add(Sendable)} and {@link ShuffleboardLayout#add(Sendable)}
+   */
+  public static SendableCameraWrapper wrap(VideoSource source) {
+    return m_wrappers.computeIfAbsent(source, SendableCameraWrapper::new);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.addStringProperty(".ShuffleboardURI", () -> m_uri, null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/Shuffleboard.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/Shuffleboard.java
new file mode 100644
index 0000000..fbce24a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/Shuffleboard.java
@@ -0,0 +1,201 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+/**
+ * The Shuffleboard class provides a mechanism with which data can be added and laid out in the
+ * Shuffleboard dashboard application from a robot program. Tabs and layouts can be specified, as
+ * well as choosing which widgets to display with and setting properties of these widgets; for
+ * example, programmers can specify a specific {@code boolean} value to be displayed with a toggle
+ * button instead of the default colored box, or set custom colors for that box.
+ *
+ * <p>For example, displaying a boolean entry with a toggle button:
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .add("My Boolean", false)
+ *   .withWidget("Toggle Button")
+ *   .getEntry();
+ * }</pre>
+ *
+ * Changing the colors of the boolean box:
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .add("My Boolean", false)
+ *   .withWidget("Boolean Box")
+ *   .withProperties(Map.of("colorWhenTrue", "green", "colorWhenFalse", "maroon"))
+ *   .getEntry();
+ * }</pre>
+ *
+ * Specifying a parent layout. Note that the layout type must <i>always</i> be specified, even if
+ * the layout has already been generated by a previously defined entry.
+ * <pre>{@code
+ * NetworkTableEntry myBoolean = Shuffleboard.getTab("Example Tab")
+ *   .getLayout("List", "Example List")
+ *   .add("My Boolean", false)
+ *   .withWidget("Toggle Button")
+ *   .getEntry();
+ * }</pre>
+ * </p>
+ *
+ * <p>Teams are encouraged to set up shuffleboard layouts at the start of the robot program.</p>
+ */
+public final class Shuffleboard {
+  /**
+   * The name of the base NetworkTable into which all Shuffleboard data will be added.
+   */
+  public static final String kBaseTableName = "/Shuffleboard";
+
+  private static final ShuffleboardRoot root =
+      new ShuffleboardInstance(NetworkTableInstance.getDefault());
+  private static final RecordingController recordingController =
+      new RecordingController(NetworkTableInstance.getDefault());
+
+  // TODO usage reporting
+
+  private Shuffleboard() {
+    throw new UnsupportedOperationException("This is a utility class and cannot be instantiated");
+  }
+
+  /**
+   * Updates all the values in Shuffleboard. Iterative and timed robots are pre-configured to call
+   * this method in the main robot loop; teams using custom robot base classes, or subclass
+   * SampleRobot, should make sure to call this repeatedly to keep data on the dashboard up to date.
+   */
+  public static void update() {
+    root.update();
+  }
+
+  /**
+   * Gets the Shuffleboard tab with the given title, creating it if it does not already exist.
+   *
+   * @param title the title of the tab
+   * @return the tab with the given title
+   */
+  public static ShuffleboardTab getTab(String title) {
+    return root.getTab(title);
+  }
+
+  /**
+   * Selects the tab in the dashboard with the given index in the range [0..n-1], where <i>n</i>
+   * is the number of tabs in the dashboard at the time this method is called.
+   *
+   * @param index the index of the tab to select
+   */
+  public static void selectTab(int index) {
+    root.selectTab(index);
+  }
+
+  /**
+   * Selects the tab in the dashboard with the given title.
+   *
+   * @param title the title of the tab to select
+   */
+  public static void selectTab(String title) {
+    root.selectTab(title);
+  }
+
+  /**
+   * Enables user control of widgets containing actuators: speed controllers, relays, etc. This
+   * should only be used when the robot is in test mode. IterativeRobotBase and SampleRobot are
+   * both configured to call this method when entering test mode; most users should not need to use
+   * this method directly.
+   */
+  public static void enableActuatorWidgets() {
+    root.enableActuatorWidgets();
+  }
+
+  /**
+   * Disables user control of widgets containing actuators. For safety reasons, actuators should
+   * only be controlled while in test mode. IterativeRobotBase and SampleRobot are both configured
+   * to call this method when exiting in test mode; most users should not need to use
+   * this method directly.
+   */
+  public static void disableActuatorWidgets() {
+    update(); // Need to update to make sure the sendable builders are initialized
+    root.disableActuatorWidgets();
+  }
+
+  /**
+   * Starts data recording on the dashboard. Has no effect if recording is already in progress.
+   *
+   * @see #stopRecording()
+   */
+  public static void startRecording() {
+    recordingController.startRecording();
+  }
+
+  /**
+   * Stops data recording on the dashboard. Has no effect if no recording is in progress.
+   *
+   * @see #startRecording()
+   */
+  public static void stopRecording() {
+    recordingController.stopRecording();
+  }
+
+  /**
+   * Sets the file name format for new recording files to use. If recording is in progress when this
+   * method is called, it will continue to use the same file. New recordings will use the format.
+   *
+   * <p>To avoid recording files overwriting each other, make sure to use unique recording file
+   * names. File name formats accept templates for inserting the date and time when the recording
+   * started with the {@code ${date}} and {@code ${time}} templates, respectively. For example,
+   * the default format is {@code "recording-${time}"} and recording files created with it will have
+   * names like {@code "recording-2018.01.15.sbr"}. Users are <strong>strongly</strong> recommended
+   * to use the {@code ${time}} template to ensure unique file names.
+   * </p>
+   *
+   * @param format the format for the
+   * @see #clearRecordingFileNameFormat()
+   */
+  public static void setRecordingFileNameFormat(String format) {
+    recordingController.setRecordingFileNameFormat(format);
+  }
+
+  /**
+   * Clears the custom name format for recording files. New recordings will use the default format.
+   *
+   * @see #setRecordingFileNameFormat(String)
+   */
+  public static void clearRecordingFileNameFormat() {
+    recordingController.clearRecordingFileNameFormat();
+  }
+
+  /**
+   * Notifies Shuffleboard of an event. Events can range from as trivial as a change in a command
+   * state to as critical as a total power loss or component failure. If Shuffleboard is recording,
+   * the event will also be recorded.
+   *
+   * <p>If {@code name} is {@code null} or empty, or {@code importance} is {@code null}, then
+   * no event will be sent and an error will be printed to the driver station.
+   *
+   * @param name        the name of the event
+   * @param description a description of the event
+   * @param importance  the importance of the event
+   */
+  public static void addEventMarker(String name, String description, EventImportance importance) {
+    recordingController.addEventMarker(name, description, importance);
+  }
+
+  /**
+   * Notifies Shuffleboard of an event. Events can range from as trivial as a change in a command
+   * state to as critical as a total power loss or component failure. If Shuffleboard is recording,
+   * the event will also be recorded.
+   *
+   * <p>If {@code name} is {@code null} or empty, or {@code importance} is {@code null}, then
+   * no event will be sent and an error will be printed to the driver station.
+   *
+   * @param name        the name of the event
+   * @param importance  the importance of the event
+   */
+  public static void addEventMarker(String name, EventImportance importance) {
+    addEventMarker(name, "", importance);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java
new file mode 100644
index 0000000..ba87d82
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardComponent.java
@@ -0,0 +1,147 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import java.util.Map;
+import java.util.Objects;
+
+import edu.wpi.first.networktables.NetworkTable;
+
+/**
+ * A generic component in Shuffleboard.
+ *
+ * @param <C> the self type
+ */
+public abstract class ShuffleboardComponent<C extends ShuffleboardComponent<C>>
+    implements ShuffleboardValue {
+  private final ShuffleboardContainer m_parent;
+  private final String m_title;
+  private String m_type;
+  private Map<String, Object> m_properties;
+  private boolean m_metadataDirty = true;
+  private int m_column = -1;
+  private int m_row = -1;
+  private int m_width = -1;
+  private int m_height = -1;
+
+  protected ShuffleboardComponent(ShuffleboardContainer parent, String title, String type) {
+    m_parent = Objects.requireNonNull(parent, "Parent cannot be null");
+    m_title = Objects.requireNonNull(title, "Title cannot be null");
+    m_type = type;
+  }
+
+  protected ShuffleboardComponent(ShuffleboardContainer parent, String title) {
+    this(parent, title, null);
+  }
+
+  public final ShuffleboardContainer getParent() {
+    return m_parent;
+  }
+
+  protected final void setType(String type) {
+    m_type = type;
+    m_metadataDirty = true;
+  }
+
+  public final String getType() {
+    return m_type;
+  }
+
+  @Override
+  public final String getTitle() {
+    return m_title;
+  }
+
+  /**
+   * Gets the custom properties for this component. May be null.
+   */
+  final Map<String, Object> getProperties() {
+    return m_properties;
+  }
+
+  /**
+   * Sets custom properties for this component. Property names are case- and whitespace-insensitive
+   * (capitalization and spaces do not matter).
+   *
+   * @param properties the properties for this component
+   * @return this component
+   */
+  public final C withProperties(Map<String, Object> properties) {
+    m_properties = properties;
+    m_metadataDirty = true;
+    return (C) this;
+  }
+
+  /**
+   * Sets the position of this component in the tab. This has no effect if this component is inside
+   * a layout.
+   *
+   * <p>If the position of a single component is set, it is recommended to set the positions of
+   * <i>all</i> components inside a tab to prevent Shuffleboard from automatically placing another
+   * component there before the one with the specific position is sent.
+   *
+   * @param columnIndex the column in the tab to place this component
+   * @param rowIndex    the row in the tab to place this component
+   * @return this component
+   */
+  public final C withPosition(int columnIndex, int rowIndex) {
+    m_column = columnIndex;
+    m_row = rowIndex;
+    m_metadataDirty = true;
+    return (C) this;
+  }
+
+  /**
+   * Sets the size of this component in the tab. This has no effect if this component is inside a
+   * layout.
+   *
+   * @param width  how many columns wide the component should be
+   * @param height how many rows high the component should be
+   * @return this component
+   */
+  public final C withSize(int width, int height) {
+    m_width = width;
+    m_height = height;
+    m_metadataDirty = true;
+    return (C) this;
+  }
+
+  protected final void buildMetadata(NetworkTable metaTable) {
+    if (!m_metadataDirty) {
+      return;
+    }
+    // Component type
+    if (getType() == null) {
+      metaTable.getEntry("PreferredComponent").delete();
+    } else {
+      metaTable.getEntry("PreferredComponent").forceSetString(getType());
+    }
+
+    // Tile size
+    if (m_width <= 0 || m_height <= 0) {
+      metaTable.getEntry("Size").delete();
+    } else {
+      metaTable.getEntry("Size").setDoubleArray(new double[]{m_width, m_height});
+    }
+
+    // Tile position
+    if (m_column < 0 || m_row < 0) {
+      metaTable.getEntry("Position").delete();
+    } else {
+      metaTable.getEntry("Position").setDoubleArray(new double[]{m_column, m_row});
+    }
+
+    // Custom properties
+    if (getProperties() != null) {
+      NetworkTable propTable = metaTable.getSubTable("Properties");
+      getProperties().forEach((name, value) -> propTable.getEntry(name).setValue(value));
+    }
+    m_metadataDirty = false;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java
new file mode 100644
index 0000000..a322af1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardContainer.java
@@ -0,0 +1,146 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import java.util.List;
+import java.util.NoSuchElementException;
+
+import edu.wpi.cscore.VideoSource;
+import edu.wpi.first.wpilibj.Sendable;
+
+/**
+ * Common interface for objects that can contain shuffleboard components.
+ */
+public interface ShuffleboardContainer extends ShuffleboardValue {
+
+  /**
+   * Gets the components that are direct children of this container.
+   */
+  List<ShuffleboardComponent<?>> getComponents();
+
+  /**
+   * Gets the layout with the given type and title, creating it if it does not already exist at the
+   * time this method is called. Note: this method should only be used to use a layout type that
+   * is not already built into Shuffleboard. To use a layout built into Shuffleboard, use
+   * {@link #getLayout(String, LayoutType)} and the layouts in {@link BuiltInLayouts}.
+   *
+   * @param title the title of the layout
+   * @param type  the type of the layout, eg "List Layout" or "Grid Layout"
+   * @return the layout
+   * @see #getLayout(String, LayoutType)
+   */
+  ShuffleboardLayout getLayout(String title, String 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
+   */
+  default ShuffleboardLayout getLayout(String title, LayoutType layoutType) {
+    return getLayout(title, layoutType.getLayoutName());
+  }
+
+  /**
+   * Gets the already-defined layout in this container with the given title.
+   *
+   * <pre>{@code
+   * Shuffleboard.getTab("Example Tab")
+   *   .getLayout("My Layout", BuiltInLayouts.kList);
+   *
+   * // Later...
+   * Shuffleboard.getTab("Example Tab")
+   *   .getLayout("My Layout");
+   * }</pre>
+   *
+   * @param title the title of the layout to get
+   * @return the layout with the given title
+   * @throws NoSuchElementException if no layout has yet been defined with the given title
+   */
+  ShuffleboardLayout getLayout(String title) throws NoSuchElementException;
+
+  /**
+   * Adds a widget to this container to display the given sendable.
+   *
+   * @param title    the title of the widget
+   * @param sendable the sendable to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *                                  title
+   */
+  ComplexWidget add(String title, Sendable sendable) throws IllegalArgumentException;
+
+  /**
+   * Adds a widget to this container to display the given video stream.
+   *
+   * @param title    the title of the widget
+   * @param video    the video stream to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *                                  title
+   */
+  default ComplexWidget add(String title, VideoSource video) throws IllegalArgumentException {
+    return add(title, SendableCameraWrapper.wrap(video));
+  }
+
+  /**
+   * Adds a widget to this container to display the given sendable.
+   *
+   * @param sendable the sendable to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *                                  title, or if the sendable's name has not been specified
+   */
+  ComplexWidget add(Sendable sendable);
+
+  /**
+   * Adds a widget to this container to display the given video stream.
+   *
+   * @param video the video to display
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this container with the same
+   *                                  title as the video source
+   */
+  default ComplexWidget add(VideoSource video) {
+    return add(SendableCameraWrapper.wrap(video));
+  }
+
+  /**
+   * Adds a widget to this container to display the given data.
+   *
+   * @param title        the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *                                  title
+   * @see #addPersistent(String, Object) add(String title, Object defaultValue)
+   */
+  SimpleWidget add(String title, Object defaultValue) throws IllegalArgumentException;
+
+  /**
+   * Adds a widget to this container to display a simple piece of data. Unlike
+   * {@link #add(String, Object)}, the value in the widget will be saved on the robot and will be
+   * used when the robot program next starts rather than {@code defaultValue}.
+   *
+   * @param title        the title of the widget
+   * @param defaultValue the default value of the widget
+   * @return a widget to display the sendable data
+   * @throws IllegalArgumentException if a widget already exists in this container with the given
+   *                                  title
+   * @see #add(String, Object) add(String title, Object defaultValue)
+   */
+  default SimpleWidget addPersistent(String title, Object defaultValue)
+      throws IllegalArgumentException {
+    SimpleWidget widget = add(title, defaultValue);
+    widget.getEntry().setPersistent();
+    return widget;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java
new file mode 100644
index 0000000..7018da0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstance.java
@@ -0,0 +1,106 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import java.util.LinkedHashMap;
+import java.util.Map;
+import java.util.Objects;
+import java.util.function.Consumer;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+final class ShuffleboardInstance implements ShuffleboardRoot {
+  private final Map<String, ShuffleboardTab> m_tabs = new LinkedHashMap<>();
+
+  private boolean m_tabsChanged = false; // NOPMD redundant field initializer
+  private final NetworkTable m_rootTable;
+  private final NetworkTable m_rootMetaTable;
+  private final NetworkTableEntry m_selectedTabEntry;
+
+  ShuffleboardInstance(NetworkTableInstance ntInstance) {
+    Objects.requireNonNull(ntInstance, "NetworkTable instance cannot be null");
+    m_rootTable = ntInstance.getTable(Shuffleboard.kBaseTableName);
+    m_rootMetaTable = m_rootTable.getSubTable(".metadata");
+    m_selectedTabEntry = m_rootMetaTable.getEntry("Selected");
+  }
+
+  @Override
+  public ShuffleboardTab getTab(String title) {
+    Objects.requireNonNull(title, "Tab title cannot be null");
+    if (!m_tabs.containsKey(title)) {
+      m_tabs.put(title, new ShuffleboardTab(this, title));
+      m_tabsChanged = true;
+    }
+    return m_tabs.get(title);
+  }
+
+  @Override
+  public void update() {
+    if (m_tabsChanged) {
+      String[] tabTitles = m_tabs.values()
+          .stream()
+          .map(ShuffleboardTab::getTitle)
+          .toArray(String[]::new);
+      m_rootMetaTable.getEntry("Tabs").forceSetStringArray(tabTitles);
+      m_tabsChanged = false;
+    }
+    for (ShuffleboardTab tab : m_tabs.values()) {
+      String title = tab.getTitle();
+      tab.buildInto(m_rootTable, m_rootMetaTable.getSubTable(title));
+    }
+  }
+
+  @Override
+  public void enableActuatorWidgets() {
+    applyToAllComplexWidgets(ComplexWidget::enableIfActuator);
+  }
+
+  @Override
+  public void disableActuatorWidgets() {
+    applyToAllComplexWidgets(ComplexWidget::disableIfActuator);
+  }
+
+  @Override
+  public void selectTab(int index) {
+    m_selectedTabEntry.forceSetDouble(index);
+  }
+
+  @Override
+  public void selectTab(String title) {
+    m_selectedTabEntry.forceSetString(title);
+  }
+
+  /**
+   * Applies the function {@code func} to all complex widgets in this root, regardless of how they
+   * are nested.
+   *
+   * @param func the function to apply to all complex widgets
+   */
+  private void applyToAllComplexWidgets(Consumer<ComplexWidget> func) {
+    for (ShuffleboardTab tab : m_tabs.values()) {
+      apply(tab, func);
+    }
+  }
+
+  /**
+   * Applies the function {@code func} to all complex widgets in {@code container}. Helper method
+   * for {@link #applyToAllComplexWidgets}.
+   */
+  private void apply(ShuffleboardContainer container, Consumer<ComplexWidget> func) {
+    for (ShuffleboardComponent<?> component : container.getComponents()) {
+      if (component instanceof ComplexWidget) {
+        func.accept((ComplexWidget) component);
+      }
+      if (component instanceof ShuffleboardContainer) {
+        apply((ShuffleboardContainer) component, func);
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java
new file mode 100644
index 0000000..2a9d425
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardLayout.java
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import java.util.List;
+import java.util.NoSuchElementException;
+import java.util.Objects;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.wpilibj.Sendable;
+
+/**
+ * A layout in a Shuffleboard tab. Layouts can contain widgets and other layouts.
+ */
+public class ShuffleboardLayout extends ShuffleboardComponent<ShuffleboardLayout>
+    implements ShuffleboardContainer {
+  private final ContainerHelper m_helper = new ContainerHelper(this);
+
+  ShuffleboardLayout(ShuffleboardContainer parent, String name, String type) {
+    super(parent, Objects.requireNonNull(type, "Layout type must be specified"), name);
+  }
+
+  @Override
+  public List<ShuffleboardComponent<?>> getComponents() {
+    return m_helper.getComponents();
+  }
+
+  @Override
+  public ShuffleboardLayout getLayout(String title, String type) {
+    return m_helper.getLayout(title, type);
+  }
+
+  @Override
+  public ShuffleboardLayout getLayout(String title) throws NoSuchElementException {
+    return m_helper.getLayout(title);
+  }
+
+  @Override
+  public ComplexWidget add(String title, Sendable sendable) throws IllegalArgumentException {
+    return m_helper.add(title, sendable);
+  }
+
+  @Override
+  public ComplexWidget add(Sendable sendable) throws IllegalArgumentException {
+    return m_helper.add(sendable);
+  }
+
+  @Override
+  public SimpleWidget add(String title, Object defaultValue) throws IllegalArgumentException {
+    return m_helper.add(title, defaultValue);
+  }
+
+  @Override
+  public void buildInto(NetworkTable parentTable, NetworkTable metaTable) {
+    buildMetadata(metaTable);
+    NetworkTable table = parentTable.getSubTable(getTitle());
+    table.getEntry(".type").setString("ShuffleboardLayout");
+    for (ShuffleboardComponent<?> component : getComponents()) {
+      component.buildInto(table, metaTable.getSubTable(component.getTitle()));
+    }
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardRoot.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardRoot.java
new file mode 100644
index 0000000..a32af69
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardRoot.java
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+/**
+ * The root of the data placed in Shuffleboard. It contains the tabs, but no data is placed
+ * directly in the root.
+ *
+ * <p>This class is package-private to minimize API surface area.
+ */
+interface ShuffleboardRoot {
+
+  /**
+   * Gets the tab with the given title, creating it if it does not already exist.
+   *
+   * @param title the title of the tab
+   * @return the tab with the given title
+   */
+  ShuffleboardTab getTab(String title);
+
+  /**
+   * Updates all tabs.
+   */
+  void update();
+
+  /**
+   * Enables all widgets in Shuffleboard that offer user control over actuators.
+   */
+  void enableActuatorWidgets();
+
+  /**
+   * Disables all widgets in Shuffleboard that offer user control over actuators.
+   */
+  void disableActuatorWidgets();
+
+  /**
+   * Selects the tab in the dashboard with the given index in the range [0..n-1], where <i>n</i>
+   * is the number of tabs in the dashboard at the time this method is called.
+   *
+   * @param index the index of the tab to select
+   */
+  void selectTab(int index);
+
+  /**
+   * Selects the tab in the dashboard with the given title.
+   *
+   * @param title the title of the tab to select
+   */
+  void selectTab(String title);
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java
new file mode 100644
index 0000000..aec70e2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTab.java
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import java.util.List;
+import java.util.NoSuchElementException;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.wpilibj.Sendable;
+
+/**
+ * Represents a tab in the Shuffleboard dashboard. Widgets can be added to the tab with
+ * {@link #add(Sendable)}, {@link #add(String, Object)}, and {@link #add(String, Sendable)}. Widgets
+ * can also be added to layouts with {@link #getLayout(String, String)}; layouts can be nested
+ * arbitrarily deep (note that too many levels may make deeper components unusable).
+ */
+public final class ShuffleboardTab implements ShuffleboardContainer {
+  private final ContainerHelper m_helper = new ContainerHelper(this);
+  private final ShuffleboardRoot m_root;
+  private final String m_title;
+
+  ShuffleboardTab(ShuffleboardRoot root, String title) {
+    m_root = root;
+    m_title = title;
+  }
+
+  @Override
+  public String getTitle() {
+    return m_title;
+  }
+
+  ShuffleboardRoot getRoot() {
+    return m_root;
+  }
+
+  @Override
+  public List<ShuffleboardComponent<?>> getComponents() {
+    return m_helper.getComponents();
+  }
+
+  @Override
+  public ShuffleboardLayout getLayout(String title, String type) {
+    return m_helper.getLayout(title, type);
+  }
+
+  @Override
+  public ShuffleboardLayout getLayout(String title) throws NoSuchElementException {
+    return m_helper.getLayout(title);
+  }
+
+  @Override
+  public ComplexWidget add(String title, Sendable sendable) {
+    return m_helper.add(title, sendable);
+  }
+
+  @Override
+  public ComplexWidget add(Sendable sendable) throws IllegalArgumentException {
+    return m_helper.add(sendable);
+  }
+
+  @Override
+  public SimpleWidget add(String title, Object defaultValue) {
+    return m_helper.add(title, defaultValue);
+  }
+
+  @Override
+  public void buildInto(NetworkTable parentTable, NetworkTable metaTable) {
+    NetworkTable tabTable = parentTable.getSubTable(m_title);
+    tabTable.getEntry(".type").setString("ShuffleboardTab");
+    for (ShuffleboardComponent<?> component : m_helper.getComponents()) {
+      component.buildInto(tabTable, metaTable.getSubTable(component.getTitle()));
+    }
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardValue.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardValue.java
new file mode 100644
index 0000000..8bfa6c3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardValue.java
@@ -0,0 +1,31 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import edu.wpi.first.networktables.NetworkTable;
+
+interface ShuffleboardValue {
+
+  /**
+   * Gets the title of this Shuffleboard value.
+   */
+  String getTitle();
+
+  /**
+   * Builds the entries for this value.
+   *
+   * @param parentTable the table containing all the data for the parent. Values that require a
+   *                    complex entry or table structure should call {@code
+   *                    parentTable.getSubTable(getTitle())} to get the table to put data into.
+   *                    Values that only use a single entry should call {@code
+   *                    parentTable.getEntry(getTitle())} to get that entry.
+   * @param metaTable   the table containing all the metadata for this value and its sub-values
+   */
+  void buildInto(NetworkTable parentTable, NetworkTable metaTable);
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardWidget.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardWidget.java
new file mode 100644
index 0000000..3dc6622
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardWidget.java
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+/**
+ * Abstract superclass for widgets.
+ *
+ * <p>This class is package-private to minimize API surface area.
+ *
+ * @param <W> the self type
+ */
+abstract class ShuffleboardWidget<W extends ShuffleboardWidget<W>>
+    extends ShuffleboardComponent<W> {
+
+  ShuffleboardWidget(ShuffleboardContainer parent, String title) {
+    super(parent, title);
+  }
+
+  /**
+   * 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
+   * @see BuiltInWidgets
+   */
+  public final W withWidget(WidgetType widgetType) {
+    return withWidget(widgetType.getWidgetName());
+  }
+
+  /**
+   * Sets the type of widget used to display the data. If not set, the default widget type will be
+   * used. This method should only be used to use a widget that does not come built into
+   * Shuffleboard (i.e. one that comes with a custom or thrid-party plugin). To use a widget that
+   * is built into Shuffleboard, use {@link #withWidget(WidgetType)} and {@link BuiltInWidgets}.
+   *
+   * @param widgetType the type of the widget used to display the data
+   * @return this widget object
+   */
+  public final W withWidget(String widgetType) {
+    setType(widgetType);
+    return (W) this;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SimpleWidget.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SimpleWidget.java
new file mode 100644
index 0000000..c645baa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/SimpleWidget.java
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+
+/**
+ * A Shuffleboard widget that handles a single data point such as a number or string.
+ */
+public final class SimpleWidget extends ShuffleboardWidget<SimpleWidget> {
+  private NetworkTableEntry m_entry;
+
+  SimpleWidget(ShuffleboardContainer parent, String title) {
+    super(parent, title);
+  }
+
+  /**
+   * Gets the NetworkTable entry that contains the data for this widget.
+   */
+  public NetworkTableEntry getEntry() {
+    if (m_entry == null) {
+      forceGenerate();
+    }
+    return m_entry;
+  }
+
+  @Override
+  public void buildInto(NetworkTable parentTable, NetworkTable metaTable) {
+    buildMetadata(metaTable);
+    if (m_entry == null) {
+      m_entry = parentTable.getEntry(getTitle());
+    }
+  }
+
+  private void forceGenerate() {
+    ShuffleboardContainer parent = getParent();
+    while (parent instanceof ShuffleboardLayout) {
+      parent = ((ShuffleboardLayout) parent).getParent();
+    }
+    ShuffleboardTab tab = (ShuffleboardTab) parent;
+    tab.getRoot().update();
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/WidgetType.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/WidgetType.java
new file mode 100644
index 0000000..1e8242f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/shuffleboard/WidgetType.java
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+/**
+ * Represents the type of a widget in Shuffleboard. Using this is preferred over specifying raw
+ * strings, to avoid typos and having to know or look up the exact string name for a desired widget.
+ *
+ * @see BuiltInWidgets the built-in widget types
+ */
+public interface WidgetType {
+  /**
+   * Gets the string type of the widget as defined by that widget in Shuffleboard.
+   */
+  String getWidgetName();
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilder.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilder.java
new file mode 100644
index 0000000..35a8b54
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilder.java
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.smartdashboard;
+
+import java.util.function.BooleanSupplier;
+import java.util.function.Consumer;
+import java.util.function.DoubleConsumer;
+import java.util.function.DoubleSupplier;
+import java.util.function.Supplier;
+
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableValue;
+
+public interface SendableBuilder {
+  /**
+   * Set the string representation of the named data type that will be used
+   * by the smart dashboard for this sendable.
+   *
+   * @param type    data type
+   */
+  void setSmartDashboardType(String type);
+
+  /**
+   * Set a flag indicating if this sendable should be treated as an actuator.
+   * By default this flag is false.
+   *
+   * @param value   true if actuator, false if not
+   */
+  void setActuator(boolean value);
+
+  /**
+   * Set the function that should be called to set the Sendable into a safe
+   * state.  This is called when entering and exiting Live Window mode.
+   *
+   * @param func    function
+   */
+  void setSafeState(Runnable func);
+
+  /**
+   * Set the function that should be called to update the network table
+   * for things other than properties.  Note this function is not passed
+   * the network table object; instead it should use the entry handles
+   * returned by getEntry().
+   *
+   * @param func    function
+   */
+  void setUpdateTable(Runnable func);
+
+  /**
+   * Add a property without getters or setters.  This can be used to get
+   * entry handles for the function called by setUpdateTable().
+   *
+   * @param key   property name
+   * @return Network table entry
+   */
+  NetworkTableEntry getEntry(String key);
+
+  /**
+   * Represents an operation that accepts a single boolean-valued argument and
+   * returns no result. This is the primitive type specialization of Consumer
+   * for boolean. Unlike most other functional interfaces, BooleanConsumer is
+   * expected to operate via side-effects.
+   *
+   * <p>This is a functional interface whose functional method is accept(boolean).
+   */
+  @FunctionalInterface
+  interface BooleanConsumer {
+    /**
+     * Performs the operation on the given value.
+     * @param value the value
+     */
+    void accept(boolean value);
+  }
+
+  /**
+   * Add a boolean property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  void addBooleanProperty(String key, BooleanSupplier getter, BooleanConsumer setter);
+
+  /**
+   * Add a double property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  void addDoubleProperty(String key, DoubleSupplier getter, DoubleConsumer setter);
+
+  /**
+   * Add a string property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  void addStringProperty(String key, Supplier<String> getter, Consumer<String> setter);
+
+  /**
+   * Add a boolean array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  void addBooleanArrayProperty(String key, Supplier<boolean[]> getter, Consumer<boolean[]> setter);
+
+  /**
+   * Add a double array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  void addDoubleArrayProperty(String key, Supplier<double[]> getter, Consumer<double[]> setter);
+
+  /**
+   * Add a string array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  void addStringArrayProperty(String key, Supplier<String[]> getter, Consumer<String[]> setter);
+
+  /**
+   * Add a raw property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  void addRawProperty(String key, Supplier<byte[]> getter, Consumer<byte[]> setter);
+
+  /**
+   * Add a NetworkTableValue property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  void addValueProperty(String key, Supplier<NetworkTableValue> getter,
+                        Consumer<NetworkTableValue> setter);
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java
new file mode 100644
index 0000000..aec5a27
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableBuilderImpl.java
@@ -0,0 +1,393 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.smartdashboard;
+
+import java.util.ArrayList;
+import java.util.List;
+import java.util.function.BooleanSupplier;
+import java.util.function.Consumer;
+import java.util.function.DoubleConsumer;
+import java.util.function.DoubleSupplier;
+import java.util.function.Function;
+import java.util.function.Supplier;
+
+import edu.wpi.first.networktables.EntryListenerFlags;
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableValue;
+
+@SuppressWarnings("PMD.TooManyMethods")
+public class SendableBuilderImpl implements SendableBuilder {
+  private static class Property {
+    Property(NetworkTable table, String key) {
+      m_entry = table.getEntry(key);
+    }
+
+    @Override
+    @SuppressWarnings("NoFinalizer")
+    protected synchronized void finalize() {
+      stopListener();
+    }
+
+    void startListener() {
+      if (m_entry.isValid() && m_listener == 0 && m_createListener != null) {
+        m_listener = m_createListener.apply(m_entry);
+      }
+    }
+
+    void stopListener() {
+      if (m_entry.isValid() && m_listener != 0) {
+        m_entry.removeListener(m_listener);
+        m_listener = 0;
+      }
+    }
+
+    final NetworkTableEntry m_entry;
+    int m_listener;
+    Consumer<NetworkTableEntry> m_update;
+    Function<NetworkTableEntry, Integer> m_createListener;
+  }
+
+  private final List<Property> m_properties = new ArrayList<>();
+  private Runnable m_safeState;
+  private Runnable m_updateTable;
+  private NetworkTable m_table;
+  private NetworkTableEntry m_controllableEntry;
+  private boolean m_actuator;
+
+  /**
+   * Set the network table.  Must be called prior to any Add* functions being
+   * called.
+   * @param table Network table
+   */
+  public void setTable(NetworkTable table) {
+    m_table = table;
+    m_controllableEntry = table.getEntry(".controllable");
+  }
+
+  /**
+   * Get the network table.
+   * @return The network table
+   */
+  public NetworkTable getTable() {
+    return m_table;
+  }
+
+  /**
+   * Return whether this sendable should be treated as an actuator.
+   * @return True if actuator, false if not.
+   */
+  public boolean isActuator() {
+    return m_actuator;
+  }
+
+  /**
+   * Update the network table values by calling the getters for all properties.
+   */
+  public void updateTable() {
+    for (Property property : m_properties) {
+      if (property.m_update != null) {
+        property.m_update.accept(property.m_entry);
+      }
+    }
+    if (m_updateTable != null) {
+      m_updateTable.run();
+    }
+  }
+
+  /**
+   * Hook setters for all properties.
+   */
+  public void startListeners() {
+    for (Property property : m_properties) {
+      property.startListener();
+    }
+    if (m_controllableEntry != null) {
+      m_controllableEntry.setBoolean(true);
+    }
+  }
+
+  /**
+   * Unhook setters for all properties.
+   */
+  public void stopListeners() {
+    for (Property property : m_properties) {
+      property.stopListener();
+    }
+    if (m_controllableEntry != null) {
+      m_controllableEntry.setBoolean(false);
+    }
+  }
+
+  /**
+   * Start LiveWindow mode by hooking the setters for all properties.  Also
+   * calls the safeState function if one was provided.
+   */
+  public void startLiveWindowMode() {
+    if (m_safeState != null) {
+      m_safeState.run();
+    }
+    startListeners();
+  }
+
+  /**
+   * Stop LiveWindow mode by unhooking the setters for all properties.  Also
+   * calls the safeState function if one was provided.
+   */
+  public void stopLiveWindowMode() {
+    stopListeners();
+    if (m_safeState != null) {
+      m_safeState.run();
+    }
+  }
+
+  /**
+   * Set the string representation of the named data type that will be used
+   * by the smart dashboard for this sendable.
+   *
+   * @param type    data type
+   */
+  @Override
+  public void setSmartDashboardType(String type) {
+    m_table.getEntry(".type").setString(type);
+  }
+
+  /**
+   * Set a flag indicating if this sendable should be treated as an actuator.
+   * By default this flag is false.
+   *
+   * @param value   true if actuator, false if not
+   */
+  @Override
+  public void setActuator(boolean value) {
+    m_table.getEntry(".actuator").setBoolean(value);
+    m_actuator = value;
+  }
+
+  /**
+   * Set the function that should be called to set the Sendable into a safe
+   * state.  This is called when entering and exiting Live Window mode.
+   *
+   * @param func    function
+   */
+  @Override
+  public void setSafeState(Runnable func) {
+    m_safeState = func;
+  }
+
+  /**
+   * Set the function that should be called to update the network table
+   * for things other than properties.  Note this function is not passed
+   * the network table object; instead it should use the entry handles
+   * returned by getEntry().
+   *
+   * @param func    function
+   */
+  @Override
+  public void setUpdateTable(Runnable func) {
+    m_updateTable = func;
+  }
+
+  /**
+   * Add a property without getters or setters.  This can be used to get
+   * entry handles for the function called by setUpdateTable().
+   *
+   * @param key   property name
+   * @return Network table entry
+   */
+  @Override
+  public NetworkTableEntry getEntry(String key) {
+    return m_table.getEntry(key);
+  }
+
+  /**
+   * Add a boolean property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  @Override
+  public void addBooleanProperty(String key, BooleanSupplier getter, BooleanConsumer setter) {
+    Property property = new Property(m_table, key);
+    if (getter != null) {
+      property.m_update = entry -> entry.setBoolean(getter.getAsBoolean());
+    }
+    if (setter != null) {
+      property.m_createListener = entry -> entry.addListener(event -> {
+        if (event.value.isBoolean()) {
+          setter.accept(event.value.getBoolean());
+        }
+      }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a double property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  @Override
+  public void addDoubleProperty(String key, DoubleSupplier getter, DoubleConsumer setter) {
+    Property property = new Property(m_table, key);
+    if (getter != null) {
+      property.m_update = entry -> entry.setDouble(getter.getAsDouble());
+    }
+    if (setter != null) {
+      property.m_createListener = entry -> entry.addListener(event -> {
+        if (event.value.isDouble()) {
+          setter.accept(event.value.getDouble());
+        }
+      }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a string property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  @Override
+  public void addStringProperty(String key, Supplier<String> getter, Consumer<String> setter) {
+    Property property = new Property(m_table, key);
+    if (getter != null) {
+      property.m_update = entry -> entry.setString(getter.get());
+    }
+    if (setter != null) {
+      property.m_createListener = entry -> entry.addListener(event -> {
+        if (event.value.isString()) {
+          setter.accept(event.value.getString());
+        }
+      }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a boolean array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  @Override
+  public void addBooleanArrayProperty(String key, Supplier<boolean[]> getter,
+                                      Consumer<boolean[]> setter) {
+    Property property = new Property(m_table, key);
+    if (getter != null) {
+      property.m_update = entry -> entry.setBooleanArray(getter.get());
+    }
+    if (setter != null) {
+      property.m_createListener = entry -> entry.addListener(event -> {
+        if (event.value.isBooleanArray()) {
+          setter.accept(event.value.getBooleanArray());
+        }
+      }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a double array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  @Override
+  public void addDoubleArrayProperty(String key, Supplier<double[]> getter,
+                                     Consumer<double[]> setter) {
+    Property property = new Property(m_table, key);
+    if (getter != null) {
+      property.m_update = entry -> entry.setDoubleArray(getter.get());
+    }
+    if (setter != null) {
+      property.m_createListener = entry -> entry.addListener(event -> {
+        if (event.value.isDoubleArray()) {
+          setter.accept(event.value.getDoubleArray());
+        }
+      }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a string array property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  @Override
+  public void addStringArrayProperty(String key, Supplier<String[]> getter,
+                                     Consumer<String[]> setter) {
+    Property property = new Property(m_table, key);
+    if (getter != null) {
+      property.m_update = entry -> entry.setStringArray(getter.get());
+    }
+    if (setter != null) {
+      property.m_createListener = entry -> entry.addListener(event -> {
+        if (event.value.isStringArray()) {
+          setter.accept(event.value.getStringArray());
+        }
+      }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a raw property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  @Override
+  public void addRawProperty(String key, Supplier<byte[]> getter, Consumer<byte[]> setter) {
+    Property property = new Property(m_table, key);
+    if (getter != null) {
+      property.m_update = entry -> entry.setRaw(getter.get());
+    }
+    if (setter != null) {
+      property.m_createListener = entry -> entry.addListener(event -> {
+        if (event.value.isRaw()) {
+          setter.accept(event.value.getRaw());
+        }
+      }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
+    }
+    m_properties.add(property);
+  }
+
+  /**
+   * Add a NetworkTableValue property.
+   *
+   * @param key     property name
+   * @param getter  getter function (returns current value)
+   * @param setter  setter function (sets new value)
+   */
+  @Override
+  public void addValueProperty(String key, Supplier<NetworkTableValue> getter,
+                               Consumer<NetworkTableValue> setter) {
+    Property property = new Property(m_table, key);
+    if (getter != null) {
+      property.m_update = entry -> entry.setValue(getter.get());
+    }
+    if (setter != null) {
+      property.m_createListener = entry -> entry.addListener(event -> {
+        setter.accept(event.value);
+      }, EntryListenerFlags.kImmediate | EntryListenerFlags.kNew | EntryListenerFlags.kUpdate);
+    }
+    m_properties.add(property);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java
new file mode 100644
index 0000000..5859705
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java
@@ -0,0 +1,187 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.smartdashboard;
+
+import java.util.ArrayList;
+import java.util.LinkedHashMap;
+import java.util.List;
+import java.util.concurrent.atomic.AtomicInteger;
+import java.util.concurrent.locks.ReentrantLock;
+
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.wpilibj.SendableBase;
+import edu.wpi.first.wpilibj.command.Command;
+
+import static java.util.Objects.requireNonNull;
+
+/**
+ * The {@link SendableChooser} class is a useful tool for presenting a selection of options to the
+ * {@link SmartDashboard}.
+ *
+ * <p>For instance, you may wish to be able to select between multiple autonomous modes. You can do
+ * this by putting every possible {@link Command} you want to run as an autonomous into a {@link
+ * SendableChooser} and then put it into the {@link SmartDashboard} to have a list of options appear
+ * on the laptop. Once autonomous starts, simply ask the {@link SendableChooser} what the selected
+ * value is.
+ *
+ * @param <V> The type of the values to be stored
+ */
+public class SendableChooser<V> extends SendableBase {
+  /**
+   * The key for the default value.
+   */
+  private static final String DEFAULT = "default";
+  /**
+   * The key for the selected option.
+   */
+  private static final String SELECTED = "selected";
+  /**
+   * The key for the active option.
+   */
+  private static final String ACTIVE = "active";
+  /**
+   * The key for the option array.
+   */
+  private static final String OPTIONS = "options";
+  /**
+   * The key for the instance number.
+   */
+  private static final String INSTANCE = ".instance";
+  /**
+   * A map linking strings to the objects the represent.
+   */
+  @SuppressWarnings("PMD.LooseCoupling")
+  private final LinkedHashMap<String, V> m_map = new LinkedHashMap<>();
+  private String m_defaultChoice = "";
+  private final int m_instance;
+  private static final AtomicInteger s_instances = new AtomicInteger();
+
+  /**
+   * Instantiates a {@link SendableChooser}.
+   */
+  public SendableChooser() {
+    super(false);
+    m_instance = s_instances.getAndIncrement();
+  }
+
+  /**
+   * Adds the given object to the list of options. On the {@link SmartDashboard} on the desktop, the
+   * object will appear as the given name.
+   *
+   * @param name   the name of the option
+   * @param object the option
+   */
+  public void addOption(String name, V object) {
+    m_map.put(name, object);
+  }
+
+  /**
+   * Adds the given object to the list of options.
+   *
+   * @deprecated Use {@link #addOption(String, Object)} instead.
+   *
+   * @param name   the name of the option
+   * @param object the option
+   */
+  @Deprecated
+  public void addObject(String name, V object) {
+    addOption(name, object);
+  }
+
+  /**
+   * Adds the given object to the list of options and marks it as the default. Functionally, this is
+   * very close to {@link #addOption(String, Object)} except that it will use this as the default
+   * option if none other is explicitly selected.
+   *
+   * @param name   the name of the option
+   * @param object the option
+   */
+  public void setDefaultOption(String name, V object) {
+    requireNonNull(name, "Provided name was null");
+
+    m_defaultChoice = name;
+    addOption(name, object);
+  }
+
+  /**
+   * Adds the given object to the list of options and marks it as the default.
+   *
+   * @deprecated Use {@link #setDefaultOption(String, Object)} instead.
+   *
+   * @param name   the name of the option
+   * @param object the option
+   */
+  @Deprecated
+  public void addDefault(String name, V object) {
+    setDefaultOption(name, object);
+  }
+
+  /**
+   * Returns the selected option. If there is none selected, it will return the default. If there is
+   * none selected and no default, then it will return {@code null}.
+   *
+   * @return the option selected
+   */
+  public V getSelected() {
+    m_mutex.lock();
+    try {
+      if (m_selected != null) {
+        return m_map.get(m_selected);
+      } else {
+        return m_map.get(m_defaultChoice);
+      }
+    } finally {
+      m_mutex.unlock();
+    }
+  }
+
+  private String m_selected;
+  private final List<NetworkTableEntry> m_activeEntries = new ArrayList<>();
+  private final ReentrantLock m_mutex = new ReentrantLock();
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setSmartDashboardType("String Chooser");
+    builder.getEntry(INSTANCE).setDouble(m_instance);
+    builder.addStringProperty(DEFAULT, () -> {
+      return m_defaultChoice;
+    }, null);
+    builder.addStringArrayProperty(OPTIONS, () -> {
+      return m_map.keySet().toArray(new String[0]);
+    }, null);
+    builder.addStringProperty(ACTIVE, () -> {
+      m_mutex.lock();
+      try {
+        if (m_selected != null) {
+          return m_selected;
+        } else {
+          return m_defaultChoice;
+        }
+      } finally {
+        m_mutex.unlock();
+      }
+    }, null);
+    m_mutex.lock();
+    try {
+      m_activeEntries.add(builder.getEntry(ACTIVE));
+    } finally {
+      m_mutex.unlock();
+    }
+    builder.addStringProperty(SELECTED, null, val -> {
+      m_mutex.lock();
+      try {
+        m_selected = val;
+        for (NetworkTableEntry entry : m_activeEntries) {
+          entry.setString(val);
+        }
+      } finally {
+        m_mutex.unlock();
+      }
+    });
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java
new file mode 100644
index 0000000..290fe33
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboard.java
@@ -0,0 +1,533 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.smartdashboard;
+
+import java.nio.ByteBuffer;
+import java.util.HashMap;
+import java.util.Map;
+import java.util.Set;
+
+import edu.wpi.first.hal.FRCNetComm.tResourceType;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.NamedSendable;
+import edu.wpi.first.wpilibj.Sendable;
+
+/**
+ * The {@link SmartDashboard} class is the bridge between robot programs and the SmartDashboard on
+ * the laptop.
+ *
+ * <p>When a value is put into the SmartDashboard here, it pops up on the SmartDashboard on the
+ * laptop. Users can put values into and get values from the SmartDashboard.
+ */
+@SuppressWarnings({"PMD.GodClass", "PMD.TooManyMethods"})
+public class SmartDashboard {
+  /**
+   * The {@link NetworkTable} used by {@link SmartDashboard}.
+   */
+  private static final NetworkTable table =
+      NetworkTableInstance.getDefault().getTable("SmartDashboard");
+
+  private static class Data {
+    Data(Sendable sendable) {
+      m_sendable = sendable;
+    }
+
+    final Sendable m_sendable;
+    final SendableBuilderImpl m_builder = new SendableBuilderImpl();
+  }
+
+  /**
+   * A table linking tables in the SmartDashboard to the {@link Sendable} objects they
+   * came from.
+   */
+  @SuppressWarnings("PMD.UseConcurrentHashMap")
+  private static final Map<String, Data> tablesToData = new HashMap<>();
+
+  static {
+    HAL.report(tResourceType.kResourceType_SmartDashboard, 0);
+  }
+
+  private SmartDashboard() {
+    throw new UnsupportedOperationException("This is a utility class!");
+  }
+
+  /**
+   * Maps the specified key to the specified value in this table. The key can not be null. The value
+   * can be retrieved by calling the get method with a key that is equal to the original key.
+   *
+   * @param key  the key
+   * @param data the value
+   * @throws IllegalArgumentException If key is null
+   */
+  public static synchronized void putData(String key, Sendable data) {
+    Data sddata = tablesToData.get(key);
+    if (sddata == null || sddata.m_sendable != data) {
+      if (sddata != null) {
+        sddata.m_builder.stopListeners();
+      }
+      sddata = new Data(data);
+      tablesToData.put(key, sddata);
+      NetworkTable dataTable = table.getSubTable(key);
+      sddata.m_builder.setTable(dataTable);
+      data.initSendable(sddata.m_builder);
+      sddata.m_builder.updateTable();
+      sddata.m_builder.startListeners();
+      dataTable.getEntry(".name").setString(key);
+    }
+  }
+
+  /**
+   * Maps the specified key (where the key is the name of the {@link NamedSendable}
+   * to the specified value in this table. The value can be retrieved by
+   * calling the get method with a key that is equal to the original key.
+   *
+   * @param value the value
+   * @throws IllegalArgumentException If key is null
+   */
+  public static void putData(Sendable value) {
+    putData(value.getName(), value);
+  }
+
+  /**
+   * Returns the value at the specified key.
+   *
+   * @param key the key
+   * @return the value
+   * @throws IllegalArgumentException  if the key is null
+   */
+  public static synchronized Sendable getData(String key) {
+    Data data = tablesToData.get(key);
+    if (data == null) {
+      throw new IllegalArgumentException("SmartDashboard data does not exist: " + key);
+    } else {
+      return data.m_sendable;
+    }
+  }
+
+  /**
+   * Gets the entry for the specified key.
+   * @param key the key name
+   * @return Network table entry.
+   */
+  public static NetworkTableEntry getEntry(String key) {
+    return table.getEntry(key);
+  }
+
+  /**
+   * Checks the table and tells if it contains the specified key.
+   *
+   * @param key the key to search for
+   * @return true if the table as a value assigned to the given key
+   */
+  public static boolean containsKey(String key) {
+    return table.containsKey(key);
+  }
+
+  /**
+   * Get the keys stored in the SmartDashboard table of NetworkTables.
+   *
+   * @param types bitmask of types; 0 is treated as a "don't care".
+   * @return keys currently in the table
+   */
+  public static Set<String> getKeys(int types) {
+    return table.getKeys(types);
+  }
+
+  /**
+   * Get the keys stored in the SmartDashboard table of NetworkTables.
+   *
+   * @return keys currently in the table.
+   */
+  public static Set<String> getKeys() {
+    return table.getKeys();
+  }
+
+  /**
+   * Makes a key's value persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  public static void setPersistent(String key) {
+    getEntry(key).setPersistent();
+  }
+
+  /**
+   * Stop making a key's value persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   */
+  public static void clearPersistent(String key) {
+    getEntry(key).clearPersistent();
+  }
+
+  /**
+   * Returns whether the value is persistent through program restarts.
+   * The key cannot be null.
+   *
+   * @param key the key name
+   * @return True if the value is persistent.
+   */
+  public static boolean isPersistent(String key) {
+    return getEntry(key).isPersistent();
+  }
+
+  /**
+   * Sets flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to set (bitmask)
+   */
+  public static void setFlags(String key, int flags) {
+    getEntry(key).setFlags(flags);
+  }
+
+  /**
+   * Clears flags on the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   * @param flags the flags to clear (bitmask)
+   */
+  public static void clearFlags(String key, int flags) {
+    getEntry(key).clearFlags(flags);
+  }
+
+  /**
+   * Returns the flags for the specified key.
+   *
+   * @param key the key name
+   * @return the flags, or 0 if the key is not defined
+   */
+  public static int getFlags(String key) {
+    return getEntry(key).getFlags();
+  }
+
+  /**
+   * Deletes the specified key in this table. The key can
+   * not be null.
+   *
+   * @param key the key name
+   */
+  public static void delete(String key) {
+    table.delete(key);
+  }
+
+  /**
+   * Put a boolean in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putBoolean(String key, boolean value) {
+    return getEntry(key).setBoolean(value);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultBoolean(String key, boolean defaultValue) {
+    return getEntry(key).setDefaultBoolean(defaultValue);
+  }
+
+  /**
+   * Returns the boolean the key maps to. If the key does not exist or is of
+   *     different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static boolean getBoolean(String key, boolean defaultValue) {
+    return getEntry(key).getBoolean(defaultValue);
+  }
+
+  /**
+   * Put a number in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putNumber(String key, double value) {
+    return getEntry(key).setDouble(value);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultNumber(String key, double defaultValue) {
+    return getEntry(key).setDefaultDouble(defaultValue);
+  }
+
+  /**
+   * Returns the number the key maps to. If the key does not exist or is of
+   *     different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static double getNumber(String key, double defaultValue) {
+    return getEntry(key).getDouble(defaultValue);
+  }
+
+  /**
+   * Put a string in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putString(String key, String value) {
+    return getEntry(key).setString(value);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultString(String key, String defaultValue) {
+    return getEntry(key).setDefaultString(defaultValue);
+  }
+
+  /**
+   * Returns the string the key maps to. If the key does not exist or is of
+   *     different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static String getString(String key, String defaultValue) {
+    return getEntry(key).getString(defaultValue);
+  }
+
+  /**
+   * Put a boolean array in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putBooleanArray(String key, boolean[] value) {
+    return getEntry(key).setBooleanArray(value);
+  }
+
+  /**
+   * Put a boolean array in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putBooleanArray(String key, Boolean[] value) {
+    return getEntry(key).setBooleanArray(value);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultBooleanArray(String key, boolean[] defaultValue) {
+    return getEntry(key).setDefaultBooleanArray(defaultValue);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultBooleanArray(String key, Boolean[] defaultValue) {
+    return getEntry(key).setDefaultBooleanArray(defaultValue);
+  }
+
+  /**
+   * Returns the boolean array the key maps to. If the key does not exist or is
+   *     of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static boolean[] getBooleanArray(String key, boolean[] defaultValue) {
+    return getEntry(key).getBooleanArray(defaultValue);
+  }
+
+  /**
+   * Returns the boolean array the key maps to. If the key does not exist or is
+   *     of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static Boolean[] getBooleanArray(String key, Boolean[] defaultValue) {
+    return getEntry(key).getBooleanArray(defaultValue);
+  }
+
+  /**
+   * Put a number array in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putNumberArray(String key, double[] value) {
+    return getEntry(key).setDoubleArray(value);
+  }
+
+  /**
+   * Put a number array in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putNumberArray(String key, Double[] value) {
+    return getEntry(key).setNumberArray(value);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultNumberArray(String key, double[] defaultValue) {
+    return getEntry(key).setDefaultDoubleArray(defaultValue);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultNumberArray(String key, Double[] defaultValue) {
+    return getEntry(key).setDefaultNumberArray(defaultValue);
+  }
+
+  /**
+   * Returns the number array the key maps to. If the key does not exist or is
+   *     of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static double[] getNumberArray(String key, double[] defaultValue) {
+    return getEntry(key).getDoubleArray(defaultValue);
+  }
+
+  /**
+   * Returns the number array the key maps to. If the key does not exist or is
+   *     of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static Double[] getNumberArray(String key, Double[] defaultValue) {
+    return getEntry(key).getDoubleArray(defaultValue);
+  }
+
+  /**
+   * Put a string array in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putStringArray(String key, String[] value) {
+    return getEntry(key).setStringArray(value);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultStringArray(String key, String[] defaultValue) {
+    return getEntry(key).setDefaultStringArray(defaultValue);
+  }
+
+  /**
+   * Returns the string array the key maps to. If the key does not exist or is
+   *     of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static String[] getStringArray(String key, String[] defaultValue) {
+    return getEntry(key).getStringArray(defaultValue);
+  }
+
+  /**
+   * Put a raw value (byte array) in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putRaw(String key, byte[] value) {
+    return getEntry(key).setRaw(value);
+  }
+
+  /**
+   * Put a raw value (bytes from a byte buffer) in the table.
+   * @param key the key to be assigned to
+   * @param value the value that will be assigned
+   * @param len the length of the value
+   * @return False if the table key already exists with a different type
+   */
+  public static boolean putRaw(String key, ByteBuffer value, int len) {
+    return getEntry(key).setRaw(value, len);
+  }
+
+  /**
+   * Gets the current value in the table, setting it if it does not exist.
+   * @param key the key
+   * @param defaultValue the default value to set if key does not exist.
+   * @return False if the table key exists with a different type
+   */
+  public static boolean setDefaultRaw(String key, byte[] defaultValue) {
+    return getEntry(key).setDefaultRaw(defaultValue);
+  }
+
+  /**
+   * Returns the raw value (byte array) the key maps to. If the key does not
+   *     exist or is of different type, it will return the default value.
+   * @param key the key to look up
+   * @param defaultValue the value to be returned if no value is found
+   * @return the value associated with the given key or the given default value
+   *     if there is no value associated with the key
+   */
+  public static byte[] getRaw(String key, byte[] defaultValue) {
+    return getEntry(key).getRaw(defaultValue);
+  }
+
+  /**
+   * Puts all sendable data to the dashboard.
+   */
+  public static synchronized void updateValues() {
+    for (Data data : tablesToData.values()) {
+      data.m_builder.updateTable();
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/SortedVector.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/SortedVector.java
new file mode 100644
index 0000000..f17d073
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/util/SortedVector.java
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.util;
+
+import java.util.Vector;
+
+/**
+ * A vector that is sorted.
+ */
+public class SortedVector<E> extends Vector<E> {
+  /**
+   * Interface used to determine the order to place sorted objects.
+   */
+  public interface Comparator {
+    /**
+     * Compare the given two objects.
+     *
+     * <p>Should return -1, 0, or 1 if the first object is less than, equal to, or greater than the
+     * second, respectively.
+     *
+     * @param object1 First object to compare
+     * @param object2 Second object to compare
+     * @return -1, 0, or 1.
+     */
+    int compare(Object object1, Object object2);
+  }
+
+  private final Comparator m_comparator;
+
+  /**
+   * Create a new sorted vector and use the given comparator to determine order.
+   *
+   * @param comparator The comparator to use to determine what order to place the elements in this
+   *                   vector.
+   */
+  public SortedVector(Comparator comparator) {
+    m_comparator = comparator;
+  }
+
+  /**
+   * Adds an element in the Vector, sorted from greatest to least.
+   *
+   * @param element The element to add to the Vector
+   */
+  @Override
+  public synchronized void addElement(E element) {
+    int highBound = size();
+    int lowBound = 0;
+    while (highBound - lowBound > 0) {
+      int index = (highBound + lowBound) / 2;
+      int result = m_comparator.compare(element, elementAt(index));
+      if (result < 0) {
+        lowBound = index + 1;
+      } else if (result > 0) {
+        highBound = index;
+      } else {
+        lowBound = index;
+        highBound = index;
+      }
+    }
+    insertElementAt(element, lowBound);
+  }
+
+  /**
+   * Sort the vector.
+   */
+  @SuppressWarnings("unchecked")
+  public synchronized void sort() {
+    Object[] array = new Object[size()];
+    copyInto(array);
+    removeAllElements();
+    for (Object o : array) {
+      addElement((E) o);
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionPipeline.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionPipeline.java
new file mode 100644
index 0000000..2c0f8f2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionPipeline.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.vision;
+
+import org.opencv.core.Mat;
+
+/**
+ * A vision pipeline is responsible for running a group of
+ * OpenCV algorithms to extract data from an image.
+ *
+ * @see VisionRunner
+ * @see VisionThread
+ *
+ * @deprecated Replaced with edu.wpi.first.vision.VisionPipeline
+ */
+@Deprecated
+public interface VisionPipeline {
+  /**
+   * Processes the image input and sets the result objects.
+   * Implementations should make these objects accessible.
+   */
+  void process(Mat image);
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionRunner.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionRunner.java
new file mode 100644
index 0000000..701b86e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionRunner.java
@@ -0,0 +1,131 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.vision;
+
+import org.opencv.core.Mat;
+
+import edu.wpi.cscore.CvSink;
+import edu.wpi.cscore.VideoSource;
+import edu.wpi.first.cameraserver.CameraServerSharedStore;
+
+/**
+ * A vision runner is a convenient wrapper object to make it easy to run vision pipelines
+ * from robot code. The easiest  way to use this is to run it in a {@link VisionThread}
+ * and use the listener to take snapshots of the pipeline's outputs.
+ *
+ * @see VisionPipeline
+ * @see VisionThread
+ * @see <a href="package-summary.html">vision</a>
+ *
+ * @deprecated Replaced with edu.wpi.first.vision.VisionRunner
+ */
+@Deprecated
+public class VisionRunner<P extends VisionPipeline> {
+  private final CvSink m_cvSink = new CvSink("VisionRunner CvSink");
+  private final P m_pipeline;
+  private final Mat m_image = new Mat();
+  private final Listener<? super P> m_listener;
+  private volatile boolean m_enabled = true;
+
+  /**
+   * Listener interface for a callback that should run after a pipeline has processed its input.
+   *
+   * @param <P> the type of the pipeline this listener is for
+   */
+  @FunctionalInterface
+  public interface Listener<P extends VisionPipeline> {
+    /**
+     * Called when the pipeline has run. This shouldn't take much time to run because it will delay
+     * later calls to the pipeline's {@link VisionPipeline#process process} method. Copying the
+     * outputs and code that uses the copies should be <i>synchronized</i> on the same mutex to
+     * prevent multiple threads from reading and writing to the same memory at the same time.
+     *
+     * @param pipeline the vision pipeline that ran
+     */
+    void copyPipelineOutputs(P pipeline);
+
+  }
+
+  /**
+   * Creates a new vision runner. It will take images from the {@code videoSource}, send them to
+   * the {@code pipeline}, and call the {@code listener} when the pipeline has finished to alert
+   * user code when it is safe to access the pipeline's outputs.
+   *
+   * @param videoSource the video source to use to supply images for the pipeline
+   * @param pipeline    the vision pipeline to run
+   * @param listener    a function to call after the pipeline has finished running
+   */
+  public VisionRunner(VideoSource videoSource, P pipeline, Listener<? super P> listener) {
+    this.m_pipeline = pipeline;
+    this.m_listener = listener;
+    m_cvSink.setSource(videoSource);
+  }
+
+  /**
+   * Runs the pipeline one time, giving it the next image from the video source specified
+   * in the constructor. This will block until the source either has an image or throws an error.
+   * If the source successfully supplied a frame, the pipeline's image input will be set,
+   * the pipeline will run, and the listener specified in the constructor will be called to notify
+   * it that the pipeline ran.
+   *
+   * <p>This method is exposed to allow teams to add additional functionality or have their own
+   * ways to run the pipeline. Most teams, however, should just use {@link #runForever} in its own
+   * thread using a {@link VisionThread}.</p>
+   */
+  public void runOnce() {
+    Long id = CameraServerSharedStore.getCameraServerShared().getRobotMainThreadId();
+
+    if (id != null && Thread.currentThread().getId() == id.longValue()) {
+      throw new IllegalStateException(
+          "VisionRunner.runOnce() cannot be called from the main robot thread");
+    }
+    runOnceInternal();
+  }
+
+  private void runOnceInternal() {
+    long frameTime = m_cvSink.grabFrame(m_image);
+    if (frameTime == 0) {
+      // There was an error, report it
+      String error = m_cvSink.getError();
+      CameraServerSharedStore.getCameraServerShared().reportDriverStationError(error);
+    } else {
+      // No errors, process the image
+      m_pipeline.process(m_image);
+      m_listener.copyPipelineOutputs(m_pipeline);
+    }
+  }
+
+  /**
+   * A convenience method that calls {@link #runOnce()} in an infinite loop. This must
+   * be run in a dedicated thread, and cannot be used in the main robot thread because
+   * it will freeze the robot program.
+   *
+   * <p><strong>Do not call this method directly from the main thread.</strong></p>
+   *
+   * @throws IllegalStateException if this is called from the main robot thread
+   * @see VisionThread
+   */
+  public void runForever() {
+    Long id = CameraServerSharedStore.getCameraServerShared().getRobotMainThreadId();
+
+    if (id != null && Thread.currentThread().getId() == id.longValue()) {
+      throw new IllegalStateException(
+          "VisionRunner.runForever() cannot be called from the main robot thread");
+    }
+    while (m_enabled && !Thread.interrupted()) {
+      runOnceInternal();
+    }
+  }
+
+  /**
+   * Stop a RunForever() loop.
+   */
+  public void stop() {
+    m_enabled = false;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionThread.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionThread.java
new file mode 100644
index 0000000..5184ba0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/VisionThread.java
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.vision;
+
+import edu.wpi.cscore.VideoSource;
+
+/**
+ * A vision thread is a special thread that runs a vision pipeline. It is a <i>daemon</i> thread;
+ * it does not prevent the program from exiting when all other non-daemon threads
+ * have finished running.
+ *
+ * @see VisionPipeline
+ * @see VisionRunner
+ * @see Thread#setDaemon(boolean)
+ *
+ * @deprecated Replaced with edu.wpi.first.vision.VisionThread
+ */
+@Deprecated
+public class VisionThread extends Thread {
+  /**
+   * Creates a vision thread that continuously runs a {@link VisionPipeline}.
+   *
+   * @param visionRunner the runner for a vision pipeline
+   */
+  public VisionThread(VisionRunner<?> visionRunner) {
+    super(visionRunner::runForever, "WPILib Vision Thread");
+    setDaemon(true);
+  }
+
+  /**
+   * Creates a new vision thread that continuously runs the given vision pipeline. This is
+   * equivalent to {@code new VisionThread(new VisionRunner<>(videoSource, pipeline, listener))}.
+   *
+   * @param videoSource the source for images the pipeline should process
+   * @param pipeline    the pipeline to run
+   * @param listener    the listener to copy outputs from the pipeline after it runs
+   * @param <P>         the type of the pipeline
+   */
+  public <P extends VisionPipeline> VisionThread(VideoSource videoSource,
+                                                 P pipeline,
+                                                 VisionRunner.Listener<? super P> listener) {
+    this(new VisionRunner<>(videoSource, pipeline, listener));
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/package-info.java b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/package-info.java
new file mode 100644
index 0000000..01c8d73
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/main/java/edu/wpi/first/wpilibj/vision/package-info.java
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/**
+ * Classes in the {@code edu.wpi.first.wpilibj.vision} package are designed to
+ * simplify using OpenCV vision processing code from a robot program.
+ *
+ * <p>An example use case for grabbing a yellow tote from 2015 in autonomous:
+ * <br>
+ * <pre><code>
+ * public class Robot extends IterativeRobot
+ *     implements VisionRunner.Listener&lt;MyFindTotePipeline&gt; {
+ *
+ *      // A USB camera connected to the roboRIO.
+ *      private {@link edu.wpi.cscore.VideoSource VideoSource} usbCamera;
+ *
+ *      // A vision pipeline. This could be handwritten or generated by GRIP.
+ *      // This has to implement {@link edu.wpi.first.wpilibj.vision.VisionPipeline}.
+ *      // For this example, assume that it's perfect and will always see the tote.
+ *      private MyFindTotePipeline findTotePipeline;
+ *      private {@link edu.wpi.first.wpilibj.vision.VisionThread} findToteThread;
+ *
+ *      // The object to synchronize on to make sure the vision thread doesn't
+ *      // write to variables the main thread is using.
+ *      private final Object visionLock = new Object();
+ *
+ *      // The pipeline outputs we want
+ *      private boolean pipelineRan = false; // lets us know when the pipeline has actually run
+ *      private double angleToTote = 0;
+ *      private double distanceToTote = 0;
+ *
+ *     {@literal @}Override
+ *      public void {@link edu.wpi.first.wpilibj.vision.VisionRunner.Listener#copyPipelineOutputs
+ *          copyPipelineOutputs(MyFindTotePipeline pipeline)} {
+ *          synchronized (visionLock) {
+ *              // Take a snapshot of the pipeline's output because
+ *              // it may have changed the next time this method is called!
+ *              this.pipelineRan = true;
+ *              this.angleToTote = pipeline.getAngleToTote();
+ *              this.distanceToTote = pipeline.getDistanceToTote();
+ *          }
+ *      }
+ *
+ *     {@literal @}Override
+ *      public void robotInit() {
+ *          usbCamera = CameraServer.getInstance().startAutomaticCapture(0);
+ *          findTotePipeline = new MyFindTotePipeline();
+ *          findToteThread = new VisionThread(usbCamera, findTotePipeline, this);
+ *      }
+ *
+ *     {@literal @}Override
+ *      public void autonomousInit() {
+ *          findToteThread.start();
+ *      }
+ *
+ *     {@literal @}Override
+ *      public void autonomousPeriodic() {
+ *          double angle;
+ *          double distance;
+ *          synchronized (visionLock) {
+ *              if (!pipelineRan) {
+ *                  // Wait until the pipeline has run
+ *                  return;
+ *              }
+ *              // Copy the outputs to make sure they're all from the same run
+ *              angle = this.angleToTote;
+ *              distance = this.distanceToTote;
+ *          }
+ *          if (!aimedAtTote()) {
+ *              turnToAngle(angle);
+ *          } else if (!droveToTote()) {
+ *              driveDistance(distance);
+ *          } else if (!grabbedTote()) {
+ *              grabTote();
+ *          } else {
+ *              // Tote was grabbed and we're done!
+ *              return;
+ *          }
+ *      }
+ *
+ * }
+ * </code></pre>
+ */
+@java.lang.Deprecated
+package edu.wpi.first.wpilibj.vision;
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/CircularBufferTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/CircularBufferTest.java
new file mode 100644
index 0000000..608361a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/CircularBufferTest.java
@@ -0,0 +1,214 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import org.junit.jupiter.api.Test;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+class CircularBufferTest {
+  private final double[] m_values = {751.848, 766.366, 342.657, 234.252, 716.126,
+      132.344, 445.697, 22.727, 421.125, 799.913};
+  private final double[] m_addFirstOut = {799.913, 421.125, 22.727, 445.697, 132.344,
+      716.126, 234.252, 342.657};
+  private final double[] m_addLastOut = {342.657, 234.252, 716.126, 132.344, 445.697,
+      22.727, 421.125, 799.913};
+
+  @Test
+  void addFirstTest() {
+    CircularBuffer queue = new CircularBuffer(8);
+
+    for (double value : m_values) {
+      queue.addFirst(value);
+    }
+
+    for (int i = 0; i < m_addFirstOut.length; i++) {
+      assertEquals(m_addFirstOut[i], queue.get(i), 0.00005);
+    }
+  }
+
+  @Test
+  void addLastTest() {
+    CircularBuffer queue = new CircularBuffer(8);
+
+    for (double value : m_values) {
+      queue.addLast(value);
+    }
+
+    for (int i = 0; i < m_addLastOut.length; i++) {
+      assertEquals(m_addLastOut[i], queue.get(i), 0.00005);
+    }
+  }
+
+  @Test
+  void pushPopTest() {
+    CircularBuffer queue = new CircularBuffer(3);
+
+    // Insert three elements into the buffer
+    queue.addLast(1.0);
+    queue.addLast(2.0);
+    queue.addLast(3.0);
+
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+    assertEquals(3.0, queue.get(2), 0.00005);
+
+    /*
+     * The buffer is full now, so pushing subsequent elements will overwrite the
+     * front-most elements.
+     */
+
+    queue.addLast(4.0); // Overwrite 1 with 4
+
+    // The buffer now contains 2, 3, and 4
+    assertEquals(2.0, queue.get(0), 0.00005);
+    assertEquals(3.0, queue.get(1), 0.00005);
+    assertEquals(4.0, queue.get(2), 0.00005);
+
+    queue.addLast(5.0); // Overwrite 2 with 5
+
+    // The buffer now contains 3, 4, and 5
+    assertEquals(3.0, queue.get(0), 0.00005);
+    assertEquals(4.0, queue.get(1), 0.00005);
+    assertEquals(5.0, queue.get(2), 0.00005);
+
+    assertEquals(5.0, queue.removeLast(), 0.00005); // 5 is removed
+
+    // The buffer now contains 3 and 4
+    assertEquals(3.0, queue.get(0), 0.00005);
+    assertEquals(4.0, queue.get(1), 0.00005);
+
+    assertEquals(3.0, queue.removeFirst(), 0.00005); // 3 is removed
+
+    // Leaving only one element with value == 4
+    assertEquals(4.0, queue.get(0), 0.00005);
+  }
+
+  @Test
+  void resetTest() {
+    CircularBuffer queue = new CircularBuffer(5);
+
+    for (int i = 0; i < 6; i++) {
+      queue.addLast(i);
+    }
+
+    queue.clear();
+
+    for (int i = 0; i < 5; i++) {
+      assertEquals(0.0, queue.get(i), 0.00005);
+    }
+  }
+
+  @Test
+  @SuppressWarnings("PMD.ExcessiveMethodLength")
+  void resizeTest() {
+    CircularBuffer queue = new CircularBuffer(5);
+
+    /* Buffer contains {1, 2, 3, _, _}
+     *                  ^ front
+     */
+    queue.addLast(1.0);
+    queue.addLast(2.0);
+    queue.addLast(3.0);
+
+    queue.resize(2);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.resize(5);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.clear();
+
+    /* Buffer contains {_, 1, 2, 3, _}
+     *                     ^ front
+     */
+    queue.addLast(0.0);
+    queue.addLast(1.0);
+    queue.addLast(2.0);
+    queue.addLast(3.0);
+    queue.removeFirst();
+
+    queue.resize(2);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.resize(5);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.clear();
+
+    /* Buffer contains {_, _, 1, 2, 3}
+     *                        ^ front
+     */
+    queue.addLast(0.0);
+    queue.addLast(0.0);
+    queue.addLast(1.0);
+    queue.addLast(2.0);
+    queue.addLast(3.0);
+    queue.removeFirst();
+    queue.removeFirst();
+
+    queue.resize(2);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.resize(5);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.clear();
+
+    /* Buffer contains {3, _, _, 1, 2}
+     *                           ^ front
+     */
+    queue.addLast(3.0);
+    queue.addFirst(2.0);
+    queue.addFirst(1.0);
+
+    queue.resize(2);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.resize(5);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.clear();
+
+    /* Buffer contains {2, 3, _, _, 1}
+     *                              ^ front
+     */
+    queue.addLast(2.0);
+    queue.addLast(3.0);
+    queue.addFirst(1.0);
+
+    queue.resize(2);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    queue.resize(5);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+
+    // Test addLast() after resize
+    queue.addLast(3.0);
+    assertEquals(1.0, queue.get(0), 0.00005);
+    assertEquals(2.0, queue.get(1), 0.00005);
+    assertEquals(3.0, queue.get(2), 0.00005);
+
+    // Test addFirst() after resize
+    queue.addFirst(4.0);
+    assertEquals(4.0, queue.get(0), 0.00005);
+    assertEquals(1.0, queue.get(1), 0.00005);
+    assertEquals(2.0, queue.get(2), 0.00005);
+    assertEquals(3.0, queue.get(3), 0.00005);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java
new file mode 100644
index 0000000..6990b50
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockHardwareExtension.java
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import org.junit.jupiter.api.extension.BeforeAllCallback;
+import org.junit.jupiter.api.extension.ExtensionContext;
+import org.junit.jupiter.api.extension.ExtensionContext.Namespace;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.sim.DriverStationSim;
+
+public final class MockHardwareExtension implements BeforeAllCallback {
+  private static ExtensionContext getRoot(ExtensionContext context) {
+    return context.getParent().map(MockHardwareExtension::getRoot).orElse(context);
+  }
+
+  @Override
+  public void beforeAll(ExtensionContext context) throws Exception {
+    getRoot(context).getStore(Namespace.GLOBAL).getOrComputeIfAbsent("HAL Initalized", key -> {
+      initializeHardware();
+      return true;
+    }, Boolean.class);
+  }
+
+  private void initializeHardware() {
+    HAL.initialize(500, 0);
+    DriverStationSim dsSim = new DriverStationSim();
+    dsSim.setDsAttached(true);
+    dsSim.setAutonomous(false);
+    dsSim.setEnabled(true);
+    dsSim.setTest(true);
+
+
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockSpeedController.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockSpeedController.java
new file mode 100644
index 0000000..d183723
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/MockSpeedController.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+public class MockSpeedController implements SpeedController {
+  private double m_speed;
+  private boolean m_isInverted;
+
+  @Override
+  public void set(double speed) {
+    m_speed = m_isInverted ? -speed : speed;
+  }
+
+  @Override
+  public double get() {
+    return m_speed;
+  }
+
+  @Override
+  public void setInverted(boolean isInverted) {
+    m_isInverted = isInverted;
+  }
+
+  @Override
+  public boolean getInverted() {
+    return m_isInverted;
+  }
+
+  @Override
+  public void disable() {
+    m_speed = 0;
+  }
+
+  @Override
+  public void stopMotor() {
+    disable();
+  }
+
+  @Override
+  public void pidWrite(double output) {
+    set(output);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/PIDToleranceTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/PIDToleranceTest.java
new file mode 100644
index 0000000..cbf3f99
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/PIDToleranceTest.java
@@ -0,0 +1,103 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+class PIDToleranceTest {
+  private PIDController m_pid;
+  private static final double m_setPoint = 50.0;
+  private static final double m_tolerance = 10.0;
+  private static final double m_range = 200;
+
+  private class FakeInput implements PIDSource {
+    public double m_val;
+
+    FakeInput() {
+      m_val = 0;
+    }
+
+    @Override
+    public PIDSourceType getPIDSourceType() {
+      return PIDSourceType.kDisplacement;
+    }
+
+    @Override
+    public double pidGet() {
+      return m_val;
+    }
+
+    @Override
+    public void setPIDSourceType(PIDSourceType arg0) {
+    }
+  }
+
+  private FakeInput m_inp;
+  private final PIDOutput m_out = new PIDOutput() {
+    @Override
+    public void pidWrite(double out) {
+    }
+
+  };
+
+
+  @BeforeEach
+  void setUp() {
+    m_inp = new FakeInput();
+    m_pid = new PIDController(0.05, 0.0, 0.0, m_inp, m_out);
+    m_pid.setInputRange(-m_range / 2, m_range / 2);
+  }
+
+  @AfterEach
+  void tearDown() {
+    m_pid.close();
+    m_pid = null;
+  }
+
+  @Test
+  void absoluteToleranceTest() {
+    m_pid.setAbsoluteTolerance(m_tolerance);
+    m_pid.setSetpoint(m_setPoint);
+    m_pid.enable();
+    Timer.delay(1);
+    assertFalse(m_pid.onTarget(), "Error was in tolerance when it should not have been. Error was "
+        + m_pid.getError());
+    m_inp.m_val = m_setPoint + m_tolerance / 2;
+    Timer.delay(1.0);
+    assertTrue(m_pid.onTarget(), "Error was not in tolerance when it should have been. Error was "
+        + m_pid.getError());
+    m_inp.m_val = m_setPoint + 10 * m_tolerance;
+    Timer.delay(1.0);
+    assertFalse(m_pid.onTarget(), "Error was in tolerance when it should not have been. Error was "
+        + m_pid.getError());
+  }
+
+  @Test
+  void percentToleranceTest() {
+    m_pid.setPercentTolerance(m_tolerance);
+    m_pid.setSetpoint(m_setPoint);
+    m_pid.enable();
+    assertFalse(m_pid.onTarget(), "Error was in tolerance when it should not have been. Error was "
+        + m_pid.getError());
+    //half of percent tolerance away from setPoint
+    m_inp.m_val = m_setPoint + m_tolerance / 200 * m_range;
+    Timer.delay(1.0);
+    assertTrue(m_pid.onTarget(), "Error was not in tolerance when it should have been. Error was "
+        + m_pid.getError());
+    //double percent tolerance away from setPoint
+    m_inp.m_val = m_setPoint + m_tolerance / 50 * m_range;
+    Timer.delay(1.0);
+    assertFalse(m_pid.onTarget(), "Error was in tolerance when it should not have been. Error was "
+        + m_pid.getError());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/RobotControllerTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/RobotControllerTest.java
new file mode 100644
index 0000000..576eb8b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/RobotControllerTest.java
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+class RobotControllerTest extends UtilityClassTest {
+  RobotControllerTest() {
+    super(RobotController.class);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/SpeedControllerGroupTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/SpeedControllerGroupTest.java
new file mode 100644
index 0000000..62e2f46
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/SpeedControllerGroupTest.java
@@ -0,0 +1,109 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.stream.DoubleStream;
+import java.util.stream.IntStream;
+import java.util.stream.Stream;
+
+import org.junit.jupiter.params.ParameterizedTest;
+import org.junit.jupiter.params.provider.Arguments;
+import org.junit.jupiter.params.provider.MethodSource;
+
+import static org.junit.jupiter.api.Assertions.assertArrayEquals;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+class SpeedControllerGroupTest {
+  private static Stream<Arguments> speedControllerArguments() {
+    return IntStream.of(1, 2, 3).mapToObj(number -> {
+      SpeedController[] speedControllers = Stream.generate(MockSpeedController::new)
+          .limit(number)
+          .toArray(SpeedController[]::new);
+      SpeedControllerGroup group = new SpeedControllerGroup(speedControllers[0],
+          Arrays.copyOfRange(speedControllers, 1, speedControllers.length));
+      return Arguments.of(group, speedControllers);
+    });
+  }
+
+  @ParameterizedTest
+  @MethodSource("speedControllerArguments")
+  void setTest(final SpeedControllerGroup group, final SpeedController[] speedControllers) {
+    group.set(1.0);
+
+    assertArrayEquals(DoubleStream.generate(() -> 1.0).limit(speedControllers.length).toArray(),
+        Arrays.stream(speedControllers).mapToDouble(SpeedController::get).toArray(),
+        0.00005);
+  }
+
+  @ParameterizedTest
+  @MethodSource("speedControllerArguments")
+  void getInvertedTest(final SpeedControllerGroup group,
+                       final SpeedController[] speedControllers) {
+    group.setInverted(true);
+
+    assertTrue(group.getInverted());
+  }
+
+  @ParameterizedTest
+  @MethodSource("speedControllerArguments")
+  void setInvertedDoesNotModifySpeedControllersTest(final SpeedControllerGroup group,
+                                                    final SpeedController[] speedControllers) {
+    group.setInverted(true);
+
+    assertArrayEquals(Stream.generate(() -> false).limit(speedControllers.length).toArray(),
+        Arrays.stream(speedControllers).map(SpeedController::getInverted).toArray());
+  }
+
+  @ParameterizedTest
+  @MethodSource("speedControllerArguments")
+  void setInvertedDoesInvertTest(final SpeedControllerGroup group,
+                                 final SpeedController[] speedControllers) {
+    group.setInverted(true);
+    group.set(1.0);
+
+    assertArrayEquals(DoubleStream.generate(() -> -1.0).limit(speedControllers.length).toArray(),
+        Arrays.stream(speedControllers).mapToDouble(SpeedController::get).toArray(),
+        0.00005);
+  }
+
+  @ParameterizedTest
+  @MethodSource("speedControllerArguments")
+  void disableTest(final SpeedControllerGroup group,
+                   final SpeedController[] speedControllers) {
+    group.set(1.0);
+    group.disable();
+
+    assertArrayEquals(DoubleStream.generate(() -> 0.0).limit(speedControllers.length).toArray(),
+        Arrays.stream(speedControllers).mapToDouble(SpeedController::get).toArray(),
+        0.00005);
+  }
+
+  @ParameterizedTest
+  @MethodSource("speedControllerArguments")
+  void stopMotorTest(final SpeedControllerGroup group,
+                     final SpeedController[] speedControllers) {
+    group.set(1.0);
+    group.stopMotor();
+
+    assertArrayEquals(DoubleStream.generate(() -> 0.0).limit(speedControllers.length).toArray(),
+        Arrays.stream(speedControllers).mapToDouble(SpeedController::get).toArray(),
+        0.00005);
+  }
+
+  @ParameterizedTest
+  @MethodSource("speedControllerArguments")
+  void pidWriteTest(final SpeedControllerGroup group,
+                    final SpeedController[] speedControllers) {
+    group.pidWrite(1.0);
+
+    assertArrayEquals(DoubleStream.generate(() -> 1.0).limit(speedControllers.length).toArray(),
+        Arrays.stream(speedControllers).mapToDouble(SpeedController::get).toArray(),
+        0.00005);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java
new file mode 100644
index 0000000..1265429
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/UtilityClassTest.java
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.lang.reflect.Constructor;
+import java.lang.reflect.InvocationTargetException;
+import java.lang.reflect.Modifier;
+import java.util.Arrays;
+import java.util.stream.Stream;
+
+import org.junit.jupiter.api.DynamicTest;
+import org.junit.jupiter.api.Test;
+import org.junit.jupiter.api.TestFactory;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertThrows;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+import static org.junit.jupiter.api.DynamicTest.dynamicTest;
+
+@SuppressWarnings("PMD.AbstractClassWithoutAbstractMethod")
+public abstract class UtilityClassTest {
+  private final Class m_clazz;
+
+  protected UtilityClassTest(Class clazz) {
+    m_clazz = clazz;
+  }
+
+  @Test
+  public void singleConstructorTest() {
+    assertEquals(1, m_clazz.getDeclaredConstructors().length,
+        "More than one constructor defined");
+  }
+
+  @Test
+  public void constructorPrivateTest() {
+    Constructor constructor = m_clazz.getDeclaredConstructors()[0];
+
+    assertFalse(constructor.isAccessible(), "Constructor is not private");
+  }
+
+  @Test
+  public void constructorReflectionTest() {
+    Constructor constructor = m_clazz.getDeclaredConstructors()[0];
+    constructor.setAccessible(true);
+    assertThrows(InvocationTargetException.class, () -> constructor.newInstance());
+  }
+
+  @TestFactory
+  Stream<DynamicTest> publicMethodsStaticTestFactory() {
+    return Arrays.stream(m_clazz.getDeclaredMethods())
+        .filter(method -> Modifier.isPublic(method.getModifiers()))
+        .map(method -> dynamicTest(method.getName(),
+            () -> assertTrue(Modifier.isStatic(method.getModifiers()))));
+  }
+}
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
new file mode 100644
index 0000000..9ed5db8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/WatchdogTest.java
@@ -0,0 +1,217 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.concurrent.atomic.AtomicInteger;
+
+import org.junit.jupiter.api.Test;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+class WatchdogTest {
+  @Test
+  void enableDisableTest() {
+    final AtomicInteger watchdogCounter = new AtomicInteger(0);
+
+    final Watchdog watchdog = new Watchdog(0.4, () -> {
+      watchdogCounter.addAndGet(1);
+    });
+
+    System.out.println("Run 1");
+    watchdog.enable();
+    try {
+      Thread.sleep(200);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.disable();
+
+    assertEquals(0, watchdogCounter.get(), "Watchdog triggered early");
+
+    System.out.println("Run 2");
+    watchdogCounter.set(0);
+    watchdog.enable();
+    try {
+      Thread.sleep(600);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.disable();
+
+    assertEquals(1, watchdogCounter.get(),
+        "Watchdog either didn't trigger or triggered more than once");
+
+    // Run 3
+    watchdogCounter.set(0);
+    watchdog.enable();
+    try {
+      Thread.sleep(1000);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.disable();
+
+    assertEquals(1, watchdogCounter.get(),
+        "Watchdog either didn't trigger or triggered more than once");
+  }
+
+  @Test
+  void resetTest() {
+    final AtomicInteger watchdogCounter = new AtomicInteger(0);
+
+    final Watchdog watchdog = new Watchdog(0.4, () -> {
+      watchdogCounter.addAndGet(1);
+    });
+
+    watchdog.enable();
+    try {
+      Thread.sleep(200);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.reset();
+    try {
+      Thread.sleep(200);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.disable();
+
+    assertEquals(0, watchdogCounter.get(), "Watchdog triggered early");
+  }
+
+  @Test
+  void setTimeoutTest() {
+    final AtomicInteger watchdogCounter = new AtomicInteger(0);
+
+    final Watchdog watchdog = new Watchdog(1.0, () -> {
+      watchdogCounter.addAndGet(1);
+    });
+
+    watchdog.enable();
+    try {
+      Thread.sleep(200);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.setTimeout(0.2);
+
+    assertEquals(0.2, watchdog.getTimeout());
+    assertEquals(0, watchdogCounter.get(), "Watchdog triggered early");
+
+    try {
+      Thread.sleep(300);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.disable();
+
+    assertEquals(1, watchdogCounter.get(),
+        "Watchdog either didn't trigger or triggered more than once");
+  }
+
+  @Test
+  void isExpiredTest() {
+    final Watchdog watchdog = new Watchdog(0.2, () -> {
+    });
+    watchdog.enable();
+
+    assertFalse(watchdog.isExpired());
+    try {
+      Thread.sleep(300);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    assertTrue(watchdog.isExpired());
+  }
+
+  @Test
+  void epochsTest() {
+    final AtomicInteger watchdogCounter = new AtomicInteger(0);
+
+    final Watchdog watchdog = new Watchdog(0.4, () -> {
+      watchdogCounter.addAndGet(1);
+    });
+
+    System.out.println("Run 1");
+    watchdog.enable();
+    watchdog.addEpoch("Epoch 1");
+    try {
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.addEpoch("Epoch 2");
+    try {
+      Thread.sleep(100);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.addEpoch("Epoch 3");
+    watchdog.disable();
+
+    assertEquals(0, watchdogCounter.get(), "Watchdog triggered early");
+
+    System.out.println("Run 2");
+    watchdog.enable();
+    watchdog.addEpoch("Epoch 1");
+    try {
+      Thread.sleep(200);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.reset();
+    try {
+      Thread.sleep(200);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog.addEpoch("Epoch 2");
+    watchdog.disable();
+
+    assertEquals(0, watchdogCounter.get(), "Watchdog triggered early");
+  }
+
+  @Test
+  void multiWatchdogTest() {
+    final AtomicInteger watchdogCounter1 = new AtomicInteger(0);
+    final AtomicInteger watchdogCounter2 = new AtomicInteger(0);
+
+    final Watchdog watchdog1 = new Watchdog(0.2, () -> {
+      watchdogCounter1.addAndGet(1);
+    });
+    final Watchdog watchdog2 = new Watchdog(0.6, () -> {
+      watchdogCounter2.addAndGet(1);
+    });
+
+    watchdog2.enable();
+    try {
+      Thread.sleep(200);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    assertEquals(0, watchdogCounter1.get(), "Watchdog triggered early");
+    assertEquals(0, watchdogCounter2.get(), "Watchdog triggered early");
+
+    // Sleep enough such that only the watchdog enabled later times out first
+    watchdog1.enable();
+    try {
+      Thread.sleep(300);
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    watchdog1.disable();
+    watchdog2.disable();
+
+    assertEquals(1, watchdogCounter1.get(),
+        "Watchdog either didn't trigger or triggered more than once");
+    assertEquals(0, watchdogCounter2.get(), "Watchdog triggered early");
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/can/CANStatusTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/can/CANStatusTest.java
new file mode 100644
index 0000000..e804d0c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/can/CANStatusTest.java
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.can;
+
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.can.CANJNI;
+import edu.wpi.first.hal.can.CANStatus;
+
+import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
+
+class CANStatusTest {
+  @Test
+  void canStatusGetDoesntThrow() {
+    HAL.initialize(500, 0);
+    CANStatus status = new CANStatus();
+    assertDoesNotThrow(() -> CANJNI.GetCANStatus(status));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java
new file mode 100644
index 0000000..1fa9aa8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/AbstractCommandTest.java
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import org.junit.jupiter.api.BeforeEach;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+/**
+ * The basic test for all {@link Command} tests.
+ */
+public abstract class AbstractCommandTest {
+  @BeforeEach
+  void commandSetup() {
+    Scheduler.getInstance().removeAll();
+    Scheduler.getInstance().enable();
+  }
+
+  public class ASubsystem extends Subsystem {
+    Command m_command;
+
+    @Override
+    protected void initDefaultCommand() {
+      if (m_command != null) {
+        setDefaultCommand(m_command);
+      }
+    }
+
+    public void init(Command command) {
+      m_command = command;
+    }
+  }
+
+
+  protected void assertCommandState(MockCommand command, int initialize, int execute,
+                                    int isFinished, int end, int interrupted) {
+    assertAll(
+        () -> assertEquals(initialize, command.getInitializeCount()),
+        () -> assertEquals(execute, command.getExecuteCount()),
+        () -> assertEquals(isFinished, command.getIsFinishedCount()),
+        () -> assertEquals(end, command.getEndCount()),
+        () -> assertEquals(interrupted, command.getInterruptedCount())
+    );
+  }
+
+  protected void sleep(int time) {
+    assertDoesNotThrow(() -> Thread.sleep(time));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java
new file mode 100644
index 0000000..3686c78
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/ButtonTest.java
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.wpilibj.buttons.InternalButton;
+
+
+/**
+ * Test that covers the {@link edu.wpi.first.wpilibj.buttons.Button} with the {@link Command}
+ * library.
+ */
+class ButtonTest extends AbstractCommandTest {
+  private InternalButton m_button1;
+  private InternalButton m_button2;
+
+  @BeforeEach
+  void setUp() {
+    m_button1 = new InternalButton();
+    m_button2 = new InternalButton();
+  }
+
+  /**
+   * Simple Button Test.
+   */
+  @Test
+  void buttonTest() {
+    final MockCommand command1 = new MockCommand();
+    final MockCommand command2 = new MockCommand();
+    final MockCommand command3 = new MockCommand();
+    final MockCommand command4 = new MockCommand();
+
+    m_button1.whenPressed(command1);
+    m_button1.whenReleased(command2);
+    m_button1.whileHeld(command3);
+    m_button2.whileHeld(command4);
+
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+    assertCommandState(command4, 0, 0, 0, 0, 0);
+    m_button1.setPressed(true);
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+    assertCommandState(command4, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+    assertCommandState(command4, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 1, 1, 1, 0, 0);
+    assertCommandState(command4, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 2, 2, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 1, 2, 2, 0, 0);
+    assertCommandState(command4, 0, 0, 0, 0, 0);
+    m_button2.setPressed(true);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 3, 3, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 1, 3, 3, 0, 0);
+    assertCommandState(command4, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 4, 4, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 1, 4, 4, 0, 0);
+    assertCommandState(command4, 1, 1, 1, 0, 0);
+    m_button1.setPressed(false);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 5, 5, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 1, 4, 4, 0, 1);
+    assertCommandState(command4, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 6, 6, 0, 0);
+    assertCommandState(command2, 1, 1, 1, 0, 0);
+    assertCommandState(command3, 1, 4, 4, 0, 1);
+    assertCommandState(command4, 1, 3, 3, 0, 0);
+    m_button2.setPressed(false);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 7, 7, 0, 0);
+    assertCommandState(command2, 1, 2, 2, 0, 0);
+    assertCommandState(command3, 1, 4, 4, 0, 1);
+    assertCommandState(command4, 1, 3, 3, 0, 1);
+    command1.cancel();
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 7, 7, 0, 1);
+    assertCommandState(command2, 1, 3, 3, 0, 0);
+    assertCommandState(command3, 1, 4, 4, 0, 1);
+    assertCommandState(command4, 1, 3, 3, 0, 1);
+    command2.setHasFinished(true);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 7, 7, 0, 1);
+    assertCommandState(command2, 1, 4, 4, 1, 0);
+    assertCommandState(command3, 1, 4, 4, 0, 1);
+    assertCommandState(command4, 1, 3, 3, 0, 1);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 7, 7, 0, 1);
+    assertCommandState(command2, 1, 4, 4, 1, 0);
+    assertCommandState(command3, 1, 4, 4, 0, 1);
+    assertCommandState(command4, 1, 3, 3, 0, 1);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java
new file mode 100644
index 0000000..b3b7ad9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandParallelGroupTest.java
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import org.junit.jupiter.api.Test;
+
+/**
+ * Ported from the old CrioTest Classes.
+ */
+class CommandParallelGroupTest extends AbstractCommandTest {
+  /**
+   * Simple Parallel Command Group With 2 commands one command terminates first.
+   */
+  @Test
+  void parallelCommandGroupWithTwoCommandsTest() {
+    final MockCommand command1 = new MockCommand();
+    final MockCommand command2 = new MockCommand();
+
+    final CommandGroup commandGroup = new CommandGroup();
+    commandGroup.addParallel(command1);
+    commandGroup.addParallel(command2);
+
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    commandGroup.start();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 0);
+    assertCommandState(command2, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 2, 2, 0, 0);
+    assertCommandState(command2, 1, 2, 2, 0, 0);
+    command1.setHasFinished(true);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 3, 3, 1, 0);
+    assertCommandState(command2, 1, 3, 3, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 3, 3, 1, 0);
+    assertCommandState(command2, 1, 4, 4, 0, 0);
+    command2.setHasFinished(true);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 3, 3, 1, 0);
+    assertCommandState(command2, 1, 5, 5, 1, 0);
+
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java
new file mode 100644
index 0000000..feb80bc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandScheduleTest.java
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import org.junit.jupiter.api.Test;
+
+/**
+ * Ported from the old CrioTest Classes.
+ */
+class CommandScheduleTest extends AbstractCommandTest {
+  /**
+   * Simple scheduling of a command and making sure the command is run and successfully terminates.
+   */
+  @Test
+  void runAndTerminateTest() {
+    final MockCommand command = new MockCommand();
+    command.start();
+    assertCommandState(command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 2, 2, 0, 0);
+    command.setHasFinished(true);
+    assertCommandState(command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 3, 3, 1, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 3, 3, 1, 0);
+  }
+
+  /**
+   * Simple scheduling of a command and making sure the command is run and cancels correctly.
+   */
+  @Test
+  void runAndCancelTest() {
+    final MockCommand command = new MockCommand();
+    command.start();
+    assertCommandState(command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 3, 3, 0, 0);
+    command.cancel();
+    assertCommandState(command, 1, 3, 3, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 3, 3, 0, 1);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 3, 3, 0, 1);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java
new file mode 100644
index 0000000..5667b05
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSequentialGroupTest.java
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import java.util.logging.Logger;
+
+import org.junit.jupiter.api.Test;
+
+/**
+ * Ported from the old CrioTest Classes.
+ */
+class CommandSequentialGroupTest extends AbstractCommandTest {
+  private static final Logger logger = Logger.getLogger(CommandSequentialGroupTest.class.getName());
+
+  /**
+   * Simple Command Group With 3 commands that all depend on a subsystem. Some commands have a
+   * timeout.
+   */
+  @Test
+  public void testThreeCommandOnSubSystem() {
+    logger.fine("Begining Test");
+    final ASubsystem subsystem = new ASubsystem();
+
+    logger.finest("Creating Mock Command1");
+    final MockCommand command1 = new MockCommand(subsystem);
+    logger.finest("Creating Mock Command2");
+    final MockCommand command2 = new MockCommand(subsystem);
+    logger.finest("Creating Mock Command3");
+    final MockCommand command3 = new MockCommand(subsystem);
+
+    logger.finest("Creating Command Group");
+    final CommandGroup commandGroup = new CommandGroup();
+    commandGroup.addSequential(command1, 1.0);
+    commandGroup.addSequential(command2, 2.0);
+    commandGroup.addSequential(command3);
+
+
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+    logger.finest("Starting Command group");
+    commandGroup.start();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+    sleep(1250); // command 1 timeout
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 1);
+    assertCommandState(command2, 1, 1, 1, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 1);
+    assertCommandState(command2, 1, 2, 2, 0, 0);
+    assertCommandState(command3, 0, 0, 0, 0, 0);
+    sleep(2500); // command 2 timeout
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 1);
+    assertCommandState(command2, 1, 2, 2, 0, 1);
+    assertCommandState(command3, 1, 1, 1, 0, 0);
+
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 1);
+    assertCommandState(command2, 1, 2, 2, 0, 1);
+    assertCommandState(command3, 1, 2, 2, 0, 0);
+    command3.setHasFinished(true);
+    assertCommandState(command1, 1, 1, 1, 0, 1);
+    assertCommandState(command2, 1, 2, 2, 0, 1);
+    assertCommandState(command3, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 1);
+    assertCommandState(command2, 1, 2, 2, 0, 1);
+    assertCommandState(command3, 1, 3, 3, 1, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 1);
+    assertCommandState(command2, 1, 2, 2, 0, 1);
+    assertCommandState(command3, 1, 3, 3, 1, 0);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java
new file mode 100644
index 0000000..4ba965f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandSupersedeTest.java
@@ -0,0 +1,102 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import org.junit.jupiter.api.Test;
+
+/**
+ * Ported from the old CrioTest Classes.
+ */
+class CommandSupersedeTest extends AbstractCommandTest {
+  /**
+   * Testing one command superseding another because of dependencies.
+   */
+  @Test
+  void oneCommandSupersedingAnotherBecauseOfDependenciesTest() {
+    final ASubsystem subsystem = new ASubsystem();
+
+    final MockCommand command1 = new MockCommand(subsystem);
+
+    final MockCommand command2 = new MockCommand(subsystem);
+
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    command1.start();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 2, 2, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 3, 3, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    command2.start();
+    assertCommandState(command1, 1, 3, 3, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 4, 4, 0, 1);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 4, 4, 0, 1);
+    assertCommandState(command2, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 4, 4, 0, 1);
+    assertCommandState(command2, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 4, 4, 0, 1);
+    assertCommandState(command2, 1, 3, 3, 0, 0);
+  }
+
+  /**
+   * Testing one command failing superseding another because of dependencies because the first
+   * command cannot be interrupted.
+   */
+  @Test
+  @SuppressWarnings("PMD.NonStaticInitializer")
+  void commandFailingSupersedingBecauseFirstCanNotBeInterruptedTest() {
+    final ASubsystem subsystem = new ASubsystem();
+
+    final MockCommand command1 = new MockCommand(subsystem) {
+      {
+        setInterruptible(false);
+      }
+    };
+
+    final MockCommand command2 = new MockCommand(subsystem);
+
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    command1.start();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 0, 0, 0, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 1, 1, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 2, 2, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 3, 3, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    command2.start();
+    assertCommandState(command1, 1, 3, 3, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command1, 1, 4, 4, 0, 0);
+    assertCommandState(command2, 0, 0, 0, 0, 0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java
new file mode 100644
index 0000000..ff7ad86
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/CommandTimeoutTest.java
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import org.junit.jupiter.api.Test;
+
+/**
+ * Test a {@link Command} that times out.
+ */
+class CommandTimeoutTest extends AbstractCommandTest {
+  /**
+   * Command 2 second Timeout Test.
+   */
+  @Test
+  void twoSecondTimeoutTest() {
+    final ASubsystem subsystem = new ASubsystem();
+
+
+    final MockCommand command = new MockCommand(subsystem, 2) {
+      @Override
+      public boolean isFinished() {
+        return super.isFinished() || isTimedOut();
+      }
+    };
+
+    command.start();
+    assertCommandState(command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 3, 3, 0, 0);
+    sleep(2500);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 4, 4, 1, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(command, 1, 4, 4, 1, 0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java
new file mode 100644
index 0000000..5f3285c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/ConditionalCommandTest.java
@@ -0,0 +1,345 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertSame;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+class ConditionalCommandTest extends AbstractCommandTest {
+  MockConditionalCommand m_command;
+  MockConditionalCommand m_commandNull;
+  MockCommand m_onTrue;
+  MockCommand m_onFalse;
+  MockSubsystem m_subsys;
+  Boolean m_condition;
+
+  @BeforeEach
+  void initCommands() {
+    m_subsys = new MockSubsystem();
+    m_onTrue = new MockCommand(m_subsys);
+    m_onFalse = new MockCommand(m_subsys);
+    m_command = new MockConditionalCommand(m_onTrue, m_onFalse);
+    m_commandNull = new MockConditionalCommand(m_onTrue, null);
+  }
+
+  protected void assertConditionalCommandState(MockConditionalCommand command, int initialize,
+                                               int execute, int isFinished, int end,
+                                               int interrupted) {
+    assertEquals(initialize, command.getInitializeCount());
+    assertEquals(execute, command.getExecuteCount());
+    assertEquals(isFinished, command.getIsFinishedCount());
+    assertEquals(end, command.getEndCount());
+    assertEquals(interrupted, command.getInterruptedCount());
+  }
+
+  @Test
+  void onTrueTest() {
+    m_command.setCondition(true);
+
+    Scheduler.getInstance().add(m_command);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
+    m_onTrue.setHasFinished(true);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
+
+    assertTrue(m_onTrue.getInitializeCount() > 0, "Did not initialize the true command");
+    assertSame(m_onFalse.getInitializeCount(), 0, "Initialized the false command");
+  }
+
+  @Test
+  void onFalseTest() {
+    m_command.setCondition(false);
+
+    Scheduler.getInstance().add(m_command);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onFalse
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onFalse
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onFalse, 1, 1, 1, 0, 0);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onFalse, 1, 2, 2, 0, 0);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
+    m_onFalse.setHasFinished(true);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onFalse, 1, 3, 3, 1, 0);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onFalse, 1, 3, 3, 1, 0);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
+
+    assertTrue(m_onFalse.getInitializeCount() > 0, "Did not initialize the false command");
+    assertSame(m_onTrue.getInitializeCount(), 0, "Initialized the true command");
+  }
+
+  @Test
+  void cancelSubCommandTest() {
+    m_command.setCondition(true);
+
+    Scheduler.getInstance().add(m_command);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
+    m_onTrue.cancel();
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
+  }
+
+  @Test
+  void cancelRequiresTest() {
+    m_command.setCondition(true);
+
+    Scheduler.getInstance().add(m_command);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
+    m_onFalse.start();
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 3, 3, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 4, 4, 0, 1);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 3, 3, 0, 1);
+    assertCommandState(m_onFalse, 1, 1, 1, 0, 0);
+    assertConditionalCommandState(m_command, 1, 4, 4, 0, 1);
+  }
+
+  @Test
+  void cancelCondCommandTest() {
+    m_command.setCondition(true);
+
+    Scheduler.getInstance().add(m_command);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
+    m_command.cancel();
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 1);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 1);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 1);
+  }
+
+  @Test
+  void onTrueTwiceTest() {
+    m_command.setCondition(true);
+
+    Scheduler.getInstance().add(m_command);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
+    m_onTrue.setHasFinished(true);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
+
+    m_onTrue.resetCounters();
+    m_command.resetCounters();
+    m_command.setCondition(true);
+    Scheduler.getInstance().add(m_command);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 2, 2, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 0, 0);
+    m_onTrue.setHasFinished(true);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 4, 4, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 3, 3, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 5, 5, 1, 0);
+  }
+
+  @Test
+  void onTrueInstantTest() {
+    m_command.setCondition(true);
+    m_onTrue.setHasFinished(true);
+
+    Scheduler.getInstance().add(m_command);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onTrue
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 1, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 1, 1, 1, 1, 0);
+    assertCommandState(m_onFalse, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_command, 1, 3, 3, 1, 0);
+  }
+
+  @Test
+  void onFalseNullTest() {
+    m_commandNull.setCondition(false);
+
+    Scheduler.getInstance().add(m_commandNull);
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_commandNull, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init command and select m_onFalse
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_commandNull, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();  // init m_onFalse
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_commandNull, 1, 1, 1, 1, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(m_onTrue, 0, 0, 0, 0, 0);
+    assertConditionalCommandState(m_commandNull, 1, 1, 1, 1, 0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java
new file mode 100644
index 0000000..1cfec7f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/DefaultCommandTest.java
@@ -0,0 +1,111 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+import org.junit.jupiter.api.Test;
+
+/**
+ * Tests the {@link Command} library.
+ */
+public class DefaultCommandTest extends AbstractCommandTest {
+  /**
+   * Testing of default commands where the interrupting command ends itself.
+   */
+  @Test
+  void defaultCommandWhereTheInteruptingCommandEndsItselfTest() {
+    final ASubsystem subsystem = new ASubsystem();
+
+
+    final MockCommand defaultCommand = new MockCommand(subsystem);
+
+    final MockCommand anotherCommand = new MockCommand(subsystem);
+    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+    subsystem.init(defaultCommand);
+
+    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
+
+    anotherCommand.start();
+    assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
+    assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
+    anotherCommand.setHasFinished(true);
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 2, 4, 4, 0, 1);
+    assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 2, 5, 5, 0, 1);
+    assertCommandState(anotherCommand, 1, 3, 3, 1, 0);
+  }
+
+
+  /**
+   * Testing of default commands where the interrupting command is canceled.
+   */
+  @Test
+  void defaultCommandsInterruptingCommandCanceledTest() {
+    final ASubsystem subsystem = new ASubsystem();
+    final MockCommand defaultCommand = new MockCommand(subsystem);
+    final MockCommand anotherCommand = new MockCommand(subsystem);
+
+    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+    subsystem.init(defaultCommand);
+    subsystem.initDefaultCommand();
+    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
+
+    anotherCommand.start();
+    assertCommandState(defaultCommand, 1, 2, 2, 0, 0);
+    assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 0, 0, 0, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 1, 1, 1, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
+    anotherCommand.cancel();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 1, 2, 2, 0, 0);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 1, 3, 3, 0, 1);
+    assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 2, 4, 4, 0, 1);
+    assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
+    Scheduler.getInstance().run();
+    assertCommandState(defaultCommand, 2, 5, 5, 0, 1);
+    assertCommandState(anotherCommand, 1, 2, 2, 0, 1);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java
new file mode 100644
index 0000000..bee2f80
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockCommand.java
@@ -0,0 +1,149 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * A class to simulate a simple command. The command keeps track of how many times each method was
+ * called.
+ */
+public class MockCommand extends Command {
+  private int m_initializeCount;
+  private int m_executeCount;
+  private int m_isFinishedCount;
+  private boolean m_hasFinished;
+  private int m_endCount;
+  private int m_interruptedCount;
+
+  public MockCommand(Subsystem subsys) {
+    super();
+    requires(subsys);
+  }
+
+  public MockCommand(Subsystem subsys, double timeout) {
+    this(subsys);
+    setTimeout(timeout);
+  }
+
+  public MockCommand() {
+    super();
+  }
+
+  @Override
+  protected void initialize() {
+    ++m_initializeCount;
+  }
+
+  @Override
+  protected void execute() {
+    ++m_executeCount;
+  }
+
+  @Override
+  protected boolean isFinished() {
+    ++m_isFinishedCount;
+    return isHasFinished();
+  }
+
+  @Override
+  protected void end() {
+    ++m_endCount;
+  }
+
+  @Override
+  protected void interrupted() {
+    ++m_interruptedCount;
+  }
+
+
+  /**
+   * How many times the initialize method has been called.
+   */
+  public int getInitializeCount() {
+    return m_initializeCount;
+  }
+
+  /**
+   * If the initialize method has been called at least once.
+   */
+  public boolean hasInitialized() {
+    return getInitializeCount() > 0;
+  }
+
+  /**
+   * How many time the execute method has been called.
+   */
+  public int getExecuteCount() {
+    return m_executeCount;
+  }
+
+  /**
+   * How many times the isFinished method has been called.
+   */
+  public int getIsFinishedCount() {
+    return m_isFinishedCount;
+  }
+
+  /**
+   * Get what value the isFinished method will return.
+   *
+   * @return what value the isFinished method will return.
+   */
+  public boolean isHasFinished() {
+    return m_hasFinished;
+  }
+
+  /**
+   * Set what value the isFinished method will return.
+   *
+   * @param hasFinished set what value the isFinished method will return.
+   */
+  public void setHasFinished(boolean hasFinished) {
+    m_hasFinished = hasFinished;
+  }
+
+  /**
+   * How many times the end method has been called.
+   */
+  public int getEndCount() {
+    return m_endCount;
+  }
+
+  /**
+   * If the end method has been called at least once.
+   */
+  public boolean hasEnd() {
+    return getEndCount() > 0;
+  }
+
+  /**
+   * How many times the interrupted method has been called.
+   */
+  public int getInterruptedCount() {
+    return m_interruptedCount;
+  }
+
+  /**
+   * If the interrupted method has been called at least once.
+   */
+  public boolean hasInterrupted() {
+    return getInterruptedCount() > 0;
+  }
+
+  /**
+   * Reset internal counters.
+   */
+  public void resetCounters() {
+    m_initializeCount = 0;
+    m_executeCount = 0;
+    m_isFinishedCount = 0;
+    m_hasFinished = false;
+    m_endCount = 0;
+    m_interruptedCount = 0;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java
new file mode 100644
index 0000000..876f1c5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockConditionalCommand.java
@@ -0,0 +1,125 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+public class MockConditionalCommand extends ConditionalCommand {
+  private boolean m_condition;
+  private int m_initializeCount;
+  private int m_executeCount;
+  private int m_isFinishedCount;
+  private int m_endCount;
+  private int m_interruptedCount;
+
+  public MockConditionalCommand(MockCommand onTrue, MockCommand onFalse) {
+    super(onTrue, onFalse);
+  }
+
+  @Override
+  protected boolean condition() {
+    return m_condition;
+  }
+
+  public void setCondition(boolean condition) {
+    this.m_condition = condition;
+  }
+
+  @Override
+  protected void initialize() {
+    ++m_initializeCount;
+  }
+
+  @Override
+  protected void execute() {
+    ++m_executeCount;
+  }
+
+  @Override
+  protected boolean isFinished() {
+    ++m_isFinishedCount;
+    return super.isFinished();
+  }
+
+  @Override
+  protected void end() {
+    ++m_endCount;
+  }
+
+  @Override
+  protected void interrupted() {
+    ++m_interruptedCount;
+  }
+
+
+  /**
+   * How many times the initialize method has been called.
+   */
+  public int getInitializeCount() {
+    return m_initializeCount;
+  }
+
+  /**
+   * If the initialize method has been called at least once.
+   */
+  public boolean hasInitialized() {
+    return getInitializeCount() > 0;
+  }
+
+  /**
+   * How many time the execute method has been called.
+   */
+  public int getExecuteCount() {
+    return m_executeCount;
+  }
+
+  /**
+   * How many times the isFinished method has been called.
+   */
+  public int getIsFinishedCount() {
+    return m_isFinishedCount;
+  }
+
+  /**
+   * How many times the end method has been called.
+   */
+  public int getEndCount() {
+    return m_endCount;
+  }
+
+  /**
+   * If the end method has been called at least once.
+   */
+  public boolean hasEnd() {
+    return getEndCount() > 0;
+  }
+
+  /**
+   * How many times the interrupted method has been called.
+   */
+  public int getInterruptedCount() {
+    return m_interruptedCount;
+  }
+
+  /**
+   * If the interrupted method has been called at least once.
+   */
+  public boolean hasInterrupted() {
+    return getInterruptedCount() > 0;
+  }
+
+  /**
+   * Reset internal counters.
+   */
+  public void resetCounters() {
+    m_condition = false;
+    m_initializeCount = 0;
+    m_executeCount = 0;
+    m_isFinishedCount = 0;
+    m_endCount = 0;
+    m_interruptedCount = 0;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java
new file mode 100644
index 0000000..df39cd1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/command/MockSubsystem.java
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.command;
+
+/**
+ * A class to simulate a simple subsystem.
+ */
+public class MockSubsystem extends Subsystem {
+  @Override
+  protected void initDefaultCommand() {}
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/JNITest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/JNITest.java
new file mode 100644
index 0000000..f70f3f8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/JNITest.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.hal;
+
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.HALUtil;
+import edu.wpi.first.networktables.NetworkTablesJNI;
+
+class JNITest {
+  @Test
+  void jniNtcoreLinkTest() {
+    // Test to verify that the JNI test link works correctly.
+    NetworkTablesJNI.flush(NetworkTablesJNI.getDefaultInstance());
+  }
+
+  @Test
+  void jniHalLinkTest() {
+    HAL.initialize(500, 0);
+    // Test to verify that the JNI test link works correctly.
+    HALUtil.getHALRuntimeType();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java
new file mode 100644
index 0000000..98b8489
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/hal/MatchInfoDataTest.java
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.hal;
+
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.MatchInfoData;
+import edu.wpi.first.hal.sim.mockdata.DriverStationDataJNI;
+import edu.wpi.first.wpilibj.DriverStation.MatchType;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+class MatchInfoDataTest {
+  @Test
+  void testSetMatchInfo() {
+
+    MatchType matchType = MatchType.Qualification;
+    DriverStationDataJNI.setMatchInfo("Event Name", "Game Message", 174, 191, matchType.ordinal());
+
+    MatchInfoData outMatchInfo = new MatchInfoData();
+    HAL.getMatchInfo(outMatchInfo);
+
+    assertAll(
+        () -> assertEquals("Event Name", outMatchInfo.eventName),
+        () -> assertEquals(matchType.ordinal(), outMatchInfo.matchType),
+        () -> assertEquals(174, outMatchInfo.matchNumber),
+        () -> assertEquals(191, outMatchInfo.replayNumber),
+        () -> assertEquals("Game Message", outMatchInfo.gameSpecificMessage)
+    );
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/livewindow/LiveWindowTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/livewindow/LiveWindowTest.java
new file mode 100644
index 0000000..da1757c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/livewindow/LiveWindowTest.java
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.livewindow;
+
+import edu.wpi.first.wpilibj.UtilityClassTest;
+
+class LiveWindowTest extends UtilityClassTest {
+  LiveWindowTest() {
+    super(LiveWindow.class);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java
new file mode 100644
index 0000000..6cbeae2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/MockActuatorSendable.java
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import edu.wpi.first.wpilibj.SendableBase;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
+
+/**
+ * A mock sendable that marks itself as an actuator.
+ */
+public class MockActuatorSendable extends SendableBase {
+  public MockActuatorSendable(String name) {
+    super(false);
+    setName(name);
+  }
+
+  @Override
+  public void initSendable(SendableBuilder builder) {
+    builder.setActuator(true);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java
new file mode 100644
index 0000000..9824f11
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardInstanceTest.java
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+public class ShuffleboardInstanceTest {
+  private NetworkTableInstance m_ntInstance;
+  private ShuffleboardInstance m_shuffleboardInstance;
+
+  @BeforeEach
+  void setupInstance() {
+    m_ntInstance = NetworkTableInstance.create();
+    m_shuffleboardInstance = new ShuffleboardInstance(m_ntInstance);
+  }
+
+  @AfterEach
+  void tearDownInstance() {
+    m_ntInstance.close();
+  }
+
+  @Test
+  void testPathFluent() {
+    NetworkTableEntry entry = m_shuffleboardInstance.getTab("Tab Title")
+                                                  .getLayout("Layout Title", "List Layout")
+                                                  .add("Data", "string")
+                                                  .withWidget("Text View")
+                                                  .getEntry();
+
+    assertAll(
+        () -> assertEquals("string", entry.getString(null), "Wrong entry value"),
+        () -> assertEquals("/Shuffleboard/Tab Title/Layout Title/Data", entry.getName(),
+                           "Entry path generated incorrectly"));
+  }
+
+  @Test
+  void testNestedLayoutsFluent() {
+    NetworkTableEntry entry = m_shuffleboardInstance.getTab("Tab")
+                                                  .getLayout("First", "List")
+                                                  .getLayout("Second", "List")
+                                                  .getLayout("Third", "List")
+                                                  .getLayout("Fourth", "List")
+                                                  .add("Value", "string")
+                                                  .getEntry();
+
+    assertAll(
+        () -> assertEquals("string", entry.getString(null), "Wrong entry value"),
+        () -> assertEquals("/Shuffleboard/Tab/First/Second/Third/Fourth/Value", entry.getName(),
+                           "Entry path generated incorrectly"));
+  }
+
+  @Test
+  void testNestedLayoutsOop() {
+    ShuffleboardTab tab = m_shuffleboardInstance.getTab("Tab");
+    ShuffleboardLayout first = tab.getLayout("First", "List");
+    ShuffleboardLayout second = first.getLayout("Second", "List");
+    ShuffleboardLayout third = second.getLayout("Third", "List");
+    ShuffleboardLayout fourth = third.getLayout("Fourth", "List");
+    SimpleWidget widget = fourth.add("Value", "string");
+    NetworkTableEntry entry = widget.getEntry();
+
+    assertAll(
+        () -> assertEquals("string", entry.getString(null), "Wrong entry value"),
+        () -> assertEquals("/Shuffleboard/Tab/First/Second/Third/Fourth/Value", entry.getName(),
+                           "Entry path generated incorrectly"));
+  }
+
+  @Test
+  void testLayoutTypeIsSet() {
+    String layoutType = "Type";
+    m_shuffleboardInstance.getTab("Tab")
+                          .getLayout("Title", layoutType);
+    m_shuffleboardInstance.update();
+    NetworkTableEntry entry = m_ntInstance.getEntry(
+        "/Shuffleboard/.metadata/Tab/Title/PreferredComponent");
+    assertEquals(layoutType, entry.getString("Not Set"), "Layout type not set");
+  }
+
+  @Test
+  void testNestedActuatorWidgetsAreDisabled() {
+    m_shuffleboardInstance.getTab("Tab")
+                          .getLayout("Title", "Layout")
+                          .add(new MockActuatorSendable("Actuator"));
+    NetworkTableEntry controllableEntry =
+        m_ntInstance.getEntry("/Shuffleboard/Tab/Title/Actuator/.controllable");
+
+    m_shuffleboardInstance.update();
+
+    // Note: we use the unsafe `getBoolean()` method because if the value is NOT a boolean, or if it
+    // is not present, then something has clearly gone very, very wrong
+    boolean controllable = controllableEntry.getValue().getBoolean();
+
+    // Sanity check
+    assertTrue(controllable, "The nested actuator widget should be enabled by default");
+    m_shuffleboardInstance.disableActuatorWidgets();
+    controllable = controllableEntry.getValue().getBoolean();
+    assertFalse(controllable, "The nested actuator widget should have been disabled");
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java
new file mode 100644
index 0000000..fe48c13
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTabTest.java
@@ -0,0 +1,152 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import java.util.HashMap;
+import java.util.Map;
+
+import org.junit.jupiter.api.AfterEach;
+import org.junit.jupiter.api.BeforeEach;
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.Sendable;
+import edu.wpi.first.wpilibj.command.InstantCommand;
+
+import static org.junit.jupiter.api.Assertions.assertAll;
+import static org.junit.jupiter.api.Assertions.assertArrayEquals;
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertThrows;
+
+@SuppressWarnings({"PMD.TooManyMethods"})
+public class ShuffleboardTabTest {
+  private NetworkTableInstance m_ntInstance;
+  private ShuffleboardTab m_tab;
+  private ShuffleboardInstance m_instance;
+
+  @BeforeEach
+  void setup() {
+    m_ntInstance = NetworkTableInstance.create();
+    m_instance = new ShuffleboardInstance(m_ntInstance);
+    m_tab = m_instance.getTab("Tab");
+  }
+
+  @AfterEach
+  void tearDown() {
+    m_ntInstance.close();
+  }
+
+  @Test
+  void testAddDouble() {
+    NetworkTableEntry entry = m_tab.add("Double", 1.0).getEntry();
+    assertAll(
+        () -> assertEquals("/Shuffleboard/Tab/Double", entry.getName()),
+        () -> assertEquals(1.0, entry.getValue().getDouble()));
+  }
+
+  @Test
+  void testAddInteger() {
+    NetworkTableEntry entry = m_tab.add("Int", 1).getEntry();
+    assertAll(
+        () -> assertEquals("/Shuffleboard/Tab/Int", entry.getName()),
+        () -> assertEquals(1.0, entry.getValue().getDouble()));
+  }
+
+  @Test
+  void testAddLong() {
+    NetworkTableEntry entry = m_tab.add("Long", 1L).getEntry();
+    assertAll(
+        () -> assertEquals("/Shuffleboard/Tab/Long", entry.getName()),
+        () -> assertEquals(1.0, entry.getValue().getDouble()));
+  }
+
+
+  @Test
+  void testAddBoolean() {
+    NetworkTableEntry entry = m_tab.add("Bool", false).getEntry();
+    assertAll(
+        () -> assertEquals("/Shuffleboard/Tab/Bool", entry.getName()),
+        () -> assertFalse(entry.getValue().getBoolean()));
+  }
+
+  @Test
+  void testAddString() {
+    NetworkTableEntry entry = m_tab.add("String", "foobar").getEntry();
+    assertAll(
+        () -> assertEquals("/Shuffleboard/Tab/String", entry.getName()),
+        () -> assertEquals("foobar", entry.getValue().getString()));
+  }
+
+  @Test
+  void testAddNamedSendableWithProperties() {
+    Sendable sendable = new InstantCommand("Command");
+    String widgetType = "Command Widget";
+    m_tab.add(sendable)
+       .withWidget(widgetType)
+       .withProperties(mapOf("foo", 1234, "bar", "baz"));
+
+    m_instance.update();
+    String meta = "/Shuffleboard/.metadata/Tab/Command";
+
+    assertAll(
+        () -> assertEquals(1234,
+                           m_ntInstance.getEntry(meta + "/Properties/foo").getDouble(-1),
+                           "Property 'foo' not set correctly"),
+        () -> assertEquals("baz",
+                           m_ntInstance.getEntry(meta + "/Properties/bar").getString(null),
+                           "Property 'bar' not set correctly"),
+        () -> assertEquals(widgetType,
+                           m_ntInstance.getEntry(meta + "/PreferredComponent").getString(null),
+                           "Preferred component not set correctly"));
+  }
+
+  @Test
+  void testAddNumberArray() {
+    NetworkTableEntry entry = m_tab.add("DoubleArray", new double[]{1, 2, 3}).getEntry();
+    assertAll(
+        () -> assertEquals("/Shuffleboard/Tab/DoubleArray", entry.getName()),
+        () -> assertArrayEquals(new double[]{1, 2, 3}, entry.getValue().getDoubleArray()));
+  }
+
+  @Test
+  void testAddBooleanArray() {
+    NetworkTableEntry entry = m_tab.add("BoolArray", new boolean[]{true, false}).getEntry();
+    assertAll(
+        () -> assertEquals("/Shuffleboard/Tab/BoolArray", entry.getName()),
+        () -> assertArrayEquals(new boolean[]{true, false}, entry.getValue().getBooleanArray()));
+  }
+
+  @Test
+  void testAddStringArray() {
+    NetworkTableEntry entry = m_tab.add("StringArray", new String[]{"foo", "bar"}).getEntry();
+    assertAll(
+        () -> assertEquals("/Shuffleboard/Tab/StringArray", entry.getName()),
+        () -> assertArrayEquals(new String[]{"foo", "bar"}, entry.getValue().getStringArray()));
+  }
+
+  @Test
+  void testTitleDuplicates() {
+    m_tab.add("foo", "bar");
+    assertThrows(IllegalArgumentException.class, () -> m_tab.add("foo", "baz"));
+  }
+
+  /**
+   * Stub for Java 9 {@code Map.of()}.
+   */
+  @SuppressWarnings({"unchecked", "PMD"})
+  private static <K, V> Map<K, V> mapOf(Object... entries) {
+    Map<K, V> map = new HashMap<>();
+    for (int i = 0; i < entries.length; i += 2) {
+      map.put((K) entries[i], (V) entries[i + 1]);
+    }
+    return map;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTest.java
new file mode 100644
index 0000000..c4285fb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/shuffleboard/ShuffleboardTest.java
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.shuffleboard;
+
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.wpilibj.UtilityClassTest;
+
+import static org.junit.jupiter.api.Assertions.assertSame;
+
+public class ShuffleboardTest extends UtilityClassTest {
+  public ShuffleboardTest() {
+    super(Shuffleboard.class);
+  }
+
+  // Most relevant tests are in ShuffleboardTabTest
+
+  @Test
+  void testTabObjectsCached() {
+    ShuffleboardTab tab1 = Shuffleboard.getTab("testTabObjectsCached");
+    ShuffleboardTab tab2 = Shuffleboard.getTab("testTabObjectsCached");
+    assertSame(tab1, tab2, "Tab objects were not cached");
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/sim/AnalogInputSimTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/sim/AnalogInputSimTest.java
new file mode 100644
index 0000000..b739a92
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/sim/AnalogInputSimTest.java
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.sim;
+
+import org.junit.jupiter.api.Test;
+
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.sim.AnalogInSim;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+
+class AnalogInputSimTest {
+  static class DoubleStore {
+    public boolean m_wasTriggered;
+    public boolean m_wasCorrectType;
+    public double m_setValue0;
+  }
+
+  @Test
+  void setCallbackTest() {
+    HAL.initialize(500, 0);
+
+    AnalogInput input = new AnalogInput(5);
+    AnalogInSim inputSim = input.getSimObject();
+
+    for (double i = 0; i < 5.0; i += 0.1) {
+      inputSim.setVoltage(0);
+
+      assertEquals(input.getVoltage(), 0, 0.001);
+
+      inputSim.setVoltage(i);
+
+      assertEquals(input.getVoltage(), i, 0.001);
+
+    }
+
+
+
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/sim/AnalogOutputSimTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/sim/AnalogOutputSimTest.java
new file mode 100644
index 0000000..258b253
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/sim/AnalogOutputSimTest.java
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.sim;
+
+import edu.wpi.first.wpilibj.AnalogOutput;
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.hal.sim.AnalogOutSim;
+import edu.wpi.first.hal.sim.CallbackStore;
+
+import static org.junit.jupiter.api.Assertions.assertEquals;
+import static org.junit.jupiter.api.Assertions.assertFalse;
+import static org.junit.jupiter.api.Assertions.assertTrue;
+
+import org.junit.jupiter.api.Test;
+
+class AnalogOutputSimTest {
+  static class DoubleStore {
+    public boolean m_wasTriggered;
+    public boolean m_wasCorrectType;
+    public double m_setValue = -1;
+
+    public void reset() {
+      m_wasCorrectType = false;
+      m_wasTriggered = false;
+      m_setValue = -1;
+    }
+  }
+
+  @Test
+  void setCallbackTest() {
+    HAL.initialize(500, 0);
+
+
+    AnalogOutput output = new AnalogOutput(0);
+    output.setVoltage(0.5);
+
+    AnalogOutSim outputSim = output.getSimObject();
+
+    DoubleStore store = new DoubleStore();
+
+    try (CallbackStore cb = outputSim.registerVoltageCallback((name, value) -> {
+      store.m_wasTriggered = true;
+      store.m_wasCorrectType = true;
+      store.m_setValue = value.getDouble();
+    }, false)) {
+      assertFalse(store.m_wasTriggered);
+
+      for (double i = 0.1; i < 5.0; i += 0.1) {
+        store.reset();
+
+        output.setVoltage(0);
+
+        assertTrue(store.m_wasTriggered);
+        assertEquals(store.m_setValue, 0, 0.001);
+
+        store.reset();
+
+        output.setVoltage(i);
+
+        assertTrue(store.m_wasTriggered);
+        assertEquals(store.m_setValue, i, 0.001);
+
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java
new file mode 100644
index 0000000..00dd002
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java
@@ -0,0 +1,16 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.smartdashboard;
+
+import edu.wpi.first.wpilibj.UtilityClassTest;
+
+class SmartDashboardTest extends UtilityClassTest {
+  SmartDashboardTest() {
+    super(SmartDashboard.class);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibj/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension b/third_party/allwpilib_2019/wpilibj/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension
new file mode 100644
index 0000000..f6d7b98
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/src/test/resources/META-INF/services/org.junit.jupiter.api.extension.Extension
@@ -0,0 +1 @@
+edu.wpi.first.wpilibj.MockHardwareExtension
diff --git a/third_party/allwpilib_2019/wpilibj/wpilibj-config.cmake b/third_party/allwpilib_2019/wpilibj/wpilibj-config.cmake
new file mode 100644
index 0000000..5e89f6d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibj/wpilibj-config.cmake
@@ -0,0 +1,2 @@
+get_filename_component(SELF_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)
+include(${SELF_DIR}/wpilibj.cmake)
diff --git a/third_party/allwpilib_2019/wpilibjExamples/build.gradle b/third_party/allwpilib_2019/wpilibjExamples/build.gradle
new file mode 100644
index 0000000..55087ba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/build.gradle
@@ -0,0 +1,48 @@
+apply plugin: 'java'
+apply plugin: 'pmd'
+
+ext {
+    useJava = true
+    useCpp = false
+    skipDev = true
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+
+
+dependencies {
+    compile project(':wpilibj')
+
+    compile project(':hal')
+    compile project(':wpiutil')
+    compile project(':ntcore')
+    compile project(':cscore')
+    compile project(':cameraserver')
+}
+
+pmd {
+    consoleOutput = true
+    reportsDir = file("$project.buildDir/reports/pmd")
+    ruleSetFiles = files(new File(rootDir, "styleguide/pmd-ruleset.xml"))
+    ruleSets = []
+}
+
+gradle.projectsEvaluated {
+    tasks.withType(JavaCompile) {
+        options.compilerArgs << "-Xlint:unchecked" << "-Xlint:deprecation"
+    }
+}
+
+apply from: 'publish.gradle'
+
+ext {
+    templateDirectory = new File("$projectDir/src/main/java/edu/wpi/first/wpilibj/templates/")
+    templateFile = new File("$projectDir/src/main/java/edu/wpi/first/wpilibj/templates/templates.json")
+    exampleDirectory = new File("$projectDir/src/main/java/edu/wpi/first/wpilibj/examples/")
+    exampleFile = new File("$projectDir/src/main/java/edu/wpi/first/wpilibj/examples/examples.json")
+    commandDirectory = new File("$projectDir/src/main/java/edu/wpi/first/wpilibj/commands/")
+    commandFile = new File("$projectDir/src/main/java/edu/wpi/first/wpilibj/commands/commands.json")
+}
+
+apply from: "${rootDir}/shared/examplecheck.gradle"
diff --git a/third_party/allwpilib_2019/wpilibjExamples/publish.gradle b/third_party/allwpilib_2019/wpilibjExamples/publish.gradle
new file mode 100644
index 0000000..b2aa3aa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/publish.gradle
@@ -0,0 +1,94 @@
+apply plugin: 'maven-publish'
+
+def pubVersion
+if (project.hasProperty("publishVersion")) {
+    pubVersion = project.publishVersion
+} else {
+    pubVersion = WPILibVersion.version
+}
+
+def baseExamplesArtifactId = 'examples'
+def baseTemplatesArtifactId = 'templates'
+def baseCommandsArtifactId = 'commands'
+def artifactGroupId = 'edu.wpi.first.wpilibj'
+
+def examplesZipBaseName = '_GROUP_edu_wpi_first_wpilibj_ID_examples_CLS'
+def templatesZipBaseName = '_GROUP_edu_wpi_first_wpilibj_ID_templates_CLS'
+def commandsZipBaseName = '_GROUP_edu_wpi_first_wpilibj_ID_commands_CLS'
+
+def outputsFolder = file("$project.buildDir/outputs")
+
+task javaExamplesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = examplesZipBaseName
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/java/edu/wpi/first/wpilibj/examples') {
+        into 'examples'
+    }
+}
+
+task javaTemplatesZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = templatesZipBaseName
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/java/edu/wpi/first/wpilibj/templates') {
+        into 'templates'
+    }
+}
+
+task javaCommandsZip(type: Zip) {
+    destinationDir = outputsFolder
+    baseName = commandsZipBaseName
+
+    from(licenseFile) {
+        into '/'
+    }
+
+    from('src/main/java/edu/wpi/first/wpilibj/commands') {
+        into 'commands'
+    }
+}
+
+build.dependsOn javaTemplatesZip
+build.dependsOn javaExamplesZip
+build.dependsOn javaCommandsZip
+
+addTaskToCopyAllOutputs(javaTemplatesZip)
+addTaskToCopyAllOutputs(javaExamplesZip)
+addTaskToCopyAllOutputs(javaCommandsZip)
+
+publishing {
+    publications {
+        examples(MavenPublication) {
+            artifact javaExamplesZip
+
+            artifactId = baseExamplesArtifactId
+            groupId artifactGroupId
+            version pubVersion
+        }
+
+        templates(MavenPublication) {
+            artifact javaTemplatesZip
+
+            artifactId = baseTemplatesArtifactId
+            groupId artifactGroupId
+            version pubVersion
+        }
+
+        commands(MavenPublication) {
+            artifact javaCommandsZip
+
+            artifactId = baseCommandsArtifactId
+            groupId artifactGroupId
+            version pubVersion
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java
new file mode 100644
index 0000000..c17ea2d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command/ReplaceMeCommand.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.commands.command;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+public class ReplaceMeCommand extends Command {
+  public ReplaceMeCommand() {
+    // Use requires() here to declare subsystem dependencies
+    // eg. requires(chassis);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+  }
+
+  // Called repeatedly when this Command is scheduled to run
+  @Override
+  protected void execute() {
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return false;
+  }
+
+  // Called once after isFinished returns true
+  @Override
+  protected void end() {
+  }
+
+  // Called when another command which requires one or more of the same
+  // subsystems is scheduled to run
+  @Override
+  protected void interrupted() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java
new file mode 100644
index 0000000..d1dae8c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commandgroup/ReplaceMeCommandGroup.java
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.commands.commandgroup;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+public class ReplaceMeCommandGroup extends CommandGroup {
+  /**
+   * Add your docs here.
+   */
+  public ReplaceMeCommandGroup() {
+    // Add Commands here:
+    // e.g. addSequential(new Command1());
+    // addSequential(new Command2());
+    // these will run in order.
+
+    // To run multiple commands at the same time,
+    // use addParallel()
+    // e.g. addParallel(new Command1());
+    // addSequential(new Command2());
+    // Command1 and Command2 will run in parallel.
+
+    // A command group will require all of the subsystems that each member
+    // would require.
+    // e.g. if Command1 requires chassis, and Command2 requires arm,
+    // a CommandGroup containing them would require both the chassis and the
+    // arm.
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json
new file mode 100644
index 0000000..2894926
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/commands.json
@@ -0,0 +1,75 @@
+[
+  {
+    "name": "Empty Class",
+    "description": "Create an empty class",
+    "tags": [
+      "class"
+    ],
+    "foldername": "emptyclass",
+    "replacename": "ReplaceMeEmptyClass"
+  },
+  {
+    "name": "Command",
+    "description": "Create a base command",
+    "tags": [
+      "command"
+    ],
+    "foldername": "command",
+    "replacename": "ReplaceMeCommand"
+  },
+  {
+    "name": "Command Group",
+    "description": "Create a command group",
+    "tags": [
+      "commandgroup"
+    ],
+    "foldername": "commandgroup",
+    "replacename": "ReplaceMeCommandGroup"
+  },
+  {
+    "name": "Instant Command",
+    "description": "A command that runs immediately",
+    "tags": [
+      "instantcommand"
+    ],
+    "foldername": "instant",
+    "replacename": "ReplaceMeInstantCommand"
+  },
+  {
+    "name": "Subsystem",
+    "description": "A subsystem",
+    "tags": [
+      "subsystem"
+    ],
+    "foldername": "subsystem",
+    "replacename": "ReplaceMeSubsystem"
+  },
+  {
+    "name": "PID Subsystem",
+    "description": "A subsystem that runs a PID loop",
+    "tags": [
+      "pidsubsystem",
+      "pid"
+    ],
+    "foldername": "pidsubsystem",
+    "replacename": "ReplaceMePIDSubsystem"
+  },
+  {
+    "name": "Timed Command",
+    "description": "A command that runs for a specified time",
+    "tags": [
+      "timedcommand"
+    ],
+    "foldername": "timed",
+    "replacename": "ReplaceMeTimedCommand"
+  },
+  {
+    "name": "Trigger",
+    "description": "A command that runs off of a trigger",
+    "tags": [
+      "trigger"
+    ],
+    "foldername": "trigger",
+    "replacename": "ReplaceMeTrigger"
+  }
+]
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/emptyclass/ReplaceMeEmptyClass.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/emptyclass/ReplaceMeEmptyClass.java
new file mode 100644
index 0000000..9498348
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/emptyclass/ReplaceMeEmptyClass.java
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/

+/* 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.                                                               */

+/*----------------------------------------------------------------------------*/

+

+package edu.wpi.first.wpilibj.commands.emptyclass;

+

+/**

+ * Add your docs here.

+ */

+public class ReplaceMeEmptyClass {

+}

diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java
new file mode 100644
index 0000000..bf24a14
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/instant/ReplaceMeInstantCommand.java
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.commands.instant;
+
+import edu.wpi.first.wpilibj.command.InstantCommand;
+
+/**
+ * Add your docs here.
+ */
+public class ReplaceMeInstantCommand extends InstantCommand {
+  /**
+   * Add your docs here.
+   */
+  public ReplaceMeInstantCommand() {
+    super();
+    // Use requires() here to declare subsystem dependencies
+    // eg. requires(chassis);
+  }
+
+  // Called once when the command executes
+  @Override
+  protected void initialize() {
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java
new file mode 100644
index 0000000..46d75f6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/pidsubsystem/ReplaceMePIDSubsystem.java
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.commands.pidsubsystem;
+
+import edu.wpi.first.wpilibj.command.PIDSubsystem;
+
+/**
+ * Add your docs here.
+ */
+public class ReplaceMePIDSubsystem extends PIDSubsystem {
+  /**
+   * Add your docs here.
+   */
+  public ReplaceMePIDSubsystem() {
+    // Intert a subsystem name and PID values here
+    super("SubsystemName", 1, 2, 3);
+    // Use these to get going:
+    // setSetpoint() - Sets where the PID controller should move the system
+    // to
+    // enable() - Enables the PID controller.
+  }
+
+  @Override
+  public void initDefaultCommand() {
+    // Set the default command for a subsystem here.
+    // setDefaultCommand(new MySpecialCommand());
+  }
+
+  @Override
+  protected double returnPIDInput() {
+    // Return your input value for the PID loop
+    // e.g. a sensor, like a potentiometer:
+    // yourPot.getAverageVoltage() / kYourMaxVoltage;
+    return 0.0;
+  }
+
+  @Override
+  protected void usePIDOutput(double output) {
+    // Use output to drive your system, like a motor
+    // e.g. yourMotor.set(output);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java
new file mode 100644
index 0000000..1c7fe6d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem/ReplaceMeSubsystem.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.commands.subsystem;
+
+import edu.wpi.first.wpilibj.command.Subsystem;
+
+/**
+ * Add your docs here.
+ */
+public class ReplaceMeSubsystem extends Subsystem {
+  // Put methods for controlling this subsystem
+  // here. Call these from Commands.
+
+  @Override
+  public void initDefaultCommand() {
+    // Set the default command for a subsystem here.
+    // setDefaultCommand(new MySpecialCommand());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java
new file mode 100644
index 0000000..41ba965
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/timed/ReplaceMeTimedCommand.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.commands.timed;
+
+import edu.wpi.first.wpilibj.command.TimedCommand;
+
+/**
+ * Add your docs here.
+ */
+public class ReplaceMeTimedCommand extends TimedCommand {
+  /**
+   * Add your docs here.
+   */
+  public ReplaceMeTimedCommand(double timeout) {
+    super(timeout);
+    // Use requires() here to declare subsystem dependencies
+    // eg. requires(chassis);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+  }
+
+  // Called repeatedly when this Command is scheduled to run
+  @Override
+  protected void execute() {
+  }
+
+  // Called once after timeout
+  @Override
+  protected void end() {
+  }
+
+  // Called when another command which requires one or more of the same
+  // subsystems is scheduled to run
+  @Override
+  protected void interrupted() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java
new file mode 100644
index 0000000..713ac6d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/trigger/ReplaceMeTrigger.java
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.commands.trigger;
+
+import edu.wpi.first.wpilibj.buttons.Trigger;
+
+/**
+ * Add your docs here.
+ */
+public class ReplaceMeTrigger extends Trigger {
+  @Override
+  public boolean get() {
+    return false;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/axiscamera/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/axiscamera/Main.java
new file mode 100644
index 0000000..1c21a4a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/axiscamera/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.axiscamera;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/axiscamera/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/axiscamera/Robot.java
new file mode 100644
index 0000000..ee4b424
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/axiscamera/Robot.java
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.axiscamera;
+
+import org.opencv.core.Mat;
+import org.opencv.core.Point;
+import org.opencv.core.Scalar;
+import org.opencv.imgproc.Imgproc;
+
+import edu.wpi.cscore.AxisCamera;
+import edu.wpi.cscore.CvSink;
+import edu.wpi.cscore.CvSource;
+import edu.wpi.first.cameraserver.CameraServer;
+import edu.wpi.first.wpilibj.TimedRobot;
+
+/**
+ * This is a demo program showing the use of OpenCV to do vision processing. The
+ * image is acquired from the Axis camera, then a rectangle is put on the image
+ * and sent to the dashboard. OpenCV has many methods for different types of
+ * processing.
+ */
+public class Robot extends TimedRobot {
+  Thread m_visionThread;
+
+  @Override
+  public void robotInit() {
+    m_visionThread = new Thread(() -> {
+      // Get the Axis camera from CameraServer
+      AxisCamera camera
+          = CameraServer.getInstance().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();
+      // Setup a CvSource. This will send images back to the Dashboard
+      CvSource outputStream
+          = CameraServer.getInstance().putVideo("Rectangle", 640, 480);
+
+      // Mats are very memory expensive. Lets reuse this Mat.
+      Mat mat = new Mat();
+
+      // This cannot be 'true'. The program will never exit if it is. This
+      // lets the robot stop this thread when restarting robot code or
+      // deploying.
+      while (!Thread.interrupted()) {
+        // Tell the CvSink to grab a frame from the camera and put it
+        // in the source mat.  If there is an error notify the output.
+        if (cvSink.grabFrame(mat) == 0) {
+          // Send the output the error.
+          outputStream.notifyError(cvSink.getError());
+          // skip the rest of the current iteration
+          continue;
+        }
+        // Put a rectangle on the image
+        Imgproc.rectangle(mat, new Point(100, 100), new Point(400, 400),
+            new Scalar(255, 255, 255), 5);
+        // Give the output stream a new image to display
+        outputStream.putFrame(mat);
+      }
+    });
+    m_visionThread.setDaemon(true);
+    m_visionThread.start();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json
new file mode 100644
index 0000000..39a92e5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/examples.json
@@ -0,0 +1,201 @@
+[
+  {
+    "name": "Getting Started",
+    "description": "An example program which demonstrates the simplest autonomous and teleoperated routines.",
+    "tags": [
+      "Getting Started with Java"
+    ],
+    "foldername": "gettingstarted",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Tank Drive",
+    "description": "Demonstrate the use of the RobotDrive class doing teleop driving with tank steering",
+    "tags": [
+      "Actuators",
+      "Joystick",
+      "Robot and Motor",
+      "Safety"
+    ],
+    "foldername": "tankdrive",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Mecanum Drive",
+    "description": "Demonstrate the use of the RobotDrive class doing teleop driving with Mecanum steering",
+    "tags": [
+      "Actuators",
+      "Joystick",
+      "Robot and Motor",
+      "Safety"
+    ],
+    "foldername": "mecanumdrive",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Ultrasonic",
+    "description": "Demonstrate maintaining a set distance using an ultrasonic sensor.",
+    "tags": [
+      "Sensors",
+      "Robot and Motor",
+      "Analog"
+    ],
+    "foldername": "ultrasonic",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Ultrasonic PID",
+    "description": "Demonstrate maintaining a set distance using an ultrasonic sensor and PID Control.",
+    "tags": [
+      "Sensors",
+      "Robot and Motor",
+      "Analog"
+    ],
+    "foldername": "ultrasonicpid",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Potentiometer PID",
+    "description": "An example to demonstrate the use of a potentiometer and PID control to reach elevator position setpoints.",
+    "tags": [
+      "Sensors",
+      "Actuators",
+      "Analog",
+      "Joystick"
+    ],
+    "foldername": "potentiometerpid",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Gyro",
+    "description": "An example program showing how to drive straight with using a gyro sensor.",
+    "tags": [
+      "Sensors",
+      "Robot and Motor",
+      "Analog",
+      "Joystick"
+    ],
+    "foldername": "gyro",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Gyro Mecanum",
+    "description": "An example program showing how to perform mecanum drive with field oriented controls.",
+    "tags": [
+      "Sensors",
+      "Robot and Motor",
+      "Analog",
+      "Joystick"
+    ],
+    "foldername": "gyromecanum",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "HID Rumble",
+    "description": "An example program showing how to make human interface devices rumble.",
+    "tags": [
+      "Joystick"
+    ],
+    "foldername": "hidrumble",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Motor Controller",
+    "description": "Demonstrate controlling a single motor with a joystick",
+    "tags": [
+      "Actuators",
+      "Joystick",
+      "Robot and Motor"
+    ],
+    "foldername": "motorcontrol",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Motor Control With Encoder",
+    "description": "Demonstrate controlling a single motor with a Joystick and displaying the net movement of the motor using an encoder.",
+    "tags": [
+      "Robot and Motor",
+      "Digital",
+      "Sensors",
+      "Actuators",
+      "Joystick",
+      "Complete List"
+    ],
+    "foldername": "motorcontrolencoder",
+    "gradlebase": "java"
+    ,"mainclass": "Main"
+  },
+  {
+    "name": "GearsBot",
+    "description": "A fully functional example CommandBased program for WPIs GearsBot robot. This code can run on your computer if it supports simulation.",
+    "tags": [
+      "Complete Robot"
+    ],
+    "foldername": "gearsbot",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "PacGoat",
+    "description": "A fully functional example CommandBased program for FRC Team 190's 2014 robot. This code can run on your computer if it supports simulation.",
+    "tags": [
+      "Complete Robot"
+    ],
+    "foldername": "pacgoat",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Simple Vision",
+    "description": "Demonstrate the use of the CameraServer class to stream from a USB Webcam without processing the images.",
+    "tags": [
+      "Vision",
+      "Complete List"
+    ],
+    "foldername": "quickvision",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Intermediate Vision",
+    "description": "Demonstrate the use of the NIVision class to capture image from a Webcam, process them, and then send them to the dashboard.",
+    "tags": [
+      "Vision",
+      "Complete List"
+    ],
+    "foldername": "intermediatevision",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Axis Camera Sample",
+    "description": "An example program that acquires images from an Axis network camera and adds some annotation to the image as you might do for showing operators the result of some image recognition, and sends it to the dashboard for display. This demonstrates the use of the AxisCamera class.",
+    "tags": [
+      "Vision"
+    ],
+    "foldername": "axiscamera",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Shuffleboard Sample",
+    "description": "An example program that adds data to various Shuffleboard tabs that demonstrates the Shuffleboard API",
+    "tags": [
+      "Shuffleboard",
+      "Dashboards"
+    ],
+    "foldername": "shuffleboard",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  }
+]
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Main.java
new file mode 100644
index 0000000..02a1475
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/OI.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/OI.java
new file mode 100644
index 0000000..2a2469f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/OI.java
@@ -0,0 +1,72 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.buttons.JoystickButton;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.Autonomous;
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.CloseClaw;
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.OpenClaw;
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.Pickup;
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.Place;
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.PrepareToPickup;
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.SetElevatorSetpoint;
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.SetWristSetpoint;
+
+/**
+ * This class is the glue that binds the controls on the physical operator
+ * interface to the commands and command groups that allow control of the robot.
+ */
+public class OI {
+  private final Joystick m_joystick = new Joystick(0);
+
+  /**
+   * Construct the OI and all of the buttons on it.
+   */
+  public OI() {
+    // Put Some buttons on the SmartDashboard
+    SmartDashboard.putData("Elevator Bottom", new SetElevatorSetpoint(0));
+    SmartDashboard.putData("Elevator Platform", new SetElevatorSetpoint(0.2));
+    SmartDashboard.putData("Elevator Top", new SetElevatorSetpoint(0.3));
+
+    SmartDashboard.putData("Wrist Horizontal", new SetWristSetpoint(0));
+    SmartDashboard.putData("Raise Wrist", new SetWristSetpoint(-45));
+
+    SmartDashboard.putData("Open Claw", new OpenClaw());
+    SmartDashboard.putData("Close Claw", new CloseClaw());
+
+    SmartDashboard.putData("Deliver Soda", new Autonomous());
+
+    // Create some buttons
+    final JoystickButton dpadUp = new JoystickButton(m_joystick, 5);
+    final JoystickButton dpadRight = new JoystickButton(m_joystick, 6);
+    final JoystickButton dpadDown = new JoystickButton(m_joystick, 7);
+    final JoystickButton dpadLeft = new JoystickButton(m_joystick, 8);
+    final JoystickButton l2 = new JoystickButton(m_joystick, 9);
+    final JoystickButton r2 = new JoystickButton(m_joystick, 10);
+    final JoystickButton l1 = new JoystickButton(m_joystick, 11);
+    final JoystickButton r1 = new JoystickButton(m_joystick, 12);
+
+    // Connect the buttons to commands
+    dpadUp.whenPressed(new SetElevatorSetpoint(0.2));
+    dpadDown.whenPressed(new SetElevatorSetpoint(-0.2));
+    dpadRight.whenPressed(new CloseClaw());
+    dpadLeft.whenPressed(new OpenClaw());
+
+    r1.whenPressed(new PrepareToPickup());
+    r2.whenPressed(new Pickup());
+    l1.whenPressed(new Place());
+    l2.whenPressed(new Autonomous());
+  }
+
+  public Joystick getJoystick() {
+    return m_joystick;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java
new file mode 100644
index 0000000..d82139f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/Robot.java
@@ -0,0 +1,108 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot;
+
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.command.Command;
+import edu.wpi.first.wpilibj.command.Scheduler;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.Autonomous;
+import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
+import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.DriveTrain;
+import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
+import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
+
+/**
+ * The VM is configured to automatically run this class, and to call the
+ * functions corresponding to each mode, as described in the TimedRobot
+ * documentation. If you change the name of this class or the package after
+ * creating this project, you must also update the manifest file in the resource
+ * directory.
+ */
+public class Robot extends TimedRobot {
+  Command m_autonomousCommand;
+
+  public static DriveTrain m_drivetrain;
+  public static Elevator m_elevator;
+  public static Wrist m_wrist;
+  public static Claw m_claw;
+  public static OI m_oi;
+
+  /**
+   * This function is run when the robot is first started up and should be
+   * used for any initialization code.
+   */
+  @Override
+  public void robotInit() {
+    // Initialize all subsystems
+    m_drivetrain = new DriveTrain();
+    m_elevator = new Elevator();
+    m_wrist = new Wrist();
+    m_claw = new Claw();
+    m_oi = new OI();
+
+    // instantiate the command used for the autonomous period
+    m_autonomousCommand = new Autonomous();
+
+    // Show what command your subsystem is running on the SmartDashboard
+    SmartDashboard.putData(m_drivetrain);
+    SmartDashboard.putData(m_elevator);
+    SmartDashboard.putData(m_wrist);
+    SmartDashboard.putData(m_claw);
+  }
+
+  @Override
+  public void autonomousInit() {
+    m_autonomousCommand.start(); // schedule the autonomous command (example)
+  }
+
+  /**
+   * This function is called periodically during autonomous.
+   */
+  @Override
+  public void autonomousPeriodic() {
+    Scheduler.getInstance().run();
+    log();
+  }
+
+  @Override
+  public void teleopInit() {
+    // This makes sure that the autonomous stops running when
+    // teleop starts running. If you want the autonomous to
+    // continue until interrupted by another command, remove
+    // this line or comment it out.
+    m_autonomousCommand.cancel();
+  }
+
+  /**
+   * This function is called periodically during teleoperated mode.
+   */
+  @Override
+  public void teleopPeriodic() {
+    Scheduler.getInstance().run();
+    log();
+  }
+
+  /**
+   * This function is called periodically during test mode.
+   */
+  @Override
+  public void testPeriodic() {
+  }
+
+  /**
+   * The log method puts interesting information to the SmartDashboard.
+   */
+  private void log() {
+    m_wrist.log();
+    m_elevator.log();
+    m_drivetrain.log();
+    m_claw.log();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Autonomous.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Autonomous.java
new file mode 100644
index 0000000..96a9d85
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Autonomous.java
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+/**
+ * The main autonomous command to pickup and deliver the soda to the box.
+ */
+public class Autonomous extends CommandGroup {
+  /**
+   * Create a new autonomous command.
+   */
+  public Autonomous() {
+    addSequential(new PrepareToPickup());
+    addSequential(new Pickup());
+    addSequential(new SetDistanceToBox(0.10));
+    // addSequential(new DriveStraight(4)); // Use Encoders if ultrasonic is
+    // broken
+    addSequential(new Place());
+    addSequential(new SetDistanceToBox(0.60));
+    // addSequential(new DriveStraight(-2)); // Use Encoders if ultrasonic
+    // is broken
+    addParallel(new SetWristSetpoint(-45));
+    addSequential(new CloseClaw());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/CloseClaw.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/CloseClaw.java
new file mode 100644
index 0000000..cdf4788
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/CloseClaw.java
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * Closes the claw for one second. Real robots should use sensors, stalling
+ * motors is BAD!
+ */
+public class CloseClaw extends Command {
+  public CloseClaw() {
+    requires(Robot.m_claw);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.m_claw.close();
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return Robot.m_claw.isGrabbing();
+  }
+
+  // Called once after isFinished returns true
+  @Override
+  protected void end() {
+    // NOTE: Doesn't stop in simulation due to lower friction causing the
+    // can to fall out
+    // + there is no need to worry about stalling the motor or crushing the
+    // can.
+    if (!Robot.isSimulation()) {
+      Robot.m_claw.stop();
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/DriveStraight.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/DriveStraight.java
new file mode 100644
index 0000000..ba8feeb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/DriveStraight.java
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.PIDController;
+import edu.wpi.first.wpilibj.PIDSource;
+import edu.wpi.first.wpilibj.PIDSourceType;
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * Drive the given distance straight (negative values go backwards). Uses a
+ * local PID controller to run a simple PID loop that is only enabled while this
+ * command is running. The input is the averaged values of the left and right
+ * encoders.
+ */
+public class DriveStraight extends Command {
+  private final PIDController m_pid;
+
+  /**
+   * Create a new DriveStraight command.
+   * @param distance The distance to drive
+   */
+  public DriveStraight(double distance) {
+    requires(Robot.m_drivetrain);
+    m_pid = new PIDController(4, 0, 0, new PIDSource() {
+      PIDSourceType m_sourceType = PIDSourceType.kDisplacement;
+
+      @Override
+      public double pidGet() {
+        return Robot.m_drivetrain.getDistance();
+      }
+
+      @Override
+      public void setPIDSourceType(PIDSourceType pidSource) {
+        m_sourceType = pidSource;
+      }
+
+      @Override
+      public PIDSourceType getPIDSourceType() {
+        return m_sourceType;
+      }
+    }, d -> Robot.m_drivetrain.drive(d, d));
+
+    m_pid.setAbsoluteTolerance(0.01);
+    m_pid.setSetpoint(distance);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    // Get everything in a safe starting state.
+    Robot.m_drivetrain.reset();
+    m_pid.reset();
+    m_pid.enable();
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return m_pid.onTarget();
+  }
+
+  // Called once after isFinished returns true
+  @Override
+  protected void end() {
+    // Stop PID and the wheels
+    m_pid.disable();
+    Robot.m_drivetrain.drive(0, 0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/OpenClaw.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/OpenClaw.java
new file mode 100644
index 0000000..486181d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/OpenClaw.java
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.TimedCommand;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * Opens the claw for one second. Real robots should use sensors, stalling
+ * motors is BAD!
+ */
+public class OpenClaw extends TimedCommand {
+  public OpenClaw() {
+    super(1);
+    requires(Robot.m_claw);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.m_claw.open();
+  }
+
+  // Called once after isFinished returns true
+  @Override
+  protected void end() {
+    Robot.m_claw.stop();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Pickup.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Pickup.java
new file mode 100644
index 0000000..304ddf9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Pickup.java
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+/**
+ * Pickup a soda can (if one is between the open claws) and get it in a safe
+ * state to drive around.
+ */
+public class Pickup extends CommandGroup {
+  /**
+   * Create a new pickup command.
+   */
+  public Pickup() {
+    addSequential(new CloseClaw());
+    addParallel(new SetWristSetpoint(-45));
+    addSequential(new SetElevatorSetpoint(0.25));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Place.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Place.java
new file mode 100644
index 0000000..c1a1841
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/Place.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+/**
+ * Place a held soda can onto the platform.
+ */
+public class Place extends CommandGroup {
+  /**
+   * Create a new place command.
+   */
+  public Place() {
+    addSequential(new SetElevatorSetpoint(0.25));
+    addSequential(new SetWristSetpoint(0));
+    addSequential(new OpenClaw());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/PrepareToPickup.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/PrepareToPickup.java
new file mode 100644
index 0000000..911c535
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/PrepareToPickup.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+/**
+ * Make sure the robot is in a state to pickup soda cans.
+ */
+public class PrepareToPickup extends CommandGroup {
+  /**
+   * Create a new prepare to pickup command.
+   */
+  public PrepareToPickup() {
+    addParallel(new OpenClaw());
+    addParallel(new SetWristSetpoint(0));
+    addSequential(new SetElevatorSetpoint(0));
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetDistanceToBox.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetDistanceToBox.java
new file mode 100644
index 0000000..71f03dc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetDistanceToBox.java
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.PIDController;
+import edu.wpi.first.wpilibj.PIDSource;
+import edu.wpi.first.wpilibj.PIDSourceType;
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * Drive until the robot is the given distance away from the box. Uses a local
+ * PID controller to run a simple PID loop that is only enabled while this
+ * command is running. The input is the averaged values of the left and right
+ * encoders.
+ */
+public class SetDistanceToBox extends Command {
+  private final PIDController m_pid;
+
+  /**
+   * Create a new set distance to box command.
+   * @param distance The distance away from the box to drive to
+   */
+  public SetDistanceToBox(double distance) {
+    requires(Robot.m_drivetrain);
+    m_pid = new PIDController(-2, 0, 0, new PIDSource() {
+      PIDSourceType m_sourceType = PIDSourceType.kDisplacement;
+
+      @Override
+      public double pidGet() {
+        return Robot.m_drivetrain.getDistanceToObstacle();
+      }
+
+      @Override
+      public void setPIDSourceType(PIDSourceType pidSource) {
+        m_sourceType = pidSource;
+      }
+
+      @Override
+      public PIDSourceType getPIDSourceType() {
+        return m_sourceType;
+      }
+    }, d -> Robot.m_drivetrain.drive(d, d));
+
+    m_pid.setAbsoluteTolerance(0.01);
+    m_pid.setSetpoint(distance);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    // Get everything in a safe starting state.
+    Robot.m_drivetrain.reset();
+    m_pid.reset();
+    m_pid.enable();
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return m_pid.onTarget();
+  }
+
+  // Called once after isFinished returns true
+  @Override
+  protected void end() {
+    // Stop PID and the wheels
+    m_pid.disable();
+    Robot.m_drivetrain.drive(0, 0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetElevatorSetpoint.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetElevatorSetpoint.java
new file mode 100644
index 0000000..0ee5193
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetElevatorSetpoint.java
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * Move the elevator to a given location. This command finishes when it is
+ * within the tolerance, but leaves the PID loop running to maintain the
+ * position. Other commands using the elevator should make sure they disable
+ * PID!
+ */
+public class SetElevatorSetpoint extends Command {
+  private final double m_setpoint;
+
+  public SetElevatorSetpoint(double setpoint) {
+    m_setpoint = setpoint;
+    requires(Robot.m_elevator);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.m_elevator.enable();
+    Robot.m_elevator.setSetpoint(m_setpoint);
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return Robot.m_elevator.onTarget();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetWristSetpoint.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetWristSetpoint.java
new file mode 100644
index 0000000..62e7a7f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetWristSetpoint.java
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * Move the wrist to a given angle. This command finishes when it is within the
+ * tolerance, but leaves the PID loop running to maintain the position. Other
+ * commands using the wrist should make sure they disable PID!
+ */
+public class SetWristSetpoint extends Command {
+  private final double m_setpoint;
+
+  public SetWristSetpoint(double setpoint) {
+    m_setpoint = setpoint;
+    requires(Robot.m_wrist);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.m_wrist.enable();
+    Robot.m_wrist.setSetpoint(m_setpoint);
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return Robot.m_wrist.onTarget();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/TankDriveWithJoystick.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/TankDriveWithJoystick.java
new file mode 100644
index 0000000..642fa5d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/TankDriveWithJoystick.java
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * Have the robot drive tank style using the PS3 Joystick until interrupted.
+ */
+public class TankDriveWithJoystick extends Command {
+  public TankDriveWithJoystick() {
+    requires(Robot.m_drivetrain);
+  }
+
+  // Called repeatedly when this Command is scheduled to run
+  @Override
+  protected void execute() {
+    Robot.m_drivetrain.drive(Robot.m_oi.getJoystick());
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return false; // Runs until interrupted
+  }
+
+  // Called once after isFinished returns true
+  @Override
+  protected void end() {
+    Robot.m_drivetrain.drive(0, 0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Claw.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Claw.java
new file mode 100644
index 0000000..550db9a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Claw.java
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
+
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.Victor;
+import edu.wpi.first.wpilibj.command.Subsystem;
+
+/**
+ * The claw subsystem is a simple system with a motor for opening and closing.
+ * If using stronger motors, you should probably use a sensor so that the motors
+ * don't stall.
+ */
+public class Claw extends Subsystem {
+  private final Victor m_motor = new Victor(7);
+  private final DigitalInput m_contact = new DigitalInput(5);
+
+  /**
+   * Create a new claw subsystem.
+   */
+  public Claw() {
+    super();
+
+    // Let's name everything on the LiveWindow
+    addChild("Motor", m_motor);
+    addChild("Limit Switch", m_contact);
+  }
+
+  @Override
+  public void initDefaultCommand() {
+  }
+
+  public void log() {
+  }
+
+  /**
+   * Set the claw motor to move in the open direction.
+   */
+  public void open() {
+    m_motor.set(-1);
+  }
+
+  /**
+   * Set the claw motor to move in the close direction.
+   */
+  @Override
+  public void close() {
+    m_motor.set(1);
+  }
+
+  /**
+   * Stops the claw motor from moving.
+   */
+  public void stop() {
+    m_motor.set(0);
+  }
+
+  /**
+   * Return true when the robot is grabbing an object hard enough to trigger
+   * the limit switch.
+   */
+  public boolean isGrabbing() {
+    return m_contact.get();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/DriveTrain.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/DriveTrain.java
new file mode 100644
index 0000000..5c55365
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/DriveTrain.java
@@ -0,0 +1,146 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
+
+import edu.wpi.first.wpilibj.AnalogGyro;
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.SpeedControllerGroup;
+import edu.wpi.first.wpilibj.command.Subsystem;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+import edu.wpi.first.wpilibj.examples.gearsbot.commands.TankDriveWithJoystick;
+
+/**
+ * The DriveTrain subsystem incorporates the sensors and actuators attached to
+ * the robots chassis. These include four drive motors, a left and right encoder
+ * and a gyro.
+ */
+public class DriveTrain extends Subsystem {
+  private final SpeedController m_leftMotor
+      = new SpeedControllerGroup(new PWMVictorSPX(0), new PWMVictorSPX(1));
+  private final SpeedController m_rightMotor
+      = new SpeedControllerGroup(new PWMVictorSPX(2), new PWMVictorSPX(3));
+
+  private final DifferentialDrive m_drive
+      = new DifferentialDrive(m_leftMotor, m_rightMotor);
+
+  private final Encoder m_leftEncoder = new Encoder(1, 2);
+  private final Encoder m_rightEncoder = new Encoder(3, 4);
+  private final AnalogInput m_rangefinder = new AnalogInput(6);
+  private final AnalogGyro m_gyro = new AnalogGyro(1);
+
+  /**
+   * Create a new drive train subsystem.
+   */
+  public DriveTrain() {
+    super();
+
+    // Encoders may measure differently in the real world and in
+    // simulation. In this example the robot moves 0.042 barleycorns
+    // per tick in the real world, but the simulated encoders
+    // simulate 360 tick encoders. This if statement allows for the
+    // real robot to handle this difference in devices.
+    if (Robot.isReal()) {
+      m_leftEncoder.setDistancePerPulse(0.042);
+      m_rightEncoder.setDistancePerPulse(0.042);
+    } else {
+      // Circumference in ft = 4in/12(in/ft)*PI
+      m_leftEncoder.setDistancePerPulse((4.0 / 12.0 * Math.PI) / 360.0);
+      m_rightEncoder.setDistancePerPulse((4.0 / 12.0 * Math.PI) / 360.0);
+    }
+
+    // Let's name the sensors on the LiveWindow
+    addChild("Drive", m_drive);
+    addChild("Left Encoder", m_leftEncoder);
+    addChild("Right Encoder", m_rightEncoder);
+    addChild("Rangefinder", m_rangefinder);
+    addChild("Gyro", m_gyro);
+  }
+
+  /**
+   * When no other command is running let the operator drive around using the
+   * PS3 joystick.
+   */
+  @Override
+  public void initDefaultCommand() {
+    setDefaultCommand(new TankDriveWithJoystick());
+  }
+
+  /**
+   * The log method puts interesting information to the SmartDashboard.
+   */
+  public void log() {
+    SmartDashboard.putNumber("Left Distance", m_leftEncoder.getDistance());
+    SmartDashboard.putNumber("Right Distance", m_rightEncoder.getDistance());
+    SmartDashboard.putNumber("Left Speed", m_leftEncoder.getRate());
+    SmartDashboard.putNumber("Right Speed", m_rightEncoder.getRate());
+    SmartDashboard.putNumber("Gyro", m_gyro.getAngle());
+  }
+
+  /**
+   * Tank style driving for the DriveTrain.
+   *
+   * @param left Speed in range [-1,1]
+   * @param right Speed in range [-1,1]
+   */
+  public void drive(double left, double right) {
+    m_drive.tankDrive(left, right);
+  }
+
+  /**
+   * Tank style driving for the DriveTrain.
+   *
+   * @param joy The ps3 style joystick to use to drive tank style.
+   */
+  public void drive(Joystick joy) {
+    drive(-joy.getY(), -joy.getThrottle());
+  }
+
+  /**
+   * Get the robot's heading.
+   *
+   * @return The robots heading in degrees.
+   */
+  public double getHeading() {
+    return m_gyro.getAngle();
+  }
+
+  /**
+   * Reset the robots sensors to the zero states.
+   */
+  public void reset() {
+    m_gyro.reset();
+    m_leftEncoder.reset();
+    m_rightEncoder.reset();
+  }
+
+  /**
+   * Get the average distance of the encoders since the last reset.
+   *
+   * @return The distance driven (average of left and right encoders).
+   */
+  public double getDistance() {
+    return (m_leftEncoder.getDistance() + m_rightEncoder.getDistance()) / 2;
+  }
+
+  /**
+   * Get the distance to the obstacle.
+   *
+   * @return The distance to the obstacle detected by the rangefinder.
+   */
+  public double getDistanceToObstacle() {
+    // Really meters in simulation since it's a rangefinder...
+    return m_rangefinder.getAverageVoltage();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Elevator.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Elevator.java
new file mode 100644
index 0000000..02d308c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Elevator.java
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
+
+import edu.wpi.first.wpilibj.AnalogPotentiometer;
+import edu.wpi.first.wpilibj.Victor;
+import edu.wpi.first.wpilibj.command.PIDSubsystem;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * The elevator subsystem uses PID to go to a given height. Unfortunately, in
+ * it's current state PID values for simulation are different than in the real
+ * world do to minor differences.
+ */
+public class Elevator extends PIDSubsystem {
+  private final Victor m_motor;
+  private final AnalogPotentiometer m_pot;
+
+  private static final double kP_real = 4;
+  private static final double kI_real = 0.07;
+  private static final double kP_simulation = 18;
+  private static final double kI_simulation = 0.2;
+
+  /**
+   * Create a new elevator subsystem.
+   */
+  public Elevator() {
+    super(kP_real, kI_real, 0);
+    if (Robot.isSimulation()) { // Check for simulation and update PID values
+      getPIDController().setPID(kP_simulation, kI_simulation, 0, 0);
+    }
+    setAbsoluteTolerance(0.005);
+
+    m_motor = new Victor(5);
+
+    // Conversion value of potentiometer varies between the real world and
+    // simulation
+    if (Robot.isReal()) {
+      m_pot = new AnalogPotentiometer(2, -2.0 / 5);
+    } else {
+      m_pot = new AnalogPotentiometer(2); // Defaults to meters
+    }
+
+    // Let's name everything on the LiveWindow
+    addChild("Motor", m_motor);
+    addChild("Pot", m_pot);
+  }
+
+  @Override
+  public void initDefaultCommand() {
+  }
+
+  /**
+   * The log method puts interesting information to the SmartDashboard.
+   */
+  public void log() {
+    SmartDashboard.putData("Elevator Pot", (AnalogPotentiometer) m_pot);
+  }
+
+  /**
+   * Use the potentiometer as the PID sensor. This method is automatically
+   * called by the subsystem.
+   */
+  @Override
+  protected double returnPIDInput() {
+    return m_pot.get();
+  }
+
+  /**
+   * Use the motor as the PID output. This method is automatically called by
+   * the subsystem.
+   */
+  @Override
+  protected void usePIDOutput(double power) {
+    m_motor.set(power);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Wrist.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Wrist.java
new file mode 100644
index 0000000..30fa38e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Wrist.java
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gearsbot.subsystems;
+
+import edu.wpi.first.wpilibj.AnalogPotentiometer;
+import edu.wpi.first.wpilibj.Victor;
+import edu.wpi.first.wpilibj.command.PIDSubsystem;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
+
+/**
+ * The wrist subsystem is like the elevator, but with a rotational joint instead
+ * of a linear joint.
+ */
+public class Wrist extends PIDSubsystem {
+  private final Victor m_motor;
+  private final AnalogPotentiometer m_pot;
+
+  private static final double kP_real = 1;
+  private static final double kP_simulation = 0.05;
+
+  /**
+   * Create a new wrist subsystem.
+   */
+  public Wrist() {
+    super(kP_real, 0, 0);
+    if (Robot.isSimulation()) { // Check for simulation and update PID values
+      getPIDController().setPID(kP_simulation, 0, 0, 0);
+    }
+    setAbsoluteTolerance(2.5);
+
+    m_motor = new Victor(6);
+
+    // Conversion value of potentiometer varies between the real world and
+    // simulation
+    if (Robot.isReal()) {
+      m_pot = new AnalogPotentiometer(3, -270.0 / 5);
+    } else {
+      m_pot = new AnalogPotentiometer(3); // Defaults to degrees
+    }
+
+    // Let's name everything on the LiveWindow
+    addChild("Motor", m_motor);
+    addChild("Pot", m_pot);
+  }
+
+  @Override
+  public void initDefaultCommand() {
+  }
+
+  /**
+   * The log method puts interesting information to the SmartDashboard.
+   */
+  public void log() {
+    SmartDashboard.putData("Wrist Angle", (AnalogPotentiometer) m_pot);
+  }
+
+  /**
+   * Use the potentiometer as the PID sensor. This method is automatically
+   * called by the subsystem.
+   */
+  @Override
+  protected double returnPIDInput() {
+    return m_pot.get();
+  }
+
+  /**
+   * Use the motor as the PID output. This method is automatically called by
+   * the subsystem.
+   */
+  @Override
+  protected void usePIDOutput(double power) {
+    m_motor.set(power);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Main.java
new file mode 100644
index 0000000..282f922
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gettingstarted;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
new file mode 100644
index 0000000..8b2f249
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gettingstarted/Robot.java
@@ -0,0 +1,80 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gettingstarted;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+
+/**
+ * The VM is configured to automatically run this class, and to call the
+ * functions corresponding to each mode, as described in the TimedRobot
+ * documentation. If you change the name of this class or the package after
+ * creating this project, you must also update the manifest file in the resource
+ * directory.
+ */
+public class Robot extends TimedRobot {
+  private final DifferentialDrive m_robotDrive
+      = new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1));
+  private final Joystick m_stick = new Joystick(0);
+  private final Timer m_timer = new Timer();
+
+  /**
+   * This function is run when the robot is first started up and should be
+   * used for any initialization code.
+   */
+  @Override
+  public void robotInit() {
+  }
+
+  /**
+   * This function is run once each time the robot enters autonomous mode.
+   */
+  @Override
+  public void autonomousInit() {
+    m_timer.reset();
+    m_timer.start();
+  }
+
+  /**
+   * This function is called periodically during autonomous.
+   */
+  @Override
+  public void autonomousPeriodic() {
+    // Drive for 2 seconds
+    if (m_timer.get() < 2.0) {
+      m_robotDrive.arcadeDrive(0.5, 0.0); // drive forwards half speed
+    } else {
+      m_robotDrive.stopMotor(); // stop robot
+    }
+  }
+
+  /**
+   * This function is called once each time the robot enters teleoperated mode.
+   */
+  @Override
+  public void teleopInit() {
+  }
+
+  /**
+   * This function is called periodically during teleoperated mode.
+   */
+  @Override
+  public void teleopPeriodic() {
+    m_robotDrive.arcadeDrive(m_stick.getY(), m_stick.getX());
+  }
+
+  /**
+   * This function is called periodically during test mode.
+   */
+  @Override
+  public void testPeriodic() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Main.java
new file mode 100644
index 0000000..4c5574e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gyro;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java
new file mode 100644
index 0000000..39b2ecb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyro/Robot.java
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gyro;
+
+import edu.wpi.first.wpilibj.AnalogGyro;
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+
+/**
+ * This is a sample program to demonstrate how to use a gyro sensor to make a
+ * robot drive straight. This program uses a joystick to drive forwards and
+ * backwards while the gyro is used for direction keeping.
+ */
+public class Robot extends TimedRobot {
+  private static final double kAngleSetpoint = 0.0;
+  private static final double kP = 0.005; // propotional turning constant
+
+  // gyro calibration constant, may need to be adjusted;
+  // gyro value of 360 is set to correspond to one full revolution
+  private static final double kVoltsPerDegreePerSecond = 0.0128;
+
+  private static final int kLeftMotorPort = 0;
+  private static final int kRightMotorPort = 1;
+  private static final int kGyroPort = 0;
+  private static final int kJoystickPort = 0;
+
+  private final DifferentialDrive m_myRobot
+      = new DifferentialDrive(new PWMVictorSPX(kLeftMotorPort),
+      new PWMVictorSPX(kRightMotorPort));
+  private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
+  private final Joystick m_joystick = new Joystick(kJoystickPort);
+
+  @Override
+  public void robotInit() {
+    m_gyro.setSensitivity(kVoltsPerDegreePerSecond);
+  }
+
+  /**
+   * The motor speed is set from the joystick while the RobotDrive turning
+   * value is assigned from the error between the setpoint and the gyro angle.
+   */
+  @Override
+  public void teleopPeriodic() {
+    double turningValue = (kAngleSetpoint - m_gyro.getAngle()) * kP;
+    // Invert the direction of the turn if we are going backwards
+    turningValue = Math.copySign(turningValue, m_joystick.getY());
+    m_myRobot.arcadeDrive(m_joystick.getY(), turningValue);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Main.java
new file mode 100644
index 0000000..63300b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gyromecanum;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java
new file mode 100644
index 0000000..079318a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyromecanum/Robot.java
@@ -0,0 +1,62 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.gyromecanum;
+
+import edu.wpi.first.wpilibj.AnalogGyro;
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.drive.MecanumDrive;
+
+/**
+ * This is a sample program that uses mecanum drive with a gyro sensor to
+ * maintian rotation vectorsin relation to the starting orientation of the robot
+ * (field-oriented controls).
+ */
+public class Robot extends TimedRobot {
+  // gyro calibration constant, may need to be adjusted;
+  // gyro value of 360 is set to correspond to one full revolution
+  private static final double kVoltsPerDegreePerSecond = 0.0128;
+
+  private static final int kFrontLeftChannel = 0;
+  private static final int kRearLeftChannel = 1;
+  private static final int kFrontRightChannel = 2;
+  private static final int kRearRightChannel = 3;
+  private static final int kGyroPort = 0;
+  private static final int kJoystickPort = 0;
+
+  private MecanumDrive m_robotDrive;
+  private final AnalogGyro m_gyro = new AnalogGyro(kGyroPort);
+  private final Joystick m_joystick = new Joystick(kJoystickPort);
+
+  @Override
+  public void robotInit() {
+    PWMVictorSPX frontLeft = new PWMVictorSPX(kFrontLeftChannel);
+    PWMVictorSPX rearLeft = new PWMVictorSPX(kRearLeftChannel);
+    PWMVictorSPX frontRight = new PWMVictorSPX(kFrontRightChannel);
+    PWMVictorSPX rearRight = new PWMVictorSPX(kRearRightChannel);
+
+    // Invert the left side motors.
+    // You may need to change or remove this to match your robot.
+    frontLeft.setInverted(true);
+    rearLeft.setInverted(true);
+
+    m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight);
+
+    m_gyro.setSensitivity(kVoltsPerDegreePerSecond);
+  }
+
+  /**
+   * Mecanum drive is used with the gyro angle as an input.
+   */
+  @Override
+  public void teleopPeriodic() {
+    m_robotDrive.driveCartesian(m_joystick.getX(), m_joystick.getY(),
+        m_joystick.getZ(), m_gyro.getAngle());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hidrumble/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hidrumble/Main.java
new file mode 100644
index 0000000..297bbf1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hidrumble/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.hidrumble;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hidrumble/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hidrumble/Robot.java
new file mode 100755
index 0000000..c7f6029
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hidrumble/Robot.java
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.hidrumble;
+
+import edu.wpi.first.wpilibj.GenericHID.RumbleType;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.XboxController;
+
+/**
+ * This is a demo program showing the use of GenericHID's rumble feature.
+ */
+public class Robot extends TimedRobot {
+  private final XboxController m_hid = new XboxController(0);
+
+  @Override
+  public void autonomousInit() {
+    // Turn on rumble at the start of auto
+    m_hid.setRumble(RumbleType.kLeftRumble, 1.0);
+    m_hid.setRumble(RumbleType.kRightRumble, 1.0);
+  }
+
+  @Override
+  public void disabledInit() {
+    // Stop the rumble when entering disabled
+    m_hid.setRumble(RumbleType.kLeftRumble, 0.0);
+    m_hid.setRumble(RumbleType.kRightRumble, 0.0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Main.java
new file mode 100644
index 0000000..a0210b4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.intermediatevision;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java
new file mode 100644
index 0000000..526e849
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/intermediatevision/Robot.java
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.intermediatevision;
+
+import org.opencv.core.Mat;
+import org.opencv.core.Point;
+import org.opencv.core.Scalar;
+import org.opencv.imgproc.Imgproc;
+
+import edu.wpi.cscore.CvSink;
+import edu.wpi.cscore.CvSource;
+import edu.wpi.cscore.UsbCamera;
+import edu.wpi.first.cameraserver.CameraServer;
+import edu.wpi.first.wpilibj.TimedRobot;
+
+/**
+ * This is a demo program showing the use of OpenCV to do vision processing. The
+ * image is acquired from the USB camera, then a rectangle is put on the image
+ * and sent to the dashboard. OpenCV has many methods for different types of
+ * processing.
+ */
+public class Robot extends TimedRobot {
+  Thread m_visionThread;
+
+  @Override
+  public void robotInit() {
+    m_visionThread = new Thread(() -> {
+      // Get the UsbCamera from CameraServer
+      UsbCamera camera = CameraServer.getInstance().startAutomaticCapture();
+      // Set the resolution
+      camera.setResolution(640, 480);
+
+      // Get a CvSink. This will capture Mats from the camera
+      CvSink cvSink = CameraServer.getInstance().getVideo();
+      // Setup a CvSource. This will send images back to the Dashboard
+      CvSource outputStream
+          = CameraServer.getInstance().putVideo("Rectangle", 640, 480);
+
+      // Mats are very memory expensive. Lets reuse this Mat.
+      Mat mat = new Mat();
+
+      // This cannot be 'true'. The program will never exit if it is. This
+      // lets the robot stop this thread when restarting robot code or
+      // deploying.
+      while (!Thread.interrupted()) {
+        // Tell the CvSink to grab a frame from the camera and put it
+        // in the source mat.  If there is an error notify the output.
+        if (cvSink.grabFrame(mat) == 0) {
+          // Send the output the error.
+          outputStream.notifyError(cvSink.getError());
+          // skip the rest of the current iteration
+          continue;
+        }
+        // Put a rectangle on the image
+        Imgproc.rectangle(mat, new Point(100, 100), new Point(400, 400),
+            new Scalar(255, 255, 255), 5);
+        // Give the output stream a new image to display
+        outputStream.putFrame(mat);
+      }
+    });
+    m_visionThread.setDaemon(true);
+    m_visionThread.start();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Main.java
new file mode 100644
index 0000000..4a8f2e1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.mecanumdrive;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java
new file mode 100755
index 0000000..35c975c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumdrive/Robot.java
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.mecanumdrive;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.drive.MecanumDrive;
+
+/**
+ * This is a demo program showing how to use Mecanum control with the RobotDrive
+ * class.
+ */
+public class Robot extends TimedRobot {
+  private static final int kFrontLeftChannel = 2;
+  private static final int kRearLeftChannel = 3;
+  private static final int kFrontRightChannel = 1;
+  private static final int kRearRightChannel = 0;
+
+  private static final int kJoystickChannel = 0;
+
+  private MecanumDrive m_robotDrive;
+  private Joystick m_stick;
+
+  @Override
+  public void robotInit() {
+    PWMVictorSPX frontLeft = new PWMVictorSPX(kFrontLeftChannel);
+    PWMVictorSPX rearLeft = new PWMVictorSPX(kRearLeftChannel);
+    PWMVictorSPX frontRight = new PWMVictorSPX(kFrontRightChannel);
+    PWMVictorSPX rearRight = new PWMVictorSPX(kRearRightChannel);
+
+    // Invert the left side motors.
+    // You may need to change or remove this to match your robot.
+    frontLeft.setInverted(true);
+    rearLeft.setInverted(true);
+
+    m_robotDrive = new MecanumDrive(frontLeft, rearLeft, frontRight, rearRight);
+
+    m_stick = new Joystick(kJoystickChannel);
+  }
+
+  @Override
+  public void teleopPeriodic() {
+    // Use the joystick X axis for lateral movement, Y axis for forward
+    // movement, and Z axis for rotation.
+    m_robotDrive.driveCartesian(m_stick.getX(), m_stick.getY(),
+        m_stick.getZ(), 0.0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Main.java
new file mode 100644
index 0000000..f817e8f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.motorcontrol;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java
new file mode 100755
index 0000000..7dfb49b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrol/Robot.java
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.motorcontrol;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.TimedRobot;
+
+/**
+ * This sample program shows how to control a motor using a joystick. In the
+ * operator control part of the program, the joystick is read and the value is
+ * written to the motor.
+ *
+ * <p>Joystick analog values range from -1 to 1 and speed controller inputs also
+ * range from -1 to 1 making it easy to work together.
+ */
+public class Robot extends TimedRobot {
+  private static final int kMotorPort = 0;
+  private static final int kJoystickPort = 0;
+
+  private SpeedController m_motor;
+  private Joystick m_joystick;
+
+  @Override
+  public void robotInit() {
+    m_motor = new PWMVictorSPX(kMotorPort);
+    m_joystick = new Joystick(kJoystickPort);
+  }
+
+  @Override
+  public void teleopPeriodic() {
+    m_motor.set(m_joystick.getY());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java
new file mode 100644
index 0000000..5b03eed
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.motorcontrolencoder;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java
new file mode 100644
index 0000000..b0cc217
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/motorcontrolencoder/Robot.java
@@ -0,0 +1,61 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.motorcontrolencoder;
+
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+/**
+ * This sample program shows how to control a motor using a joystick. In the
+ * operator control part of the program, the joystick is read and the value is
+ * written to the motor.
+ *
+ * <p>Joystick analog values range from -1 to 1 and speed controller inputs also
+ * range from -1 to 1 making it easy to work together.
+ *
+ * <p>In addition, the encoder value of an encoder connected to ports 0 and 1 is
+ * consistently sent to the Dashboard.
+ */
+public class Robot extends TimedRobot {
+  private static final int kMotorPort = 0;
+  private static final int kJoystickPort = 0;
+  private static final int kEncoderPortA = 0;
+  private static final int kEncoderPortB = 1;
+
+  private SpeedController m_motor;
+  private Joystick m_joystick;
+  private Encoder m_encoder;
+
+  @Override
+  public void robotInit() {
+    m_motor = new PWMVictorSPX(kMotorPort);
+    m_joystick = new Joystick(kJoystickPort);
+    m_encoder = new Encoder(kEncoderPortA, kEncoderPortB);
+    // Use SetDistancePerPulse to set the multiplier for GetDistance
+    // This is set up assuming a 6 inch wheel with a 360 CPR encoder.
+    m_encoder.setDistancePerPulse((Math.PI * 6) / 360.0);
+  }
+
+  /*
+   * The RobotPeriodic function is called every control packet no matter the
+   * robot mode.
+   */
+  @Override
+  public void robotPeriodic() {
+    SmartDashboard.putNumber("Encoder", m_encoder.getDistance());
+  }
+
+  @Override
+  public void teleopPeriodic() {
+    m_motor.set(m_joystick.getY());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Main.java
new file mode 100644
index 0000000..04a26be
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/OI.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/OI.java
new file mode 100644
index 0000000..c1646e1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/OI.java
@@ -0,0 +1,60 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.buttons.JoystickButton;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.Collect;
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.DriveForward;
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.LowGoal;
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.SetCollectionSpeed;
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.SetPivotSetpoint;
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.Shoot;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Collector;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Pivot;
+import edu.wpi.first.wpilibj.examples.pacgoat.triggers.DoubleButton;
+
+/**
+ * The operator interface of the robot, it has been simplified from the real
+ * robot to allow control with a single PS3 joystick. As a result, not all
+ * functionality from the real robot is available.
+ */
+public class OI {
+  public Joystick m_joystick = new Joystick(0);
+
+  /**
+   * Create a new OI and all of the buttons on it.
+   */
+  public OI() {
+    new JoystickButton(m_joystick, 12).whenPressed(new LowGoal());
+    new JoystickButton(m_joystick, 10).whenPressed(new Collect());
+
+    new JoystickButton(m_joystick, 11).whenPressed(
+        new SetPivotSetpoint(Pivot.kShoot));
+    new JoystickButton(m_joystick, 9).whenPressed(
+        new SetPivotSetpoint(Pivot.kShootNear));
+
+    new DoubleButton(m_joystick, 2, 3).whenActive(new Shoot());
+
+    // SmartDashboard Buttons
+    SmartDashboard.putData("Drive Forward", new DriveForward(2.25));
+    SmartDashboard.putData("Drive Backward", new DriveForward(-2.25));
+    SmartDashboard.putData("Start Rollers",
+        new SetCollectionSpeed(Collector.kForward));
+    SmartDashboard.putData("Stop Rollers",
+        new SetCollectionSpeed(Collector.kStop));
+    SmartDashboard.putData("Reverse Rollers",
+        new SetCollectionSpeed(Collector.kReverse));
+  }
+
+  public Joystick getJoystick() {
+    return m_joystick;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Robot.java
new file mode 100644
index 0000000..3e1c397
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/Robot.java
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat;
+
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.command.Command;
+import edu.wpi.first.wpilibj.command.Scheduler;
+import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.DriveAndShootAutonomous;
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.DriveForward;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Collector;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.DriveTrain;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Pivot;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Pneumatics;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Shooter;
+
+/**
+ * This is the main class for running the PacGoat code.
+ *
+ * <p>The VM is configured to automatically run this class, and to call the
+ * functions corresponding to each mode, as described in the TimedRobot
+ * documentation. If you change the name of this class or the package after
+ * creating this project, you must also update the manifest file in the resource
+ * directory.
+ */
+public class Robot extends TimedRobot {
+  Command m_autonomousCommand;
+  public static OI oi;
+
+  // Initialize the subsystems
+  public static DriveTrain drivetrain = new DriveTrain();
+  public static Collector collector = new Collector();
+  public static Shooter shooter = new Shooter();
+  public static Pneumatics pneumatics = new Pneumatics();
+  public static Pivot pivot = new Pivot();
+
+  public SendableChooser<Command> m_autoChooser;
+
+  // This function is run when the robot is first started up and should be
+  // used for any initialization code.
+  @Override
+  public void robotInit() {
+    SmartDashboard.putData(drivetrain);
+    SmartDashboard.putData(collector);
+    SmartDashboard.putData(shooter);
+    SmartDashboard.putData(pneumatics);
+    SmartDashboard.putData(pivot);
+
+    // This MUST be here. If the OI creates Commands (which it very likely
+    // will), constructing it during the construction of CommandBase (from
+    // which commands extend), subsystems are not guaranteed to be
+    // yet. Thus, their requires() statements may grab null pointers. Bad
+    // news. Don't move it.
+    oi = new OI();
+
+    // instantiate the command used for the autonomous period
+    m_autoChooser = new SendableChooser<Command>();
+    m_autoChooser.setDefaultOption("Drive and Shoot", new DriveAndShootAutonomous());
+    m_autoChooser.addOption("Drive Forward", new DriveForward());
+    SmartDashboard.putData("Auto Mode", m_autoChooser);
+  }
+
+  @Override
+  public void autonomousInit() {
+    m_autonomousCommand = (Command) m_autoChooser.getSelected();
+    m_autonomousCommand.start();
+  }
+
+  // This function is called periodically during autonomous
+  @Override
+  public void autonomousPeriodic() {
+    Scheduler.getInstance().run();
+    log();
+  }
+
+  @Override
+  public void teleopInit() {
+    // This makes sure that the autonomous stops running when
+    // teleop starts running. If you want the autonomous to
+    // continue until interrupted by another command, remove
+    // this line or comment it out.
+    if (m_autonomousCommand != null) {
+      m_autonomousCommand.cancel();
+    }
+  }
+
+  // This function is called periodically during operator control
+  @Override
+  public void teleopPeriodic() {
+    Scheduler.getInstance().run();
+    log();
+  }
+
+  // This function called periodically during test mode
+  @Override
+  public void testPeriodic() {
+  }
+
+  @Override
+  public void disabledInit() {
+    Robot.shooter.unlatch();
+  }
+
+  // This function is called periodically while disabled
+  @Override
+  public void disabledPeriodic() {
+    log();
+  }
+
+  /**
+   * Log interesting values to the SmartDashboard.
+   */
+  private void log() {
+    Robot.pneumatics.writePressure();
+    SmartDashboard.putNumber("Pivot Pot Value", Robot.pivot.getAngle());
+    SmartDashboard.putNumber("Left Distance",
+        drivetrain.getLeftEncoder().getDistance());
+    SmartDashboard.putNumber("Right Distance",
+        drivetrain.getRightEncoder().getDistance());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/CheckForHotGoal.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/CheckForHotGoal.java
new file mode 100644
index 0000000..4136ed1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/CheckForHotGoal.java
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * This command looks for the hot goal and waits until it's detected or timed
+ * out. The timeout is because it's better to shoot and get some autonomous
+ * points than get none. When called sequentially, this command will block until
+ * the hot goal is detected or until it is timed out.
+ */
+public class CheckForHotGoal extends Command {
+  public CheckForHotGoal(double time) {
+    setTimeout(time);
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return isTimedOut() || Robot.shooter.goalIsHot();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/CloseClaw.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/CloseClaw.java
new file mode 100644
index 0000000..e9c154a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/CloseClaw.java
@@ -0,0 +1,30 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.InstantCommand;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * Close the claw.
+ *
+ * <p>NOTE: It doesn't wait for the claw to close since there is no sensor to
+ * detect that.
+ */
+public class CloseClaw extends InstantCommand {
+  public CloseClaw() {
+    requires(Robot.collector);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.collector.close();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/Collect.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/Collect.java
new file mode 100644
index 0000000..d9db916
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/Collect.java
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Collector;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Pivot;
+
+/**
+ * Get the robot set to collect balls.
+ */
+public class Collect extends CommandGroup {
+  /**
+   * Create a new collect command.
+   */
+  public Collect() {
+    addSequential(new SetCollectionSpeed(Collector.kForward));
+    addParallel(new CloseClaw());
+    addSequential(new SetPivotSetpoint(Pivot.kCollect));
+    addSequential(new WaitForBall());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveAndShootAutonomous.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveAndShootAutonomous.java
new file mode 100644
index 0000000..f614e8f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveAndShootAutonomous.java
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * Drive over the line and then shoot the ball. If the hot goal is not detected,
+ * it will wait briefly.
+ */
+public class DriveAndShootAutonomous extends CommandGroup {
+  /**
+   * Create a new drive and shoot autonomous.
+   */
+  public DriveAndShootAutonomous() {
+    addSequential(new CloseClaw());
+    addSequential(new WaitForPressure(), 2);
+    if (Robot.isReal()) {
+      // NOTE: Simulation doesn't currently have the concept of hot.
+      addSequential(new CheckForHotGoal(2));
+    }
+    addSequential(new SetPivotSetpoint(45));
+    addSequential(new DriveForward(8, 0.3));
+    addSequential(new Shoot());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveForward.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveForward.java
new file mode 100644
index 0000000..219233b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveForward.java
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * This command drives the robot over a given distance with simple proportional
+ * control This command will drive a given distance limiting to a maximum speed.
+ */
+public class DriveForward extends Command {
+  private final double m_driveForwardSpeed;
+  private final double m_distance;
+  private double m_error;
+  private static final double kTolerance = 0.1;
+  private static final double kP = -1.0 / 5.0;
+
+  public DriveForward() {
+    this(10, 0.5);
+  }
+
+  public DriveForward(double dist) {
+    this(dist, 0.5);
+  }
+
+  /**
+   * Create a new drive forward command.
+   * @param dist The distance to drive
+   * @param maxSpeed The maximum speed to drive at
+   */
+  public DriveForward(double dist, double maxSpeed) {
+    requires(Robot.drivetrain);
+    m_distance = dist;
+    m_driveForwardSpeed = maxSpeed;
+  }
+
+  @Override
+  protected void initialize() {
+    Robot.drivetrain.getRightEncoder().reset();
+    setTimeout(2);
+  }
+
+  @Override
+  protected void execute() {
+    m_error = m_distance - Robot.drivetrain.getRightEncoder().getDistance();
+    if (m_driveForwardSpeed * kP * m_error >= m_driveForwardSpeed) {
+      Robot.drivetrain.tankDrive(m_driveForwardSpeed, m_driveForwardSpeed);
+    } else {
+      Robot.drivetrain.tankDrive(m_driveForwardSpeed * kP * m_error,
+          m_driveForwardSpeed * kP * m_error);
+    }
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return Math.abs(m_error) <= kTolerance || isTimedOut();
+  }
+
+  @Override
+  protected void end() {
+    Robot.drivetrain.stop();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveWithJoystick.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveWithJoystick.java
new file mode 100644
index 0000000..883ff62
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/DriveWithJoystick.java
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * This command allows PS3 joystick to drive the robot. It is always running
+ * except when interrupted by another command.
+ */
+public class DriveWithJoystick extends Command {
+  public DriveWithJoystick() {
+    requires(Robot.drivetrain);
+  }
+
+  @Override
+  protected void execute() {
+    Robot.drivetrain.tankDrive(Robot.oi.getJoystick());
+  }
+
+  @Override
+  protected boolean isFinished() {
+    return false;
+  }
+
+  @Override
+  protected void end() {
+    Robot.drivetrain.stop();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/ExtendShooter.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/ExtendShooter.java
new file mode 100644
index 0000000..cfad93d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/ExtendShooter.java
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.TimedCommand;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * Extend the shooter and then retract it after a second.
+ */
+public class ExtendShooter extends TimedCommand {
+  public ExtendShooter() {
+    super(1);
+    requires(Robot.shooter);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.shooter.extendBoth();
+  }
+
+  // Called once after isFinished returns true
+  @Override
+  protected void end() {
+    Robot.shooter.retractBoth();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/LowGoal.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/LowGoal.java
new file mode 100644
index 0000000..08214e1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/LowGoal.java
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Collector;
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Pivot;
+
+/**
+ * Spit the ball out into the low goal assuming that the robot is in front of
+ * it.
+ */
+public class LowGoal extends CommandGroup {
+  /**
+   * Create a new low goal command.
+   */
+  public LowGoal() {
+    addSequential(new SetPivotSetpoint(Pivot.kLowGoal));
+    addSequential(new SetCollectionSpeed(Collector.kReverse));
+    addSequential(new ExtendShooter());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/OpenClaw.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/OpenClaw.java
new file mode 100644
index 0000000..f59a6f6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/OpenClaw.java
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * Opens the claw.
+ */
+public class OpenClaw extends Command {
+  public OpenClaw() {
+    requires(Robot.collector);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.collector.open();
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return Robot.collector.isOpen();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/SetCollectionSpeed.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/SetCollectionSpeed.java
new file mode 100644
index 0000000..172905d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/SetCollectionSpeed.java
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.InstantCommand;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * This command sets the collector rollers spinning at the given speed. Since
+ * there is no sensor for detecting speed, it finishes immediately. As a result,
+ * the spinners may still be adjusting their speed.
+ */
+public class SetCollectionSpeed extends InstantCommand {
+  private final double m_speed;
+
+  public SetCollectionSpeed(double speed) {
+    requires(Robot.collector);
+    this.m_speed = speed;
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.collector.setSpeed(m_speed);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/SetPivotSetpoint.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/SetPivotSetpoint.java
new file mode 100644
index 0000000..74a81a0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/SetPivotSetpoint.java
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * Moves the pivot to a given angle. This command finishes when it is within the
+ * tolerance, but leaves the PID loop running to maintain the position. Other
+ * commands using the pivot should make sure they disable PID!
+ */
+public class SetPivotSetpoint extends Command {
+  private final double m_setpoint;
+
+  public SetPivotSetpoint(double setpoint) {
+    this.m_setpoint = setpoint;
+    requires(Robot.pivot);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+    Robot.pivot.enable();
+    Robot.pivot.setSetpoint(m_setpoint);
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return Robot.pivot.onTarget();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/Shoot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/Shoot.java
new file mode 100644
index 0000000..40ccb25
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/Shoot.java
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.CommandGroup;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.subsystems.Collector;
+
+/**
+ * Shoot the ball at the current angle.
+ */
+public class Shoot extends CommandGroup {
+  /**
+   * Create a new shoot command.
+   */
+  public Shoot() {
+    addSequential(new WaitForPressure());
+    addSequential(new SetCollectionSpeed(Collector.kStop));
+    addSequential(new OpenClaw());
+    addSequential(new ExtendShooter());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/WaitForBall.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/WaitForBall.java
new file mode 100644
index 0000000..bf1d506
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/WaitForBall.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * Wait until the collector senses that it has the ball. This command does
+ * nothing and is intended to be used in command groups to wait for this
+ * condition.
+ */
+public class WaitForBall extends Command {
+  public WaitForBall() {
+    requires(Robot.collector);
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return Robot.collector.hasBall();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/WaitForPressure.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/WaitForPressure.java
new file mode 100644
index 0000000..39bac0a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/commands/WaitForPressure.java
@@ -0,0 +1,28 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * Wait until the pneumatics are fully pressurized. This command does nothing
+ * and is intended to be used in command groups to wait for this condition.
+ */
+public class WaitForPressure extends Command {
+  public WaitForPressure() {
+    requires(Robot.pneumatics);
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return Robot.pneumatics.isPressurized();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Collector.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Collector.java
new file mode 100644
index 0000000..6bff9ff
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Collector.java
@@ -0,0 +1,103 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.subsystems;
+
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.Solenoid;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.Victor;
+import edu.wpi.first.wpilibj.command.Subsystem;
+
+/**
+ * The Collector subsystem has one motor for the rollers, a limit switch for
+ * ball detection, a piston for opening and closing the claw, and a reed switch
+ * to check if the piston is open.
+ */
+public class Collector extends Subsystem {
+  // Constants for some useful speeds
+  public static final double kForward = 1;
+  public static final double kStop = 0;
+  public static final double kReverse = -1;
+
+  // Subsystem devices
+  private final SpeedController m_rollerMotor = new Victor(6);
+  private final DigitalInput m_ballDetector = new DigitalInput(10);
+  private final DigitalInput m_openDetector = new DigitalInput(6);
+  private final Solenoid m_piston = new Solenoid(1, 1);
+
+  /**
+   * Create a new collector subsystem.
+   */
+  public Collector() {
+    // Put everything to the LiveWindow for testing.
+    addChild("Roller Motor", (Victor) m_rollerMotor);
+    addChild("Ball Detector", m_ballDetector);
+    addChild("Claw Open Detector", m_openDetector);
+    addChild("Piston", m_piston);
+  }
+
+  /**
+   * Whether or not the robot has the ball.
+   *
+   * <p>NOTE: The current simulation model uses the the lower part of the claw
+   * since the limit switch wasn't exported. At some point, this will be
+   * updated.
+   *
+   * @return Whether or not the robot has the ball.
+   */
+  public boolean hasBall() {
+    return m_ballDetector.get(); // TODO: prepend ! to reflect real robot
+  }
+
+  /**
+   * Set the speed to spin the collector rollers.
+   *
+   * @param speed The speed to spin the rollers.
+   */
+  public void setSpeed(double speed) {
+    m_rollerMotor.set(-speed);
+  }
+
+  /**
+   * Stop the rollers from spinning.
+   */
+  public void stop() {
+    m_rollerMotor.set(0);
+  }
+
+  /**
+   * Wether or not the claw is open.
+   *
+   * @return Whether or not the claw is open.
+   */
+  public boolean isOpen() {
+    return m_openDetector.get(); // TODO: prepend ! to reflect real robot
+  }
+
+  /**
+   * Open the claw up (For shooting).
+   */
+  public void open() {
+    m_piston.set(true);
+  }
+
+  /**
+   * Close the claw (For collecting and driving).
+   */
+  @Override
+  public void close() {
+    m_piston.set(false);
+  }
+
+  /**
+   * No default command.
+   */
+  @Override
+  protected void initDefaultCommand() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/DriveTrain.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/DriveTrain.java
new file mode 100644
index 0000000..d27347d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/DriveTrain.java
@@ -0,0 +1,143 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.subsystems;
+
+import edu.wpi.first.wpilibj.AnalogGyro;
+import edu.wpi.first.wpilibj.CounterBase.EncodingType;
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PIDSourceType;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.SpeedControllerGroup;
+import edu.wpi.first.wpilibj.Victor;
+import edu.wpi.first.wpilibj.command.Subsystem;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+import edu.wpi.first.wpilibj.examples.pacgoat.commands.DriveWithJoystick;
+
+/**
+ * The DriveTrain subsystem controls the robot's chassis and reads in
+ * information about it's speed and position.
+ */
+public class DriveTrain extends Subsystem {
+  // Subsystem devices
+  private final SpeedController m_frontLeftCIM = new Victor(1);
+  private final SpeedController m_frontRightCIM = new Victor(2);
+  private final SpeedController m_rearLeftCIM = new Victor(3);
+  private final SpeedController m_rearRightCIM = new Victor(4);
+  private final SpeedControllerGroup m_leftCIMs = new SpeedControllerGroup(
+      m_frontLeftCIM, m_rearLeftCIM);
+  private final SpeedControllerGroup m_rightCIMs = new SpeedControllerGroup(
+      m_frontRightCIM, m_rearRightCIM);
+  private final DifferentialDrive m_drive;
+  private final Encoder m_rightEncoder = new Encoder(1, 2, true, EncodingType.k4X);
+  private final Encoder m_leftEncoder = new Encoder(3, 4, false, EncodingType.k4X);
+  private final AnalogGyro m_gyro = new AnalogGyro(0);
+
+  /**
+   * Create a new drive train subsystem.
+   */
+  public DriveTrain() {
+    // Configure drive motors
+    addChild("Front Left CIM", (Victor) m_frontLeftCIM);
+    addChild("Front Right CIM", (Victor) m_frontRightCIM);
+    addChild("Back Left CIM", (Victor) m_rearLeftCIM);
+    addChild("Back Right CIM", (Victor) m_rearRightCIM);
+
+    // Configure the DifferentialDrive to reflect the fact that all motors
+    // are wired backwards (right is inverted in DifferentialDrive).
+    m_leftCIMs.setInverted(true);
+    m_drive = new DifferentialDrive(m_leftCIMs, m_rightCIMs);
+    m_drive.setSafetyEnabled(true);
+    m_drive.setExpiration(0.1);
+    m_drive.setMaxOutput(1.0);
+
+    // Configure encoders
+    m_rightEncoder.setPIDSourceType(PIDSourceType.kDisplacement);
+    m_leftEncoder.setPIDSourceType(PIDSourceType.kDisplacement);
+
+    if (Robot.isReal()) { // Converts to feet
+      m_rightEncoder.setDistancePerPulse(0.0785398);
+      m_leftEncoder.setDistancePerPulse(0.0785398);
+    } else {
+      // Convert to feet 4in diameter wheels with 360 tick sim encoders
+      m_rightEncoder.setDistancePerPulse(
+          (4.0/* in */ * Math.PI) / (360.0 * 12.0/* in/ft */));
+      m_leftEncoder.setDistancePerPulse(
+          (4.0/* in */ * Math.PI) / (360.0 * 12.0/* in/ft */));
+    }
+
+    addChild("Right Encoder", m_rightEncoder);
+    addChild("Left Encoder", m_leftEncoder);
+
+    // Configure gyro
+    if (Robot.isReal()) {
+      m_gyro.setSensitivity(0.007); // TODO: Handle more gracefully?
+    }
+    addChild("Gyro", m_gyro);
+  }
+
+  /**
+   * When other commands aren't using the drivetrain, allow tank drive with
+   * the joystick.
+   */
+  @Override
+  public void initDefaultCommand() {
+    setDefaultCommand(new DriveWithJoystick());
+  }
+
+  /**
+   * Tank drive using a PS3 joystick.
+   *
+   * @param joy PS3 style joystick to use as the input for tank drive.
+   */
+  public void tankDrive(Joystick joy) {
+    m_drive.tankDrive(joy.getY(), joy.getRawAxis(4));
+  }
+
+  /**
+   * Tank drive using individual joystick axes.
+   *
+   * @param leftAxis Left sides value
+   * @param rightAxis Right sides value
+   */
+  public void tankDrive(double leftAxis, double rightAxis) {
+    m_drive.tankDrive(leftAxis, rightAxis);
+  }
+
+  /**
+   * Stop the drivetrain from moving.
+   */
+  public void stop() {
+    m_drive.tankDrive(0, 0);
+  }
+
+  /**
+   * The encoder getting the distance and speed of left side of the
+   * drivetrain.
+   */
+  public Encoder getLeftEncoder() {
+    return m_leftEncoder;
+  }
+
+  /**
+   * The encoder getting the distance and speed of right side of the
+   * drivetrain.
+   */
+  public Encoder getRightEncoder() {
+    return m_rightEncoder;
+  }
+
+  /**
+   * The current angle of the drivetrain as measured by the Gyro.
+   */
+  public double getAngle() {
+    return m_gyro.getAngle();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pivot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pivot.java
new file mode 100644
index 0000000..44e197c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pivot.java
@@ -0,0 +1,107 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.subsystems;
+
+import edu.wpi.first.wpilibj.AnalogPotentiometer;
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.Victor;
+import edu.wpi.first.wpilibj.command.PIDSubsystem;
+import edu.wpi.first.wpilibj.interfaces.Potentiometer;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * The Pivot subsystem contains the Van-door motor and the pot for PID control
+ * of angle of the pivot and claw.
+ */
+public class Pivot extends PIDSubsystem {
+  // Constants for some useful angles
+  public static final double kCollect = 105;
+  public static final double kLowGoal = 90;
+  public static final double kShoot = 45;
+  public static final double kShootNear = 30;
+
+  // Sensors for measuring the position of the pivot.
+  private final DigitalInput m_upperLimitSwitch = new DigitalInput(13);
+  private final DigitalInput m_lowerLimitSwitch = new DigitalInput(12);
+
+  // 0 degrees is vertical facing up.
+  // Angle increases the more forward the pivot goes.
+  private final Potentiometer m_pot = new AnalogPotentiometer(1);
+
+  // Motor to move the pivot.
+  private final SpeedController m_motor = new Victor(5);
+
+  /**
+   * Create a new pivot subsystem.
+   */
+  public Pivot() {
+    super("Pivot", 7.0, 0.0, 8.0);
+    setAbsoluteTolerance(0.005);
+    getPIDController().setContinuous(false);
+    if (Robot.isSimulation()) { // PID is different in simulation.
+      getPIDController().setPID(0.5, 0.001, 2);
+      setAbsoluteTolerance(5);
+    }
+
+    // Put everything to the LiveWindow for testing.
+    addChild("Upper Limit Switch", m_upperLimitSwitch);
+    addChild("Lower Limit Switch", m_lowerLimitSwitch);
+    addChild("Pot", (AnalogPotentiometer) m_pot);
+    addChild("Motor", (Victor) m_motor);
+    addChild("PIDSubsystem Controller", getPIDController());
+  }
+
+  /**
+   * No default command, if PID is enabled, the current setpoint will be
+   * maintained.
+   */
+  @Override
+  public void initDefaultCommand() {
+  }
+
+  /**
+   * The angle read in by the potentiometer.
+   */
+  @Override
+  protected double returnPIDInput() {
+    return m_pot.get();
+  }
+
+  /**
+   * Set the motor speed based off of the PID output.
+   */
+  @Override
+  protected void usePIDOutput(double output) {
+    m_motor.pidWrite(output);
+  }
+
+  /**
+   * If the pivot is at its upper limit.
+   */
+  public boolean isAtUpperLimit() {
+    // TODO: inverted from real robot (prefix with !)
+    return m_upperLimitSwitch.get();
+  }
+
+  /**
+   * If the pivot is at its lower limit.
+   */
+  public boolean isAtLowerLimit() {
+    // TODO: inverted from real robot (prefix with !)
+    return m_lowerLimitSwitch.get();
+  }
+
+  /**
+   * The current angle of the pivot.
+   */
+  public double getAngle() {
+    return m_pot.get();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pneumatics.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pneumatics.java
new file mode 100644
index 0000000..88dc838
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Pneumatics.java
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.subsystems;
+
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.command.Subsystem;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+import edu.wpi.first.wpilibj.examples.pacgoat.Robot;
+
+/**
+ * The Pneumatics subsystem contains a pressure sensor.
+ *
+ * <p>NOTE: The simulator currently doesn't support the compressor or pressure
+ * sensors.
+ */
+public class Pneumatics extends Subsystem {
+  AnalogInput m_pressureSensor = new AnalogInput(3);
+
+  private static final double kMaxPressure = 2.55;
+
+  public Pneumatics() {
+    addChild("Pressure Sensor", m_pressureSensor);
+  }
+
+  /**
+   * No default command.
+   */
+  @Override
+  public void initDefaultCommand() {
+  }
+
+  /**
+   * Whether or not the system is fully pressurized.
+   */
+  public boolean isPressurized() {
+    if (Robot.isReal()) {
+      return kMaxPressure <= m_pressureSensor.getVoltage();
+    } else {
+      return true; // NOTE: Simulation always has full pressure
+    }
+  }
+
+  /**
+   * Puts the pressure on the SmartDashboard.
+   */
+  public void writePressure() {
+    SmartDashboard.putNumber("Pressure", m_pressureSensor.getVoltage());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Shooter.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Shooter.java
new file mode 100644
index 0000000..5c70e71
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/subsystems/Shooter.java
@@ -0,0 +1,177 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.subsystems;
+
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.DoubleSolenoid;
+import edu.wpi.first.wpilibj.Solenoid;
+import edu.wpi.first.wpilibj.command.Subsystem;
+
+/**
+ * The Shooter subsystem handles shooting. The mechanism for shooting is
+ * slightly complicated because it has to pneumatic cylinders for shooting, and
+ * a third latch to allow the pressure to partially build up and reduce the
+ * effect of the airflow. For shorter shots, when full power isn't needed, only
+ * one cylinder fires.
+ *
+ * <p>NOTE: Simulation currently approximates this as as single pneumatic
+ * cylinder and ignores the latch.
+ */
+@SuppressWarnings("PMD.TooManyMethods")
+public class Shooter extends Subsystem {
+  // Devices
+  DoubleSolenoid m_piston1 = new DoubleSolenoid(1, 3, 4);
+  DoubleSolenoid m_piston2 = new DoubleSolenoid(1, 5, 6);
+  Solenoid m_latchPiston = new Solenoid(1, 2);
+  DigitalInput m_piston1ReedSwitchFront = new DigitalInput(9);
+  DigitalInput m_piston1ReedSwitchBack = new DigitalInput(11);
+  //NOTE: currently ignored in simulation
+  DigitalInput m_hotGoalSensor = new DigitalInput(7);
+
+  /**
+   * Create a new shooter subsystem.
+   */
+  public Shooter() {
+    // Put everything to the LiveWindow for testing.
+    addChild("Hot Goal Sensor", m_hotGoalSensor);
+    addChild("Piston1 Reed Switch Front ", m_piston1ReedSwitchFront);
+    addChild("Piston1 Reed Switch Back ", m_piston1ReedSwitchBack);
+    addChild("Latch Piston", m_latchPiston);
+  }
+
+  /**
+   * No default command.
+   */
+  @Override
+  public void initDefaultCommand() {
+  }
+
+  /**
+   * Extend both solenoids to shoot.
+   */
+  public void extendBoth() {
+    m_piston1.set(DoubleSolenoid.Value.kForward);
+    m_piston2.set(DoubleSolenoid.Value.kForward);
+  }
+
+  /**
+   * Retract both solenoids to prepare to shoot.
+   */
+  public void retractBoth() {
+    m_piston1.set(DoubleSolenoid.Value.kReverse);
+    m_piston2.set(DoubleSolenoid.Value.kReverse);
+  }
+
+  /**
+   * Extend solenoid 1 to shoot.
+   */
+  public void extend1() {
+    m_piston1.set(DoubleSolenoid.Value.kForward);
+  }
+
+  /**
+   * Retract solenoid 1 to prepare to shoot.
+   */
+  public void retract1() {
+    m_piston1.set(DoubleSolenoid.Value.kReverse);
+  }
+
+  /**
+   * Extend solenoid 2 to shoot.
+   */
+  public void extend2() {
+    m_piston2.set(DoubleSolenoid.Value.kReverse);
+  }
+
+  /**
+   * Retract solenoid 2 to prepare to shoot.
+   */
+  public void retract2() {
+    m_piston2.set(DoubleSolenoid.Value.kForward);
+  }
+
+  /**
+   * Turns off the piston1 double solenoid. This won't actuate anything
+   * because double solenoids preserve their state when turned off. This
+   * should be called in order to reduce the amount of time that the coils
+   * are powered.
+   */
+  public void off1() {
+    m_piston1.set(DoubleSolenoid.Value.kOff);
+  }
+
+  /**
+   * Turns off the piston2 double solenoid. This won't actuate anything
+   * because double solenoids preserve their state when turned off. This
+   * should be called in order to reduce the amount of time that the coils
+   * are powered.
+   */
+  public void off2() {
+    m_piston2.set(DoubleSolenoid.Value.kOff);
+  }
+
+  /**
+   * Release the latch so that we can shoot.
+   */
+  public void unlatch() {
+    m_latchPiston.set(true);
+  }
+
+  /**
+   * Latch so that pressure can build up and we aren't limited by air flow.
+   */
+  public void latch() {
+    m_latchPiston.set(false);
+  }
+
+  /**
+   * Toggles the latch postions.
+   */
+  public void toggleLatchPosition() {
+    m_latchPiston.set(!m_latchPiston.get());
+  }
+
+  /**
+   * Is Piston 1 extended (after shooting).
+   *
+   * @return Whether or not piston 1 is fully extended.
+   */
+  public boolean piston1IsExtended() {
+    return !m_piston1ReedSwitchFront.get();
+  }
+
+  /**
+   * Is Piston 1 retracted (before shooting).
+   *
+   * @return Whether or not piston 1 is fully retracted.
+   */
+  public boolean piston1IsRetracted() {
+    return !m_piston1ReedSwitchBack.get();
+  }
+
+  /**
+   * Turns off all double solenoids. Double solenoids hold their position when
+   * they are turned off. We should turn them off whenever possible to extend
+   * the life of the coils.
+   */
+  public void offBoth() {
+    m_piston1.set(DoubleSolenoid.Value.kOff);
+    m_piston2.set(DoubleSolenoid.Value.kOff);
+  }
+
+  /**
+   * Return whether the goal is hot as read by the banner sensor.
+   *
+   * <p>NOTE: doesn't work in simulation.
+   *
+   * @return Whether or not the goal is hot
+   */
+  public boolean goalIsHot() {
+    return m_hotGoalSensor.get();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/triggers/DoubleButton.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/triggers/DoubleButton.java
new file mode 100644
index 0000000..e795593
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/pacgoat/triggers/DoubleButton.java
@@ -0,0 +1,38 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.pacgoat.triggers;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.buttons.Trigger;
+
+/**
+ * A custom button that is triggered when two buttons on a Joystick are
+ * simultaneously pressed.
+ */
+public class DoubleButton extends Trigger {
+  private final Joystick m_joy;
+  private final int m_button1;
+  private final int m_button2;
+
+  /**
+   * Create a new double button trigger.
+   * @param joy The joystick
+   * @param button1 The first button
+   * @param button2 The second button
+   */
+  public DoubleButton(Joystick joy, int button1, int button2) {
+    this.m_joy = joy;
+    this.m_button1 = button1;
+    this.m_button2 = button2;
+  }
+
+  @Override
+  public boolean get() {
+    return m_joy.getRawButton(m_button1) && m_joy.getRawButton(m_button2);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Main.java
new file mode 100644
index 0000000..72b9454
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.potentiometerpid;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java
new file mode 100644
index 0000000..302ce16
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/potentiometerpid/Robot.java
@@ -0,0 +1,76 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.potentiometerpid;
+
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PIDController;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.TimedRobot;
+
+/**
+ * This is a sample program to demonstrate how to use a soft potentiometer and a
+ * PID controller to reach and maintain position setpoints on an elevator
+ * mechanism.
+ */
+public class Robot extends TimedRobot {
+  private static final int kPotChannel = 1;
+  private static final int kMotorChannel = 7;
+  private static final int kJoystickChannel = 0;
+
+  // bottom, middle, and top elevator setpoints
+  private static final double[] kSetPoints = {1.0, 2.6, 4.3};
+
+  // proportional, integral, and derivative speed constants; motor inverted
+  // DANGER: when tuning PID constants, high/inappropriate values for kP, kI,
+  // and kD may cause dangerous, uncontrollable, or undesired behavior!
+  // these may need to be positive for a non-inverted motor
+  private static final double kP = -5.0;
+  private static final double kI = -0.02;
+  private static final double kD = -2.0;
+
+  private PIDController m_pidController;
+  @SuppressWarnings("PMD.SingularField")
+  private AnalogInput m_potentiometer;
+  @SuppressWarnings("PMD.SingularField")
+  private SpeedController m_elevatorMotor;
+  private Joystick m_joystick;
+
+  private int m_index;
+  private boolean m_previousButtonValue;
+
+  @Override
+  public void robotInit() {
+    m_potentiometer = new AnalogInput(kPotChannel);
+    m_elevatorMotor = new PWMVictorSPX(kMotorChannel);
+    m_joystick = new Joystick(kJoystickChannel);
+
+    m_pidController = new PIDController(kP, kI, kD, m_potentiometer, m_elevatorMotor);
+    m_pidController.setInputRange(0, 5);
+  }
+
+  @Override
+  public void teleopInit() {
+    m_pidController.enable();
+  }
+
+  @Override
+  public void teleopPeriodic() {
+    // when the button is pressed once, the selected elevator setpoint
+    // is incremented
+    boolean currentButtonValue = m_joystick.getTrigger();
+    if (currentButtonValue && !m_previousButtonValue) {
+      // index of the elevator setpoint wraps around.
+      m_index = (m_index + 1) % kSetPoints.length;
+    }
+    m_previousButtonValue = currentButtonValue;
+
+    m_pidController.setSetpoint(kSetPoints[m_index]);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Main.java
new file mode 100644
index 0000000..be7edc6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.quickvision;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java
new file mode 100644
index 0000000..9816f13
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/quickvision/Robot.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.quickvision;
+
+import edu.wpi.first.cameraserver.CameraServer;
+import edu.wpi.first.wpilibj.TimedRobot;
+
+/**
+ * Uses the CameraServer class to automatically capture video from a USB webcam
+ * and send it to the FRC dashboard without doing any vision processing. This
+ * is the easiest way to get camera images to the dashboard. Just add this to
+ * the robotInit() method in your program.
+ */
+public class Robot extends TimedRobot {
+  @Override
+  public void robotInit() {
+    CameraServer.getInstance().startAutomaticCapture();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Main.java
new file mode 100644
index 0000000..d2283df
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.shuffleboard;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java
new file mode 100644
index 0000000..7f59e14
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/shuffleboard/Robot.java
@@ -0,0 +1,63 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.shuffleboard;
+
+import edu.wpi.first.networktables.NetworkTableEntry;
+import edu.wpi.first.wpilibj.AnalogPotentiometer;
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
+import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardLayout;
+import edu.wpi.first.wpilibj.shuffleboard.ShuffleboardTab;
+
+public class Robot extends TimedRobot {
+  private final DifferentialDrive m_tankDrive = new DifferentialDrive(new PWMVictorSPX(0),
+                                                                      new PWMVictorSPX(1));
+  private final Encoder m_leftEncoder = new Encoder(0, 1);
+  private final Encoder m_rightEncoder = new Encoder(2, 3);
+
+  private final PWMVictorSPX m_elevatorMotor = new PWMVictorSPX(2);
+  private final AnalogPotentiometer m_elevatorPot = new AnalogPotentiometer(0);
+  private NetworkTableEntry m_maxSpeed;
+
+  @Override
+  public void robotInit() {
+    // Add a 'max speed' widget to a tab named 'Configuration', using a number slider
+    // The widget will be placed in the second column and row and will be two columns wide
+    m_maxSpeed = Shuffleboard.getTab("Configuration")
+                           .add("Max Speed", 1)
+                           .withWidget("Number Slider")
+                           .withPosition(1, 1)
+                           .withSize(2, 1)
+                           .getEntry();
+
+    // Add the tank drive and encoders to a 'Drivebase' tab
+    ShuffleboardTab driveBaseTab = Shuffleboard.getTab("Drivebase");
+    driveBaseTab.add("Tank Drive", m_tankDrive);
+    // Put both encoders in a list layout
+    ShuffleboardLayout encoders = driveBaseTab.getLayout("List Layout", "Encoders")
+                                              .withPosition(0, 0)
+                                              .withSize(2, 2);
+    encoders.add("Left Encoder", m_leftEncoder);
+    encoders.add("Right Encoder", m_rightEncoder);
+
+    // Add the elevator motor and potentiometer to an 'Elevator' tab
+    ShuffleboardTab elevatorTab = Shuffleboard.getTab("Elevator");
+    elevatorTab.add("Motor", m_elevatorMotor);
+    elevatorTab.add("Potentiometer", m_elevatorPot);
+  }
+
+  @Override
+  public void autonomousInit() {
+    // Read the value of the 'max speed' widget from the dashboard
+    m_tankDrive.setMaxOutput(m_maxSpeed.getDouble(1.0));
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Main.java
new file mode 100644
index 0000000..e1dc017
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.tankdrive;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java
new file mode 100755
index 0000000..b8a9202
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/tankdrive/Robot.java
@@ -0,0 +1,35 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.tankdrive;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+
+/**
+ * This is a demo program showing the use of the RobotDrive class, specifically
+ * it contains the code necessary to operate a robot with tank drive.
+ */
+public class Robot extends TimedRobot {
+  private DifferentialDrive m_myRobot;
+  private Joystick m_leftStick;
+  private Joystick m_rightStick;
+
+  @Override
+  public void robotInit() {
+    m_myRobot = new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1));
+    m_leftStick = new Joystick(0);
+    m_rightStick = new Joystick(1);
+  }
+
+  @Override
+  public void teleopPeriodic() {
+    m_myRobot.tankDrive(m_leftStick.getY(), m_rightStick.getY());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Main.java
new file mode 100644
index 0000000..edf56f8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.ultrasonic;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java
new file mode 100644
index 0000000..e03c66c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonic/Robot.java
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.ultrasonic;
+
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+
+/**
+ * This is a sample program demonstrating how to use an ultrasonic sensor and
+ * proportional control to maintain a set distance from an object.
+ */
+
+public class Robot extends TimedRobot {
+  // distance in inches the robot wants to stay from an object
+  private static final double kHoldDistance = 12.0;
+
+  // factor to convert sensor values to a distance in inches
+  private static final double kValueToInches = 0.125;
+
+  // proportional speed constant
+  private static final double kP = 0.05;
+
+  private static final int kLeftMotorPort = 0;
+  private static final int kRightMotorPort = 1;
+  private static final int kUltrasonicPort = 0;
+
+  private final AnalogInput m_ultrasonic = new AnalogInput(kUltrasonicPort);
+  private final DifferentialDrive m_robotDrive
+      = new DifferentialDrive(new PWMVictorSPX(kLeftMotorPort),
+      new PWMVictorSPX(kRightMotorPort));
+
+  /**
+   * Tells the robot to drive to a set distance (in inches) from an object
+   * using proportional control.
+   */
+  @Override
+  public void teleopPeriodic() {
+    // sensor returns a value from 0-4095 that is scaled to inches
+    double currentDistance = m_ultrasonic.getValue() * kValueToInches;
+
+    // convert distance error to a motor speed
+    double currentSpeed = (kHoldDistance - currentDistance) * kP;
+
+    // drive robot
+    m_robotDrive.arcadeDrive(currentSpeed, 0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Main.java
new file mode 100644
index 0000000..b8bffc7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.ultrasonicpid;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java
new file mode 100644
index 0000000..cc80432
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ultrasonicpid/Robot.java
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.examples.ultrasonicpid;
+
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.PIDController;
+import edu.wpi.first.wpilibj.PIDOutput;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+
+/**
+ * This is a sample program to demonstrate the use of a PIDController with an
+ * ultrasonic sensor to reach and maintain a set distance from an object.
+ */
+public class Robot extends TimedRobot {
+  // distance in inches the robot wants to stay from an object
+  private static final double kHoldDistance = 12.0;
+
+  // maximum distance in inches we expect the robot to see
+  private static final double kMaxDistance = 24.0;
+
+  // factor to convert sensor values to a distance in inches
+  private static final double kValueToInches = 0.125;
+
+  // proportional speed constant
+  private static final double kP = 7.0;
+
+  // integral speed constant
+  private static final double kI = 0.018;
+
+  // derivative speed constant
+  private static final double kD = 1.5;
+
+  private static final int kLeftMotorPort = 0;
+  private static final int kRightMotorPort = 1;
+  private static final int kUltrasonicPort = 0;
+
+  private final AnalogInput m_ultrasonic = new AnalogInput(kUltrasonicPort);
+  private final DifferentialDrive m_robotDrive
+      = new DifferentialDrive(new PWMVictorSPX(kLeftMotorPort),
+      new PWMVictorSPX(kRightMotorPort));
+  private final PIDController m_pidController
+      = new PIDController(kP, kI, kD, m_ultrasonic, new MyPidOutput());
+
+  /**
+   * Drives the robot a set distance from an object using PID control and the
+   * ultrasonic sensor.
+   */
+  @Override
+  public void teleopInit() {
+    // Set expected range to 0-24 inches; e.g. at 24 inches from object go
+    // full forward, at 0 inches from object go full backward.
+    m_pidController.setInputRange(0, kMaxDistance * kValueToInches);
+    // Set setpoint of the pid controller
+    m_pidController.setSetpoint(kHoldDistance * kValueToInches);
+    m_pidController.enable(); // begin PID control
+  }
+
+  private class MyPidOutput implements PIDOutput {
+    @Override
+    public void pidWrite(double output) {
+      m_robotDrive.arcadeDrive(output, 0);
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Main.java
new file mode 100644
index 0000000..84ddea4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.commandbased;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/OI.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/OI.java
new file mode 100644
index 0000000..990eb2a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/OI.java
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.commandbased;
+
+/**
+ * This class is the glue that binds the controls on the physical operator
+ * interface to the commands and command groups that allow control of the robot.
+ */
+public class OI {
+  //// CREATING BUTTONS
+  // One type of button is a joystick button which is any button on a
+  //// joystick.
+  // You create one by telling it which joystick it's on and which button
+  // number it is.
+  // Joystick stick = new Joystick(port);
+  // Button button = new JoystickButton(stick, buttonNumber);
+
+  // There are a few additional built in buttons you can use. Additionally,
+  // by subclassing Button you can create custom triggers and bind those to
+  // commands the same as any other Button.
+
+  //// TRIGGERING COMMANDS WITH BUTTONS
+  // Once you have a button, it's trivial to bind it to a button in one of
+  // three ways:
+
+  // Start the command when the button is pressed and let it run the command
+  // until it is finished as determined by it's isFinished method.
+  // button.whenPressed(new ExampleCommand());
+
+  // Run the command while the button is being held down and interrupt it once
+  // the button is released.
+  // button.whileHeld(new ExampleCommand());
+
+  // Start the command when the button is released and let it run the command
+  // until it is finished as determined by it's isFinished method.
+  // button.whenReleased(new ExampleCommand());
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java
new file mode 100644
index 0000000..7727bff
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/Robot.java
@@ -0,0 +1,131 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.commandbased;
+
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.command.Command;
+import edu.wpi.first.wpilibj.command.Scheduler;
+import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+import edu.wpi.first.wpilibj.templates.commandbased.commands.ExampleCommand;
+import edu.wpi.first.wpilibj.templates.commandbased.subsystems.ExampleSubsystem;
+
+/**
+ * The VM is configured to automatically run this class, and to call the
+ * functions corresponding to each mode, as described in the TimedRobot
+ * documentation. If you change the name of this class or the package after
+ * creating this project, you must also update the build.gradle file in the
+ * project.
+ */
+public class Robot extends TimedRobot {
+  public static ExampleSubsystem m_subsystem = new ExampleSubsystem();
+  public static OI m_oi;
+
+  Command m_autonomousCommand;
+  SendableChooser<Command> m_chooser = new SendableChooser<>();
+
+  /**
+   * This function is run when the robot is first started up and should be
+   * used for any initialization code.
+   */
+  @Override
+  public void robotInit() {
+    m_oi = new OI();
+    m_chooser.setDefaultOption("Default Auto", new ExampleCommand());
+    // chooser.addOption("My Auto", new MyAutoCommand());
+    SmartDashboard.putData("Auto mode", m_chooser);
+  }
+
+  /**
+   * This function is called every robot packet, no matter the mode. Use
+   * this for items like diagnostics that you want ran during disabled,
+   * autonomous, teleoperated and test.
+   *
+   * <p>This runs after the mode specific periodic functions, but before
+   * LiveWindow and SmartDashboard integrated updating.
+   */
+  @Override
+  public void robotPeriodic() {
+  }
+
+  /**
+   * This function is called once each time the robot enters Disabled mode.
+   * You can use it to reset any subsystem information you want to clear when
+   * the robot is disabled.
+   */
+  @Override
+  public void disabledInit() {
+  }
+
+  @Override
+  public void disabledPeriodic() {
+    Scheduler.getInstance().run();
+  }
+
+  /**
+   * This autonomous (along with the chooser code above) shows how to select
+   * between different autonomous modes using the dashboard. The sendable
+   * chooser code works with the Java SmartDashboard. If you prefer the
+   * LabVIEW Dashboard, remove all of the chooser code and uncomment the
+   * getString code to get the auto name from the text box below the Gyro
+   *
+   * <p>You can add additional auto modes by adding additional commands to the
+   * chooser code above (like the commented example) or additional comparisons
+   * to the switch structure below with additional strings & commands.
+   */
+  @Override
+  public void autonomousInit() {
+    m_autonomousCommand = m_chooser.getSelected();
+
+    /*
+     * String autoSelected = SmartDashboard.getString("Auto Selector",
+     * "Default"); switch(autoSelected) { case "My Auto": autonomousCommand
+     * = new MyAutoCommand(); break; case "Default Auto": default:
+     * autonomousCommand = new ExampleCommand(); break; }
+     */
+
+    // schedule the autonomous command (example)
+    if (m_autonomousCommand != null) {
+      m_autonomousCommand.start();
+    }
+  }
+
+  /**
+   * This function is called periodically during autonomous.
+   */
+  @Override
+  public void autonomousPeriodic() {
+    Scheduler.getInstance().run();
+  }
+
+  @Override
+  public void teleopInit() {
+    // This makes sure that the autonomous stops running when
+    // teleop starts running. If you want the autonomous to
+    // continue until interrupted by another command, remove
+    // this line or comment it out.
+    if (m_autonomousCommand != null) {
+      m_autonomousCommand.cancel();
+    }
+  }
+
+  /**
+   * This function is called periodically during operator control.
+   */
+  @Override
+  public void teleopPeriodic() {
+    Scheduler.getInstance().run();
+  }
+
+  /**
+   * This function is called periodically during test mode.
+   */
+  @Override
+  public void testPeriodic() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/RobotMap.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/RobotMap.java
new file mode 100644
index 0000000..ef213c4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/RobotMap.java
@@ -0,0 +1,26 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.commandbased;
+
+/**
+ * The RobotMap is a mapping from the ports sensors and actuators are wired into
+ * to a variable name. This provides flexibility changing wiring, makes checking
+ * the wiring easier and significantly reduces the number of magic numbers
+ * floating around.
+ */
+public class RobotMap {
+  // For example to map the left and right motors, you could define the
+  // following variables to use with your drivetrain subsystem.
+  // public static int leftMotor = 1;
+  // public static int rightMotor = 2;
+
+  // If you are using multiple modules, make sure to define both the port
+  // number and the module. For example you with a rangefinder:
+  // public static int rangefinderPort = 1;
+  // public static int rangefinderModule = 1;
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java
new file mode 100644
index 0000000..10ceb6e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.commandbased.commands;
+
+import edu.wpi.first.wpilibj.command.Command;
+import edu.wpi.first.wpilibj.templates.commandbased.Robot;
+
+/**
+ * An example command.  You can replace me with your own command.
+ */
+public class ExampleCommand extends Command {
+  public ExampleCommand() {
+    // Use requires() here to declare subsystem dependencies
+    requires(Robot.m_subsystem);
+  }
+
+  // Called just before this Command runs the first time
+  @Override
+  protected void initialize() {
+  }
+
+  // Called repeatedly when this Command is scheduled to run
+  @Override
+  protected void execute() {
+  }
+
+  // Make this return true when this Command no longer needs to run execute()
+  @Override
+  protected boolean isFinished() {
+    return false;
+  }
+
+  // Called once after isFinished returns true
+  @Override
+  protected void end() {
+  }
+
+  // Called when another command which requires one or more of the same
+  // subsystems is scheduled to run
+  @Override
+  protected void interrupted() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java
new file mode 100644
index 0000000..a03b73f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.commandbased.subsystems;
+
+import edu.wpi.first.wpilibj.command.Subsystem;
+
+/**
+ * An example subsystem.  You can replace me with your own Subsystem.
+ */
+public class ExampleSubsystem extends Subsystem {
+  // Put methods for controlling this subsystem
+  // here. Call these from Commands.
+
+  @Override
+  public void initDefaultCommand() {
+    // Set the default command for a subsystem here.
+    // setDefaultCommand(new MySpecialCommand());
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/iterative/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/iterative/Main.java
new file mode 100644
index 0000000..d7f6e26
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/iterative/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.iterative;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/iterative/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/iterative/Robot.java
new file mode 100644
index 0000000..7f38b8a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/iterative/Robot.java
@@ -0,0 +1,98 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.iterative;
+
+import edu.wpi.first.wpilibj.IterativeRobot;
+import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+/**
+ * The VM is configured to automatically run this class, and to call the
+ * functions corresponding to each mode, as described in the IterativeRobot
+ * documentation. If you change the name of this class or the package after
+ * creating this project, you must also update the build.gradle file in the
+ * project.
+ */
+public class Robot extends IterativeRobot {
+  private static final String kDefaultAuto = "Default";
+  private static final String kCustomAuto = "My Auto";
+  private String m_autoSelected;
+  private final SendableChooser<String> m_chooser = new SendableChooser<>();
+
+  /**
+   * This function is run when the robot is first started up and should be
+   * used for any initialization code.
+   */
+  @Override
+  public void robotInit() {
+    m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
+    m_chooser.addOption("My Auto", kCustomAuto);
+    SmartDashboard.putData("Auto choices", m_chooser);
+  }
+
+  /**
+   * This function is called every robot packet, no matter the mode. Use
+   * this for items like diagnostics that you want ran during disabled,
+   * autonomous, teleoperated and test.
+   *
+   * <p>This runs after the mode specific periodic functions, but before
+   * LiveWindow and SmartDashboard integrated updating.
+   */
+  @Override
+  public void robotPeriodic() {
+  }
+
+  /**
+   * This autonomous (along with the chooser code above) shows how to select
+   * between different autonomous modes using the dashboard. The sendable
+   * chooser code works with the Java SmartDashboard. If you prefer the
+   * LabVIEW Dashboard, remove all of the chooser code and uncomment the
+   * getString line to get the auto name from the text box below the Gyro
+   *
+   * <p>You can add additional auto modes by adding additional comparisons to
+   * the switch structure below with additional strings. If using the
+   * SendableChooser make sure to add them to the chooser code above as well.
+   */
+  @Override
+  public void autonomousInit() {
+    m_autoSelected = m_chooser.getSelected();
+    // autoSelected = SmartDashboard.getString("Auto Selector",
+    // defaultAuto);
+    System.out.println("Auto selected: " + m_autoSelected);
+  }
+
+  /**
+   * This function is called periodically during autonomous.
+   */
+  @Override
+  public void autonomousPeriodic() {
+    switch (m_autoSelected) {
+      case kCustomAuto:
+        // Put custom auto code here
+        break;
+      case kDefaultAuto:
+      default:
+        // Put default auto code here
+        break;
+    }
+  }
+
+  /**
+   * This function is called periodically during operator control.
+   */
+  @Override
+  public void teleopPeriodic() {
+  }
+
+  /**
+   * This function is called periodically during test mode.
+   */
+  @Override
+  public void testPeriodic() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Main.java
new file mode 100644
index 0000000..787aff0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.sample;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Robot.java
new file mode 100644
index 0000000..9a670f0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/sample/Robot.java
@@ -0,0 +1,155 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.sample;
+
+import edu.wpi.first.wpilibj.Joystick;
+import edu.wpi.first.wpilibj.PWMVictorSPX;
+import edu.wpi.first.wpilibj.SampleRobot;
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+/**
+ * This is a demo program showing the use of the RobotDrive class. The
+ * SampleRobot class is the base of a robot application that will automatically
+ * call your Autonomous and OperatorControl methods at the right time as
+ * controlled by the switches on the driver station or the field controls.
+ *
+ * <p>The VM is configured to automatically run this class, and to call the
+ * functions corresponding to each mode, as described in the SampleRobot
+ * documentation. If you change the name of this class or the package after
+ * creating this project, you must also update the build.properties file in the
+ * project.
+ *
+ * <p>WARNING: While it may look like a good choice to use for your code if
+ * you're inexperienced, don't. Unless you know what you are doing, complex code
+ * will be much more difficult under this system. Use TimedRobot or
+ * Command-Based instead if you're new.
+ */
+public class Robot extends SampleRobot {
+  private static final String kDefaultAuto = "Default";
+  private static final String kCustomAuto = "My Auto";
+
+  private final DifferentialDrive m_robotDrive
+      = new DifferentialDrive(new PWMVictorSPX(0), new PWMVictorSPX(1));
+  private final Joystick m_stick = new Joystick(0);
+  private final SendableChooser<String> m_chooser = new SendableChooser<>();
+
+  public Robot() {
+    m_robotDrive.setExpiration(0.1);
+  }
+
+  @Override
+  public void robotInit() {
+    m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
+    m_chooser.addOption("My Auto", kCustomAuto);
+    SmartDashboard.putData("Auto modes", m_chooser);
+  }
+
+  /**
+   * This autonomous (along with the chooser code above) shows how to select
+   * between different autonomous modes using the dashboard. The sendable
+   * chooser code works with the Java SmartDashboard. If you prefer the
+   * LabVIEW Dashboard, remove all of the chooser code and uncomment the
+   * getString line to get the auto name from the text box below the Gyro
+   *
+   * <p>You can add additional auto modes by adding additional comparisons to
+   * the if-else structure below with additional strings. If using the
+   * SendableChooser make sure to add them to the chooser code above as well.
+   *
+   * <p>If you wanted to run a similar autonomous mode with an TimedRobot
+   * you would write:
+   *
+   * <blockquote><pre>{@code
+   * Timer timer = new Timer();
+   *
+   * // This function is run once each time the robot enters autonomous mode
+   * public void autonomousInit() {
+   *     timer.reset();
+   *     timer.start();
+   * }
+   *
+   * // This function is called periodically during autonomous
+   * public void autonomousPeriodic() {
+   * // Drive for 2 seconds
+   *     if (timer.get() < 2.0) {
+   *         myRobot.drive(-0.5, 0.0); // drive forwards half speed
+   *     } else if (timer.get() < 5.0) {
+   *         myRobot.drive(-1.0, 0.0); // drive forwards full speed
+   *     } else {
+   *         myRobot.drive(0.0, 0.0); // stop robot
+   *     }
+   * }
+   * }</pre></blockquote>
+   */
+  @Override
+  public void autonomous() {
+    String autoSelected = m_chooser.getSelected();
+    // String autoSelected = SmartDashboard.getString("Auto Selector",
+    // defaultAuto);
+    System.out.println("Auto selected: " + autoSelected);
+
+    // MotorSafety improves safety when motors are updated in loops
+    // but is disabled here because motor updates are not looped in
+    // this autonomous mode.
+    m_robotDrive.setSafetyEnabled(false);
+
+    switch (autoSelected) {
+      case kCustomAuto:
+        // Spin at half speed for two seconds
+        m_robotDrive.arcadeDrive(0.0, 0.5);
+        Timer.delay(2.0);
+
+        // Stop robot
+        m_robotDrive.arcadeDrive(0.0, 0.0);
+        break;
+      case kDefaultAuto:
+      default:
+        // Drive forwards for two seconds
+        m_robotDrive.arcadeDrive(-0.5, 0.0);
+        Timer.delay(2.0);
+
+        // Stop robot
+        m_robotDrive.arcadeDrive(0.0, 0.0);
+        break;
+    }
+  }
+
+  /**
+   * Runs the motors with arcade steering.
+   *
+   * <p>If you wanted to run a similar teleoperated mode with an TimedRobot
+   * you would write:
+   *
+   * <blockquote><pre>{@code
+   * // This function is called periodically during operator control
+   * public void teleopPeriodic() {
+   *     myRobot.arcadeDrive(stick);
+   * }
+   * }</pre></blockquote>
+   */
+  @Override
+  public void operatorControl() {
+    m_robotDrive.setSafetyEnabled(true);
+    while (isOperatorControl() && isEnabled()) {
+      // Drive arcade style
+      m_robotDrive.arcadeDrive(-m_stick.getY(), m_stick.getX());
+
+      // The motors will be updated every 5ms
+      Timer.delay(0.005);
+    }
+  }
+
+  /**
+   * Runs during test mode.
+   */
+  @Override
+  public void test() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json
new file mode 100644
index 0000000..430da80
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/templates.json
@@ -0,0 +1,52 @@
+[
+  {
+    "name": "Iterative Robot",
+    "description": "Iterative style",
+    "tags": [
+      "Iterative"
+    ],
+    "foldername": "iterative",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Timed Robot",
+    "description": "Timed style",
+    "tags": [
+      "Timed"
+    ],
+    "foldername": "timed",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Timed Skeleton (Advanced)",
+    "description": "Skeleton (stub) code for TimedRobot",
+    "tags": [
+      "Timed", "Skeleton"
+    ],
+    "foldername": "timedskeleton",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Command Robot",
+    "description": "Command style",
+    "tags": [
+      "Command"
+    ],
+    "foldername": "commandbased",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  },
+  {
+    "name": "Sample Robot",
+    "description": "Sample style",
+    "tags": [
+      "Sample"
+    ],
+    "foldername": "sample",
+    "gradlebase": "java",
+    "mainclass": "Main"
+  }
+]
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Main.java
new file mode 100644
index 0000000..4cc64e0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.timed;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java
new file mode 100644
index 0000000..9930de7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timed/Robot.java
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.timed;
+
+import edu.wpi.first.wpilibj.TimedRobot;
+import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
+
+/**
+ * The VM is configured to automatically run this class, and to call the
+ * functions corresponding to each mode, as described in the TimedRobot
+ * documentation. If you change the name of this class or the package after
+ * creating this project, you must also update the build.gradle file in the
+ * project.
+ */
+public class Robot extends TimedRobot {
+  private static final String kDefaultAuto = "Default";
+  private static final String kCustomAuto = "My Auto";
+  private String m_autoSelected;
+  private final SendableChooser<String> m_chooser = new SendableChooser<>();
+
+  /**
+   * This function is run when the robot is first started up and should be
+   * used for any initialization code.
+   */
+  @Override
+  public void robotInit() {
+    m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
+    m_chooser.addOption("My Auto", kCustomAuto);
+    SmartDashboard.putData("Auto choices", m_chooser);
+  }
+
+  /**
+   * This function is called every robot packet, no matter the mode. Use
+   * this for items like diagnostics that you want ran during disabled,
+   * autonomous, teleoperated and test.
+   *
+   * <p>This runs after the mode specific periodic functions, but before
+   * LiveWindow and SmartDashboard integrated updating.
+   */
+  @Override
+  public void robotPeriodic() {
+  }
+
+  /**
+   * This autonomous (along with the chooser code above) shows how to select
+   * between different autonomous modes using the dashboard. The sendable
+   * chooser code works with the Java SmartDashboard. If you prefer the
+   * LabVIEW Dashboard, remove all of the chooser code and uncomment the
+   * getString line to get the auto name from the text box below the Gyro
+   *
+   * <p>You can add additional auto modes by adding additional comparisons to
+   * the switch structure below with additional strings. If using the
+   * SendableChooser make sure to add them to the chooser code above as well.
+   */
+  @Override
+  public void autonomousInit() {
+    m_autoSelected = m_chooser.getSelected();
+    // m_autoSelected = SmartDashboard.getString("Auto Selector", kDefaultAuto);
+    System.out.println("Auto selected: " + m_autoSelected);
+  }
+
+  /**
+   * This function is called periodically during autonomous.
+   */
+  @Override
+  public void autonomousPeriodic() {
+    switch (m_autoSelected) {
+      case kCustomAuto:
+        // Put custom auto code here
+        break;
+      case kDefaultAuto:
+      default:
+        // Put default auto code here
+        break;
+    }
+  }
+
+  /**
+   * This function is called periodically during operator control.
+   */
+  @Override
+  public void teleopPeriodic() {
+  }
+
+  /**
+   * This function is called periodically during test mode.
+   */
+  @Override
+  public void testPeriodic() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Main.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Main.java
new file mode 100644
index 0000000..6a895ba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Main.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.timedskeleton;
+
+import edu.wpi.first.wpilibj.RobotBase;
+
+/**
+ * Do NOT add any static variables to this class, or any initialization at all.
+ * Unless you know what you are doing, do not modify this file except to
+ * change the parameter class to the startRobot call.
+ */
+public final class Main {
+  private Main() {
+  }
+
+  /**
+   * Main initialization function. Do not perform any initialization here.
+   *
+   * <p>If you change your main robot class, change the parameter type.
+   */
+  public static void main(String... args) {
+    RobotBase.startRobot(Robot::new);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java
new file mode 100644
index 0000000..9ec7991
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/timedskeleton/Robot.java
@@ -0,0 +1,52 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.templates.timedskeleton;
+
+import edu.wpi.first.wpilibj.TimedRobot;
+
+/**
+ * The VM is configured to automatically run this class, and to call the
+ * functions corresponding to each mode, as described in the TimedRobot
+ * documentation. If you change the name of this class or the package after
+ * creating this project, you must also update the build.gradle file in the
+ * project.
+ */
+public class Robot extends TimedRobot {
+  /**
+   * This function is run when the robot is first started up and should be used
+   * for any initialization code.
+   */
+  @Override
+  public void robotInit() {
+  }
+
+  @Override
+  public void autonomousInit() {
+  }
+
+  @Override
+  public void autonomousPeriodic() {
+  }
+
+  @Override
+  public void teleopInit() {
+  }
+
+  @Override
+  public void teleopPeriodic() {
+  }
+
+  @Override
+  public void testInit() {
+  }
+
+  @Override
+  public void testPeriodic() {
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/build.gradle b/third_party/allwpilib_2019/wpilibjIntegrationTests/build.gradle
new file mode 100644
index 0000000..2fc6793
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/build.gradle
@@ -0,0 +1,49 @@
+plugins {
+    id 'java'
+    id 'application'
+}
+
+ext {
+    useJava = true
+    useCpp = false
+    skipDev = true
+}
+
+apply from: "${rootDir}/shared/opencv.gradle"
+
+mainClassName = 'edu.wpi.first.wpilibj.test.AntJunitLanucher'
+
+apply plugin: 'com.github.johnrengelman.shadow'
+
+repositories {
+    mavenCentral()
+}
+
+dependencies {
+    compile project(':wpilibj')
+    compile project(':hal')
+    compile project(':wpiutil')
+    compile project(':ntcore')
+    compile project(':cscore')
+    compile project(':cameraserver')
+    compile 'junit:junit:4.11'
+    testCompile 'org.hamcrest:hamcrest-all:1.3'
+    compile 'com.googlecode.junit-toolbox:junit-toolbox:2.0'
+    compile 'org.apache.ant:ant:1.9.4'
+    compile 'org.apache.ant:ant-junit:1.9.4'
+}
+
+build.dependsOn shadowJar
+
+def testOutputFolder = file("${project(':').buildDir}/integrationTestFiles")
+
+task copyWpilibJIntegrationTestJarToOutput(type: Copy) {
+    destinationDir testOutputFolder
+    dependsOn shadowJar
+    inputs.file shadowJar.archivePath
+    from(shadowJar) {
+        into 'java'
+    }
+}
+
+build.dependsOn copyWpilibJIntegrationTestJarToOutput
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java
new file mode 100644
index 0000000..3e40bd9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AbstractInterruptTest.java
@@ -0,0 +1,311 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.concurrent.atomic.AtomicBoolean;
+import java.util.concurrent.atomic.AtomicInteger;
+import java.util.concurrent.atomic.AtomicLong;
+
+import org.junit.After;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.hamcrest.Matchers.both;
+import static org.hamcrest.Matchers.greaterThan;
+import static org.hamcrest.Matchers.lessThan;
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertSame;
+import static org.junit.Assert.assertThat;
+
+/**
+ * This class should not be run as a test explicitly. Instead it should be extended by tests that
+ * use the InterruptableSensorBase.
+ */
+public abstract class AbstractInterruptTest extends AbstractComsSetup {
+  private InterruptableSensorBase m_interruptable = null;
+
+  private InterruptableSensorBase getInterruptable() {
+    if (m_interruptable == null) {
+      m_interruptable = giveInterruptableSensorBase();
+    }
+    return m_interruptable;
+  }
+
+
+  @After
+  public void interruptTeardown() {
+    if (m_interruptable != null) {
+      freeInterruptableSensorBase();
+      m_interruptable = null;
+    }
+  }
+
+  /**
+   * Give the interruptable sensor base that interrupts can be attached to.
+   */
+  abstract InterruptableSensorBase giveInterruptableSensorBase();
+
+  /**
+   * Cleans up the interruptable sensor base. This is only called if {@link
+   * #giveInterruptableSensorBase()} is called.
+   */
+  abstract void freeInterruptableSensorBase();
+
+  /**
+   * Perform whatever action is required to set the interrupt high.
+   */
+  abstract void setInterruptHigh();
+
+  /**
+   * Perform whatever action is required to set the interrupt low.
+   */
+  abstract void setInterruptLow();
+
+
+  private class InterruptCounter {
+    private final AtomicInteger m_count = new AtomicInteger();
+
+    void increment() {
+      m_count.addAndGet(1);
+    }
+
+    int getCount() {
+      return m_count.get();
+    }
+  }
+
+  private class TestInterruptHandlerFunction extends InterruptHandlerFunction<InterruptCounter> {
+    protected final AtomicBoolean m_exceptionThrown = new AtomicBoolean(false);
+    /**
+     * Stores the time that the interrupt fires.
+     */
+    final AtomicLong m_interruptFireTime = new AtomicLong();
+    /**
+     * Stores if the interrupt has completed at least once.
+     */
+    final AtomicBoolean m_interruptComplete = new AtomicBoolean(false);
+    protected Exception m_ex;
+    final InterruptCounter m_counter;
+
+    TestInterruptHandlerFunction(InterruptCounter counter) {
+      m_counter = counter;
+    }
+
+    @Override
+    public void interruptFired(int interruptAssertedMask, InterruptCounter param) {
+      m_interruptFireTime.set(RobotController.getFPGATime());
+      m_counter.increment();
+      try {
+        // This won't cause the test to fail
+        assertSame(m_counter, param);
+      } catch (Exception ex) {
+        // So we must throw the exception within the test
+        m_exceptionThrown.set(true);
+        m_ex = ex;
+      }
+      m_interruptComplete.set(true);
+    }
+
+    @Override
+    public InterruptCounter overridableParameter() {
+      return m_counter;
+    }
+  }
+
+  @Test(timeout = 1000)
+  public void testSingleInterruptsTriggering() throws Exception {
+    // Given
+    final InterruptCounter counter = new InterruptCounter();
+    TestInterruptHandlerFunction function = new TestInterruptHandlerFunction(counter);
+
+    // When
+    getInterruptable().requestInterrupts(function);
+    getInterruptable().enableInterrupts();
+
+    setInterruptLow();
+    Timer.delay(0.01);
+    // Note: Utility.getFPGATime() is used because double values can turn over
+    // after the robot has been running for a long time
+    final long interruptTriggerTime = RobotController.getFPGATime();
+    setInterruptHigh();
+
+    // Delay until the interrupt is complete
+    while (!function.m_interruptComplete.get()) {
+      Timer.delay(.005);
+    }
+
+
+    // Then
+    assertEquals("The interrupt did not fire the expected number of times", 1, counter.getCount());
+    // If the test within the interrupt failed
+    if (function.m_exceptionThrown.get()) {
+      throw function.m_ex;
+    }
+    final long range = 10000; // in microseconds
+    assertThat(
+        "The interrupt did not fire within the expected time period (values in milliseconds)",
+        function.m_interruptFireTime.get(),
+        both(greaterThan(interruptTriggerTime - range)).and(lessThan(interruptTriggerTime
+            + range)));
+    assertThat(
+        "The readRisingTimestamp() did not return the correct value (values in seconds)",
+        getInterruptable().readRisingTimestamp(),
+        both(greaterThan((interruptTriggerTime - range) / 1e6)).and(
+            lessThan((interruptTriggerTime + range) / 1e6)));
+  }
+
+  @Test(timeout = 2000)
+  public void testMultipleInterruptsTriggering() throws Exception {
+    // Given
+    final InterruptCounter counter = new InterruptCounter();
+    TestInterruptHandlerFunction function = new TestInterruptHandlerFunction(counter);
+
+    // When
+    getInterruptable().requestInterrupts(function);
+    getInterruptable().enableInterrupts();
+
+    final int fireCount = 50;
+    for (int i = 0; i < fireCount; i++) {
+      setInterruptLow();
+      setInterruptHigh();
+      // Wait for the interrupt to complete before moving on
+      while (!function.m_interruptComplete.getAndSet(false)) {
+        Timer.delay(.005);
+      }
+    }
+    // Then
+    assertEquals("The interrupt did not fire the expected number of times", fireCount,
+        counter.getCount());
+  }
+
+  /**
+   * The timeout length for this test in seconds.
+   */
+  private static final int synchronousTimeout = 5;
+
+  @Test(timeout = (long) (synchronousTimeout * 1e3))
+  public void testSynchronousInterruptsTriggering() {
+    // Given
+    getInterruptable().requestInterrupts();
+
+    final double synchronousDelay = synchronousTimeout / 2.;
+    final Runnable runnable = () -> {
+      Timer.delay(synchronousDelay);
+      setInterruptLow();
+      setInterruptHigh();
+    };
+
+    // When
+
+    // Note: the long time value is used because doubles can flip if the robot
+    // is left running for long enough
+    final long startTimeStamp = RobotController.getFPGATime();
+    new Thread(runnable).start();
+    // Delay for twice as long as the timeout so the test should fail first
+    getInterruptable().waitForInterrupt(synchronousTimeout * 2);
+    final long stopTimeStamp = RobotController.getFPGATime();
+
+    // Then
+    // The test will not have timed out and:
+    final double interruptRunTime = (stopTimeStamp - startTimeStamp) * 1e-6;
+    assertEquals("The interrupt did not run for the expected amount of time (units in seconds)",
+        synchronousDelay, interruptRunTime, .1);
+  }
+
+  @Test(timeout = (long) (synchronousTimeout * 1e3))
+  public void testSynchronousInterruptsWaitResultTimeout() {
+    // Given
+    getInterruptable().requestInterrupts();
+
+    //Don't fire interrupt. Expect it to timeout.
+    InterruptableSensorBase.WaitResult result = getInterruptable()
+        .waitForInterrupt(synchronousTimeout / 2);
+
+    assertEquals("The interrupt did not time out correctly.", result, InterruptableSensorBase
+        .WaitResult.kTimeout);
+  }
+
+  @Test(timeout = (long) (synchronousTimeout * 1e3))
+  public void testSynchronousInterruptsWaitResultRisingEdge() {
+    // Given
+    getInterruptable().requestInterrupts();
+
+    final double synchronousDelay = synchronousTimeout / 2.;
+    final Runnable runnable = () -> {
+      Timer.delay(synchronousDelay);
+      setInterruptLow();
+      setInterruptHigh();
+    };
+
+    new Thread(runnable).start();
+    // Delay for twice as long as the timeout so the test should fail first
+    InterruptableSensorBase.WaitResult result = getInterruptable()
+        .waitForInterrupt(synchronousTimeout * 2);
+
+    assertEquals("The interrupt did not fire on the rising edge.", result,
+        InterruptableSensorBase.WaitResult.kRisingEdge);
+  }
+
+  @Test(timeout = (long) (synchronousTimeout * 1e3))
+  public void testSynchronousInterruptsWaitResultFallingEdge() {
+    // Given
+    getInterruptable().requestInterrupts();
+    getInterruptable().setUpSourceEdge(false, true);
+
+    final double synchronousDelay = synchronousTimeout / 2.;
+    final Runnable runnable = () -> {
+      Timer.delay(synchronousDelay);
+      setInterruptHigh();
+      setInterruptLow();
+    };
+
+    new Thread(runnable).start();
+    // Delay for twice as long as the timeout so the test should fail first
+    InterruptableSensorBase.WaitResult result = getInterruptable()
+        .waitForInterrupt(synchronousTimeout * 2);
+
+    assertEquals("The interrupt did not fire on the falling edge.", result,
+        InterruptableSensorBase.WaitResult.kFallingEdge);
+  }
+
+
+  @Test(timeout = 4000)
+  public void testDisableStopsInterruptFiring() {
+    final InterruptCounter counter = new InterruptCounter();
+    TestInterruptHandlerFunction function = new TestInterruptHandlerFunction(counter);
+
+    // When
+    getInterruptable().requestInterrupts(function);
+    getInterruptable().enableInterrupts();
+
+    final int fireCount = 50;
+    for (int i = 0; i < fireCount; i++) {
+      setInterruptLow();
+      setInterruptHigh();
+      // Wait for the interrupt to complete before moving on
+      while (!function.m_interruptComplete.getAndSet(false)) {
+        Timer.delay(.005);
+      }
+    }
+    getInterruptable().disableInterrupts();
+    // TestBench.out().println("Finished disabling the robot");
+
+    for (int i = 0; i < fireCount; i++) {
+      setInterruptLow();
+      setInterruptHigh();
+      // Just wait because the interrupt should not fire
+      Timer.delay(.005);
+    }
+
+    // Then
+    assertEquals("The interrupt did not fire the expected number of times", fireCount,
+        counter.getCount());
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java
new file mode 100644
index 0000000..796e919
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogCrossConnectTest.java
@@ -0,0 +1,198 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.AnalogTriggerOutput.AnalogTriggerType;
+import edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Test that covers the {@link AnalogCrossConnectFixture}.
+ */
+public class AnalogCrossConnectTest extends AbstractInterruptTest {
+  private static final Logger logger = Logger.getLogger(AnalogCrossConnectTest.class.getName());
+
+  private static AnalogCrossConnectFixture analogIO;
+
+  static final double kDelayTime = 0.01;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+
+  @BeforeClass
+  public static void setUpBeforeClass() throws Exception {
+    analogIO = TestBench.getAnalogCrossConnectFixture();
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() throws Exception {
+    analogIO.teardown();
+    analogIO = null;
+  }
+
+  @Before
+  public void setUp() throws Exception {
+    analogIO.setup();
+  }
+
+
+  @Test
+  public void testAnalogOuput() {
+    for (int i = 0; i < 50; i++) {
+      analogIO.getOutput().setVoltage(i / 10.0);
+      Timer.delay(kDelayTime);
+      assertEquals(analogIO.getOutput().getVoltage(), analogIO.getInput().getVoltage(), 0.01);
+    }
+  }
+
+  @Test
+  public void testAnalogTriggerBelowWindow() {
+    // Given
+    AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput());
+    trigger.setLimitsVoltage(2.0, 3.0);
+
+    // When the output voltage is than less the lower limit
+    analogIO.getOutput().setVoltage(1.0);
+    Timer.delay(kDelayTime);
+
+    // Then the analog trigger is not in the window and the trigger state is off
+    assertFalse("Analog trigger is in the window (2V, 3V)", trigger.getInWindow());
+    assertFalse("Analog trigger is on", trigger.getTriggerState());
+
+    trigger.close();
+  }
+
+  @Test
+  public void testAnalogTriggerInWindow() {
+    // Given
+    AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput());
+    trigger.setLimitsVoltage(2.0, 3.0);
+
+    // When the output voltage is within the lower and upper limits
+    analogIO.getOutput().setVoltage(2.5f);
+    Timer.delay(kDelayTime);
+
+    // Then the analog trigger is in the window and the trigger state is off
+    assertTrue("Analog trigger is not in the window (2V, 3V)", trigger.getInWindow());
+    assertFalse("Analog trigger is on", trigger.getTriggerState());
+
+    trigger.close();
+  }
+
+  @Test
+  public void testAnalogTriggerAboveWindow() {
+    // Given
+    AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput());
+    trigger.setLimitsVoltage(2.0, 3.0);
+
+    // When the output voltage is greater than the upper limit
+    analogIO.getOutput().setVoltage(4.0);
+    Timer.delay(kDelayTime);
+
+    // Then the analog trigger is not in the window and the trigger state is on
+    assertFalse("Analog trigger is in the window (2V, 3V)", trigger.getInWindow());
+    assertTrue("Analog trigger is not on", trigger.getTriggerState());
+
+    trigger.close();
+  }
+
+  @Test
+  public void testAnalogTriggerCounter() {
+    // Given
+    AnalogTrigger trigger = new AnalogTrigger(analogIO.getInput());
+    trigger.setLimitsVoltage(2.0, 3.0);
+    Counter counter = new Counter(trigger);
+
+    // When the analog output is turned low and high 50 times
+    for (int i = 0; i < 50; i++) {
+      analogIO.getOutput().setVoltage(1.0);
+      Timer.delay(kDelayTime);
+      analogIO.getOutput().setVoltage(4.0);
+      Timer.delay(kDelayTime);
+    }
+
+    // Then the counter should be at 50
+    assertEquals("Analog trigger counter did not count 50 ticks", 50, counter.get());
+  }
+
+  @Test(expected = RuntimeException.class)
+  public void testRuntimeExceptionOnInvalidAccumulatorPort() {
+    analogIO.getInput().getAccumulatorCount();
+  }
+
+  private AnalogTrigger m_interruptTrigger;
+  private AnalogTriggerOutput m_interruptTriggerOutput;
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see
+   * edu.wpi.first.wpilibj.AbstractInterruptTest#giveInterruptableSensorBase()
+   */
+  @Override
+  InterruptableSensorBase giveInterruptableSensorBase() {
+    m_interruptTrigger = new AnalogTrigger(analogIO.getInput());
+    m_interruptTrigger.setLimitsVoltage(2.0, 3.0);
+    m_interruptTriggerOutput = new AnalogTriggerOutput(m_interruptTrigger,
+        AnalogTriggerType.kState);
+    return m_interruptTriggerOutput;
+  }
+
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see
+   * edu.wpi.first.wpilibj.AbstractInterruptTest#freeInterruptableSensorBase()
+   */
+  @Override
+  void freeInterruptableSensorBase() {
+    m_interruptTriggerOutput.cancelInterrupts();
+    m_interruptTriggerOutput.close();
+    m_interruptTriggerOutput = null;
+    m_interruptTrigger.close();
+    m_interruptTrigger = null;
+  }
+
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.AbstractInterruptTest#setInterruptHigh()
+   */
+  @Override
+  void setInterruptHigh() {
+    analogIO.getOutput().setVoltage(4.0);
+    Timer.delay(kDelayTime);
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.AbstractInterruptTest#setInterruptLow()
+   */
+  @Override
+  void setInterruptLow() {
+    analogIO.getOutput().setVoltage(1.0);
+    Timer.delay(kDelayTime);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java
new file mode 100644
index 0000000..8f5ad48
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/AnalogPotentiometerTest.java
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.Before;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture;
+import edu.wpi.first.wpilibj.mockhardware.FakePotentiometerSource;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Tests the {@link AnalogPotentiometer}.
+ */
+public class AnalogPotentiometerTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(AnalogPotentiometerTest.class.getName());
+  private AnalogCrossConnectFixture m_analogIO;
+  private FakePotentiometerSource m_potSource;
+  private AnalogPotentiometer m_pot;
+
+  private static final double DOUBLE_COMPARISON_DELTA = 2.0;
+
+  @Before
+  public void setUp() throws Exception {
+    m_analogIO = TestBench.getAnalogCrossConnectFixture();
+    m_potSource = new FakePotentiometerSource(m_analogIO.getOutput(), 360);
+    m_pot = new AnalogPotentiometer(m_analogIO.getInput(), 360.0, 0);
+
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    m_potSource.reset();
+    m_pot.close();
+    m_analogIO.teardown();
+  }
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  @Test
+  public void testInitialSettings() {
+    assertEquals(0, m_pot.get(), DOUBLE_COMPARISON_DELTA);
+  }
+
+  @Test
+  public void testRangeValues() {
+    for (double i = 0.0; i < 360.0; i = i + 1.0) {
+      m_potSource.setAngle(i);
+      m_potSource.setMaxVoltage(ControllerPower.getVoltage5V());
+      Timer.delay(.02);
+      assertEquals(i, m_pot.get(), DOUBLE_COMPARISON_DELTA);
+    }
+  }
+
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometerTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometerTest.java
new file mode 100644
index 0000000..dbfddfa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/BuiltInAccelerometerTest.java
@@ -0,0 +1,69 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.BeforeClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.interfaces.Accelerometer;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+@RunWith(Parameterized.class)
+public class BuiltInAccelerometerTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(BuiltInAccelerometerTest.class.getName());
+  private static final double kAccelerationTolerance = 0.1;
+  private final BuiltInAccelerometer m_accelerometer;
+
+  public BuiltInAccelerometerTest(Accelerometer.Range range) {
+    m_accelerometer = new BuiltInAccelerometer(range);
+  }
+
+  @BeforeClass
+  public static void waitASecond() {
+    /*
+     * The testbench sometimes shakes a little from a previous test. Give it
+     * some time.
+     */
+    Timer.delay(1.0);
+  }
+
+  /**
+   * Test with all valid ranges to make sure unpacking is always done correctly.
+   */
+  @Parameters
+  public static Collection<Accelerometer.Range[]> generateData() {
+    return Arrays.asList(new Accelerometer.Range[][]{{Accelerometer.Range.k2G},
+        {Accelerometer.Range.k4G}, {Accelerometer.Range.k8G}});
+  }
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * There's not much we can automatically test with the on-board accelerometer, but checking for
+   * gravity is probably good enough to tell that it's working.
+   */
+  @Test
+  public void testAccelerometer() {
+    assertEquals(0.0, m_accelerometer.getX(), kAccelerationTolerance);
+    assertEquals(1.0, m_accelerometer.getY(), kAccelerationTolerance);
+    assertEquals(0.0, m_accelerometer.getZ(), kAccelerationTolerance);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/ConstantsPortsTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/ConstantsPortsTest.java
new file mode 100644
index 0000000..aae1661
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/ConstantsPortsTest.java
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Tests for checking our constant and port values.
+ */
+public class ConstantsPortsTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(ConstantsPortsTest.class.getName());
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * kDigitalChannels.
+   */
+  @Test
+  public void testDigitalChannels() {
+    assertEquals(31, SensorUtil.kDigitalChannels);
+  }
+
+  /**
+   * kAnalogInputChannels.
+   */
+  @Test
+  public void testAnalogInputChannels() {
+    assertEquals(8, SensorUtil.kAnalogInputChannels);
+  }
+
+  /**
+   * kAnalogOutputChannels.
+   */
+  @Test
+  public void testAnalogOutputChannels() {
+    assertEquals(2, SensorUtil.kAnalogOutputChannels);
+  }
+
+  /**
+   * kSolenoidChannels.
+   */
+  @Test
+  public void testSolenoidChannels() {
+    assertEquals(8, SensorUtil.kSolenoidChannels);
+  }
+
+  /**
+   * kPwmChannels.
+   */
+  @Test
+  public void testPwmChannels() {
+    assertEquals(20, SensorUtil.kPwmChannels);
+  }
+
+  /**
+   * kRelayChannels.
+   */
+  @Test
+  public void testRelayChannels() {
+    assertEquals(4, SensorUtil.kRelayChannels);
+  }
+
+  /**
+   * kPDPChannels.
+   */
+  @Test
+  public void testPDPChannels() {
+    assertEquals(16, SensorUtil.kPDPChannels);
+  }
+
+  /**
+   * kPDPModules.
+   */
+  @Test
+  public void testPDPModules() {
+    assertEquals(63, SensorUtil.kPDPModules);
+  }
+
+  /**
+   * kPCMModules.
+   */
+  @Test
+  public void testPCMModules() {
+    assertEquals(63, SensorUtil.kPCMModules);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CounterTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CounterTest.java
new file mode 100644
index 0000000..3d6bd2e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/CounterTest.java
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.FakeCounterFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests to see if the Counter is working properly.
+ */
+@RunWith(Parameterized.class)
+public class CounterTest extends AbstractComsSetup {
+  private static FakeCounterFixture counter = null;
+  private static final Logger logger = Logger.getLogger(CounterTest.class.getName());
+
+  Integer m_input;
+  Integer m_output;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * Constructs a Counter Test with the given inputs.
+   *
+   * @param input  The input Port
+   * @param output The output Port
+   */
+  public CounterTest(Integer input, Integer output) {
+    assert input != null;
+    assert output != null;
+
+    m_input = input;
+    m_output = output;
+    // System.out.println("Counter Test: Input: " + input + " Output: " +
+    // output);
+    if (counter != null) {
+      counter.teardown();
+    }
+    counter = new FakeCounterFixture(input, output);
+  }
+
+  /**
+   * Test data generator. This method is called the the JUnit parameterized test runner and returns
+   * a Collection of Arrays. For each Array in the Collection, each array element corresponds to a
+   * parameter in the constructor.
+   */
+  @Parameters
+  public static Collection<Integer[]> generateData() {
+    // In this example, the parameter generator returns a List of
+    // arrays. Each array has two elements: { Digital input port, Digital output
+    // 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();
+  }
+
+
+  @BeforeClass
+  public static void setUpBeforeClass() throws Exception {
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() throws Exception {
+    counter.teardown();
+    counter = null;
+  }
+
+  @Before
+  public void setUp() throws Exception {
+    counter.setup();
+  }
+
+  /**
+   * Tests the default state of the counter immediately after reset.
+   */
+  @Test
+  public void testDefault() {
+    assertEquals("Counter did not reset to 0", 0, counter.getCounter().get());
+  }
+
+  @Test(timeout = 5000)
+  public void testCount() {
+    final int goal = 100;
+    counter.getFakeCounterSource().setCount(goal);
+    counter.getFakeCounterSource().execute();
+
+    final int count = counter.getCounter().get();
+
+    assertTrue("Fake Counter, Input: " + m_input + ", Output: " + m_output + ", did not return "
+        + goal + " instead got: " + count, count == goal);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java
new file mode 100644
index 0000000..b61b761
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DIOCrossConnectTest.java
@@ -0,0 +1,196 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.DIOCrossConnectFixture;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests to see if the Digital ports are working properly.
+ */
+@RunWith(Parameterized.class)
+public class DIOCrossConnectTest extends AbstractInterruptTest {
+  private static final Logger logger = Logger.getLogger(DIOCrossConnectTest.class.getName());
+
+  private static DIOCrossConnectFixture dio = null;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * Default constructor for the DIOCrossConnectTest This test is parameterized in order to allow it
+   * to be tested using a variety of different input/output pairs without duplicate code.<br> This
+   * class takes Integer port values instead of DigitalClasses because it would force them to be
+   * instantiated at the same time which could (untested) cause port binding errors.
+   *
+   * @param input  The port for the input wire
+   * @param output The port for the output wire
+   */
+  public DIOCrossConnectTest(Integer input, Integer output) {
+    if (dio != null) {
+      dio.teardown();
+    }
+    dio = new DIOCrossConnectFixture(input, output);
+  }
+
+
+  /**
+   * Test data generator. This method is called the the JUnit parameterized test runner and returns
+   * a Collection of Arrays. For each Array in the Collection, each array element corresponds to a
+   * parameter in the constructor.
+   */
+  @Parameters(name = "{index}: Input Port: {0} Output Port: {1}")
+  public static Collection<Integer[]> generateData() {
+    // In this example, the parameter generator returns a List of
+    // arrays. Each array has two elements: { Digital input port, Digital output
+    // 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();
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() throws Exception {
+    dio.teardown();
+    dio = null;
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    dio.reset();
+  }
+
+  /**
+   * Tests to see if the DIO can create and recognize a high value.
+   */
+  @Test
+  public void testSetHigh() {
+    dio.getOutput().set(true);
+    assertTrue("DIO Not High after no delay", dio.getInput().get());
+    Timer.delay(.02);
+    assertTrue("DIO Not High after .05s delay", dio.getInput().get());
+  }
+
+  /**
+   * Tests to see if the DIO can create and recognize a low value.
+   */
+  @Test
+  public void testSetLow() {
+    dio.getOutput().set(false);
+    assertFalse("DIO Not Low after no delay", dio.getInput().get());
+    Timer.delay(.02);
+    assertFalse("DIO Not Low after .05s delay", dio.getInput().get());
+  }
+
+  /**
+   * Tests to see if the DIO PWM functionality works.
+   */
+  @Test
+  public void testDIOpulseWidthModulation() {
+    dio.getOutput().set(false);
+    assertFalse("DIO Not Low after no delay", dio.getInput().get());
+    //Set frequency to 2.0 Hz
+    dio.getOutput().setPWMRate(2.0);
+    //Enable PWM, but leave it off.
+    dio.getOutput().enablePWM(0.0);
+    Timer.delay(0.5);
+    dio.getOutput().updateDutyCycle(0.5);
+    dio.getInput().requestInterrupts();
+    dio.getInput().setUpSourceEdge(false, true);
+    //TODO: Add return value from WaitForInterrupt
+    dio.getInput().waitForInterrupt(3.0, true);
+    Timer.delay(0.5);
+    final boolean firstCycle = dio.getInput().get();
+    Timer.delay(0.5);
+    final boolean secondCycle = dio.getInput().get();
+    Timer.delay(0.5);
+    final boolean thirdCycle = dio.getInput().get();
+    Timer.delay(0.5);
+    final boolean forthCycle = dio.getInput().get();
+    Timer.delay(0.5);
+    final boolean fifthCycle = dio.getInput().get();
+    Timer.delay(0.5);
+    final boolean sixthCycle = dio.getInput().get();
+    Timer.delay(0.5);
+    final boolean seventhCycle = dio.getInput().get();
+    dio.getOutput().disablePWM();
+    Timer.delay(0.5);
+    final boolean firstAfterStop = dio.getInput().get();
+    Timer.delay(0.5);
+    final boolean secondAfterStop = dio.getInput().get();
+
+    assertFalse("DIO Not Low after first delay", firstCycle);
+    assertTrue("DIO Not High after second delay", secondCycle);
+    assertFalse("DIO Not Low after third delay", thirdCycle);
+    assertTrue("DIO Not High after forth delay", forthCycle);
+    assertFalse("DIO Not Low after fifth delay", fifthCycle);
+    assertTrue("DIO Not High after sixth delay", sixthCycle);
+    assertFalse("DIO Not Low after seventh delay", seventhCycle);
+    assertFalse("DIO Not Low after stopping first read", firstAfterStop);
+    assertFalse("DIO Not Low after stopping second read", secondAfterStop);
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see
+   * edu.wpi.first.wpilibj.AbstractInterruptTest#giveInterruptableSensorBase()
+   */
+  @Override
+  InterruptableSensorBase giveInterruptableSensorBase() {
+    return dio.getInput();
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see
+   * edu.wpi.first.wpilibj.AbstractInterruptTest#freeInterruptableSensorBase()
+   */
+  @Override
+  void freeInterruptableSensorBase() {
+    // Handled in the fixture
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.AbstractInterruptTest#setInterruptHigh()
+   */
+  @Override
+  void setInterruptHigh() {
+    dio.getOutput().set(true);
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.AbstractInterruptTest#setInterruptLow()
+   */
+  @Override
+  void setInterruptLow() {
+    dio.getOutput().set(false);
+
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilterTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilterTest.java
new file mode 100644
index 0000000..821f5cc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DigitalGlitchFilterTest.java
@@ -0,0 +1,83 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Test for the DigitalGlitchFilter class.
+ */
+public class DigitalGlitchFilterTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(
+      DigitalGlitchFilterTest.class.getName());
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * This is a test to make sure that filters can be created and are consistent. This assumes that
+   * the FPGA implementation to actually implement the filter has been tested.  It does validate
+   * that we are successfully able to set and get the active filters for ports and makes sure that
+   * the FPGA filter is changed correctly, and does the same for the period.
+   */
+  @Test
+  public void testDigitalGlitchFilterBasic() {
+    final DigitalInput input1 = new DigitalInput(1);
+    final DigitalInput input2 = new DigitalInput(2);
+    final DigitalInput input3 = new DigitalInput(3);
+    final DigitalInput input4 = new DigitalInput(4);
+    final Encoder encoder5 = new Encoder(5, 6);
+    final Counter counter7 = new Counter(7);
+
+    final DigitalGlitchFilter filter1 = new DigitalGlitchFilter();
+    filter1.add(input1);
+    filter1.setPeriodNanoSeconds(4200);
+
+    final DigitalGlitchFilter filter2 = new DigitalGlitchFilter();
+    filter2.add(input2);
+    filter2.add(input3);
+    filter2.setPeriodNanoSeconds(97100);
+
+    final DigitalGlitchFilter filter3 = new DigitalGlitchFilter();
+    filter3.add(input4);
+    filter3.add(encoder5);
+    filter3.add(counter7);
+    filter3.setPeriodNanoSeconds(167800);
+
+    assertEquals(4200, filter1.getPeriodNanoSeconds());
+    assertEquals(97100, filter2.getPeriodNanoSeconds());
+    assertEquals(167800, filter3.getPeriodNanoSeconds());
+
+    filter1.remove(input1);
+
+    filter2.remove(input2);
+    filter2.remove(input3);
+
+    filter3.remove(input4);
+    filter3.remove(encoder5);
+    filter3.remove(counter7);
+
+    input1.close();
+    input2.close();
+    input3.close();
+    input4.close();
+    encoder5.close();
+    counter7.close();
+    filter1.close();
+    filter2.close();
+    filter3.close();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java
new file mode 100644
index 0000000..301a7ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/DriverStationTest.java
@@ -0,0 +1,44 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+
+public class DriverStationTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(TimerTest.class.getName());
+  private static final double TIMER_TOLERANCE = 0.2;
+  private static final long TIMER_RUNTIME = 1000000; // 1 second
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  @Test
+  public void waitForDataTest() {
+    long startTime = RobotController.getFPGATime();
+
+    // Wait for data 50 times
+    for (int i = 0; i < 50; i++) {
+      DriverStation.getInstance().waitForData();
+    }
+    long endTime = RobotController.getFPGATime();
+    long difference = endTime - startTime;
+
+    assertEquals("DriverStation waitForData did not wait long enough", TIMER_RUNTIME, difference,
+        TIMER_TOLERANCE * TIMER_RUNTIME);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/EncoderTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/EncoderTest.java
new file mode 100644
index 0000000..9833790
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/EncoderTest.java
@@ -0,0 +1,149 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.FakeEncoderFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertTrue;
+
+
+/**
+ * Test to see if the FPGA properly recognizes a mock Encoder input.
+ */
+@RunWith(Parameterized.class)
+public class EncoderTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(EncoderTest.class.getName());
+  private static FakeEncoderFixture encoder = null;
+
+  private final boolean m_flip; // Does this test need to flip the inputs
+  private final int m_inputA;
+  private final int m_inputB;
+  private final int m_outputA;
+  private final int m_outputB;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * Test data generator. This method is called the the JUnit parametrized test runner and returns
+   * a Collection of Arrays. For each Array in the Collection, each array element corresponds to a
+   * parameter in the constructor.
+   */
+  @Parameters
+  public static Collection<Integer[]> generateData() {
+    return TestBench.getInstance().getEncoderDIOCrossConnectCollection();
+  }
+
+  /**
+   * Constructs a parametrized Encoder Test.
+   *
+   * @param inputA  The port number for inputA
+   * @param outputA The port number for outputA
+   * @param inputB  The port number for inputB
+   * @param outputB The port number for outputB
+   * @param flip    whether or not these set of values require the encoder to be reversed (0 or 1)
+   */
+  public EncoderTest(int inputA, int outputA, int inputB, int outputB, int flip) {
+    m_inputA = inputA;
+    m_inputB = inputB;
+    m_outputA = outputA;
+    m_outputB = outputB;
+
+    // If the encoder from a previous test is allocated then we must free its
+    // members
+    if (encoder != null) {
+      encoder.teardown();
+    }
+    m_flip = flip == 0;
+    encoder = new FakeEncoderFixture(inputA, outputA, inputB, outputB);
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() throws Exception {
+    encoder.teardown();
+    encoder = null;
+  }
+
+  /**
+   * Sets up the test and verifies that the test was reset to the default state.
+   */
+  @Before
+  public void setUp() throws Exception {
+    encoder.setup();
+    testDefaultState();
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    encoder.reset();
+  }
+
+  /**
+   * Tests to see if Encoders initialize to zero.
+   */
+  @Test
+  public void testDefaultState() {
+    int value = encoder.getEncoder().get();
+    assertTrue(errorMessage(0, value), value == 0);
+  }
+
+  /**
+   * Tests to see if Encoders can count up successfully.
+   */
+  @Test
+  public void testCountUp() {
+    int goal = 100;
+    encoder.getFakeEncoderSource().setCount(goal);
+    encoder.getFakeEncoderSource().setForward(m_flip);
+    encoder.getFakeEncoderSource().execute();
+    int value = encoder.getEncoder().get();
+    assertTrue(errorMessage(goal, value), value == goal);
+
+  }
+
+  /**
+   * Tests to see if Encoders can count down successfully.
+   */
+  @Test
+  public void testCountDown() {
+    int goal = -100;
+    encoder.getFakeEncoderSource().setCount(goal); // Goal has to be positive
+    encoder.getFakeEncoderSource().setForward(!m_flip);
+    encoder.getFakeEncoderSource().execute();
+    int value = encoder.getEncoder().get();
+    assertTrue(errorMessage(goal, value), value == goal);
+
+  }
+
+  /**
+   * Creates a simple message with the error that was encountered for the Encoders.
+   *
+   * @param goal      The goal that was trying to be reached
+   * @param trueValue The actual value that was reached by the test
+   * @return A fully constructed message with data about where and why the the test failed.
+   */
+  private String errorMessage(int goal, int trueValue) {
+    return "Encoder ({In,Out}): {" + m_inputA + ", " + m_outputA + "},{" + m_inputB + ", "
+        + m_outputB + "} Returned: " + trueValue + ", Wanted: " + goal;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/FilterNoiseTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/FilterNoiseTest.java
new file mode 100644
index 0000000..2349016
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/FilterNoiseTest.java
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.FilterNoiseFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertTrue;
+
+
+@RunWith(Parameterized.class)
+public class FilterNoiseTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(FilterNoiseTest.class.getName());
+
+  private static FilterNoiseFixture<?> me = null;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * Constructs the FilterNoiseTest.
+   *
+   * @param mef The fixture under test.
+   */
+  public FilterNoiseTest(FilterNoiseFixture<?> mef) {
+    logger.fine("Constructor with: " + mef.getType());
+    if (me != null && !me.equals(mef)) {
+      me.teardown();
+    }
+    me = mef;
+  }
+
+  @Parameters(name = "{index}: {0}")
+  public static Collection<FilterNoiseFixture<?>[]> generateData() {
+    return Arrays.asList(new FilterNoiseFixture<?>[][]{
+        {TestBench.getInstance().getSinglePoleIIRNoiseFixture()},
+        {TestBench.getInstance().getMovAvgNoiseFixture()}});
+  }
+
+  @Before
+  public void setUp() {
+    me.setup();
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    me.reset();
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() {
+    // Clean up the fixture after the test
+    me.teardown();
+    me = null;
+  }
+
+  /**
+   * Test if the filter reduces the noise produced by a signal generator.
+   */
+  @Test
+  public void testNoiseReduce() {
+    double noiseGenError = 0.0;
+    double filterError = 0.0;
+
+    FilterNoiseFixture.NoiseGenerator noise = me.getNoiseGenerator();
+
+    noise.reset();
+    for (double t = 0; t < TestBench.kFilterTime; t += TestBench.kFilterStep) {
+      final double theoryData = noise.getData(t);
+      filterError += Math.abs(me.getFilter().pidGet() - theoryData);
+      noiseGenError += Math.abs(noise.get() - theoryData);
+    }
+
+    assertTrue(me.getType() + " should have reduced noise accumulation from " + noiseGenError
+        + " but failed. The filter error was " + filterError, noiseGenError > filterError);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/FilterOutputTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/FilterOutputTest.java
new file mode 100644
index 0000000..a672f1a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/FilterOutputTest.java
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.FilterOutputFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+
+
+@RunWith(Parameterized.class)
+public class FilterOutputTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(FilterOutputTest.class.getName());
+
+  private double m_expectedOutput;
+
+  private static FilterOutputFixture<?> me = null;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * Constructs a filter output test.
+   *
+   * @param mef The fixture under test.
+   */
+  public FilterOutputTest(FilterOutputFixture<?> mef) {
+    logger.fine("Constructor with: " + mef.getType());
+    if (me != null && !me.equals(mef)) {
+      me.teardown();
+    }
+    me = mef;
+    m_expectedOutput = me.getExpectedOutput();
+  }
+
+  @Parameters(name = "{index}: {0}")
+  public static Collection<FilterOutputFixture<?>[]> generateData() {
+    return Arrays.asList(new FilterOutputFixture<?>[][]{
+        {TestBench.getInstance().getSinglePoleIIROutputFixture()},
+        {TestBench.getInstance().getHighPassOutputFixture()},
+        {TestBench.getInstance().getMovAvgOutputFixture()},
+        {TestBench.getInstance().getPulseFixture()}});
+  }
+
+  @Before
+  public void setUp() {
+    me.setup();
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    me.reset();
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() {
+    // Clean up the fixture after the test
+    me.teardown();
+    me = null;
+  }
+
+  /**
+   * Test if the filter produces consistent output for a given data set.
+   */
+  @Test
+  public void testOutput() {
+    me.reset();
+
+    double filterOutput = 0.0;
+    for (double t = 0.0; t < TestBench.kFilterTime; t += TestBench.kFilterStep) {
+      filterOutput = me.getFilter().pidGet();
+    }
+
+    assertEquals(me.getType() + " output was incorrect.", m_expectedOutput, filterOutput, 0.00005);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/GyroTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/GyroTest.java
new file mode 100644
index 0000000..aee0514
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/GyroTest.java
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.Before;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.fixtures.TiltPanCameraFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Tests that the {@link TiltPanCameraFixture}.
+ */
+public class GyroTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(GyroTest.class.getName());
+
+  public static final double TEST_ANGLE = 90.0;
+
+  private TiltPanCameraFixture m_tpcam;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  @Before
+  public void setUp() throws Exception {
+    logger.fine("Setup: TiltPan camera");
+    m_tpcam = TestBench.getInstance().getTiltPanCam();
+    m_tpcam.setup();
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    m_tpcam.teardown();
+  }
+
+  @Test
+  public void testAllGyroTests() {
+    testInitial(m_tpcam.getGyro());
+    testDeviationOverTime(m_tpcam.getGyro());
+    testGyroAngle(m_tpcam.getGyro());
+    testGyroAngleCalibratedParameters();
+  }
+
+  public void testInitial(AnalogGyro gyro) {
+    double angle = gyro.getAngle();
+    assertEquals(errorMessage(angle, 0), 0, angle, .5);
+  }
+
+  /**
+   * Test to see if the Servo and the gyroscope is turning 90 degrees Note servo on TestBench is not
+   * the same type of servo that servo class was designed for so setAngle is significantly off. This
+   * has been calibrated for the servo on the rig.
+   */
+  public void testGyroAngle(AnalogGyro gyro) {
+    // Set angle
+    for (int i = 0; i < 5; i++) {
+      m_tpcam.getPan().set(0);
+      Timer.delay(.1);
+    }
+
+    Timer.delay(0.5);
+    // Reset for setup
+    gyro.reset();
+    Timer.delay(0.5);
+
+    // Perform test
+    for (int i = 0; i < 53; i++) {
+      m_tpcam.getPan().set(i / 100.0);
+      Timer.delay(0.05);
+    }
+    Timer.delay(1.2);
+
+    double angle = gyro.getAngle();
+
+    double difference = TEST_ANGLE - angle;
+
+    double diff = Math.abs(difference);
+
+    assertEquals(errorMessage(diff, TEST_ANGLE), TEST_ANGLE, angle, 10);
+  }
+
+
+  protected void testDeviationOverTime(AnalogGyro gyro) {
+    // Make sure that the test isn't influenced by any previous motions.
+    Timer.delay(0.5);
+    gyro.reset();
+    Timer.delay(0.25);
+    double angle = gyro.getAngle();
+    assertEquals(errorMessage(angle, 0), 0, angle, .5);
+    Timer.delay(5);
+    angle = gyro.getAngle();
+    assertEquals("After 5 seconds " + errorMessage(angle, 0), 0, angle, 2.0);
+  }
+
+  /**
+   * Gets calibrated parameters from already calibrated gyro, allocates a new gyro with the center
+   * and offset parameters, and re-runs the test.
+   */
+  public void testGyroAngleCalibratedParameters() {
+    // Get calibrated parameters to make new Gyro with parameters
+    final double calibratedOffset = m_tpcam.getGyro().getOffset();
+    final int calibratedCenter = m_tpcam.getGyro().getCenter();
+    m_tpcam.freeGyro();
+    m_tpcam.setupGyroParam(calibratedCenter, calibratedOffset);
+    Timer.delay(TiltPanCameraFixture.RESET_TIME);
+    // Repeat tests
+    testInitial(m_tpcam.getGyroParam());
+    testDeviationOverTime(m_tpcam.getGyroParam());
+    testGyroAngle(m_tpcam.getGyroParam());
+  }
+
+  private String errorMessage(double difference, double target) {
+    return "Gyro angle skewed " + difference + " deg away from target " + target;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
new file mode 100644
index 0000000..0998ee9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockDS.java
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.io.IOException;
+import java.net.DatagramPacket;
+import java.net.DatagramSocket;
+import java.net.InetSocketAddress;
+import java.net.SocketException;
+
+public class MockDS {
+  private Thread m_thread;
+
+  private void generateEnabledDsPacket(byte[] data, short sendCount) {
+    data[0] = (byte) (sendCount >> 8);
+    data[1] = (byte) sendCount;
+    data[2] = 0x01; // general data tag
+    data[3] = 0x04; // teleop enabled
+    data[4] = 0x10; // normal data request
+    data[5] = 0x00; // red 1 station
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  public void start() {
+    m_thread = new Thread(() -> {
+      DatagramSocket socket;
+      try {
+        socket = new DatagramSocket();
+      } catch (SocketException e1) {
+        // TODO Auto-generated catch block
+        e1.printStackTrace();
+        return;
+      }
+      InetSocketAddress addr = new InetSocketAddress("127.0.0.1", 1110);
+      byte[] sendData = new byte[6];
+      DatagramPacket packet = new DatagramPacket(sendData, 0, 6, addr);
+      short sendCount = 0;
+      int initCount = 0;
+      while (!Thread.currentThread().isInterrupted()) {
+        try {
+          Thread.sleep(20);
+          generateEnabledDsPacket(sendData, sendCount++);
+          // ~50 disabled packets are required to make the robot actually enable
+          // 1 is definitely not enough.
+          if (initCount < 50) {
+            initCount++;
+            sendData[3] = 0;
+          }
+          packet.setData(sendData);
+          socket.send(packet);
+        } catch (InterruptedException ex) {
+          Thread.currentThread().interrupt();
+        } catch (IOException ex) {
+          // TODO Auto-generated catch block
+          ex.printStackTrace();
+        }
+      }
+      socket.close();
+    });
+    // Because of the test setup in Java, this thread will not be stopped
+    // So it must be a daemon thread
+    m_thread.setDaemon(true);
+    m_thread.start();
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  public void stop() {
+    if (m_thread == null) {
+      return;
+    }
+    m_thread.interrupt();
+    try {
+      m_thread.join(1000);
+    } catch (InterruptedException ex) {
+      // TODO Auto-generated catch block
+      ex.printStackTrace();
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java
new file mode 100644
index 0000000..d183723
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MockSpeedController.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+public class MockSpeedController implements SpeedController {
+  private double m_speed;
+  private boolean m_isInverted;
+
+  @Override
+  public void set(double speed) {
+    m_speed = m_isInverted ? -speed : speed;
+  }
+
+  @Override
+  public double get() {
+    return m_speed;
+  }
+
+  @Override
+  public void setInverted(boolean isInverted) {
+    m_isInverted = isInverted;
+  }
+
+  @Override
+  public boolean getInverted() {
+    return m_isInverted;
+  }
+
+  @Override
+  public void disable() {
+    m_speed = 0;
+  }
+
+  @Override
+  public void stopMotor() {
+    disable();
+  }
+
+  @Override
+  public void pidWrite(double output) {
+    set(output);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java
new file mode 100644
index 0000000..59400c7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorEncoderTest.java
@@ -0,0 +1,236 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.filters.LinearDigitalFilter;
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+
+@RunWith(Parameterized.class)
+public class MotorEncoderTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(MotorEncoderTest.class.getName());
+
+  private static final double MOTOR_RUNTIME = .25;
+
+  // private static final List<MotorEncoderFixture> pairs = new
+  // ArrayList<MotorEncoderFixture>();
+  private static MotorEncoderFixture<?> me = null;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  /**
+   * Constructs the test.
+   *
+   * @param mef The fixture under test.
+   */
+  public MotorEncoderTest(MotorEncoderFixture<?> mef) {
+    logger.fine("Constructor with: " + mef.getType());
+    if (me != null && !me.equals(mef)) {
+      me.teardown();
+    }
+    me = mef;
+  }
+
+  @Parameters(name = "{index}: {0}")
+  public static Collection<MotorEncoderFixture<?>[]> generateData() {
+    // logger.fine("Loading the MotorList");
+    return Arrays.asList(new MotorEncoderFixture<?>[][]{{TestBench.getInstance().getTalonPair()},
+        {TestBench.getInstance().getVictorPair()}, {TestBench.getInstance().getJaguarPair()}});
+  }
+
+  @Before
+  public void setUp() {
+    double initialSpeed = me.getMotor().get();
+    assertTrue(me.getType() + " Did not start with an initial speed of 0 instead got: "
+        + initialSpeed, Math.abs(initialSpeed) < 0.001);
+    me.setup();
+
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    me.reset();
+    encodersResetCheck(me);
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() {
+    // Clean up the fixture after the test
+    me.teardown();
+    me = null;
+  }
+
+  /**
+   * Test to ensure that the isMotorWithinRange method is functioning properly. Really only needs to
+   * run on one MotorEncoderFixture to ensure that it is working correctly.
+   */
+  @Test
+  public void testIsMotorWithinRange() {
+    double range = 0.01;
+    assertTrue(me.getType() + " 1", me.isMotorSpeedWithinRange(0.0, range));
+    assertTrue(me.getType() + " 2", me.isMotorSpeedWithinRange(0.0, -range));
+    assertFalse(me.getType() + " 3", me.isMotorSpeedWithinRange(1.0, range));
+    assertFalse(me.getType() + " 4", me.isMotorSpeedWithinRange(-1.0, range));
+  }
+
+  /**
+   * This test is designed to see if the values of different motors will increment when spun
+   * forward.
+   */
+  @Test
+  public void testIncrement() {
+    int startValue = me.getEncoder().get();
+
+    me.getMotor().set(.2);
+    Timer.delay(MOTOR_RUNTIME);
+    int currentValue = me.getEncoder().get();
+    assertTrue(me.getType() + " Encoder not incremented: start: " + startValue + "; current: "
+        + currentValue, startValue < currentValue);
+
+  }
+
+  /**
+   * This test is designed to see if the values of different motors will decrement when spun in
+   * reverse.
+   */
+  @Test
+  public void testDecrement() {
+    int startValue = me.getEncoder().get();
+
+    me.getMotor().set(-.2);
+    Timer.delay(MOTOR_RUNTIME);
+    int currentValue = me.getEncoder().get();
+    assertTrue(me.getType() + " Encoder not decremented: start: " + startValue + "; current: "
+        + currentValue, startValue > currentValue);
+  }
+
+  /**
+   * This method test if the counters count when the motors rotate.
+   */
+  @Test
+  public void testCounter() {
+    final int counter1Start = me.getCounters()[0].get();
+    final int counter2Start = me.getCounters()[1].get();
+
+    me.getMotor().set(.75);
+    Timer.delay(MOTOR_RUNTIME);
+    int counter1End = me.getCounters()[0].get();
+    int counter2End = me.getCounters()[1].get();
+    assertTrue(me.getType() + " Counter not incremented: start: " + counter1Start + "; current: "
+        + counter1End, counter1Start < counter1End);
+    assertTrue(me.getType() + " Counter not incremented: start: " + counter1Start + "; current: "
+        + counter2End, counter2Start < counter2End);
+    me.reset();
+    encodersResetCheck(me);
+  }
+
+  /**
+   * Tests to see if you set the speed to something not {@literal <=} 1.0 if the code appropriately
+   * throttles the value.
+   */
+  @Test
+  public void testSetHighForwardSpeed() {
+    me.getMotor().set(15);
+    assertTrue(me.getType() + " Motor speed was not close to 1.0, was: " + me.getMotor().get(),
+        me.isMotorSpeedWithinRange(1.0, 0.001));
+  }
+
+  /**
+   * Tests to see if you set the speed to something not {@literal >=} -1.0 if the code appropriately
+   * throttles the value.
+   */
+  @Test
+  public void testSetHighReverseSpeed() {
+    me.getMotor().set(-15);
+    assertTrue(me.getType() + " Motor speed was not close to 1.0, was: " + me.getMotor().get(),
+        me.isMotorSpeedWithinRange(-1.0, 0.001));
+  }
+
+
+  @Test
+  public void testPositionPIDController() {
+    me.getEncoder().setPIDSourceType(PIDSourceType.kDisplacement);
+    PIDController pid = new PIDController(0.001, 0.0005, 0, me.getEncoder(), me.getMotor());
+    pid.setAbsoluteTolerance(50.0);
+    pid.setOutputRange(-0.2, 0.2);
+    pid.setSetpoint(1000);
+
+    pid.enable();
+    Timer.delay(10.0);
+    pid.disable();
+
+    assertTrue(
+        "PID loop did not reach setpoint within 10 seconds. The current error was" + pid
+            .getError(), pid.onTarget());
+
+    pid.close();
+  }
+
+  @Test
+  public void testVelocityPIDController() {
+    me.getEncoder().setPIDSourceType(PIDSourceType.kRate);
+    LinearDigitalFilter filter = LinearDigitalFilter.movingAverage(me.getEncoder(), 50);
+    PIDController pid =
+        new PIDController(1e-5, 0.0, 3e-5, 8e-5, filter, me.getMotor());
+    pid.setAbsoluteTolerance(200);
+    pid.setOutputRange(-0.3, 0.3);
+    pid.setSetpoint(600);
+
+    pid.enable();
+    Timer.delay(10.0);
+    pid.disable();
+
+    assertTrue(
+        "PID loop did not reach setpoint within 10 seconds. The error was: " + pid.getError(),
+        pid.onTarget());
+
+    pid.close();
+  }
+
+  /**
+   * Checks to see if the encoders and counters are appropriately reset to zero when reset.
+   *
+   * @param me The MotorEncoderFixture under test
+   */
+  private void encodersResetCheck(MotorEncoderFixture<?> me) {
+    assertEquals(me.getType() + " Encoder value was incorrect after reset.", me.getEncoder().get(),
+        0);
+    assertEquals(me.getType() + " Motor value was incorrect after reset.", me.getMotor().get(), 0,
+        0);
+    assertEquals(me.getType() + " Counter1 value was incorrect after reset.",
+        me.getCounters()[0].get(), 0);
+    assertEquals(me.getType() + " Counter2 value was incorrect after reset.",
+        me.getCounters()[1].get(), 0);
+    Timer.delay(0.5); // so this doesn't fail with the 0.5 second default
+    // timeout on the encoders
+    assertTrue(me.getType() + " Encoder.getStopped() returned false after the motor was reset.", me
+        .getEncoder().getStopped());
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorInvertingTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorInvertingTest.java
new file mode 100644
index 0000000..5857681
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/MotorInvertingTest.java
@@ -0,0 +1,134 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests Inversion of motors using the SpeedController setInverted.
+ */
+@RunWith(Parameterized.class)
+public class MotorInvertingTest extends AbstractComsSetup {
+  static MotorEncoderFixture<?> fixture = null;
+  private static final double motorspeed = 0.2;
+  private static final double delaytime = 0.3;
+
+
+  /**
+   * Constructs the test.
+   *
+   * @param afixture The fixture under test.
+   */
+  public MotorInvertingTest(MotorEncoderFixture<?> afixture) {
+    logger.fine("Constructor with: " + afixture.getType());
+    if (fixture != null && !fixture.equals(afixture)) {
+      fixture.teardown();
+    }
+    fixture = afixture;
+    fixture.setup();
+  }
+
+  @Parameters(name = "{index}: {0}")
+  public static Collection<MotorEncoderFixture<?>[]> generateData() {
+    // logger.fine("Loading the MotorList");
+    return Arrays.asList(new MotorEncoderFixture<?>[][]{{TestBench.getInstance().getTalonPair()},
+        {TestBench.getInstance().getVictorPair()}, {TestBench.getInstance().getJaguarPair()}});
+  }
+
+  private static final Logger logger = Logger.getLogger(MotorInvertingTest.class.getName());
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  @Before
+  public void setUp() {
+    // Reset the fixture elements before every test
+    fixture.reset();
+  }
+
+  @AfterClass
+  public static void tearDown() {
+    fixture.getMotor().setInverted(false);
+    // Clean up the fixture after the test
+    fixture.teardown();
+  }
+
+  @Test
+  public void testInvertingPositive() {
+    fixture.getMotor().setInverted(false);
+    fixture.getMotor().set(motorspeed);
+    Timer.delay(delaytime);
+    final boolean initDirection = fixture.getEncoder().getDirection();
+    fixture.getMotor().setInverted(true);
+    fixture.getMotor().set(motorspeed);
+    Timer.delay(delaytime);
+    assertFalse("Inverting with Positive value does not change direction", fixture.getEncoder()
+        .getDirection() == initDirection);
+    fixture.getMotor().set(0);
+  }
+
+  @Test
+  public void testInvertingNegative() {
+    fixture.getMotor().setInverted(false);
+    fixture.getMotor().set(-motorspeed);
+    Timer.delay(delaytime);
+    final boolean initDirection = fixture.getEncoder().getDirection();
+    fixture.getMotor().setInverted(true);
+    fixture.getMotor().set(-motorspeed);
+    Timer.delay(delaytime);
+    assertFalse("Inverting with Negative value does not change direction", fixture.getEncoder()
+        .getDirection() == initDirection);
+    fixture.getMotor().set(0);
+  }
+
+  @Test
+  public void testInvertingSwitchingPosToNeg() {
+    fixture.getMotor().setInverted(false);
+    fixture.getMotor().set(motorspeed);
+    Timer.delay(delaytime);
+    final boolean initDirection = fixture.getEncoder().getDirection();
+    fixture.getMotor().setInverted(true);
+    fixture.getMotor().set(-motorspeed);
+    Timer.delay(delaytime);
+    assertTrue("Inverting with Switching value does change direction", fixture.getEncoder()
+        .getDirection() == initDirection);
+    fixture.getMotor().set(0);
+  }
+
+  @Test
+  public void testInvertingSwitchingNegToPos() {
+    fixture.getMotor().setInverted(false);
+    fixture.getMotor().set(-motorspeed);
+    Timer.delay(delaytime);
+    final boolean initDirection = fixture.getEncoder().getDirection();
+    fixture.getMotor().setInverted(true);
+    fixture.getMotor().set(motorspeed);
+    Timer.delay(delaytime);
+    assertTrue("Inverting with Switching value does change direction", fixture.getEncoder()
+        .getDirection() == initDirection);
+    fixture.getMotor().set(0);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java
new file mode 100644
index 0000000..b703138
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PCMTest.java
@@ -0,0 +1,276 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Test that covers the {@link Compressor}.
+ */
+
+public class PCMTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(PCMTest.class.getName());
+  /*
+   * The PCM switches the compressor up to 2 seconds after the pressure switch
+   * changes.
+   */
+  protected static final double kCompressorDelayTime = 2.0;
+
+  /* Solenoids should change much more quickly */
+  protected static final double kSolenoidDelayTime = 1.0;
+
+  /*
+   * The voltage divider on the test bench should bring the compressor output to
+   * around these values.
+   */
+  protected static final double kCompressorOnVoltage = 5.00;
+  protected static final double kCompressorOffVoltage = 1.68;
+
+  private static Compressor compressor;
+
+  private static DigitalOutput fakePressureSwitch;
+  private static AnalogInput fakeCompressor;
+
+  private static DigitalInput fakeSolenoid1;
+  private static DigitalInput fakeSolenoid2;
+
+  @BeforeClass
+  public static void setUpBeforeClass() throws Exception {
+    compressor = new Compressor();
+
+    fakePressureSwitch = new DigitalOutput(11);
+    fakeCompressor = new AnalogInput(1);
+
+    fakeSolenoid1 = new DigitalInput(12);
+    fakeSolenoid2 = new DigitalInput(13);
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() throws Exception {
+    compressor.close();
+
+    fakePressureSwitch.close();
+    fakeCompressor.close();
+
+    fakeSolenoid1.close();
+    fakeSolenoid2.close();
+  }
+
+  @Before
+  public void reset() throws Exception {
+    compressor.stop();
+    fakePressureSwitch.set(false);
+  }
+
+  /**
+   * Test if the compressor turns on and off when the pressure switch is toggled.
+   */
+  @Test
+  public void testPressureSwitch() throws Exception {
+    final double range = 0.5;
+    reset();
+    compressor.setClosedLoopControl(true);
+
+    // Turn on the compressor
+    fakePressureSwitch.set(true);
+    Timer.delay(kCompressorDelayTime);
+    assertEquals("Compressor did not turn on when the pressure switch turned on.",
+        kCompressorOnVoltage, fakeCompressor.getVoltage(), range);
+
+    // Turn off the compressor
+    fakePressureSwitch.set(false);
+    Timer.delay(kCompressorDelayTime);
+    assertEquals("Compressor did not turn off when the pressure switch turned off.",
+        kCompressorOffVoltage, fakeCompressor.getVoltage(), range);
+  }
+
+  /**
+   * Test if the correct solenoids turn on and off when they should.
+   */
+  @Test
+  public void testSolenoid() throws Exception {
+    reset();
+
+    Solenoid solenoid1 = new Solenoid(0);
+    Solenoid solenoid2 = new Solenoid(1);
+
+    solenoid1.set(false);
+    solenoid2.set(false);
+    Timer.delay(kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+    // Turn Solenoid #1 on, and turn Solenoid #2 off
+    solenoid1.set(true);
+    solenoid2.set(false);
+    Timer.delay(kSolenoidDelayTime);
+    assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertTrue("Solenoid #1 did not report on", solenoid1.get());
+    assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+    // Turn Solenoid #1 off, and turn Solenoid #2 on
+    solenoid1.set(false);
+    solenoid2.set(true);
+    Timer.delay(kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertTrue("Solenoid #2 did not report on", solenoid2.get());
+
+    // Turn both Solenoids on
+    solenoid1.set(true);
+    solenoid2.set(true);
+    Timer.delay(kSolenoidDelayTime);
+    assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+    assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+    assertTrue("Solenoid #1 did not report on", solenoid1.get());
+    assertTrue("Solenoid #2 did not report on", solenoid2.get());
+
+    solenoid1.close();
+    solenoid2.close();
+  }
+
+  /**
+   * Test if the correct solenoids turn on and off when they should when used with the
+   * DoubleSolenoid class.
+   */
+  @Test
+  public void doubleSolenoid() {
+    DoubleSolenoid solenoid = new DoubleSolenoid(0, 1);
+
+    solenoid.set(DoubleSolenoid.Value.kOff);
+    Timer.delay(kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertTrue("DoubleSolenoid did not report off", solenoid.get() == DoubleSolenoid.Value.kOff);
+
+    solenoid.set(DoubleSolenoid.Value.kForward);
+    Timer.delay(kSolenoidDelayTime);
+    assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertTrue("DoubleSolenoid did not report Forward", solenoid.get() == DoubleSolenoid.Value
+        .kForward);
+
+    solenoid.set(DoubleSolenoid.Value.kReverse);
+    Timer.delay(kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+    assertTrue("DoubleSolenoid did not report Reverse", solenoid.get() == DoubleSolenoid.Value
+        .kReverse);
+
+    solenoid.close();
+  }
+
+  /**
+   * Test if the correct solenoids turn on and off when they should.
+   */
+  @Test
+  public void testOneShot() throws Exception {
+    reset();
+
+    Solenoid solenoid1 = new Solenoid(0);
+    Solenoid solenoid2 = new Solenoid(1);
+
+    solenoid1.set(false);
+    solenoid2.set(false);
+    Timer.delay(kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+    // Pulse Solenoid #1 on, and turn Solenoid #2 off
+    solenoid1.setPulseDuration(2 * kSolenoidDelayTime);
+    solenoid1.startPulse();
+    solenoid2.set(false);
+    Timer.delay(kSolenoidDelayTime);
+    assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertTrue("Solenoid #1 did not report on", solenoid1.get());
+    assertFalse("Solenoid #2 did not report off", solenoid2.get());
+    Timer.delay(2 * kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+    // Turn Solenoid #1 off, and pulse Solenoid #2 on
+    solenoid1.set(false);
+    solenoid2.setPulseDuration(2 * kSolenoidDelayTime);
+    solenoid2.startPulse();
+    Timer.delay(kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertTrue("Solenoid #2 did not report on", solenoid2.get());
+    Timer.delay(2 * kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+    // Pulse both Solenoids on
+    solenoid1.setPulseDuration(2 * kSolenoidDelayTime);
+    solenoid2.setPulseDuration(2 * kSolenoidDelayTime);
+    solenoid1.startPulse();
+    solenoid2.startPulse();
+    Timer.delay(kSolenoidDelayTime);
+    assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+    assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+    assertTrue("Solenoid #1 did not report on", solenoid1.get());
+    assertTrue("Solenoid #2 did not report on", solenoid2.get());
+    Timer.delay(2 * kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+    // Pulse both Solenoids on with different durations
+    solenoid1.setPulseDuration(1.5 * kSolenoidDelayTime);
+    solenoid2.setPulseDuration(2.5 * kSolenoidDelayTime);
+    solenoid1.startPulse();
+    solenoid2.startPulse();
+    Timer.delay(kSolenoidDelayTime);
+    assertFalse("Solenoid #1 did not turn on", fakeSolenoid1.get());
+    assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+    assertTrue("Solenoid #1 did not report on", solenoid1.get());
+    assertTrue("Solenoid #2 did not report on", solenoid2.get());
+    Timer.delay(kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertFalse("Solenoid #2 did not turn on", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertTrue("Solenoid #2 did not report on", solenoid2.get());
+    Timer.delay(kSolenoidDelayTime);
+    assertTrue("Solenoid #1 did not turn off", fakeSolenoid1.get());
+    assertTrue("Solenoid #2 did not turn off", fakeSolenoid2.get());
+    assertFalse("Solenoid #1 did not report off", solenoid1.get());
+    assertFalse("Solenoid #2 did not report off", solenoid2.get());
+
+    solenoid1.close();
+    solenoid2.close();
+  }
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
new file mode 100644
index 0000000..7c49f81
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PDPTest.java
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.BeforeClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.hal.can.CANMessageNotFoundException;
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.hamcrest.Matchers.greaterThan;
+import static org.hamcrest.Matchers.is;
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertThat;
+
+/**
+ * Test that covers the {@link PowerDistributionPanel}.
+ */
+@RunWith(Parameterized.class)
+public class PDPTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(PCMTest.class.getName());
+
+  private static PowerDistributionPanel pdp;
+  private static MotorEncoderFixture<?> me;
+  private final double m_expectedStoppedCurrentDraw;
+
+  @BeforeClass
+  public static void setUpBeforeClass() throws Exception {
+    pdp = new PowerDistributionPanel();
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() throws Exception {
+    pdp.close();
+    pdp = null;
+    me.teardown();
+    me = null;
+  }
+
+
+  @SuppressWarnings("JavadocMethod")
+  public PDPTest(MotorEncoderFixture<?> mef, Double expectedCurrentDraw) {
+    logger.fine("Constructor with: " + mef.getType());
+    if (me != null && !me.equals(mef)) {
+      me.teardown();
+    }
+    me = mef;
+    me.setup();
+
+    m_expectedStoppedCurrentDraw = expectedCurrentDraw;
+  }
+
+  @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(), new Double(0.0)}});
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    me.reset();
+  }
+
+
+  /**
+   * Test if the current changes when the motor is driven using a talon.
+   */
+  @Test
+  public void checkStoppedCurrentForSpeedController() throws CANMessageNotFoundException {
+    Timer.delay(0.25);
+
+    /* The Current should be 0 */
+    assertEquals("The low current was not within the expected range.", m_expectedStoppedCurrentDraw,
+        pdp.getCurrent(me.getPDPChannel()), 0.001);
+  }
+
+  /**
+   * Test if the current changes when the motor is driven using a talon.
+   */
+  @Test
+  public void checkRunningCurrentForSpeedController() throws CANMessageNotFoundException {
+    /* Set the motor to full forward */
+    me.getMotor().set(1.0);
+    Timer.delay(2);
+
+    /* The current should now be greater than the low current */
+    assertThat("The driven current is not greater than the resting current.",
+        pdp.getCurrent(me.getPDPChannel()), is(greaterThan(m_expectedStoppedCurrentDraw)));
+  }
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
new file mode 100644
index 0000000..ad05703
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PIDTest.java
@@ -0,0 +1,206 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Parameterized;
+import org.junit.runners.Parameterized.Parameters;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.hamcrest.CoreMatchers.is;
+import static org.hamcrest.CoreMatchers.not;
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertThat;
+import static org.junit.Assert.assertTrue;
+
+
+/**
+ * Test that covers the {@link PIDController}.
+ */
+
+@RunWith(Parameterized.class)
+public class PIDTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(PIDTest.class.getName());
+  private NetworkTable m_table;
+  private SendableBuilderImpl m_builder;
+
+  private static final double absoluteTolerance = 50;
+  private static final double outputRange = 0.25;
+
+  private PIDController m_controller = null;
+  private static MotorEncoderFixture me = null;
+
+  @SuppressWarnings({"MemberName", "EmptyLineSeparator", "MultipleVariableDeclarations"})
+  private final Double k_p, k_i, k_d;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+
+  @SuppressWarnings({"ParameterName", "JavadocMethod"})
+  public PIDTest(Double p, Double i, Double d, MotorEncoderFixture mef) {
+    logger.fine("Constructor with: " + mef.getType());
+    if (PIDTest.me != null && !PIDTest.me.equals(mef)) {
+      PIDTest.me.teardown();
+    }
+    PIDTest.me = mef;
+    this.k_p = p;
+    this.k_i = i;
+    this.k_d = d;
+  }
+
+
+  @Parameters
+  public static Collection<Object[]> generateData() {
+    // logger.fine("Loading the MotorList");
+    Collection<Object[]> data = new ArrayList<Object[]>();
+    double kp = 0.001;
+    double ki = 0.0005;
+    double kd = 0.0;
+    for (int i = 0; i < 1; i++) {
+      data.addAll(Arrays.asList(new Object[][]{
+          {kp, ki, kd, TestBench.getInstance().getTalonPair()},
+          {kp, ki, kd, TestBench.getInstance().getVictorPair()},
+          {kp, ki, kd, TestBench.getInstance().getJaguarPair()}}));
+    }
+    return data;
+  }
+
+  @BeforeClass
+  public static void setUpBeforeClass() throws Exception {
+  }
+
+  @AfterClass
+  public static void tearDownAfterClass() throws Exception {
+    logger.fine("TearDownAfterClass: " + me.getType());
+    me.teardown();
+    me = null;
+  }
+
+  @Before
+  public void setUp() throws Exception {
+    logger.fine("Setup: " + me.getType());
+    me.setup();
+    m_table = NetworkTableInstance.getDefault().getTable("TEST_PID");
+    m_builder = new SendableBuilderImpl();
+    m_builder.setTable(m_table);
+    m_controller = new PIDController(k_p, k_i, k_d, me.getEncoder(), me.getMotor());
+    m_controller.initSendable(m_builder);
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    logger.fine("Teardown: " + me.getType());
+    m_controller.disable();
+    m_controller.close();
+    m_controller = null;
+    me.reset();
+  }
+
+  private void setupAbsoluteTolerance() {
+    m_controller.setAbsoluteTolerance(absoluteTolerance);
+  }
+
+  private void setupOutputRange() {
+    m_controller.setOutputRange(-outputRange, outputRange);
+  }
+
+  @Test
+  public void testInitialSettings() {
+    setupAbsoluteTolerance();
+    setupOutputRange();
+    double setpoint = 2500.0;
+    m_controller.setSetpoint(setpoint);
+    assertFalse("PID did not begin disabled", m_controller.isEnabled());
+    assertEquals("PID.getError() did not start at " + setpoint, setpoint,
+        m_controller.getError(), 0);
+    m_builder.updateTable();
+    assertEquals(k_p, m_table.getEntry("p").getDouble(9999999), 0);
+    assertEquals(k_i, m_table.getEntry("i").getDouble(9999999), 0);
+    assertEquals(k_d, m_table.getEntry("d").getDouble(9999999), 0);
+    assertEquals(setpoint, m_table.getEntry("setpoint").getDouble(9999999), 0);
+    assertFalse(m_table.getEntry("enabled").getBoolean(true));
+  }
+
+  @Test
+  public void testRestartAfterEnable() {
+    setupAbsoluteTolerance();
+    setupOutputRange();
+    double setpoint = 2500.0;
+    m_controller.setSetpoint(setpoint);
+    m_controller.enable();
+    m_builder.updateTable();
+    assertTrue(m_table.getEntry("enabled").getBoolean(false));
+    assertTrue(m_controller.isEnabled());
+    assertThat(0.0, is(not(me.getMotor().get())));
+    m_controller.reset();
+    m_builder.updateTable();
+    assertFalse(m_table.getEntry("enabled").getBoolean(true));
+    assertFalse(m_controller.isEnabled());
+    assertEquals(0, me.getMotor().get(), 0);
+  }
+
+  @Test
+  public void testSetSetpoint() {
+    setupAbsoluteTolerance();
+    setupOutputRange();
+    Double setpoint = 2500.0;
+    m_controller.disable();
+    m_controller.setSetpoint(setpoint);
+    m_controller.enable();
+    assertEquals("Did not correctly set set-point", setpoint, new Double(m_controller
+        .getSetpoint()));
+  }
+
+  @Test(timeout = 10000)
+  public void testRotateToTarget() {
+    setupAbsoluteTolerance();
+    setupOutputRange();
+    double setpoint = 1000.0;
+    assertEquals(pidData() + "did not start at 0", 0, m_controller.get(), 0);
+    m_controller.setSetpoint(setpoint);
+    assertEquals(pidData() + "did not have an error of " + setpoint, setpoint,
+        m_controller.getError(), 0);
+    m_controller.enable();
+    Timer.delay(5);
+    m_controller.disable();
+    assertTrue(pidData() + "Was not on Target. Controller Error: " + m_controller.getError(),
+        m_controller.onTarget());
+  }
+
+  private String pidData() {
+    return me.getType() + " PID {P:" + m_controller.getP() + " I:" + m_controller.getI() + " D:"
+        + m_controller.getD() + "} ";
+  }
+
+
+  @Test(expected = RuntimeException.class)
+  public void testOnTargetNoToleranceSet() {
+    setupOutputRange();
+    m_controller.onTarget();
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PreferencesTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PreferencesTest.java
new file mode 100644
index 0000000..41633ad
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/PreferencesTest.java
@@ -0,0 +1,144 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.io.File;
+import java.io.FileOutputStream;
+import java.io.IOException;
+import java.io.OutputStream;
+import java.util.Arrays;
+import java.util.logging.Logger;
+
+import org.junit.Before;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.networktables.NetworkTable;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests the {@link Preferences}.
+ */
+public class PreferencesTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(PreferencesTest.class.getName());
+
+  private NetworkTable m_prefTable;
+  private Preferences m_pref;
+  private long m_check;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+
+  @Before
+  public void setUp() throws Exception {
+    NetworkTable.shutdown();
+    try {
+      File file = new File("networktables.ini");
+      file.mkdirs();
+      if (file.exists()) {
+        file.delete();
+      }
+      file.createNewFile();
+      OutputStream output = new FileOutputStream(file);
+      output
+          .write(("[NetworkTables Storage 3.0]\ndouble \"/Preferences/checkedValueInt\"=2\ndouble "
+              + "\"/Preferences/checkedValueDouble\"=.2\ndouble "
+              + "\"/Preferences/checkedValueFloat\"=3.14\ndouble "
+              + "\"/Preferences/checkedValueLong\"=172\nstring "
+              + "\"/Preferences/checkedValueString\"=\"hello \\nHow are you ?\"\nboolean "
+              + "\"/Preferences/checkedValueBoolean\"=false\n")
+              .getBytes());
+
+    } catch (IOException ex) {
+      ex.printStackTrace();
+    }
+    NetworkTable.initialize();
+
+    m_pref = Preferences.getInstance();
+    m_prefTable = NetworkTable.getTable("Preferences");
+    m_check = System.currentTimeMillis();
+  }
+
+
+  protected void remove() {
+    m_pref.remove("checkedValueLong");
+    m_pref.remove("checkedValueDouble");
+    m_pref.remove("checkedValueString");
+    m_pref.remove("checkedValueInt");
+    m_pref.remove("checkedValueFloat");
+    m_pref.remove("checkedValueBoolean");
+  }
+
+  protected void addCheckedValue() {
+    m_pref.putLong("checkedValueLong", m_check);
+    m_pref.putDouble("checkedValueDouble", 1);
+    m_pref.putString("checkedValueString", "checked");
+    m_pref.putInt("checkedValueInt", 1);
+    m_pref.putFloat("checkedValueFloat", 1);
+    m_pref.putBoolean("checkedValueBoolean", true);
+  }
+
+  /**
+   * Just checking to make sure our helper method works.
+   */
+  @Test
+  public void testRemove() {
+    remove();
+    assertEquals("Preferences was not empty!  Preferences in table: "
+        + Arrays.toString(m_pref.getKeys().toArray()),
+        1, m_pref.getKeys().size());
+  }
+
+  @Test
+  public void testRemoveAll() {
+    m_pref.removeAll();
+    assertEquals("Preferences was not empty!  Preferences in table: "
+        + Arrays.toString(m_pref.getKeys().toArray()),
+        1, m_pref.getKeys().size());
+  }
+
+  @Test
+  public void testAddRemoveSave() {
+    assertEquals(m_pref.getLong("checkedValueLong", 0), 172L);
+    assertEquals(m_pref.getDouble("checkedValueDouble", 0), .2, 0);
+    assertEquals(m_pref.getString("checkedValueString", ""), "hello \nHow are you ?");
+    assertEquals(m_pref.getInt("checkedValueInt", 0), 2);
+    assertEquals(m_pref.getFloat("checkedValueFloat", 0), 3.14, .001);
+    assertFalse(m_pref.getBoolean("checkedValueBoolean", true));
+    remove();
+    assertEquals(m_pref.getLong("checkedValueLong", 0), 0);
+    assertEquals(m_pref.getDouble("checkedValueDouble", 0), 0, 0);
+    assertEquals(m_pref.getString("checkedValueString", ""), "");
+    assertEquals(m_pref.getInt("checkedValueInt", 0), 0);
+    assertEquals(m_pref.getFloat("checkedValueFloat", 0), 0, 0);
+    assertFalse(m_pref.getBoolean("checkedValueBoolean", false));
+    addCheckedValue();
+    assertEquals(m_check, m_pref.getLong("checkedValueLong", 0));
+    assertEquals(m_pref.getDouble("checkedValueDouble", 0), 1, 0);
+    assertEquals(m_pref.getString("checkedValueString", ""), "checked");
+    assertEquals(m_pref.getInt("checkedValueInt", 0), 1);
+    assertEquals(m_pref.getFloat("checkedValueFloat", 0), 1, 0);
+    assertTrue(m_pref.getBoolean("checkedValueBoolean", false));
+  }
+
+  @Test
+  public void testPreferencesToNetworkTables() {
+    String networkedNumber = "networkCheckedValue";
+    int networkNumberValue = 100;
+    m_pref.putInt(networkedNumber, networkNumberValue);
+    assertEquals(networkNumberValue, (int) (m_prefTable.getNumber(networkedNumber, 9999999)));
+    m_pref.remove(networkedNumber);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java
new file mode 100644
index 0000000..a55a816
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RelayCrossConnectTest.java
@@ -0,0 +1,150 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.After;
+import org.junit.Before;
+import org.junit.Test;
+
+import edu.wpi.first.networktables.NetworkTable;
+import edu.wpi.first.networktables.NetworkTableInstance;
+import edu.wpi.first.wpilibj.Relay.Direction;
+import edu.wpi.first.wpilibj.Relay.InvalidValueException;
+import edu.wpi.first.wpilibj.Relay.Value;
+import edu.wpi.first.wpilibj.fixtures.RelayCrossConnectFixture;
+import edu.wpi.first.wpilibj.smartdashboard.SendableBuilderImpl;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+import static org.junit.Assert.assertEquals;
+import static org.junit.Assert.assertFalse;
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Tests the {@link RelayCrossConnectFixture}.
+ */
+public class RelayCrossConnectTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(RelayCrossConnectTest.class.getName());
+  private static final NetworkTable table =
+      NetworkTableInstance.getDefault().getTable("_RELAY_CROSS_CONNECT_TEST_");
+  private RelayCrossConnectFixture m_relayFixture;
+  private SendableBuilderImpl m_builder;
+
+
+  @Before
+  public void setUp() throws Exception {
+    m_relayFixture = TestBench.getRelayCrossConnectFixture();
+    m_relayFixture.setup();
+    m_builder = new SendableBuilderImpl();
+    m_builder.setTable(table);
+    m_relayFixture.getRelay().initSendable(m_builder);
+  }
+
+  @After
+  public void tearDown() throws Exception {
+    m_relayFixture.reset();
+    m_relayFixture.teardown();
+  }
+
+  @Test
+  public void testBothHigh() {
+    m_relayFixture.getRelay().setDirection(Direction.kBoth);
+    m_relayFixture.getRelay().set(Value.kOn);
+    m_builder.updateTable();
+    assertTrue("Input one was not high when relay set both high", m_relayFixture.getInputOne()
+        .get());
+    assertTrue("Input two was not high when relay set both high", m_relayFixture.getInputTwo()
+        .get());
+    assertEquals(Value.kOn, m_relayFixture.getRelay().get());
+    assertEquals("On", table.getEntry("Value").getString(""));
+  }
+
+  @Test
+  public void testFirstHigh() {
+    m_relayFixture.getRelay().setDirection(Direction.kBoth);
+    m_relayFixture.getRelay().set(Value.kForward);
+    m_builder.updateTable();
+    assertFalse("Input one was not low when relay set Value.kForward", m_relayFixture.getInputOne()
+        .get());
+    assertTrue("Input two was not high when relay set Value.kForward", m_relayFixture
+        .getInputTwo()
+        .get());
+    assertEquals(Value.kForward, m_relayFixture.getRelay().get());
+    assertEquals("Forward", table.getEntry("Value").getString(""));
+  }
+
+  @Test
+  public void testSecondHigh() {
+    m_relayFixture.getRelay().setDirection(Direction.kBoth);
+    m_relayFixture.getRelay().set(Value.kReverse);
+    m_builder.updateTable();
+    assertTrue("Input one was not high when relay set Value.kReverse", m_relayFixture.getInputOne()
+        .get());
+    assertFalse("Input two was not low when relay set Value.kReverse", m_relayFixture
+        .getInputTwo()
+        .get());
+    assertEquals(Value.kReverse, m_relayFixture.getRelay().get());
+    assertEquals("Reverse", table.getEntry("Value").getString(""));
+  }
+
+  @Test
+  public void testForwardDirection() {
+    m_relayFixture.getRelay().setDirection(Direction.kForward);
+    m_relayFixture.getRelay().set(Value.kOn);
+    m_builder.updateTable();
+    assertFalse("Input one was not low when relay set Value.kOn in kForward Direction",
+        m_relayFixture.getInputOne().get());
+    assertTrue("Input two was not high when relay set Value.kOn in kForward Direction",
+        m_relayFixture.getInputTwo().get());
+    assertEquals(Value.kOn, m_relayFixture.getRelay().get());
+    assertEquals("On", table.getEntry("Value").getString(""));
+  }
+
+  @Test
+  public void testReverseDirection() {
+    m_relayFixture.getRelay().setDirection(Direction.kReverse);
+    m_relayFixture.getRelay().set(Value.kOn);
+    m_builder.updateTable();
+    assertTrue("Input one was not high when relay set Value.kOn in kReverse Direction",
+        m_relayFixture.getInputOne().get());
+    assertFalse("Input two was not low when relay set Value.kOn in kReverse Direction",
+        m_relayFixture.getInputTwo().get());
+    assertEquals(Value.kOn, m_relayFixture.getRelay().get());
+    assertEquals("On", table.getEntry("Value").getString(""));
+  }
+
+  @Test(expected = InvalidValueException.class)
+  public void testSetValueForwardWithDirectionReverseThrowingException() {
+    m_relayFixture.getRelay().setDirection(Direction.kForward);
+    m_relayFixture.getRelay().set(Value.kReverse);
+  }
+
+  @Test(expected = InvalidValueException.class)
+  public void testSetValueReverseWithDirectionForwardThrowingException() {
+    m_relayFixture.getRelay().setDirection(Direction.kReverse);
+    m_relayFixture.getRelay().set(Value.kForward);
+  }
+
+  @Test
+  public void testInitialSettings() {
+    m_builder.updateTable();
+    assertEquals(Value.kOff, m_relayFixture.getRelay().get());
+    // Initially both outputs should be off
+    assertFalse(m_relayFixture.getInputOne().get());
+    assertFalse(m_relayFixture.getInputTwo().get());
+    assertEquals("Off", table.getEntry("Value").getString(""));
+  }
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RobotDriveTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RobotDriveTest.java
new file mode 100644
index 0000000..006c723
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/RobotDriveTest.java
@@ -0,0 +1,183 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.BeforeClass;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.drive.DifferentialDrive;
+import edu.wpi.first.wpilibj.drive.MecanumDrive;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Tests the eqivilance of RobotDrive and DifferentialDrive/MecanumDrive.
+ */
+public class RobotDriveTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(RobotDriveTest.class.getName());
+
+  private static MockSpeedController m_rdFrontLeft = new MockSpeedController();
+  private static MockSpeedController m_rdRearLeft = new MockSpeedController();
+  private static MockSpeedController m_rdFrontRight = new MockSpeedController();
+  private static MockSpeedController m_rdRearRight = new MockSpeedController();
+  private static MockSpeedController m_frontLeft = new MockSpeedController();
+  private static MockSpeedController m_rearLeft = new MockSpeedController();
+  private static MockSpeedController m_frontRight = new MockSpeedController();
+  private static MockSpeedController m_rearRight = new MockSpeedController();
+  private static RobotDrive m_robotDrive =
+      new RobotDrive(m_rdFrontLeft, m_rdRearLeft, m_rdFrontRight, m_rdRearRight);
+  private static DifferentialDrive m_differentialDrive =
+      new DifferentialDrive(m_frontLeft, m_frontRight);
+  private static MecanumDrive m_mecanumDrive =
+      new MecanumDrive(m_frontLeft, m_rearLeft, m_frontRight, m_rearRight);
+
+  private final double[] m_testJoystickValues = {1.0, 0.9, 0.5, 0.01, 0.0, -0.01, -0.5, -0.9,
+                                                 -1.0};
+  private final double[] m_testGyroValues = {0, 30, 45, 90, 135, 180, 225, 270, 305, 360, 540,
+                                             -45, -90, -135, -180, -225, -270, -305, -360, -540};
+
+  @BeforeClass
+  public static void before() {
+    m_differentialDrive.setDeadband(0.0);
+    m_differentialDrive.setSafetyEnabled(false);
+    m_mecanumDrive.setDeadband(0.0);
+    m_mecanumDrive.setSafetyEnabled(false);
+    m_robotDrive.setSafetyEnabled(false);
+  }
+
+  @Test
+  public void testTankDriveSquared() {
+    for (double leftJoystick : m_testJoystickValues) {
+      for (double rightJoystick : m_testJoystickValues) {
+        m_robotDrive.tankDrive(leftJoystick, rightJoystick);
+        m_differentialDrive.tankDrive(leftJoystick, rightJoystick);
+        assertEquals("Left Motor squared didn't match. Left Joystick: " + leftJoystick
+            + " Right Joystick: " + rightJoystick + " ", m_rdFrontLeft.get(), m_frontLeft.get(),
+            0.01);
+        assertEquals("Right Motor squared didn't match. Left Joystick: " + leftJoystick
+            + " Right Joystick: " + rightJoystick + " ", m_rdFrontRight.get(), m_frontRight.get(),
+            0.01);
+      }
+    }
+  }
+
+  @Test
+  public void testTankDrive() {
+    for (double leftJoystick : m_testJoystickValues) {
+      for (double rightJoystick : m_testJoystickValues) {
+        m_robotDrive.tankDrive(leftJoystick, rightJoystick, false);
+        m_differentialDrive.tankDrive(leftJoystick, rightJoystick, false);
+        assertEquals("Left Motor didn't match. Left Joystick: " + leftJoystick
+            + " Right Joystick: " + rightJoystick + " ", m_rdFrontLeft.get(), m_frontLeft.get(),
+            0.01);
+        assertEquals("Right Motor didn't match. Left Joystick: " + leftJoystick
+            + " Right Joystick: " + rightJoystick + " ", m_rdFrontRight.get(), m_frontRight.get(),
+            0.01);
+      }
+    }
+  }
+
+  @Test
+  public void testArcadeDriveSquared() {
+    for (double moveJoystick : m_testJoystickValues) {
+      for (double rotateJoystick : m_testJoystickValues) {
+        m_robotDrive.arcadeDrive(moveJoystick, rotateJoystick);
+        m_differentialDrive.arcadeDrive(moveJoystick, -rotateJoystick);
+        assertEquals("Left Motor squared didn't match. Move Joystick: " + moveJoystick
+            + " Rotate Joystick: " + rotateJoystick + " ", m_rdFrontLeft.get(), m_frontLeft.get(),
+            0.01);
+        assertEquals("Right Motor squared didn't match. Move Joystick: " + moveJoystick
+            + " Rotate Joystick: " + rotateJoystick + " ", m_rdFrontRight.get(),
+            m_frontRight.get(), 0.01);
+      }
+    }
+  }
+
+  @Test
+  public void testArcadeDrive() {
+    for (double moveJoystick : m_testJoystickValues) {
+      for (double rotateJoystick : m_testJoystickValues) {
+        m_robotDrive.arcadeDrive(moveJoystick, rotateJoystick, false);
+        m_differentialDrive.arcadeDrive(moveJoystick, -rotateJoystick, false);
+        assertEquals("Left Motor didn't match. Move Joystick: " + moveJoystick
+            + " Rotate Joystick: " + rotateJoystick + " ", m_rdFrontLeft.get(), m_frontLeft.get(),
+            0.01);
+        assertEquals("Right Motor didn't match. Move Joystick: " + moveJoystick
+            + " Rotate Joystick: " + rotateJoystick + " ", m_rdFrontRight.get(),
+            m_frontRight.get(), 0.01);
+      }
+    }
+  }
+
+  @Test
+  public void testMecanumPolar() {
+    System.out.println("magnitudeJoystick, directionJoystick , rotationJoystick, "
+        + "m_rdFrontLeft, m_frontLeft, m_rdFrontRight, m_frontRight, m_rdRearLeft, "
+        + "m_rearLeft, m_rdRearRight, m_rearRight");
+    for (double magnitudeJoystick : m_testJoystickValues) {
+      for (double directionJoystick : m_testGyroValues) {
+        for (double rotationJoystick : m_testJoystickValues) {
+          m_robotDrive.mecanumDrive_Polar(magnitudeJoystick, directionJoystick, rotationJoystick);
+          m_mecanumDrive.drivePolar(magnitudeJoystick, directionJoystick, rotationJoystick);
+          assertEquals("Left Front Motor didn't match. Magnitude Joystick: " + magnitudeJoystick
+              + " Direction Joystick: " + directionJoystick + " RotationJoystick: "
+              + rotationJoystick, m_rdFrontLeft.get(), m_frontLeft.get(), 0.01);
+          assertEquals("Right Front Motor didn't match. Magnitude Joystick: " + magnitudeJoystick
+              + " Direction Joystick: " + directionJoystick + " RotationJoystick: "
+              + rotationJoystick, m_rdFrontRight.get(), -m_frontRight.get(), 0.01);
+          assertEquals("Left Rear Motor didn't match. Magnitude Joystick: " + magnitudeJoystick
+              + " Direction Joystick: " + directionJoystick + " RotationJoystick: "
+              + rotationJoystick, m_rdRearLeft.get(), m_rearLeft.get(), 0.01);
+          assertEquals("Right Rear Motor didn't match. Magnitude Joystick: " + magnitudeJoystick
+              + " Direction Joystick: " + directionJoystick + " RotationJoystick: "
+              + rotationJoystick, m_rdRearRight.get(), -m_rearRight.get(), 0.01);
+        }
+      }
+    }
+  }
+
+  @Test
+  @SuppressWarnings("checkstyle:LocalVariableName")
+  public void testMecanumCartesian() {
+    for (double x_Joystick : m_testJoystickValues) {
+      for (double y_Joystick : m_testJoystickValues) {
+        for (double rotationJoystick : m_testJoystickValues) {
+          for (double gyroValue : m_testGyroValues) {
+            m_robotDrive.mecanumDrive_Cartesian(x_Joystick, y_Joystick, rotationJoystick,
+                                                gyroValue);
+            m_mecanumDrive.driveCartesian(x_Joystick, -y_Joystick, rotationJoystick, -gyroValue);
+            assertEquals("Left Front Motor didn't match. X Joystick: " + x_Joystick
+                + " Y Joystick: " + y_Joystick + " RotationJoystick: "
+                + rotationJoystick + " Gyro: " + gyroValue, m_rdFrontLeft.get(),
+                m_frontLeft.get(), 0.01);
+            assertEquals("Right Front Motor didn't match. X Joystick: " + x_Joystick
+                + " Y Joystick: " + y_Joystick + " RotationJoystick: "
+                + rotationJoystick + " Gyro: " + gyroValue, m_rdFrontRight.get(),
+                -m_frontRight.get(), 0.01);
+            assertEquals("Left Rear Motor didn't match. X Joystick: " + x_Joystick
+                + " Y Joystick: " + y_Joystick + " RotationJoystick: "
+                + rotationJoystick + " Gyro: " + gyroValue, m_rdRearLeft.get(),
+                m_rearLeft.get(), 0.01);
+            assertEquals("Right Rear Motor didn't match. X Joystick: " + x_Joystick
+                + " Y Joystick: " + y_Joystick + " RotationJoystick: "
+                + rotationJoystick + " Gyro: " + gyroValue, m_rdRearRight.get(),
+                -m_rearRight.get(), 0.01);
+          }
+        }
+      }
+    }
+  }
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/SampleTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/SampleTest.java
new file mode 100644
index 0000000..efcea23
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/SampleTest.java
@@ -0,0 +1,66 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.AfterClass;
+import org.junit.Before;
+import org.junit.BeforeClass;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.fixtures.SampleFixture;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertTrue;
+
+/**
+ * Sample test for a sample PID controller. This demonstrates the general pattern of how to create a
+ * test and use testing fixtures and categories. All tests must extend from {@link
+ * AbstractComsSetup} in order to ensure that Network Communications are set up before the tests are
+ * run.
+ */
+public class SampleTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(SampleTest.class.getName());
+
+  static SampleFixture fixture = new SampleFixture();
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  @BeforeClass
+  public static void classSetup() {
+    // Set up the fixture before the test is created
+    fixture.setup();
+  }
+
+  @Before
+  public void setUp() {
+    // Reset the fixture elements before every test
+    fixture.reset();
+  }
+
+  @AfterClass
+  public static void tearDown() {
+    // Clean up the fixture after the test
+    fixture.teardown();
+  }
+
+  /**
+   * This is just a sample test that asserts true. Any traditional junit code can be used, these are
+   * ordinary junit tests!
+   */
+  @Test
+  public void test() {
+    Timer.delay(0.5);
+    assertTrue(true);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java
new file mode 100644
index 0000000..2acd5bb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/TimerTest.java
@@ -0,0 +1,45 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+
+public class TimerTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(TimerTest.class.getName());
+  private static final long TIMER_TOLERANCE = (long) (2.5 * 1000);
+  private static final long TIMER_RUNTIME = 5 * 1000000;
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  @Test
+  public void delayTest() {
+    // Given
+    long startTime = RobotController.getFPGATime();
+
+    // When
+    Timer.delay(TIMER_RUNTIME / 1000000);
+    long endTime = RobotController.getFPGATime();
+    long difference = endTime - startTime;
+
+    // Then
+    long offset = difference - TIMER_RUNTIME;
+    assertEquals("Timer.delay ran " + offset + " microseconds too long", TIMER_RUNTIME, difference,
+        TIMER_TOLERANCE);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java
new file mode 100644
index 0000000..1a1c9f5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/WpiLibJTestSuite.java
@@ -0,0 +1,29 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj;
+
+import org.junit.runner.RunWith;
+import org.junit.runners.Suite;
+import org.junit.runners.Suite.SuiteClasses;
+
+import edu.wpi.first.wpilibj.test.AbstractTestSuite;
+
+/**
+ * Holds all of the tests in the root wpilibj directory. Please list alphabetically so that it is
+ * easy to determine if a test is missing from the list.
+ */
+@RunWith(Suite.class)
+@SuiteClasses({AnalogCrossConnectTest.class, AnalogPotentiometerTest.class,
+    BuiltInAccelerometerTest.class, ConstantsPortsTest.class, CounterTest.class,
+    DigitalGlitchFilterTest.class, DIOCrossConnectTest.class, DriverStationTest.class,
+    EncoderTest.class, FilterNoiseTest.class, FilterOutputTest.class, GyroTest.class,
+    MotorEncoderTest.class, MotorInvertingTest.class, PCMTest.class, PDPTest.class,
+    PIDTest.class, PreferencesTest.class, RelayCrossConnectTest.class,
+    RobotDriveTest.class, SampleTest.class, TimerTest.class})
+public class WpiLibJTestSuite extends AbstractTestSuite {
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java
new file mode 100644
index 0000000..6aa6c8e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/can/CANStatusTest.java
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.can;
+
+import org.junit.Test;
+
+import edu.wpi.first.hal.can.CANJNI;
+import edu.wpi.first.hal.can.CANStatus;
+
+public class CANStatusTest {
+  @Test
+  public void canStatusGetDoesntThrow() {
+    CANStatus status = new CANStatus();
+    CANJNI.GetCANStatus(status);
+    // Nothing we can assert, so just make sure it didn't throw.
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java
new file mode 100644
index 0000000..ece1dc9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/AnalogCrossConnectFixture.java
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.AnalogOutput;
+
+/**
+ * A fixture that connects an {@link AnalogInput} and an {@link AnalogOutput}.
+ */
+public abstract class AnalogCrossConnectFixture implements ITestFixture {
+  private boolean m_initialized = false;
+
+  private AnalogInput m_input;
+  private AnalogOutput m_output;
+
+  protected abstract AnalogInput giveAnalogInput();
+
+  protected abstract AnalogOutput giveAnalogOutput();
+
+
+  private void initialize() {
+    synchronized (this) {
+      if (!m_initialized) {
+        m_input = giveAnalogInput();
+        m_output = giveAnalogOutput();
+        m_initialized = true;
+      }
+    }
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup()
+   */
+  @Override
+  public boolean setup() {
+    initialize();
+    m_output.setVoltage(0);
+    return true;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset()
+   */
+  @Override
+  public boolean reset() {
+    initialize();
+    return true;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown()
+   */
+  @Override
+  public boolean teardown() {
+    m_input.close();
+    m_output.close();
+    return true;
+  }
+
+  /**
+   * Analog Output.
+   */
+  public final AnalogOutput getOutput() {
+    initialize();
+    return m_output;
+  }
+
+  public final AnalogInput getInput() {
+    initialize();
+    return m_input;
+  }
+
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java
new file mode 100644
index 0000000..ade9e69
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/DIOCrossConnectFixture.java
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.DigitalOutput;
+
+/**
+ * Connects a digital input to a digital output.
+ */
+public class DIOCrossConnectFixture implements ITestFixture {
+  private static final Logger logger = Logger.getLogger(DIOCrossConnectFixture.class.getName());
+
+  private final DigitalInput m_input;
+  private final DigitalOutput m_output;
+  private boolean m_allocated;
+
+  /**
+   * Constructs using two pre-allocated digital objects.
+   *
+   * @param input  The input
+   * @param output The output.
+   */
+  public DIOCrossConnectFixture(DigitalInput input, DigitalOutput output) {
+    assert input != null;
+    assert output != null;
+    m_input = input;
+    m_output = output;
+    m_allocated = false;
+  }
+
+  /**
+   * Constructs a {@link DIOCrossConnectFixture} using the ports of the digital objects.
+   *
+   * @param input  The port of the {@link DigitalInput}
+   * @param output The port of the {@link DigitalOutput}
+   */
+  public DIOCrossConnectFixture(Integer input, Integer output) {
+    assert input != null;
+    assert output != null;
+    assert !input.equals(output);
+    m_input = new DigitalInput(input);
+    m_output = new DigitalOutput(output);
+    m_allocated = true;
+  }
+
+  public DigitalInput getInput() {
+    return m_input;
+  }
+
+  public DigitalOutput getOutput() {
+    return m_output;
+  }
+
+  @Override
+  public boolean setup() {
+    return true;
+  }
+
+  @Override
+  public boolean reset() {
+    try {
+      m_input.cancelInterrupts();
+    } catch (IllegalStateException ex) {
+      // This will happen if the interrupt has not been allocated for this test.
+    }
+    m_output.set(false);
+    return true;
+  }
+
+  @Override
+  public boolean teardown() {
+    logger.log(Level.FINE, "Begining teardown");
+    if (m_allocated) {
+      m_input.close();
+      m_output.close();
+      m_allocated = false;
+    }
+    return true;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java
new file mode 100644
index 0000000..a944421
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeCounterFixture.java
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.Counter;
+import edu.wpi.first.wpilibj.mockhardware.FakeCounterSource;
+
+/**
+ * A fixture that can test the {@link Counter} using a {@link DIOCrossConnectFixture}.
+ */
+public class FakeCounterFixture implements ITestFixture {
+  private static final Logger logger = Logger.getLogger(FakeEncoderFixture.class.getName());
+
+  private final DIOCrossConnectFixture m_dio;
+  private boolean m_allocated;
+  private final FakeCounterSource m_source;
+  private final Counter m_counter;
+
+  /**
+   * Constructs a FakeCounterFixture.
+   *
+   * @param dio A previously allocated DIOCrossConnectFixture (must be freed outside this class)
+   */
+  public FakeCounterFixture(DIOCrossConnectFixture dio) {
+    m_dio = dio;
+    m_allocated = false;
+    m_source = new FakeCounterSource(dio.getOutput());
+    m_counter = new Counter(dio.getInput());
+  }
+
+
+  /**
+   * Constructs a FakeCounterFixture using two port numbers.
+   *
+   * @param input  the input port
+   * @param output the output port
+   */
+  public FakeCounterFixture(int input, int output) {
+    m_dio = new DIOCrossConnectFixture(input, output);
+    m_allocated = true;
+    m_source = new FakeCounterSource(m_dio.getOutput());
+    m_counter = new Counter(m_dio.getInput());
+  }
+
+  /**
+   * Retrieves the FakeCouterSource for use.
+   *
+   * @return the FakeCounterSource
+   */
+  public FakeCounterSource getFakeCounterSource() {
+    return m_source;
+  }
+
+  /**
+   * Gets the Counter for use.
+   *
+   * @return the Counter
+   */
+  public Counter getCounter() {
+    return m_counter;
+  }
+
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup()
+   */
+  @Override
+  public boolean setup() {
+    return true;
+
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset()
+   */
+  @Override
+  public boolean reset() {
+    m_counter.reset();
+    return true;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown()
+   */
+  @Override
+  public boolean teardown() {
+    logger.log(Level.FINE, "Begining teardown");
+    m_counter.close();
+    m_source.close();
+    if (m_allocated) { // Only tear down the dio if this class allocated it
+      m_dio.teardown();
+      m_allocated = false;
+    }
+    return true;
+  }
+
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java
new file mode 100644
index 0000000..2b2b852
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FakeEncoderFixture.java
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.mockhardware.FakeEncoderSource;
+
+/**
+ * An encoder that uses two {@link DIOCrossConnectFixture DIOCrossConnectFixtures} to test the
+ * {@link Encoder}.
+ */
+public class FakeEncoderFixture implements ITestFixture {
+  private static final Logger logger = Logger.getLogger(FakeEncoderFixture.class.getName());
+
+  private final DIOCrossConnectFixture m_dio1;
+  private final DIOCrossConnectFixture m_dio2;
+  private boolean m_allocated;
+
+  private final FakeEncoderSource m_source;
+  private int[] m_sourcePort = new int[2];
+  private final Encoder m_encoder;
+  private int[] m_encoderPort = new int[2];
+
+  /**
+   * Constructs a FakeEncoderFixture from two DIOCrossConnectFixture.
+   */
+  public FakeEncoderFixture(DIOCrossConnectFixture dio1, DIOCrossConnectFixture dio2) {
+    assert dio1 != null;
+    assert dio2 != null;
+    m_dio1 = dio1;
+    m_dio2 = dio2;
+    m_allocated = false;
+    m_source = new FakeEncoderSource(dio1.getOutput(), dio2.getOutput());
+    m_encoder = new Encoder(dio1.getInput(), dio2.getInput());
+  }
+
+  /**
+   * Construcst a FakeEncoderFixture from a set of Digital I/O ports.
+   */
+  public FakeEncoderFixture(int inputA, int outputA, int inputB, int outputB) {
+    assert outputA != outputB;
+    assert outputA != inputA;
+    assert outputA != inputB;
+    assert outputB != inputA;
+    assert outputB != inputB;
+    assert inputA != inputB;
+    m_dio1 = new DIOCrossConnectFixture(inputA, outputA);
+    m_dio2 = new DIOCrossConnectFixture(inputB, outputB);
+    m_allocated = true;
+    m_sourcePort[0] = outputA;
+    m_sourcePort[1] = outputB;
+    m_encoderPort[0] = inputA;
+    m_encoderPort[1] = inputB;
+    m_source = new FakeEncoderSource(m_dio1.getOutput(), m_dio2.getOutput());
+    m_encoder = new Encoder(m_dio1.getInput(), m_dio2.getInput());
+  }
+
+  public FakeEncoderSource getFakeEncoderSource() {
+    return m_source;
+  }
+
+  public Encoder getEncoder() {
+    return m_encoder;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup()
+   */
+  @Override
+  public boolean setup() {
+    return true;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset()
+   */
+  @Override
+  public boolean reset() {
+    m_dio1.reset();
+    m_dio2.reset();
+    m_encoder.reset();
+    return true;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown()
+   */
+  @Override
+  public boolean teardown() {
+    logger.fine("Begining teardown");
+    m_source.close();
+    logger.finer("Source freed " + m_sourcePort[0] + ",  " + m_sourcePort[1]);
+    m_encoder.close();
+    logger.finer("Encoder freed " + m_encoderPort[0] + ", " + m_encoderPort[1]);
+    if (m_allocated) {
+      m_dio1.teardown();
+      m_dio2.teardown();
+    }
+    return true;
+  }
+
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FilterNoiseFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FilterNoiseFixture.java
new file mode 100644
index 0000000..ee899b3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FilterNoiseFixture.java
@@ -0,0 +1,159 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.lang.reflect.ParameterizedType;
+import java.util.Random;
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.PIDSource;
+import edu.wpi.first.wpilibj.PIDSourceType;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+/**
+ * Represents a physically connected Motor and Encoder to allow for unit tests on these different
+ * pairs<br> Designed to allow the user to easily setup and tear down the fixture to allow for
+ * reuse. This class should be explicitly instantiated in the TestBed class to allow any test to
+ * access this fixture. This allows tests to be mailable so that you can easily reconfigure the
+ * physical testbed without breaking the tests.
+ */
+public abstract class FilterNoiseFixture<T extends PIDSource> implements ITestFixture {
+  private static final Logger logger = Logger.getLogger(FilterNoiseFixture.class.getName());
+  private boolean m_initialized = false;
+  private boolean m_tornDown = false;
+  protected T m_filter;
+  private NoiseGenerator m_data;
+
+  /**
+   * Where the implementer of this class should pass the filter constructor.
+   */
+  protected abstract T giveFilter(PIDSource source);
+
+  private void initialize() {
+    synchronized (this) {
+      if (!m_initialized) {
+        m_initialized = true; // This ensures it is only initialized once
+
+        m_data = new NoiseGenerator(TestBench.kStdDev) {
+          @Override
+          @SuppressWarnings("ParameterName")
+          public double getData(double t) {
+            return 100.0 * Math.sin(2.0 * Math.PI * t);
+          }
+        };
+        m_filter = giveFilter(m_data);
+      }
+    }
+  }
+
+  @Override
+  public boolean setup() {
+    initialize();
+    return true;
+  }
+
+  /**
+   * Gets the filter for this Object.
+   *
+   * @return the filter this object refers too
+   */
+  public T getFilter() {
+    initialize();
+    return m_filter;
+  }
+
+  /**
+   * Gets the noise generator for this object.
+   *
+   * @return the noise generator that this object refers too
+   */
+  public NoiseGenerator getNoiseGenerator() {
+    initialize();
+    return m_data;
+  }
+
+  /**
+   * Retrieves the name of the filter that this object refers to.
+   *
+   * @return The simple name of the filter {@link Class#getSimpleName()}
+   */
+  public String getType() {
+    initialize();
+    return m_filter.getClass().getSimpleName();
+  }
+
+  // test here?
+
+  @Override
+  public boolean reset() {
+    return true;
+  }
+
+  @Override
+  public boolean teardown() {
+    return true;
+  }
+
+  @Override
+  public String toString() {
+    StringBuilder string = new StringBuilder("FilterNoiseFixture<");
+    // Get the generic type as a class
+    @SuppressWarnings("unchecked")
+    Class<T> class1 =
+        (Class<T>) ((ParameterizedType) getClass().getGenericSuperclass())
+            .getActualTypeArguments()[0];
+    string.append(class1.getSimpleName());
+    string.append(">");
+    return string.toString();
+  }
+
+  /**
+   * Adds Gaussian white noise to a function returning data. The noise will have the standard
+   * deviation provided in the constructor.
+   */
+  public abstract class NoiseGenerator implements PIDSource {
+    private double m_noise = 0.0;
+
+    // Make sure first call to pidGet() uses count == 0
+    private double m_count = -TestBench.kFilterStep;
+
+    private double m_stdDev;
+    private Random m_gen = new Random();
+
+    NoiseGenerator(double stdDev) {
+      m_stdDev = stdDev;
+    }
+
+    @SuppressWarnings("ParameterName")
+    public abstract double getData(double t);
+
+    @Override
+    public void setPIDSourceType(PIDSourceType pidSource) {
+    }
+
+    @Override
+    public PIDSourceType getPIDSourceType() {
+      return PIDSourceType.kDisplacement;
+    }
+
+    public double get() {
+      return getData(m_count) + m_noise;
+    }
+
+    @Override
+    public double pidGet() {
+      m_noise = m_gen.nextGaussian() * m_stdDev;
+      m_count += TestBench.kFilterStep;
+      return getData(m_count) + m_noise;
+    }
+
+    public void reset() {
+      m_count = -TestBench.kFilterStep;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FilterOutputFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FilterOutputFixture.java
new file mode 100644
index 0000000..3c31982
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/FilterOutputFixture.java
@@ -0,0 +1,159 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.lang.reflect.ParameterizedType;
+import java.util.function.DoubleFunction;
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.PIDSource;
+import edu.wpi.first.wpilibj.PIDSourceType;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+/**
+ * Represents a filter to allow for unit tests on them<br> Designed to allow the user to easily
+ * setup and tear down the fixture to allow for reuse. This class should be explicitly instantiated
+ * in the TestBed class to allow any test to access this fixture. This allows tests to be mailable
+ * so that you can easily reconfigure the physical testbed without breaking the tests.
+ */
+public abstract class FilterOutputFixture<T extends PIDSource> implements ITestFixture {
+  private static final Logger logger = Logger.getLogger(FilterOutputFixture.class.getName());
+  private boolean m_initialized = false;
+  private boolean m_tornDown = false;
+  protected T m_filter;
+  protected DataWrapper m_data;
+  private double m_expectedOutput;
+
+  public FilterOutputFixture(double expectedOutput) {
+    m_expectedOutput = expectedOutput;
+  }
+
+  /**
+   * Get expected output of fixture.
+   */
+  public double getExpectedOutput() {
+    return m_expectedOutput;
+  }
+
+  public static DoubleFunction<Double> getData = new DoubleFunction<Double>() {
+    @Override
+    @SuppressWarnings("ParameterName")
+    public Double apply(double t) {
+      return 100.0 * Math.sin(2.0 * Math.PI * t) + 20.0 * Math.cos(50.0 * Math.PI * t);
+    }
+  };
+
+  public static DoubleFunction<Double> getPulseData = new DoubleFunction<Double>() {
+    @Override
+    @SuppressWarnings("ParameterName")
+    public Double apply(double t) {
+      if (Math.abs(t - 1.0) < 0.001) {
+        return 1.0;
+      } else {
+        return 0.0;
+      }
+    }
+  };
+
+  /**
+   * Where the implementer of this class should pass the filter constructor.
+   */
+  protected abstract T giveFilter();
+
+  private void initialize() {
+    synchronized (this) {
+      if (!m_initialized) {
+        m_initialized = true; // This ensures it is only initialized once
+
+        m_filter = giveFilter();
+      }
+    }
+  }
+
+  @Override
+  public boolean setup() {
+    initialize();
+    return true;
+  }
+
+  /**
+   * Gets the filter for this Object.
+   *
+   * @return the filter this object refers too
+   */
+  public T getFilter() {
+    initialize();
+    return m_filter;
+  }
+
+  /**
+   * Retrieves the name of the filter that this object refers to.
+   *
+   * @return The simple name of the filter {@link Class#getSimpleName()}
+   */
+  public String getType() {
+    initialize();
+    return m_filter.getClass().getSimpleName();
+  }
+
+  @Override
+  public boolean reset() {
+    m_data.reset();
+    return true;
+  }
+
+  @Override
+  public boolean teardown() {
+    return true;
+  }
+
+  @Override
+  public String toString() {
+    StringBuilder string = new StringBuilder("FilterOutputFixture<");
+    // Get the generic type as a class
+    @SuppressWarnings("unchecked")
+    Class<T> class1 =
+        (Class<T>) ((ParameterizedType) getClass().getGenericSuperclass())
+            .getActualTypeArguments()[0];
+    string.append(class1.getSimpleName());
+    string.append(">");
+    return string.toString();
+  }
+
+  public class DataWrapper implements PIDSource {
+    // Make sure first call to pidGet() uses count == 0
+    private double m_count = -TestBench.kFilterStep;
+
+    private DoubleFunction<Double> m_func;
+
+    public DataWrapper(DoubleFunction<Double> func) {
+      m_func = func;
+    }
+
+    @Override
+    public void setPIDSourceType(PIDSourceType pidSource) {
+    }
+
+
+    @Override
+    public PIDSourceType getPIDSourceType() {
+      return PIDSourceType.kDisplacement;
+    }
+
+
+    @Override
+    public double pidGet() {
+      m_count += TestBench.kFilterStep;
+      return m_func.apply(m_count);
+    }
+
+    public void reset() {
+      m_count = -TestBench.kFilterStep;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java
new file mode 100644
index 0000000..df797f1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/ITestFixture.java
@@ -0,0 +1,47 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import edu.wpi.first.wpilibj.test.TestBench;
+
+/**
+ * Master interface for all test fixtures. This ensures that all test fixtures have setup and
+ * teardown methods, to ensure that the tests run properly. Test fixtures should be modeled around
+ * the content of a test, rather than the actual physical layout of the testing board. They should
+ * obtain references to hardware from the {@link TestBench} class, which is a singleton. Testing
+ * Fixtures are responsible for ensuring that the hardware is in an appropriate state for the start
+ * of a test, and ensuring that future tests will not be affected by the results of a test.
+ */
+public interface ITestFixture {
+  /**
+   * Performs any required setup for this fixture, ensuring that all fixture elements are ready for
+   * testing.
+   *
+   * @return True if the fixture is ready for testing
+   */
+  boolean setup();
+
+  /**
+   * Resets the fixture back to test start state. This should be called by the test class in the
+   * test setup method to ensure that the hardware is in the default state. This differs from {@link
+   * ITestFixture#setup()} as that is called once, before the class is constructed, so it may need
+   * to start sensors. This method should not have to start anything, just reset sensors and ensure
+   * that motors are stopped.
+   *
+   * @return True if the fixture is ready for testing
+   */
+  boolean reset();
+
+  /**
+   * Performs any required teardown after use of the fixture, ensuring that future tests will not
+   * run into conflicts.
+   *
+   * @return True if the teardown succeeded
+   */
+  boolean teardown();
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
new file mode 100644
index 0000000..fab3306
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/MotorEncoderFixture.java
@@ -0,0 +1,245 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.lang.reflect.ParameterizedType;
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.Counter;
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.Encoder;
+import edu.wpi.first.wpilibj.PWM;
+import edu.wpi.first.wpilibj.SpeedController;
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.test.TestBench;
+
+/**
+ * Represents a physically connected Motor and Encoder to allow for unit tests on these different
+ * pairs<br> Designed to allow the user to easily setup and tear down the fixture to allow for
+ * reuse. This class should be explicitly instantiated in the TestBed class to allow any test to
+ * access this fixture. This allows tests to be mailable so that you can easily reconfigure the
+ * physical testbed without breaking the tests.
+ */
+public abstract class MotorEncoderFixture<T extends SpeedController> implements ITestFixture {
+  private static final Logger logger = Logger.getLogger(MotorEncoderFixture.class.getName());
+  private boolean m_initialized = false;
+  private boolean m_tornDown = false;
+  protected T m_motor;
+  private Encoder m_encoder;
+  private final Counter[] m_counters = new Counter[2];
+  protected DigitalInput m_alphaSource; // Stored so it can be freed at tear down
+  protected DigitalInput m_betaSource;
+
+  /**
+   * Default constructor for a MotorEncoderFixture.
+   */
+  public MotorEncoderFixture() {
+  }
+
+  public abstract int getPDPChannel();
+
+  /**
+   * Where the implementer of this class should pass the speed controller Constructor should only be
+   * called from outside this class if the Speed controller is not also an implementation of PWM
+   * interface.
+   *
+   * @return SpeedController
+   */
+  protected abstract T giveSpeedController();
+
+  /**
+   * Where the implementer of this class should pass one of the digital inputs.
+   *
+   * <p>CONSTRUCTOR SHOULD NOT BE CALLED FROM OUTSIDE THIS CLASS!
+   *
+   * @return DigitalInput
+   */
+  protected abstract DigitalInput giveDigitalInputA();
+
+  /**
+   * Where the implementer fo this class should pass the other digital input.
+   *
+   * <p>CONSTRUCTOR SHOULD NOT BE CALLED FROM OUTSIDE THIS CLASS!
+   *
+   * @return Input B to be used when this class is instantiated
+   */
+  protected abstract DigitalInput giveDigitalInputB();
+
+  private void initialize() {
+    synchronized (this) {
+      if (!m_initialized) {
+        m_initialized = true; // This ensures it is only initialized once
+
+        m_alphaSource = giveDigitalInputA();
+        m_betaSource = giveDigitalInputB();
+
+
+        m_encoder = new Encoder(m_alphaSource, m_betaSource);
+        m_counters[0] = new Counter(m_alphaSource);
+        m_counters[1] = new Counter(m_betaSource);
+        logger.fine("Creating the speed controller!");
+        m_motor = giveSpeedController();
+      }
+    }
+  }
+
+  @Override
+  public boolean setup() {
+    initialize();
+    return true;
+  }
+
+  /**
+   * Gets the motor for this Object.
+   *
+   * @return the motor this object refers too
+   */
+  public T getMotor() {
+    initialize();
+    return m_motor;
+  }
+
+  /**
+   * Gets the encoder for this object.
+   *
+   * @return the encoder that this object refers too
+   */
+  public Encoder getEncoder() {
+    initialize();
+    return m_encoder;
+  }
+
+  public Counter[] getCounters() {
+    initialize();
+    return m_counters;
+  }
+
+  /**
+   * Retrieves the name of the motor that this object refers to.
+   *
+   * @return The simple name of the motor {@link Class#getSimpleName()}
+   */
+  public String getType() {
+    initialize();
+    return m_motor.getClass().getSimpleName();
+  }
+
+  /**
+   * Checks to see if the speed of the motor is within some range of a given value. This is used
+   * instead of equals() because doubles can have inaccuracies.
+   *
+   * @param value    The value to compare against
+   * @param accuracy The accuracy range to check against to see if the
+   * @return true if the range of values between motors speed accuracy contains the 'value'.
+   */
+  public boolean isMotorSpeedWithinRange(double value, double accuracy) {
+    initialize();
+    return Math.abs(Math.abs(m_motor.get()) - Math.abs(value)) < Math.abs(accuracy);
+  }
+
+  @Override
+  public boolean reset() {
+    initialize();
+    m_motor.setInverted(false);
+    m_motor.set(0);
+    Timer.delay(TestBench.MOTOR_STOP_TIME); // DEFINED IN THE TestBench
+    m_encoder.reset();
+    for (Counter c : m_counters) {
+      c.reset();
+    }
+
+    boolean wasReset = true;
+    wasReset = wasReset && m_motor.get() == 0;
+    wasReset = wasReset && m_encoder.get() == 0;
+    for (Counter c : m_counters) {
+      wasReset = wasReset && c.get() == 0;
+    }
+
+    return wasReset;
+  }
+
+
+  /**
+   * Safely tears down the MotorEncoder Fixture in a way that makes sure that even if an object
+   * fails to initialize the rest of the fixture can still be torn down and the resources
+   * deallocated.
+   */
+  @Override
+  @SuppressWarnings("Regexp")
+  public boolean teardown() {
+    String type;
+    if (m_motor != null) {
+      type = getType();
+    } else {
+      type = "null";
+    }
+    if (!m_tornDown) {
+      boolean wasNull = false;
+      if (m_motor instanceof PWM && m_motor != null) {
+        ((PWM) m_motor).close();
+        m_motor = null;
+      } else if (m_motor == null) {
+        wasNull = true;
+      }
+      if (m_encoder != null) {
+        m_encoder.close();
+        m_encoder = null;
+      } else {
+        wasNull = true;
+      }
+      if (m_counters[0] != null) {
+        m_counters[0].close();
+        m_counters[0] = null;
+      } else {
+        wasNull = true;
+      }
+      if (m_counters[1] != null) {
+        m_counters[1].close();
+        m_counters[1] = null;
+      } else {
+        wasNull = true;
+      }
+      if (m_alphaSource != null) {
+        m_alphaSource.close();
+        m_alphaSource = null;
+      } else {
+        wasNull = true;
+      }
+      if (m_betaSource != null) {
+        m_betaSource.close();
+        m_betaSource = null;
+      } else {
+        wasNull = true;
+      }
+
+      m_tornDown = true;
+
+      if (wasNull) {
+        throw new NullPointerException("MotorEncoderFixture had null params at teardown");
+      }
+    } else {
+      throw new RuntimeException(type + " Motor Encoder torn down multiple times");
+    }
+
+    return true;
+  }
+
+  @Override
+  public String toString() {
+    StringBuilder string = new StringBuilder("MotorEncoderFixture<");
+    // Get the generic type as a class
+    @SuppressWarnings("unchecked")
+    Class<T> class1 =
+        (Class<T>) ((ParameterizedType) getClass().getGenericSuperclass())
+            .getActualTypeArguments()[0];
+    string.append(class1.getSimpleName());
+    string.append(">");
+    return string.toString();
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java
new file mode 100644
index 0000000..382b4bb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/RelayCrossConnectFixture.java
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.Relay;
+
+/**
+ * A connection between a {@link Relay} and two {@link DigitalInput DigitalInputs}.
+ */
+public abstract class RelayCrossConnectFixture implements ITestFixture {
+  private DigitalInput m_inputOne;
+  private DigitalInput m_inputTwo;
+  private Relay m_relay;
+
+  private boolean m_initialized = false;
+  private boolean m_freed = false;
+
+
+  protected abstract Relay giveRelay();
+
+  protected abstract DigitalInput giveInputOne();
+
+  protected abstract DigitalInput giveInputTwo();
+
+  private void initialize() {
+    synchronized (this) {
+      if (!m_initialized) {
+        m_relay = giveRelay();
+        m_inputOne = giveInputOne();
+        m_inputTwo = giveInputTwo();
+        m_initialized = true;
+      }
+    }
+  }
+
+  public Relay getRelay() {
+    initialize();
+    return m_relay;
+  }
+
+  public DigitalInput getInputOne() {
+    initialize();
+    return m_inputOne;
+  }
+
+  public DigitalInput getInputTwo() {
+    initialize();
+    return m_inputTwo;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#setup()
+   */
+  @Override
+  public boolean setup() {
+    initialize();
+    return true;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#reset()
+   */
+  @Override
+  public boolean reset() {
+    initialize();
+    return true;
+  }
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.fixtures.ITestFixture#teardown()
+   */
+  @Override
+  public boolean teardown() {
+    if (!m_freed) {
+      m_relay.close();
+      m_inputOne.close();
+      m_inputTwo.close();
+      m_freed = true;
+    } else {
+      throw new RuntimeException("You attempted to free the "
+          + RelayCrossConnectFixture.class.getSimpleName() + " multiple times");
+    }
+    return true;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java
new file mode 100644
index 0000000..994c6ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/SampleFixture.java
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+
+/**
+ * This is an example of how to use the {@link ITestFixture} interface to create test fixtures for a
+ * test.
+ */
+public class SampleFixture implements ITestFixture {
+  @Override
+  public boolean setup() {
+    /*
+     * If this fixture actually accessed the hardware, here is where it would
+     * set up the starting state of the test bench. For example, reseting
+     * encoders, ensuring motors are stopped, reseting any serial communication
+     * if necessary, etc.
+     */
+    return true;
+  }
+
+  @Override
+  public boolean reset() {
+    /*
+     * This is where the fixture would reset any sensors or motors used by the
+     * fixture to test default state. This method should not worry about whether
+     * or not the sensors have been allocated correctly, that is the job of the
+     * setup function.
+     */
+    return false;
+  }
+
+  @Override
+  public boolean teardown() {
+    /*
+     * This is where the fixture would deallocate and reset back to normal
+     * conditions any necessary hardware. This includes ensuring motors are
+     * stopped, stoppable sensors are actually stopped, ensuring serial
+     * communications are ready for the next test, etc.
+     */
+    return true;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java
new file mode 100644
index 0000000..afeaf38
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/fixtures/TiltPanCameraFixture.java
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.fixtures;
+
+import java.util.logging.Logger;
+
+import edu.wpi.first.wpilibj.AnalogGyro;
+import edu.wpi.first.wpilibj.Servo;
+import edu.wpi.first.wpilibj.Timer;
+
+/**
+ * A class to represent the a physical Camera with two servos (tilt and pan) designed to test to see
+ * if the gyroscope is operating normally.
+ */
+public abstract class TiltPanCameraFixture implements ITestFixture {
+  public static final Logger logger = Logger.getLogger(TiltPanCameraFixture.class.getName());
+
+  public static final double RESET_TIME = 2.0;
+  private AnalogGyro m_gyro;
+  private AnalogGyro m_gyroParam;
+  private Servo m_tilt;
+  private Servo m_pan;
+  private boolean m_initialized = false;
+
+
+  protected abstract AnalogGyro giveGyro();
+
+  protected abstract AnalogGyro giveGyroParam(int center, double offset);
+
+  protected abstract Servo giveTilt();
+
+  protected abstract Servo givePan();
+
+  /**
+   * Constructs the TiltPanCamera.
+   */
+  public TiltPanCameraFixture() {
+  }
+
+  @Override
+  public boolean setup() {
+    boolean wasSetup = false;
+    if (!m_initialized) {
+      m_initialized = true;
+      m_tilt = giveTilt();
+      m_tilt.set(0);
+      m_pan = givePan();
+      m_pan.set(0);
+      Timer.delay(RESET_TIME);
+
+      logger.fine("Initializing the gyro");
+      m_gyro = giveGyro();
+      m_gyro.reset();
+      wasSetup = true;
+    }
+    return wasSetup;
+  }
+
+  @Override
+  public boolean reset() {
+    if (m_gyro != null) {
+      m_gyro.reset();
+    }
+    return true;
+  }
+
+  public Servo getTilt() {
+    return m_tilt;
+  }
+
+  public Servo getPan() {
+    return m_pan;
+  }
+
+  public AnalogGyro getGyro() {
+    return m_gyro;
+  }
+
+  public AnalogGyro getGyroParam() {
+    return m_gyroParam;
+  }
+
+  // Do not call unless all other instances of Gyro have been deallocated
+  public void setupGyroParam(int center, double offset) {
+    m_gyroParam = giveGyroParam(center, offset);
+    m_gyroParam.reset();
+  }
+
+  public void freeGyro() {
+    m_gyro.close();
+    m_gyro = null;
+  }
+
+  @Override
+  public boolean teardown() {
+    m_tilt.close();
+    m_tilt = null;
+    m_pan.close();
+    m_pan = null;
+    if (m_gyro != null) { //in case not freed during gyro tests
+      m_gyro.close();
+      m_gyro = null;
+    }
+    if (m_gyroParam != null) { //in case gyro tests failed before getting to this point
+      m_gyroParam.close();
+      m_gyroParam = null;
+    }
+    return true;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java
new file mode 100644
index 0000000..5608491
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeCounterSource.java
@@ -0,0 +1,138 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.mockhardware;
+
+import edu.wpi.first.wpilibj.DigitalOutput;
+import edu.wpi.first.wpilibj.Timer;
+
+/**
+ * Simulates an encoder for testing purposes.
+ */
+public class FakeCounterSource implements AutoCloseable {
+  private Thread m_task;
+  private int m_count;
+  private int m_milliSec;
+  private DigitalOutput m_output;
+  private boolean m_allocated;
+
+  /**
+   * Thread object that allows emulation of an encoder.
+   */
+  private class EncoderThread extends Thread {
+    FakeCounterSource m_encoder;
+
+    EncoderThread(FakeCounterSource encode) {
+      m_encoder = encode;
+    }
+
+    @Override
+    public void run() {
+      m_encoder.m_output.set(false);
+      try {
+        for (int i = 0; i < m_encoder.m_count; i++) {
+          Thread.sleep(m_encoder.m_milliSec);
+          m_encoder.m_output.set(true);
+          Thread.sleep(m_encoder.m_milliSec);
+          m_encoder.m_output.set(false);
+        }
+      } catch (InterruptedException ex) {
+        Thread.currentThread().interrupt();
+      }
+    }
+  }
+
+  /**
+   * Create a fake encoder on a given port.
+   *
+   * @param output the port to output the given signal to
+   */
+  public FakeCounterSource(DigitalOutput output) {
+    m_output = output;
+    m_allocated = false;
+    initEncoder();
+  }
+
+  /**
+   * Create a fake encoder on a given port.
+   *
+   * @param port The port the encoder is supposed to be on
+   */
+  public FakeCounterSource(int port) {
+    m_output = new DigitalOutput(port);
+    m_allocated = true;
+    initEncoder();
+  }
+
+  /**
+   * Destroy Object with minimum memory leak.
+   */
+  @Override
+  public void close() {
+    m_task = null;
+    if (m_allocated) {
+      m_output.close();
+      m_output = null;
+      m_allocated = false;
+    }
+  }
+
+  /**
+   * Common initailization code.
+   */
+  private void initEncoder() {
+    m_milliSec = 1;
+    m_task = new EncoderThread(this);
+    m_output.set(false);
+  }
+
+  /**
+   * Starts the thread execution task.
+   */
+  public void start() {
+    m_task.start();
+  }
+
+  /**
+   * Waits for the thread to complete.
+   */
+  public void complete() {
+    try {
+      m_task.join();
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    m_task = new EncoderThread(this);
+    Timer.delay(.01);
+  }
+
+  /**
+   * Starts and completes a task set - does not return until thred has finished its operations.
+   */
+  public void execute() {
+    start();
+    complete();
+  }
+
+  /**
+   * Sets the count to run encoder.
+   *
+   * @param count The count to emulate to the controller
+   */
+  public void setCount(int count) {
+    m_count = count;
+  }
+
+  /**
+   * Specify the rate to send pulses.
+   *
+   * @param milliSec The rate to send out pulses at
+   */
+  public void setRate(int milliSec) {
+    m_milliSec = milliSec;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java
new file mode 100644
index 0000000..bdb6886
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakeEncoderSource.java
@@ -0,0 +1,180 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2014-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.mockhardware;
+
+import edu.wpi.first.wpilibj.DigitalOutput;
+import edu.wpi.first.wpilibj.Timer;
+
+/**
+ * Emulates a quadrature encoder.
+ */
+public class FakeEncoderSource implements AutoCloseable {
+  private Thread m_task;
+  private int m_count;
+  private int m_milliSec;
+  private boolean m_forward;
+  private final DigitalOutput m_outputA;
+  private final DigitalOutput m_outputB;
+  private final boolean m_allocatedOutputs;
+
+  /**
+   * Thread object that allows emulation of a quadrature encoder.
+   */
+  private class QuadEncoderThread extends Thread {
+    FakeEncoderSource m_encoder;
+
+    QuadEncoderThread(FakeEncoderSource encode) {
+      m_encoder = encode;
+    }
+
+    @Override
+    public void run() {
+      final DigitalOutput lead;
+      final DigitalOutput lag;
+
+      m_encoder.m_outputA.set(false);
+      m_encoder.m_outputB.set(false);
+
+      if (m_encoder.isForward()) {
+        lead = m_encoder.m_outputA;
+        lag = m_encoder.m_outputB;
+      } else {
+        lead = m_encoder.m_outputB;
+        lag = m_encoder.m_outputA;
+      }
+
+      try {
+        for (int i = 0; i < m_encoder.m_count; i++) {
+          lead.set(true);
+          Thread.sleep(m_encoder.m_milliSec);
+          lag.set(true);
+          Thread.sleep(m_encoder.m_milliSec);
+          lead.set(false);
+          Thread.sleep(m_encoder.m_milliSec);
+          lag.set(false);
+          Thread.sleep(m_encoder.m_milliSec);
+        }
+      } catch (InterruptedException ex) {
+        Thread.currentThread().interrupt();
+      }
+    }
+  }
+
+  /**
+   * Creates an encoder source using two ports.
+   *
+   * @param portA The A port
+   * @param portB The B port
+   */
+  public FakeEncoderSource(int portA, int portB) {
+    m_outputA = new DigitalOutput(portA);
+    m_outputB = new DigitalOutput(portB);
+    m_allocatedOutputs = true;
+    initQuadEncoder();
+  }
+
+  /**
+   * Creates the fake encoder using two digital outputs.
+   *
+   * @param outputA The A digital output
+   * @param outputB The B digital output
+   */
+  public FakeEncoderSource(DigitalOutput outputA, DigitalOutput outputB) {
+    m_outputA = outputA;
+    m_outputB = outputB;
+    m_allocatedOutputs = false;
+    initQuadEncoder();
+  }
+
+  /**
+   * Frees the resource.
+   */
+  @Override
+  public void close() {
+    m_task = null;
+    if (m_allocatedOutputs) {
+      m_outputA.close();
+      m_outputB.close();
+    }
+  }
+
+  /**
+   * Common initialization code.
+   */
+  private void initQuadEncoder() {
+    m_milliSec = 1;
+    m_forward = true;
+    m_task = new QuadEncoderThread(this);
+    m_outputA.set(false);
+    m_outputB.set(false);
+  }
+
+  /**
+   * Starts the thread.
+   */
+  public void start() {
+    m_task.start();
+  }
+
+  /**
+   * Waits for thread to end.
+   */
+  public void complete() {
+    try {
+      m_task.join();
+    } catch (InterruptedException ex) {
+      Thread.currentThread().interrupt();
+    }
+    m_task = new QuadEncoderThread(this);
+    Timer.delay(.01);
+  }
+
+  /**
+   * Runs and waits for thread to end before returning.
+   */
+  public void execute() {
+    start();
+    complete();
+  }
+
+  /**
+   * Rate of pulses to send.
+   *
+   * @param milliSec Pulse Rate
+   */
+  public void setRate(int milliSec) {
+    m_milliSec = milliSec;
+  }
+
+  /**
+   * Set the number of pulses to simulate.
+   *
+   * @param count Pulse count
+   */
+  public void setCount(int count) {
+    m_count = Math.abs(count);
+  }
+
+  /**
+   * Set which direction the encoder simulates motion in.
+   *
+   * @param isForward Whether to simulate forward motion
+   */
+  public void setForward(boolean isForward) {
+    m_forward = isForward;
+  }
+
+  /**
+   * Accesses whether the encoder is simulating forward motion.
+   *
+   * @return Whether the simulated motion is in the forward direction
+   */
+  public boolean isForward() {
+    return m_forward;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakePotentiometerSource.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakePotentiometerSource.java
new file mode 100644
index 0000000..63af674
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/mockhardware/FakePotentiometerSource.java
@@ -0,0 +1,94 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.mockhardware;
+
+import edu.wpi.first.wpilibj.AnalogOutput;
+
+/**
+ * A fake source to provide output to a {@link edu.wpi.first.wpilibj.interfaces.Potentiometer}.
+ */
+public class FakePotentiometerSource implements AutoCloseable {
+  private AnalogOutput m_output;
+  private boolean m_initOutput;
+  private double m_potMaxAngle;
+  private double m_potMaxVoltage = 5.0;
+  private final double m_defaultPotMaxAngle;
+
+  /**
+   * Constructs the fake source.
+   *
+   * @param output             The analog port to output the signal on
+   * @param defaultPotMaxAngle The default maximum angle the pot supports.
+   */
+  public FakePotentiometerSource(AnalogOutput output, double defaultPotMaxAngle) {
+    m_defaultPotMaxAngle = defaultPotMaxAngle;
+    m_potMaxAngle = defaultPotMaxAngle;
+    m_output = output;
+    m_initOutput = false;
+  }
+
+  public FakePotentiometerSource(int port, double defaultPotMaxAngle) {
+    this(new AnalogOutput(port), defaultPotMaxAngle);
+    m_initOutput = true;
+  }
+
+  /**
+   * Sets the maximum voltage output. If not the default is 5.0V.
+   *
+   * @param voltage The voltage that indicates that the pot is at the max value.
+   */
+  public void setMaxVoltage(double voltage) {
+    m_potMaxVoltage = voltage;
+  }
+
+  public void setRange(double range) {
+    m_potMaxAngle = range;
+  }
+
+  public void reset() {
+    m_potMaxAngle = m_defaultPotMaxAngle;
+    m_output.setVoltage(0.0);
+  }
+
+  public void setAngle(double angle) {
+    m_output.setVoltage((m_potMaxVoltage / m_potMaxAngle) * angle);
+  }
+
+  public void setVoltage(double voltage) {
+    m_output.setVoltage(voltage);
+  }
+
+  public double getVoltage() {
+    return m_output.getVoltage();
+  }
+
+  /**
+   * Returns the currently set angle.
+   *
+   * @return the current angle
+   */
+  public double getAngle() {
+    double voltage = m_output.getVoltage();
+    if (voltage == 0) { // Removes divide by zero error
+      return 0;
+    }
+    return voltage * (m_potMaxAngle / m_potMaxVoltage);
+  }
+
+  /**
+   * Frees the resouce.
+   */
+  @Override
+  public void close() {
+    if (m_initOutput) {
+      m_output.close();
+      m_output = null;
+      m_initOutput = false;
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java
new file mode 100644
index 0000000..b7e98b1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTest.java
@@ -0,0 +1,89 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.smartdashboard;
+
+import java.util.logging.Logger;
+
+import org.junit.Ignore;
+import org.junit.Test;
+
+import edu.wpi.first.wpilibj.networktables.NetworkTable;
+import edu.wpi.first.wpilibj.test.AbstractComsSetup;
+
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Test that covers {@link SmartDashboard}.
+ */
+public class SmartDashboardTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(SmartDashboardTest.class.getName());
+  private static final NetworkTable table = NetworkTable.getTable("SmartDashboard");
+
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+  @Test
+  public void testGetBadValue() {
+    assertEquals("", SmartDashboard.getString("_404_STRING_KEY_SHOULD_NOT_BE_FOUND_", ""));
+  }
+
+  @Test
+  public void testPutString() {
+    String key = "testPutString";
+    String value = "thisIsAValue";
+    SmartDashboard.putString(key, value);
+    assertEquals(value, SmartDashboard.getString(key, ""));
+    assertEquals(value, table.getString(key, ""));
+  }
+
+  @Test
+  public void testPutNumber() {
+    String key = "testPutNumber";
+    int value = 2147483647;
+    SmartDashboard.putNumber(key, value);
+    assertEquals(value, SmartDashboard.getNumber(key, 0), 0.01);
+    assertEquals(value, table.getNumber(key, 0), 0.01);
+  }
+
+  @Test
+  public void testPutBoolean() {
+    String key = "testPutBoolean";
+    boolean value = true;
+    SmartDashboard.putBoolean(key, value);
+    assertEquals(value, SmartDashboard.getBoolean(key, !value));
+    assertEquals(value, table.getBoolean(key, false));
+  }
+
+  @Test
+  public void testReplaceString() {
+    String key = "testReplaceString";
+    String valueOld = "oldValue";
+    SmartDashboard.putString(key, valueOld);
+    assertEquals(valueOld, SmartDashboard.getString(key, ""));
+    assertEquals(valueOld, table.getString(key, ""));
+
+    String valueNew = "newValue";
+    SmartDashboard.putString(key, valueNew);
+    assertEquals(valueNew, SmartDashboard.getString(key, ""));
+    assertEquals(valueNew, table.getString(key, ""));
+  }
+
+  @Ignore
+  @Test(expected = IllegalArgumentException.class)
+  public void testPutStringNullKey() {
+    SmartDashboard.putString(null, "This should not work");
+  }
+
+  @Ignore
+  @Test(expected = IllegalArgumentException.class)
+  public void testPutStringNullValue() {
+    SmartDashboard.putString("KEY_SHOULD_NOT_BE_STORED", null);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTestSuite.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTestSuite.java
new file mode 100644
index 0000000..d3e475e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SmartDashboardTestSuite.java
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.smartdashboard;
+
+import org.junit.runner.RunWith;
+import org.junit.runners.Suite;
+import org.junit.runners.Suite.SuiteClasses;
+
+import edu.wpi.first.wpilibj.test.AbstractTestSuite;
+
+/**
+ * All tests pertaining to {@link SmartDashboard}.
+ */
+@RunWith(Suite.class)
+@SuiteClasses({SmartDashboardTest.class})
+public class SmartDashboardTestSuite extends AbstractTestSuite {
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
new file mode 100644
index 0000000..28f4d2b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractComsSetup.java
@@ -0,0 +1,245 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import org.junit.BeforeClass;
+import org.junit.Rule;
+import org.junit.rules.TestWatcher;
+import org.junit.runner.Description;
+import org.junit.runners.model.MultipleFailureException;
+
+import edu.wpi.first.hal.HAL;
+import edu.wpi.first.wpilibj.DriverStation;
+import edu.wpi.first.wpilibj.MockDS;
+import edu.wpi.first.wpilibj.Timer;
+import edu.wpi.first.wpilibj.livewindow.LiveWindow;
+
+/**
+ * This class serves as a superclass for all tests that involve the hardware on the roboRIO. It uses
+ * an {@link BeforeClass} statement to initialize network communications. Any test that needs to use
+ * the hardware <b>MUST</b> extend from this class, to ensure that all of the hardware will be able
+ * to run.
+ */
+public abstract class AbstractComsSetup {
+  /**
+   * Stores whether network coms have been initialized.
+   */
+  private static boolean initialized = false;
+
+  // We have no way to stop the MockDS, so its thread is daemon.
+  private static  MockDS ds;
+
+  /**
+   * This sets up the network communications library to enable the driver
+   * station. After starting network coms, it will loop until the driver station
+   * returns that the robot is enabled, to ensure that tests will be able to run
+   * on the hardware.
+   */
+  static {
+    if (!initialized) {
+      try {
+        // Set some implementations so that the static methods work properly
+        HAL.initialize(500, 0);
+        HAL.observeUserProgramStarting();
+        DriverStation.getInstance().getAlliance();
+
+        ds = new MockDS();
+        ds.start();
+
+        LiveWindow.setEnabled(false);
+        TestBench.out().println("Started coms");
+      } catch (Exception ex) {
+        TestBench.out().println("Exception during AbstractComsSetup initialization: " + ex);
+        ex.printStackTrace(TestBench.out());
+        throw ex;
+      }
+
+      // Wait until the robot is enabled before starting the tests
+      int enableCounter = 0;
+      while (!DriverStation.getInstance().isEnabled()) {
+        if (enableCounter > 50) {
+          // Robot did not enable properly after 5 seconds.
+          // Force exit
+          TestBench.err().println("Failed to enable. Aborting");
+          System.exit(1);
+        }
+        try {
+          Thread.sleep(100);
+        } catch (InterruptedException ex) {
+          ex.printStackTrace();
+        }
+        TestBench.out().println("Waiting for enable: " + enableCounter++);
+      }
+      TestBench.out().println();
+
+      // Ready to go!
+      initialized = true;
+      TestBench.out().println("Running!");
+    }
+  }
+
+
+  protected abstract Logger getClassLogger();
+
+  /**
+   * This causes a stack trace to be printed as the test is running as well as at the end.
+   */
+  @Rule
+  public final TestWatcher getTestWatcher() {
+    return getOverridenTestWatcher();
+  }
+
+  /**
+   * Given as a way to provide a custom test watcher for a test or set of tests.
+   *
+   * @return the test watcher to use
+   */
+  protected TestWatcher getOverridenTestWatcher() {
+    return new DefaultTestWatcher();
+  }
+
+  protected class DefaultTestWatcher extends TestWatcher {
+    /**
+     * Allows a failure to supply a custom status message to be displayed along with the stack
+     * trace.
+     */
+    protected void failed(Throwable throwable, Description description, String status) {
+      TestBench.out().println();
+      // Instance of is the best way I know to retrieve this data.
+      if (throwable instanceof MultipleFailureException) {
+        /*
+         * MultipleFailureExceptions hold multiple exceptions in one exception.
+         * In order to properly display these stack traces we have to cast the
+         * throwable and work with the list of thrown exceptions stored within
+         * it.
+         */
+        int exceptionCount = 1; // Running exception count
+        int failureCount = ((MultipleFailureException) throwable).getFailures().size();
+        for (Throwable singleThrown : ((MultipleFailureException) throwable).getFailures()) {
+          getClassLogger().logp(
+              Level.SEVERE,
+              description.getClassName(),
+              description.getMethodName(),
+              (exceptionCount++) + "/" + failureCount + " " + description.getDisplayName() + " "
+                  + "failed " + singleThrown.getMessage() + "\n" + status, singleThrown);
+        }
+
+      } else {
+        getClassLogger().logp(Level.SEVERE, description.getClassName(),
+            description.getMethodName(),
+            description.getDisplayName() + " failed " + throwable.getMessage() + "\n" + status,
+            throwable);
+      }
+      super.failed(throwable, description);
+    }
+
+    /*
+     * (non-Javadoc)
+     *
+     * @see org.junit.rules.TestWatcher#failed(java.lang.Throwable,
+     * org.junit.runner.Description)
+     */
+    @Override
+    protected void failed(Throwable exception, Description description) {
+      failed(exception, description, "");
+    }
+
+
+    /*
+     * (non-Javadoc)
+     *
+     * @see org.junit.rules.TestWatcher#starting(org.junit.runner.Description)
+     */
+    @Override
+    protected void starting(Description description) {
+      TestBench.out().println();
+      // Wait until the robot is enabled before starting the next tests
+      int enableCounter = 0;
+      while (!DriverStation.getInstance().isEnabled()) {
+        try {
+          Thread.sleep(100);
+        } catch (InterruptedException ex) {
+          ex.printStackTrace();
+        }
+        // Prints the message on one line overwriting itself each time
+        TestBench.out().print("\rWaiting for enable: " + enableCounter++);
+      }
+      getClassLogger().logp(Level.INFO, description.getClassName(), description.getMethodName(),
+          "Starting");
+      super.starting(description);
+    }
+
+    @Override
+    protected void succeeded(Description description) {
+      simpleLog(Level.INFO, "TEST PASSED!");
+      super.succeeded(description);
+    }
+
+  }
+
+  /**
+   * Logs a simple message without the logger formatting associated with it.
+   *
+   * @param level   The level to log the message at
+   * @param message The message to log
+   */
+  protected void simpleLog(Level level, String message) {
+    if (getClassLogger().isLoggable(level)) {
+      TestBench.out().println(message);
+    }
+  }
+
+  /**
+   * Provided as a replacement to lambda functions to allow for repeatable checks to see if a
+   * correct state is reached.
+   */
+  public abstract class BooleanCheck {
+    public BooleanCheck() {
+    }
+
+    /**
+     * Runs the enclosed code and evaluates it to determine what state it should return.
+     *
+     * @return true if the code provided within the method returns true
+     */
+    public abstract boolean getAsBoolean();
+  }
+
+  /**
+   * Delays until either the correct state is reached or we reach the timeout.
+   *
+   * @param level        The level to log the message at.
+   * @param timeout      How long the delay should run before it should timeout and allow the test
+   *                     to continue
+   * @param message      The message to accompany the delay. The message will display 'message' took
+   *                     'timeout' seconds if it passed.
+   * @param correctState A method to determine if the test has reached a state where it is valid to
+   *                     continue
+   * @return a double representing how long the delay took to run in seconds.
+   */
+  public double delayTillInCorrectStateWithMessage(Level level, double timeout, String message,
+                                                   BooleanCheck correctState) {
+    int timeoutIndex;
+    // As long as we are not in the correct state and the timeout has not been
+    // reached then continue to run this loop
+    for (timeoutIndex = 0; timeoutIndex < (timeout * 100) && !correctState.getAsBoolean();
+         timeoutIndex++) {
+      Timer.delay(.01);
+    }
+    if (correctState.getAsBoolean()) {
+      simpleLog(level, message + " took " + (timeoutIndex * .01) + " seconds");
+    } else {
+      simpleLog(level, message + " timed out after " + (timeoutIndex * .01) + " seconds");
+    }
+    return timeoutIndex * .01;
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java
new file mode 100644
index 0000000..b8af56d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuite.java
@@ -0,0 +1,257 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.lang.reflect.Method;
+import java.util.List;
+import java.util.Vector;
+import java.util.logging.Level;
+import java.util.logging.Logger;
+import java.util.regex.Pattern;
+
+import org.junit.Ignore;
+import org.junit.Test;
+import org.junit.runner.Request;
+import org.junit.runners.Suite.SuiteClasses;
+
+/**
+ * Allows tests suites and tests to be run selectively from the command line using a regex text
+ * pattern.
+ */
+public abstract class AbstractTestSuite {
+  private static final Logger logger = Logger.getLogger(AbstractTestSuite.class.getName());
+
+  /**
+   * Gets all of the classes listed within the SuiteClasses annotation. To use it, annotate a class
+   * with <code>@RunWith(Suite.class)</code> and <code>@SuiteClasses({TestClass1.class,
+   * ...})</code>. When you run this class, it will run all the tests in all the suite classes. When
+   * loading the tests using regex the test list will be generated from this annotation.
+   *
+   * @return the list of classes listed in the <code>@SuiteClasses({TestClass1.class, ...})</code>.
+   * @throws RuntimeException If the <code>@SuiteClasses</code> annotation is missing.
+   */
+  protected List<Class<?>> getAnnotatedTestClasses() {
+    SuiteClasses annotation = getClass().getAnnotation(SuiteClasses.class);
+    List<Class<?>> classes = new Vector<Class<?>>();
+    if (annotation == null) {
+      throw new RuntimeException(String.format("class '%s' must have a SuiteClasses annotation",
+          getClass().getName()));
+    }
+    for (Class<?> c : annotation.value()) {
+      classes.add(c);
+    }
+    return classes;
+  }
+
+  private boolean areAnySuperClassesOfTypeAbstractTestSuite(Class<?> check) {
+    while (check != null) {
+      if (check.equals(AbstractTestSuite.class)) {
+        return true;
+      }
+      check = check.getSuperclass();
+    }
+    return false;
+  }
+
+  /**
+   * Stores a method name and method class pair. Used when searching for methods matching a given
+   * regex text.
+   */
+  protected class ClassMethodPair {
+    public final Class<?> m_methodClass;
+    public final String m_methodName;
+
+    public ClassMethodPair(Class<?> klass, Method method) {
+      m_methodClass = klass;
+      m_methodName = method.getName();
+    }
+
+    public Request getMethodRunRequest() {
+      return Request.method(m_methodClass, m_methodName);
+    }
+  }
+
+  protected List<ClassMethodPair> getMethodMatching(final String regex) {
+    List<ClassMethodPair> classMethodPairs = new Vector<ClassMethodPair>();
+    // Get all of the test classes
+    for (Class<?> c : getAllContainedBaseTests()) {
+      for (Method m : c.getMethods()) {
+        // If this is a test method that is not trying to be ignored and it
+        // matches the regex
+        if (m.getAnnotation(Test.class) != null && m.getAnnotation(Ignore.class) == null
+            && Pattern.matches(regex, m.getName())) {
+          ClassMethodPair pair = new ClassMethodPair(c, m);
+          classMethodPairs.add(pair);
+        }
+      }
+    }
+    return classMethodPairs;
+  }
+
+
+  /**
+   * Gets all of the test classes listed in this suite. Does not include any of the test suites. All
+   * of these classes contain tests.
+   *
+   * @param runningList the running list of classes to prevent recursion.
+   * @return The list of base test classes.
+   */
+  private List<Class<?>> getAllContainedBaseTests(List<Class<?>> runningList) {
+    for (Class<?> c : getAnnotatedTestClasses()) {
+      // Check to see if this is a test class or a suite
+      if (areAnySuperClassesOfTypeAbstractTestSuite(c)) {
+        // Create a new instance of this class so that we can retrieve its data
+        try {
+          AbstractTestSuite suite = (AbstractTestSuite) c.newInstance();
+          // Add the tests from this suite that match the regex to the list of
+          // tests to run
+          runningList = suite.getAllContainedBaseTests(runningList);
+        } catch (InstantiationException | IllegalAccessException ex) {
+          // This shouldn't happen unless the constructor is changed in some
+          // way.
+          logger.log(Level.SEVERE, "Test suites can not take paramaters in their constructors.",
+              ex);
+        }
+      } else if (c.getAnnotation(SuiteClasses.class) != null) {
+        logger.log(Level.SEVERE,
+            String.format("class '%s' must extend %s to be searchable using regex.",
+                c.getName(), AbstractTestSuite.class.getName()));
+      } else { // This is a class containing tests
+        // so add it to the list
+        runningList.add(c);
+      }
+    }
+    return runningList;
+  }
+
+  /**
+   * Gets all of the test classes listed in this suite. Does not include any of the test suites. All
+   * of these classes contain tests.
+   *
+   * @return The list of base test classes.
+   */
+  public List<Class<?>> getAllContainedBaseTests() {
+    List<Class<?>> runningBaseTests = new Vector<Class<?>>();
+    return getAllContainedBaseTests(runningBaseTests);
+  }
+
+
+  /**
+   * Retrieves all of the classes listed in the <code>@SuiteClasses</code> annotation that match the
+   * given regex text.
+   *
+   * @param regex       the text pattern to retrieve.
+   * @param runningList the running list of classes to prevent recursion
+   * @return The list of classes matching the regex pattern
+   */
+  private List<Class<?>> getAllClassMatching(final String regex, final List<Class<?>> runningList) {
+    for (Class<?> c : getAnnotatedTestClasses()) {
+      // Compare the regex against the simple name of the class
+      if (Pattern.matches(regex, c.getName()) && !runningList.contains(c)) {
+        runningList.add(c);
+      }
+    }
+    return runningList;
+  }
+
+  /**
+   * Retrieves all of the classes listed in the <code>@SuiteClasses</code> annotation that match the
+   * given regex text.
+   *
+   * @param regex the text pattern to retrieve.
+   * @return The list of classes matching the regex pattern
+   */
+  public List<Class<?>> getAllClassMatching(final String regex) {
+    final List<Class<?>> matchingClasses = new Vector<Class<?>>();
+    return getAllClassMatching(regex, matchingClasses);
+  }
+
+  /**
+   * Searches through all of the suites and tests and loads only the test or test suites matching
+   * the regex text. This method also prevents a single test from being loaded multiple times by
+   * loading the suite first then loading tests from all non loaded suites.
+   *
+   * @param regex the regex text to search for
+   * @return the list of suite and/or test classes matching the regex.
+   */
+  private List<Class<?>> getSuiteOrTestMatchingRegex(final String regex, List<Class<?>>
+      runningList) {
+    // Get any test suites matching the regex using the superclass methods
+    runningList = getAllClassMatching(regex, runningList);
+
+
+    // Then search any test suites not retrieved already for test classes
+    // matching the regex.
+    List<Class<?>> unCollectedSuites = getAllClasses();
+    // If we already have a test suite then we don't want to load the test twice
+    // so remove the suite from the list
+    unCollectedSuites.removeAll(runningList);
+    for (Class<?> c : unCollectedSuites) {
+      // Prevents recursively adding tests/suites that have already been added
+      if (!runningList.contains(c)) {
+        try {
+          final AbstractTestSuite suite;
+          // Check the class to make sure that it is not a test class
+          if (areAnySuperClassesOfTypeAbstractTestSuite(c)) {
+            // Create a new instance of this class so that we can retrieve its
+            // data.
+            suite = (AbstractTestSuite) c.newInstance();
+            // Add the tests from this suite that match the regex to the list of
+            // tests to run
+            runningList = suite.getSuiteOrTestMatchingRegex(regex, runningList);
+          }
+
+        } catch (InstantiationException | IllegalAccessException ex) {
+          // This shouldn't happen unless the constructor is changed in some
+          // way.
+          logger.log(Level.SEVERE, "Test suites can not take paramaters in their constructors.",
+              ex);
+        }
+      }
+    }
+    return runningList;
+  }
+
+  /**
+   * Searches through all of the suites and tests and loads only the test or test suites matching
+   * the regex text. This method also prevents a single test from being loaded multiple times by
+   * loading the suite first then loading tests from all non loaded suites.
+   *
+   * @param regex the regex text to search for
+   * @return the list of suite and/or test classes matching the regex.
+   */
+  protected List<Class<?>> getSuiteOrTestMatchingRegex(final String regex) {
+    final List<Class<?>> matchingClasses = new Vector<Class<?>>();
+    return getSuiteOrTestMatchingRegex(regex, matchingClasses);
+  }
+
+
+  /**
+   * Retrieves all of the classes listed in the <code>@SuiteClasses</code> annotation.
+   *
+   * @return List of SuiteClasses
+   * @throws RuntimeException If the <code>@SuiteClasses</code> annotation is missing.
+   */
+  public List<Class<?>> getAllClasses() {
+    return getAnnotatedTestClasses();
+  }
+
+  /**
+   * Gets the name of all of the classes listed within the <code>@SuiteClasses</code> annotation.
+   *
+   * @return the list of classes.
+   * @throws RuntimeException If the <code>@SuiteClasses</code> annotation is missing.
+   */
+  public List<String> getAllClassName() {
+    List<String> classNames = new Vector<String>();
+    for (Class<?> c : getAnnotatedTestClasses()) {
+      classNames.add(c.getName());
+    }
+    return classNames;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
new file mode 100644
index 0000000..acff9d4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AbstractTestSuiteTest.java
@@ -0,0 +1,155 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.util.List;
+
+import org.junit.Before;
+import org.junit.Ignore;
+import org.junit.Test;
+import org.junit.runner.RunWith;
+import org.junit.runners.Suite;
+import org.junit.runners.Suite.SuiteClasses;
+import org.junit.runners.model.InitializationError;
+
+import edu.wpi.first.wpilibj.test.AbstractTestSuite.ClassMethodPair;
+
+import static org.hamcrest.MatcherAssert.assertThat;
+import static org.hamcrest.Matchers.hasItems;
+import static org.hamcrest.Matchers.not;
+import static org.junit.Assert.assertEquals;
+
+/**
+ * Yes, this is the test system testing itself. Functionally, this is making sure that all tests get
+ * run correctly when you use parametrized arguments.
+ */
+@SuppressWarnings("MultipleTopLevelClasses")
+public class AbstractTestSuiteTest {
+  @Ignore("Prevents ANT from trying to run these as tests")
+  @RunWith(Suite.class)
+  @SuiteClasses({FirstSampleTest.class, SecondSampleTest.class, ThirdSampleTest.class,
+      FourthSampleTest.class, UnusualTest.class, ExampleSubSuite.class, EmptySuite.class})
+  class TestForAbstractTestSuite extends AbstractTestSuite {
+  }
+
+  TestForAbstractTestSuite m_testSuite;
+
+  @Before
+  public void setUp() throws Exception {
+    m_testSuite = new TestForAbstractTestSuite();
+  }
+
+  @Test
+  public void testGetTestsMatchingAll() throws InitializationError {
+    // when
+    List<Class<?>> collectedTests = m_testSuite.getAllClassMatching(".*");
+    // then
+    assertEquals(7, collectedTests.size());
+  }
+
+  @Test
+  public void testGetTestsMatchingSample() throws InitializationError {
+    // when
+    List<Class<?>> collectedTests = m_testSuite.getAllClassMatching(".*Sample.*");
+    // then
+    assertEquals(4, collectedTests.size());
+  }
+
+  @Test
+  public void testGetTestsMatchingUnusual() throws InitializationError {
+    // when
+    List<Class<?>> collectedTests = m_testSuite.getAllClassMatching(".*Unusual.*");
+    // then
+    assertEquals(1, collectedTests.size());
+    assertEquals(UnusualTest.class, collectedTests.get(0));
+  }
+
+  @Test
+  public void testGetTestsFromSuiteMatchingAll() throws InitializationError {
+    // when
+    List<Class<?>> collectedTests = m_testSuite.getSuiteOrTestMatchingRegex(".*");
+    // then
+    assertEquals(7, collectedTests.size());
+  }
+
+  @Test
+  public void testGetTestsFromSuiteMatchingTest() throws InitializationError {
+    // when
+    List<Class<?>> collectedTests = m_testSuite.getSuiteOrTestMatchingRegex(".*Test.*");
+    // then
+    assertEquals(7, collectedTests.size());
+    assertThat(collectedTests, hasItems(FirstSubSuiteTest.class,
+        SecondSubSuiteTest.class, UnusualTest.class));
+    assertThat(collectedTests,
+        not(hasItems(new Class<?>[]{ExampleSubSuite.class, EmptySuite.class})));
+  }
+
+  @Test
+  public void testGetMethodFromTest() {
+    // when
+    List<ClassMethodPair> pairs = m_testSuite.getMethodMatching(".*Method.*");
+    // then
+    assertEquals(1, pairs.size());
+    assertEquals(FirstSubSuiteTest.class, pairs.get(0).m_methodClass);
+    assertEquals(FirstSubSuiteTest.METHODNAME, pairs.get(0).m_methodName);
+
+  }
+
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class FirstSampleTest {
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class SecondSampleTest {
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class ThirdSampleTest {
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class FourthSampleTest {
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class UnusualTest {
+} // This is a member of both suites
+
+
+@Ignore("Prevents ANT from trying to run these as tests")
+@SuppressWarnings("OneTopLevelClass")
+class FirstSubSuiteTest {
+  public static final String METHODNAME = "aTestMethod";
+
+  @Test
+  @SuppressWarnings("MethodName")
+  public void aTestMethod() {
+  }
+}
+
+@SuppressWarnings("OneTopLevelClass")
+class SecondSubSuiteTest {
+}
+
+
+@RunWith(Suite.class)
+@SuiteClasses({FirstSubSuiteTest.class, SecondSubSuiteTest.class, UnusualTest.class})
+@Ignore("Prevents ANT from trying to run these as tests")
+@SuppressWarnings("OneTopLevelClass")
+class ExampleSubSuite extends AbstractTestSuite {
+}
+
+
+@Ignore("Prevents ANT from trying to run these as tests")
+@RunWith(Suite.class)
+@SuiteClasses({})
+@SuppressWarnings("OneTopLevelClass")
+class EmptySuite extends AbstractTestSuite {
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java
new file mode 100644
index 0000000..0350ea4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/AntJunitLanucher.java
@@ -0,0 +1,91 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.io.File;
+
+import org.apache.tools.ant.BuildLogger;
+import org.apache.tools.ant.DefaultLogger;
+import org.apache.tools.ant.Project;
+import org.apache.tools.ant.taskdefs.optional.junit.FormatterElement;
+import org.apache.tools.ant.taskdefs.optional.junit.JUnitTask;
+import org.apache.tools.ant.taskdefs.optional.junit.JUnitTest;
+
+/**
+ * Provides an entry point for tests to run with ANT. This allows ant to output JUnit XML test
+ * results for Jenkins.
+ */
+public class AntJunitLanucher {
+  /**
+   * Main entry point for jenkins.
+   *
+   * @param args Arguments passed to java.
+   */
+  public static void main(String... args) {
+    if (args.length == 0) {
+      String path =
+          String.format("%s/%s", System.getProperty("user.dir"), "/testResults/AntReports");
+      String pathToReports = path;
+      Project project = new Project();
+
+      try {
+        // Create the file to store the test output
+        new File(pathToReports).mkdirs();
+
+        project.setProperty("java.io.tmpdir", pathToReports);
+
+        /* Output to screen */
+        FormatterElement.TypeAttribute typeScreen = new FormatterElement.TypeAttribute();
+        typeScreen.setValue("plain");
+        FormatterElement formatToScreen = new FormatterElement();
+        formatToScreen.setType(typeScreen);
+        formatToScreen.setUseFile(false);
+        formatToScreen.setOutput(System.out);
+
+        JUnitTask task = new JUnitTask();
+        task.addFormatter(formatToScreen);
+
+        // add a build listener to the project
+        BuildLogger logger = new DefaultLogger();
+        logger.setOutputPrintStream(System.out);
+        logger.setErrorPrintStream(System.err);
+        logger.setMessageOutputLevel(Project.MSG_INFO);
+        logger.setEmacsMode(true);
+        project.addBuildListener(logger);
+
+        task.setProject(project);
+
+        // Set the output to the XML file
+        FormatterElement.TypeAttribute type = new FormatterElement.TypeAttribute();
+        type.setValue("xml");
+
+        FormatterElement formater = new FormatterElement();
+        formater.setType(type);
+        task.addFormatter(formater);
+
+        // Create the JUnitTest
+        JUnitTest test = new JUnitTest(TestSuite.class.getName());
+        test.setTodir(new File(pathToReports));
+        task.addTest(test);
+
+        TestBench.out().println("Beginning Test Execution With ANT");
+        task.execute();
+      } catch (Exception ex) {
+        ex.printStackTrace();
+      }
+    } else {
+      TestBench.out().println(
+          "Run will not output XML for Jenkins because " + "tests are not being run with ANT");
+      // This should never return as it makes its own call to
+      // System.exit();
+      TestSuite.main(args);
+    }
+    System.exit(0);
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/QuickTest.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/QuickTest.java
new file mode 100644
index 0000000..87b05d0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/QuickTest.java
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.util.logging.Logger;
+
+import org.junit.Test;
+
+/**
+ * This class is designated to allow for simple testing of the library without the overlying testing
+ * framework. This test is NOT run as a normal part of the testing process and must be explicitly
+ * selected at runtime by using the 'quick' argument. This test should never be committed with
+ * changes to it but can be used during development to aid in feature testing.
+ */
+public class QuickTest extends AbstractComsSetup {
+  private static final Logger logger = Logger.getLogger(QuickTest.class.getName());
+
+  /*
+   * (non-Javadoc)
+   *
+   * @see edu.wpi.first.wpilibj.test.AbstractComsSetup#getClassLogger()
+   */
+  @Override
+  protected Logger getClassLogger() {
+    return logger;
+  }
+
+
+  @Test
+  public void test() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/RepeatRule.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/RepeatRule.java
new file mode 100644
index 0000000..deb0da8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/RepeatRule.java
@@ -0,0 +1,65 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.lang.annotation.Retention;
+import java.lang.annotation.RetentionPolicy;
+import java.lang.annotation.Target;
+
+import org.junit.rules.TestRule;
+import org.junit.runner.Description;
+import org.junit.runners.model.Statement;
+
+/**
+ * This JUnit Rule allows you to apply this rule to any test to allow it to run multiple times. This
+ * is important if you have a test that fails only "sometimes" and needs to be rerun to find the
+ * issue.
+ *
+ * <p>This code was originally found here:
+ * <a href="http://www.codeaffine.com/2013/04/10/running-junit-tests-repeatedly-without-loops/">
+ * Running JUnit Tests Repeatedly Without Loops</a>
+ */
+public class RepeatRule implements TestRule {
+  @Retention(RetentionPolicy.RUNTIME)
+  @Target({java.lang.annotation.ElementType.METHOD})
+  public @interface Repeat {
+    /**
+     * The number of times to repeat the test.
+     */
+    int times();
+  }
+
+
+  private static class RepeatStatement extends Statement {
+    private final int m_times;
+    private final Statement m_statement;
+
+    private RepeatStatement(int times, Statement statement) {
+      m_times = times;
+      m_statement = statement;
+    }
+
+    @Override
+    public void evaluate() throws Throwable {
+      for (int i = 0; i < m_times; i++) {
+        m_statement.evaluate();
+      }
+    }
+  }
+
+  @Override
+  public Statement apply(Statement statement, Description description) {
+    Statement result = statement;
+    Repeat repeat = description.getAnnotation(Repeat.class);
+    if (repeat != null) {
+      int times = repeat.times();
+      result = new RepeatStatement(times, statement);
+    }
+    return result;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java
new file mode 100644
index 0000000..39585da
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestBench.java
@@ -0,0 +1,477 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.io.PrintStream;
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.Collection;
+import java.util.List;
+
+import edu.wpi.first.wpilibj.AnalogGyro;
+import edu.wpi.first.wpilibj.AnalogInput;
+import edu.wpi.first.wpilibj.AnalogOutput;
+import edu.wpi.first.wpilibj.DigitalInput;
+import edu.wpi.first.wpilibj.Jaguar;
+import edu.wpi.first.wpilibj.PIDSource;
+import edu.wpi.first.wpilibj.Relay;
+import edu.wpi.first.wpilibj.Servo;
+import edu.wpi.first.wpilibj.Talon;
+import edu.wpi.first.wpilibj.Victor;
+import edu.wpi.first.wpilibj.filters.LinearDigitalFilter;
+import edu.wpi.first.wpilibj.fixtures.AnalogCrossConnectFixture;
+import edu.wpi.first.wpilibj.fixtures.DIOCrossConnectFixture;
+import edu.wpi.first.wpilibj.fixtures.FilterNoiseFixture;
+import edu.wpi.first.wpilibj.fixtures.FilterOutputFixture;
+import edu.wpi.first.wpilibj.fixtures.MotorEncoderFixture;
+import edu.wpi.first.wpilibj.fixtures.RelayCrossConnectFixture;
+import edu.wpi.first.wpilibj.fixtures.TiltPanCameraFixture;
+
+/**
+ * This class provides access to all of the elements on the test bench, for use in fixtures. This
+ * class is a singleton, you should use {@link #getInstance()} to obtain a reference to the {@code
+ * TestBench}.
+ */
+public final class TestBench {
+  /**
+   * The time that it takes to have a motor go from rotating at full speed to completely stopped.
+   */
+  public static final double MOTOR_STOP_TIME = 0.25;
+
+  public static final int kTalonChannel = 10;
+  public static final int kVictorChannel = 1;
+  public static final int kJaguarChannel = 2;
+
+  /* TiltPanCamera Channels */
+  public static final int kGyroChannel = 0;
+  public static final double kGyroSensitivity = 0.013;
+  public static final int kTiltServoChannel = 9;
+  public static final int kPanServoChannel = 8;
+
+
+  /* PowerDistributionPanel channels */
+  public static final int kJaguarPDPChannel = 6;
+  public static final int kVictorPDPChannel = 8;
+  public static final int kTalonPDPChannel = 10;
+
+  // THESE MUST BE IN INCREMENTING ORDER
+  public static final int DIOCrossConnectB2 = 9;
+  public static final int DIOCrossConnectB1 = 8;
+  public static final int DIOCrossConnectA2 = 7;
+  public static final int DIOCrossConnectA1 = 6;
+
+  // Filter constants
+  public static final double kStdDev = 10.0;
+  public static final double kFilterStep = 0.005;
+  public static final double kFilterTime = 2.0;
+  public static final double kSinglePoleIIRTimeConstant = 0.015915;
+  public static final double kSinglePoleIIRExpectedOutput = -3.2172003;
+  public static final double kHighPassTimeConstant = 0.006631;
+  public static final double kHighPassExpectedOutput = 10.074717;
+  public static final int kMovAvgTaps = 6;
+  public static final double kMovAvgExpectedOutput = -10.191644;
+
+  /**
+   * The Singleton instance of the Test Bench.
+   */
+  private static TestBench instance = null;
+
+  /**
+   * The single constructor for the TestBench. This method is private in order to prevent multiple
+   * TestBench objects from being allocated.
+   */
+  protected TestBench() {
+  }
+
+  /**
+   * Constructs a new set of objects representing a connected set of Talon controlled Motors and an
+   * encoder.
+   *
+   * @return a freshly allocated Talon, Encoder pair
+   */
+  public MotorEncoderFixture<Talon> getTalonPair() {
+    MotorEncoderFixture<Talon> talonPair = new MotorEncoderFixture<Talon>() {
+      @Override
+      protected Talon giveSpeedController() {
+        return new Talon(kTalonChannel);
+      }
+
+      @Override
+      protected DigitalInput giveDigitalInputA() {
+        return new DigitalInput(0);
+      }
+
+      @Override
+      protected DigitalInput giveDigitalInputB() {
+        return new DigitalInput(1);
+      }
+
+      @Override
+      public int getPDPChannel() {
+        return kTalonPDPChannel;
+      }
+    };
+    return talonPair;
+  }
+
+  /**
+   * Constructs a new set of objects representing a connected set of Victor controlled Motors and an
+   * encoder.
+   *
+   * @return a freshly allocated Victor, Encoder pair
+   */
+  public MotorEncoderFixture<Victor> getVictorPair() {
+    MotorEncoderFixture<Victor> vicPair = new MotorEncoderFixture<Victor>() {
+      @Override
+      protected Victor giveSpeedController() {
+        return new Victor(kVictorChannel);
+      }
+
+      @Override
+      protected DigitalInput giveDigitalInputA() {
+        return new DigitalInput(2);
+      }
+
+      @Override
+      protected DigitalInput giveDigitalInputB() {
+        return new DigitalInput(3);
+      }
+
+      @Override
+      public int getPDPChannel() {
+        return kVictorPDPChannel;
+      }
+    };
+    return vicPair;
+  }
+
+  /**
+   * Constructs a new set of objects representing a connected set of Jaguar controlled Motors and an
+   * encoder.
+   *
+   * @return a freshly allocated Jaguar, Encoder pair
+   */
+  public MotorEncoderFixture<Jaguar> getJaguarPair() {
+    MotorEncoderFixture<Jaguar> jagPair = new MotorEncoderFixture<Jaguar>() {
+      @Override
+      protected Jaguar giveSpeedController() {
+        return new Jaguar(kJaguarChannel);
+      }
+
+      @Override
+      protected DigitalInput giveDigitalInputA() {
+        return new DigitalInput(4);
+      }
+
+      @Override
+      protected DigitalInput giveDigitalInputB() {
+        return new DigitalInput(5);
+      }
+
+      @Override
+      public int getPDPChannel() {
+        return kJaguarPDPChannel;
+      }
+    };
+    return jagPair;
+  }
+
+  /**
+   * Constructs a new set of two Servo's and a Gyroscope.
+   *
+   * @return a freshly allocated Servo's and a freshly allocated Gyroscope
+   */
+  public TiltPanCameraFixture getTiltPanCam() {
+    TiltPanCameraFixture tpcam = new TiltPanCameraFixture() {
+      @Override
+      protected AnalogGyro giveGyro() {
+        AnalogGyro gyro = new AnalogGyro(kGyroChannel);
+        gyro.setSensitivity(kGyroSensitivity);
+        return gyro;
+      }
+
+      @Override
+      protected AnalogGyro giveGyroParam(int center, double offset) {
+        AnalogGyro gyro = new AnalogGyro(kGyroChannel, center, offset);
+        gyro.setSensitivity(kGyroSensitivity);
+        return gyro;
+      }
+
+      @Override
+      protected Servo giveTilt() {
+        return new Servo(kTiltServoChannel);
+      }
+
+      @Override
+      protected Servo givePan() {
+        return new Servo(kPanServoChannel);
+      }
+    };
+
+    return tpcam;
+  }
+
+  public DIOCrossConnectFixture getDIOCrossConnectFixture(int inputPort, int outputPort) {
+    DIOCrossConnectFixture dio = new DIOCrossConnectFixture(inputPort, outputPort);
+    return dio;
+  }
+
+  /**
+   * Gets two lists of possible DIO pairs for the two pairs.
+   */
+  private List<List<Integer[]>> getDIOCrossConnect() {
+    List<List<Integer[]>> pairs = new ArrayList<List<Integer[]>>();
+    List<Integer[]> setA =
+        Arrays.asList(new Integer[][]{
+            {new Integer(DIOCrossConnectA1), new Integer(DIOCrossConnectA2)},
+            {new Integer(DIOCrossConnectA2), new Integer(DIOCrossConnectA1)}});
+    pairs.add(setA);
+
+    List<Integer[]> setB =
+        Arrays.asList(new Integer[][]{
+            {new Integer(DIOCrossConnectB1), new Integer(DIOCrossConnectB2)},
+            {new Integer(DIOCrossConnectB2), new Integer(DIOCrossConnectB1)}});
+    pairs.add(setB);
+    // NOTE: IF MORE DIOCROSSCONNECT PAIRS ARE ADDED ADD THEM HERE
+    return pairs;
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  public static AnalogCrossConnectFixture getAnalogCrossConnectFixture() {
+    AnalogCrossConnectFixture analogIO = new AnalogCrossConnectFixture() {
+      @Override
+      protected AnalogOutput giveAnalogOutput() {
+        return new AnalogOutput(0);
+      }
+
+      @Override
+      protected AnalogInput giveAnalogInput() {
+        return new AnalogInput(2);
+      }
+    };
+    return analogIO;
+  }
+
+  @SuppressWarnings("JavadocMethod")
+  public static RelayCrossConnectFixture getRelayCrossConnectFixture() {
+    RelayCrossConnectFixture relay = new RelayCrossConnectFixture() {
+      @Override
+      protected Relay giveRelay() {
+        return new Relay(0);
+      }
+
+      @Override
+      protected DigitalInput giveInputTwo() {
+        return new DigitalInput(18);
+      }
+
+      @Override
+      protected DigitalInput giveInputOne() {
+        return new DigitalInput(19);
+      }
+    };
+    return relay;
+  }
+
+  /**
+   * Return a single Collection containing all of the DIOCrossConnectFixtures in all two pair
+   * combinations.
+   *
+   * @return pairs of DIOCrossConnectFixtures
+   */
+  public Collection<Integer[]> getDIOCrossConnectCollection() {
+    Collection<Integer[]> pairs = new ArrayList<Integer[]>();
+    for (Collection<Integer[]> collection : getDIOCrossConnect()) {
+      pairs.addAll(collection);
+    }
+    return pairs;
+  }
+
+  /**
+   * Gets an array of pairs for the encoder to use using two different lists.
+   *
+   * @param flip whether this encoder needs to be flipped
+   * @return A list of different inputs to use for the tests
+   */
+  private Collection<Integer[]> getPairArray(List<Integer[]> listA, List<Integer[]> listB,
+                                             boolean flip) {
+    Collection<Integer[]> encoderPortPairs = new ArrayList<Integer[]>();
+    for (Integer[] portPairsA : listA) {
+      Integer[] inputs = new Integer[5];
+      inputs[0] = portPairsA[0]; // InputA
+      inputs[1] = portPairsA[1]; // InputB
+
+      for (Integer[] portPairsB : listB) {
+        inputs[2] = portPairsB[0]; // OutputA
+        inputs[3] = portPairsB[1]; // OutputB
+        inputs[4] = flip ? 0 : 1; // The flip bit
+      }
+
+      ArrayList<Integer[]> construtorInput = new ArrayList<Integer[]>();
+      construtorInput.add(inputs);
+
+      inputs = inputs.clone();
+      for (Integer[] portPairsB : listB) {
+        inputs[2] = portPairsB[1]; // OutputA
+        inputs[3] = portPairsB[0]; // OutputB
+        inputs[4] = flip ? 0 : 1; // The flip bit
+      }
+      construtorInput.add(inputs);
+      encoderPortPairs.addAll(construtorInput);
+    }
+    return encoderPortPairs;
+  }
+
+  /**
+   * Constructs the list of inputs to be used for the encoder test.
+   *
+   * @return A collection of different input pairs to use for the encoder
+   */
+  public Collection<Integer[]> getEncoderDIOCrossConnectCollection() {
+    Collection<Integer[]> encoderPortPairs = new ArrayList<Integer[]>();
+    assert getDIOCrossConnect().size() == 2;
+    encoderPortPairs.addAll(getPairArray(getDIOCrossConnect().get(0), getDIOCrossConnect().get(1),
+        false));
+    encoderPortPairs.addAll(getPairArray(getDIOCrossConnect().get(1), getDIOCrossConnect().get(0),
+        false));
+    assert encoderPortPairs.size() == 8;
+    return encoderPortPairs;
+  }
+
+  /**
+   * Constructs a new set of objects representing a single-pole IIR filter with a noisy data source.
+   *
+   * @return a single-pole IIR filter with a noisy data source
+   */
+  public FilterNoiseFixture<LinearDigitalFilter> getSinglePoleIIRNoiseFixture() {
+    return new FilterNoiseFixture<LinearDigitalFilter>() {
+      @Override
+      protected LinearDigitalFilter giveFilter(PIDSource source) {
+        return LinearDigitalFilter.singlePoleIIR(source,
+            kSinglePoleIIRTimeConstant,
+            kFilterStep);
+      }
+    };
+  }
+
+  /**
+   * Constructs a new set of objects representing a moving average filter with a noisy data source
+   * using a linear digital filter.
+   *
+   * @return a moving average filter with a noisy data source
+   */
+  public FilterNoiseFixture<LinearDigitalFilter> getMovAvgNoiseFixture() {
+    return new FilterNoiseFixture<LinearDigitalFilter>() {
+      @Override
+      protected LinearDigitalFilter giveFilter(PIDSource source) {
+        return LinearDigitalFilter.movingAverage(source, kMovAvgTaps);
+      }
+    };
+  }
+
+  /**
+   * Constructs a new set of objects representing a single-pole IIR filter with a repeatable data
+   * source.
+   *
+   * @return a single-pole IIR filter with a repeatable data source
+   */
+  public FilterOutputFixture<LinearDigitalFilter> getSinglePoleIIROutputFixture() {
+    return new FilterOutputFixture<LinearDigitalFilter>(kSinglePoleIIRExpectedOutput) {
+      @Override
+      protected LinearDigitalFilter giveFilter() {
+        m_data = new DataWrapper(getData);
+        return LinearDigitalFilter.singlePoleIIR(m_data,
+            kSinglePoleIIRTimeConstant,
+            kFilterStep);
+      }
+    };
+  }
+
+  /**
+   * Constructs a new set of objects representing a high-pass filter with a repeatable data source.
+   *
+   * @return a high-pass filter with a repeatable data source
+   */
+  public FilterOutputFixture<LinearDigitalFilter> getHighPassOutputFixture() {
+    return new FilterOutputFixture<LinearDigitalFilter>(kHighPassExpectedOutput) {
+      @Override
+      protected LinearDigitalFilter giveFilter() {
+        m_data = new DataWrapper(getData);
+        return LinearDigitalFilter.highPass(m_data, kHighPassTimeConstant,
+            kFilterStep);
+      }
+    };
+  }
+
+  /**
+   * Constructs a new set of objects representing a moving average filter with a repeatable data
+   * source using a linear digital filter.
+   *
+   * @return a moving average filter with a repeatable data source
+   */
+  public FilterOutputFixture<LinearDigitalFilter> getMovAvgOutputFixture() {
+    return new FilterOutputFixture<LinearDigitalFilter>(kMovAvgExpectedOutput) {
+      @Override
+      protected LinearDigitalFilter giveFilter() {
+        m_data = new DataWrapper(getData);
+        return LinearDigitalFilter.movingAverage(m_data, kMovAvgTaps);
+      }
+    };
+  }
+
+  /**
+   * Constructs a new set of objects representing a moving average filter with a repeatable data
+   * source using a linear digital filter.
+   *
+   * @return a moving average filter with a repeatable data source
+   */
+  public FilterOutputFixture<LinearDigitalFilter> getPulseFixture() {
+    return new FilterOutputFixture<LinearDigitalFilter>(0.0) {
+      @Override
+      protected LinearDigitalFilter giveFilter() {
+        m_data = new DataWrapper(getPulseData);
+        return LinearDigitalFilter.movingAverage(m_data, kMovAvgTaps);
+      }
+    };
+  }
+
+  /**
+   * Gets the singleton of the TestBench. If the TestBench is not already allocated in constructs an
+   * new instance of it. Otherwise it returns the existing instance.
+   *
+   * @return The Singleton instance of the TestBench
+   */
+  public static TestBench getInstance() {
+    if (instance == null) {
+      instance = new TestBench();
+    }
+    return instance;
+  }
+
+  /**
+   * Provides access to the output stream for the test system. This should be used instead of
+   * System.out This is gives us a way to implement changes to where the output text of this test
+   * system is sent.
+   *
+   * @return The test bench global print stream.
+   */
+  public static PrintStream out() {
+    return System.out;
+  }
+
+  /**
+   * Provides access to the error stream for the test system. This should be used instead of
+   * System.err This is gives us a way to implement changes to where the output text of this test
+   * system is sent.
+   *
+   * @return The test bench global print stream.
+   */
+  public static PrintStream err() {
+    return System.err;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java
new file mode 100644
index 0000000..5422d8f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/TestSuite.java
@@ -0,0 +1,380 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2008-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpilibj.test;
+
+import java.io.IOException;
+import java.io.InputStream;
+import java.util.ArrayList;
+import java.util.Arrays;
+import java.util.List;
+import java.util.Objects;
+import java.util.logging.LogManager;
+import java.util.logging.Logger;
+import java.util.regex.Pattern;
+
+import org.junit.runner.JUnitCore;
+import org.junit.runner.Result;
+import org.junit.runner.RunWith;
+import org.junit.runner.notification.Failure;
+import org.junit.runners.Suite;
+import org.junit.runners.Suite.SuiteClasses;
+
+import junit.framework.JUnit4TestAdapter;
+import junit.runner.Version;
+
+import edu.wpi.first.wpilibj.WpiLibJTestSuite;
+import edu.wpi.first.wpilibj.smartdashboard.SmartDashboardTestSuite;
+
+/**
+ * The WPILibJ Integeration Test Suite collects all of the tests to be run by junit. In order for a
+ * test to be run, it must be added the list of suite classes below. The tests will be run in the
+ * order they are listed in the suite classes annotation.
+ */
+@RunWith(Suite.class)
+// These are listed on separate lines to prevent merge conflicts
+@SuiteClasses({WpiLibJTestSuite.class, SmartDashboardTestSuite.class})
+public class TestSuite extends AbstractTestSuite {
+  static {
+    // Sets up the logging output
+    final InputStream inputStream = TestSuite.class.getResourceAsStream("/logging.properties");
+    try {
+      Objects.requireNonNull(inputStream, "./logging.properties was not loaded");
+      LogManager.getLogManager().readConfiguration(inputStream);
+      Logger.getAnonymousLogger().info("Loaded");
+    } catch (final IOException | NullPointerException ex) {
+      Logger.getAnonymousLogger().severe("Could not load default logging.properties file");
+      Logger.getAnonymousLogger().severe(ex.getMessage());
+    }
+
+    TestBench.out().println("Starting Tests");
+  }
+
+  private static final Logger WPILIBJ_ROOT_LOGGER = Logger.getLogger("edu.wpi.first.wpilibj");
+  private static final Logger WPILIBJ_COMMAND_ROOT_LOGGER = Logger
+      .getLogger("edu.wpi.first.wpilibj.command");
+
+
+  private static final Class<?> QUICK_TEST = QuickTest.class;
+  private static final String QUICK_TEST_FLAG = "--quick";
+  private static final String HELP_FLAG = "--help";
+  private static final String METHOD_NAME_FILTER = "--methodFilter=";
+  private static final String METHOD_REPEAT_FILTER = "--repeat=";
+  private static final String CLASS_NAME_FILTER = "--filter=";
+
+  private static TestSuite instance = null;
+
+  /**
+   * Get the singleton instance of the test suite.
+   */
+  public static TestSuite getInstance() {
+    if (instance == null) {
+      instance = new TestSuite();
+    }
+    return instance;
+  }
+
+  /**
+   * This has to be public so that the JUnit4.
+   */
+  public TestSuite() {
+  }
+
+  /**
+   * Displays a help message for the user when they use the --help flag at runtime.
+   */
+  protected static void displayHelp() {
+    StringBuilder helpMessage = new StringBuilder("Test Parameters help: \n");
+    helpMessage.append("\t" + QUICK_TEST_FLAG
+        + " will cause the quick test to be run. Ignores other flags except for "
+        + METHOD_REPEAT_FILTER + "\n");
+    helpMessage.append("\t" + CLASS_NAME_FILTER
+        + " will use the supplied regex text to search for suite/test class names "
+        + "matching the regex and run them.\n");
+    helpMessage.append("\t" + METHOD_NAME_FILTER
+        + " will use the supplied regex text to search for test methods (excluding methods "
+        + "with the @Ignore annotation) and run only those methods. Can be paired with "
+        + METHOD_REPEAT_FILTER + " to " + "repeat the selected tests multiple times.\n");
+    helpMessage.append("\t" + METHOD_REPEAT_FILTER + " will repeat the tests selected with either "
+        + QUICK_TEST_FLAG + " or " + CLASS_NAME_FILTER
+        + " and run them the given number of times.\n");
+    helpMessage
+        .append("[NOTE] All regex uses the syntax defined by java.util.regex.Pattern. This "
+            + "documentation can be found at "
+            + "http://docs.oracle.com/javase/7/docs/api/java/util/regex/Pattern.html\n");
+    helpMessage.append("\n");
+    helpMessage.append("\n");
+
+    TestBench.out().println(helpMessage);
+  }
+
+  /**
+   * Lets the user know that they used the TestSuite improperly and gives details about how to use
+   * it correctly in the future.
+   */
+  protected static void displayInvalidUsage(String message, String... args) {
+    StringBuilder invalidMessage = new StringBuilder("Invalid Usage: " + message + "\n");
+    invalidMessage.append("Params received: ");
+    for (String a : args) {
+      invalidMessage.append(a + " ");
+    }
+    invalidMessage.append("\n");
+    invalidMessage
+        .append("For details on proper usage of the runtime flags please run again with the "
+            + HELP_FLAG + " flag.\n\n");
+
+    TestBench.out().println(invalidMessage);
+
+  }
+
+  /**
+   * Prints the loaded tests before they are run.
+   *
+   * @param classes the classes that were loaded.
+   */
+  protected static void printLoadedTests(final Class<?>... classes) {
+    StringBuilder loadedTestsMessage = new StringBuilder("The following tests were loaded:\n");
+    Package packagE = null;
+    for (Class<?> c : classes) {
+      if (c.getPackage().equals(packagE)) {
+        packagE = c.getPackage();
+        loadedTestsMessage.append(packagE.getName() + "\n");
+      }
+      loadedTestsMessage.append("\t" + c.getSimpleName() + "\n");
+    }
+    TestBench.out().println(loadedTestsMessage);
+  }
+
+
+  /**
+   * Parses the arguments passed at runtime and runs the appropriate tests based upon these
+   * arguments.
+   *
+   * @param args the args passed into the program at runtime
+   * @return the restults of the tests that have run. If no tests were run then null is returned.
+   */
+  protected static Result parseArgsRunAndGetResult(final String[] args) {
+    if (args.length == 0) { // If there are no args passed at runtime then just
+      // run all of the tests.
+      printLoadedTests(TestSuite.class);
+      return JUnitCore.runClasses(TestSuite.class);
+    }
+
+    // The method filter was passed
+    boolean methodFilter = false;
+    String methodRegex = "";
+    // The class filter was passed
+    boolean classFilter = false;
+    String classRegex = "";
+    int repeatCount = 1;
+
+    for (String s : args) {
+      if (Pattern.matches(METHOD_NAME_FILTER + ".*", s)) {
+        methodFilter = true;
+        methodRegex = new String(s).replace(METHOD_NAME_FILTER, "");
+      }
+      if (Pattern.matches(METHOD_REPEAT_FILTER + ".*", s)) {
+        try {
+          repeatCount = Integer.parseInt(new String(s).replace(METHOD_REPEAT_FILTER, ""));
+        } catch (NumberFormatException ex) {
+          displayInvalidUsage("The argument passed to the repeat rule was not a valid integer.",
+              args);
+        }
+      }
+      if (Pattern.matches(CLASS_NAME_FILTER + ".*", s)) {
+        classFilter = true;
+        classRegex = s.replace(CLASS_NAME_FILTER, "");
+      }
+    }
+
+
+    ArrayList<String> argsParsed = new ArrayList<String>(Arrays.asList(args));
+    if (argsParsed.contains(HELP_FLAG)) {
+      // If the user inputs the help flag then return the help message and exit
+      // without running any tests
+      displayHelp();
+      return null;
+    }
+    if (argsParsed.contains(QUICK_TEST_FLAG)) {
+      printLoadedTests(QUICK_TEST);
+      return JUnitCore.runClasses(QUICK_TEST);
+    }
+
+    /**
+     * Stores the data from multiple {@link Result}s in one class that can be
+     * returned to display the results.
+     */
+    class MultipleResult extends Result {
+      private static final long serialVersionUID = 1L;
+      private final List<Failure> m_failures = new ArrayList<>();
+      private int m_runCount = 0;
+      private int m_ignoreCount = 0;
+      private long m_runTime = 0;
+
+      @Override
+      public int getRunCount() {
+        return m_runCount;
+      }
+
+      @Override
+      public int getFailureCount() {
+        return m_failures.size();
+      }
+
+      @Override
+      public long getRunTime() {
+        return m_runTime;
+      }
+
+      @Override
+      public List<Failure> getFailures() {
+        return m_failures;
+      }
+
+      @Override
+      public int getIgnoreCount() {
+        return m_ignoreCount;
+      }
+
+      /**
+       * Adds the given result's data to this result.
+       *
+       * @param result the result to add to this result
+       */
+      void addResult(Result result) {
+        m_failures.addAll(result.getFailures());
+        m_runCount += result.getRunCount();
+        m_ignoreCount += result.getIgnoreCount();
+        m_runTime += result.getRunTime();
+      }
+    }
+
+    // If a specific method has been requested
+    if (methodFilter) {
+      List<ClassMethodPair> pairs = (new TestSuite()).getMethodMatching(methodRegex);
+      if (pairs.size() == 0) {
+        displayInvalidUsage("None of the arguments passed to the method name filter matched.",
+            args);
+        return null;
+      }
+      // Print out the list of tests before we run them
+      TestBench.out().println("Running the following tests:");
+      Class<?> classListing = null;
+      for (ClassMethodPair p : pairs) {
+        if (!p.m_methodClass.equals(classListing)) {
+          // Only display the class name every time it changes
+          classListing = p.m_methodClass;
+          TestBench.out().println(classListing);
+        }
+        TestBench.out().println("\t" + p.m_methodName);
+      }
+
+
+      // The test results will be saved here
+      MultipleResult results = new MultipleResult();
+      // Runs tests multiple times if the repeat rule is used
+      for (int i = 0; i < repeatCount; i++) {
+        // Now run all of the tests
+        for (ClassMethodPair p : pairs) {
+          Result result = (new JUnitCore()).run(p.getMethodRunRequest());
+          // Store the given results in one cohesive result
+          results.addResult(result);
+        }
+      }
+
+      return results;
+    }
+
+    // If a specific class has been requested
+    if (classFilter) {
+      List<Class<?>> testClasses = (new TestSuite()).getSuiteOrTestMatchingRegex(classRegex);
+      if (testClasses.size() == 0) {
+        displayInvalidUsage("None of the arguments passed to the filter matched.", args);
+        return null;
+      }
+      printLoadedTests(testClasses.toArray(new Class[0]));
+      MultipleResult results = new MultipleResult();
+      // Runs tests multiple times if the repeat rule is used
+      for (int i = 0; i < repeatCount; i++) {
+        Result result = (new JUnitCore()).run(testClasses.toArray(new Class[0]));
+        // Store the given results in one cohesive result
+        results.addResult(result);
+      }
+      return results;
+    }
+    displayInvalidUsage(
+        "None of the parameters that you passed matched any of the accepted flags.", args);
+
+    return null;
+  }
+
+  protected static void displayResults(Result result) {
+    // Results are collected and displayed here
+    TestBench.out().println("\n");
+    if (!result.wasSuccessful()) {
+      // Prints out a list of stack traces for the failed tests
+      TestBench.out().println("Failure List: ");
+      for (Failure f : result.getFailures()) {
+        TestBench.out().println(f.getDescription());
+        TestBench.out().println(f.getTrace());
+      }
+      TestBench.out().println();
+      TestBench.out().println("FAILURES!!!");
+      // Print the test statistics
+      TestBench.out().println(
+          "Tests run: " + result.getRunCount() + ", Failures: " + result.getFailureCount()
+              + ", Ignored: " + result.getIgnoreCount() + ", In " + result.getRunTime() + "ms");
+
+      // Prints out a list of test that failed
+      TestBench.out().println("Failure List (short):");
+      String failureClass = result.getFailures().get(0).getDescription().getClassName();
+      TestBench.out().println(failureClass);
+      for (Failure f : result.getFailures()) {
+        if (!failureClass.equals(f.getDescription().getClassName())) {
+          failureClass = f.getDescription().getClassName();
+          TestBench.out().println(failureClass);
+        }
+        TestBench.err().println("\t" + f.getDescription());
+      }
+    } else {
+      TestBench.out().println("SUCCESS!");
+      TestBench.out().println(
+          "Tests run: " + result.getRunCount() + ", Ignored: " + result.getIgnoreCount() + ", In "
+              + result.getRunTime() + "ms");
+    }
+    TestBench.out().println();
+  }
+
+  /**
+   * This is used by ant to get the Junit tests. This is required because the tests try to load
+   * using a JUnit 3 framework. JUnit4 uses annotations to load tests. This method allows JUnit3 to
+   * load JUnit4 tests.
+   */
+  public static junit.framework.Test suite() {
+    return new JUnit4TestAdapter(TestSuite.class);
+  }
+
+
+  /**
+   * The method called at runtime.
+   *
+   * @param args The test suites to run
+   */
+  public static void main(String[] args) {
+    TestBench.out().println("JUnit version " + Version.id());
+
+    // Tests are run here
+    Result result = parseArgsRunAndGetResult(args);
+    if (result != null) {
+      // Results are collected and displayed here
+      displayResults(result);
+
+      System.exit(result.wasSuccessful() ? 0 : 1);
+    }
+    System.exit(1);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/package-info.java b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/package-info.java
new file mode 100644
index 0000000..481cb08
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/java/edu/wpi/first/wpilibj/test/package-info.java
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/**
+ * This is the starting point for the integration testing framework. This package should contain
+ * classes that are not explicitly for testing the library but instead provide the framework that
+ * the tests can extend from. Every test should extend from
+ * {@link edu.wpi.first.wpilibj.test.AbstractComsSetup}
+ * to ensure that Network Communications is properly instantiated before the test is run. The
+ * {@link edu.wpi.first.wpilibj.test.TestBench} should contain the port numbers for all of the
+ * hardware and these values should not be explicitly defined anywhere else in the testing
+ * framework.
+ */
+package edu.wpi.first.wpilibj.test;
diff --git a/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/resources/logging.properties b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/resources/logging.properties
new file mode 100644
index 0000000..b15c534
--- /dev/null
+++ b/third_party/allwpilib_2019/wpilibjIntegrationTests/src/main/resources/logging.properties
@@ -0,0 +1,25 @@
+# "handlers" specifies a comma separated list of log Handler
+# classes.  These handlers will be installed during VM startup.
+# By default we only configure a ConsoleHandler, which will only
+# show messages at the INFO and above levels.
+handlers=java.util.logging.ConsoleHandler
+# Default global logging level.
+# This specifies which kinds of events are logged across
+# all loggers.  For any given facility this global level
+# can be overriden by a facility specific level
+# Note that the ConsoleHandler also has a separate level
+# setting to limit messages printed to the console.
+#.level= INFO
+.level=INFO
+############################################################
+# Handler specific properties.
+# Describes specific configuration info for Handlers.
+############################################################
+java.util.logging.ConsoleHandler.level=FINER
+java.util.logging.ConsoleHandler.formatter=java.util.logging.SimpleFormatter
+############################################################
+# Facility specific properties.
+# Provides extra control for each logger.
+############################################################
+edu.wpi.first.wpilibj.level=INFO
+edu.wpi.first.wpilibj.command.level=INFO
diff --git a/third_party/allwpilib_2019/wpiutil/.styleguide b/third_party/allwpilib_2019/wpiutil/.styleguide
new file mode 100644
index 0000000..2c65222
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/.styleguide
@@ -0,0 +1,81 @@
+cppHeaderFileInclude {
+  \.h$
+  \.inc$
+}
+
+cppSrcFileInclude {
+  \.cpp$
+}
+
+generatedFileExclude {
+  src/main/native/cpp/http_parser\.cpp$
+  src/main/native/cpp/llvm/
+  src/main/native/include/llvm/
+  src/main/native/include/wpi/AlignOf\.h$
+  src/main/native/include/wpi/ArrayRef\.h$
+  src/main/native/include/wpi/Compiler\.h$
+  src/main/native/include/wpi/ConvertUTF\.h$
+  src/main/native/include/wpi/DenseMap\.h$
+  src/main/native/include/wpi/DenseMapInfo\.h$
+  src/main/native/include/wpi/EpochTracker\.h$
+  src/main/native/include/wpi/ErrorOr\.h$
+  src/main/native/include/wpi/FileSystem\.h$
+  src/main/native/include/wpi/Format\.h$
+  src/main/native/include/wpi/Hashing\.h$
+  src/main/native/include/wpi/IntrusiveRefCntPtr\.h$
+  src/main/native/include/wpi/MapVector\.h$
+  src/main/native/include/wpi/MathExtras\.h$
+  src/main/native/include/wpi/NativeFormatting\.h$
+  src/main/native/include/wpi/Path\.h$
+  src/main/native/include/wpi/PointerLikeTypeTraits\.h$
+  src/main/native/include/wpi/STLExtras\.h$
+  src/main/native/include/wpi/Signal\.h$
+  src/main/native/include/wpi/SmallPtrSet\.h$
+  src/main/native/include/wpi/SmallSet\.h$
+  src/main/native/include/wpi/SmallString\.h$
+  src/main/native/include/wpi/SmallVector\.h$
+  src/main/native/include/wpi/StringExtras\.h$
+  src/main/native/include/wpi/StringMap\.h$
+  src/main/native/include/wpi/StringRef\.h$
+  src/main/native/include/wpi/Twine\.h$
+  src/main/native/include/wpi/WindowsError\.h$
+  src/main/native/include/wpi/http_parser\.h$
+  src/main/native/include/wpi/iterator\.h$
+  src/main/native/include/wpi/iterator_range\.h$
+  src/main/native/include/wpi/raw_os_ostream\.h$
+  src/main/native/include/wpi/raw_ostream\.h$
+  src/main/native/include/wpi/type_traits\.h$
+  src/main/native/cpp/json
+  src/main/native/include/wpi/json
+  src/test/native/cpp/json/
+  src/main/native/include/uv\.h$
+  src/main/native/include/uv/
+  src/main/native/libuv/
+  src/main/native/include/wpi/optional\.h$
+  src/test/native/cpp/test_optional\.cpp$
+  src/main/native/resources/
+}
+
+licenseUpdateExclude {
+  src/main/native/cpp/Base64\.cpp$
+  src/main/native/cpp/sha1\.cpp$
+  src/main/native/cpp/TCPAcceptor\.cpp$
+  src/main/native/cpp/TCPConnector\.cpp$
+  src/main/native/cpp/TCPStream\.cpp$
+  src/main/native/include/wpi/ConcurrentQueue\.h$
+  src/main/native/include/wpi/Path\.h$
+  src/main/native/include/wpi/sha1\.h$
+  src/main/native/include/wpi/TCPAcceptor\.h$
+  src/main/native/include/wpi/TCPConnector\.h$
+  src/main/native/include/wpi/TCPStream\.h$
+}
+
+repoRootNameOverride {
+  wpiutil
+}
+
+includeGuardRoots {
+  wpiutil/src/main/native/cpp/
+  wpiutil/src/main/native/include/
+  wpiutil/src/test/native/cpp/
+}
diff --git a/third_party/allwpilib_2019/wpiutil/CMakeLists.txt b/third_party/allwpilib_2019/wpiutil/CMakeLists.txt
new file mode 100644
index 0000000..ac18ebd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/CMakeLists.txt
@@ -0,0 +1,143 @@
+project(wpiutil)
+
+include(SubDirList)
+include(GenResources)
+
+# Java bindings
+if (NOT WITHOUT_JAVA)
+  find_package(Java)
+  include(UseJava)
+  set(CMAKE_JAVA_COMPILE_FLAGS "-Xlint:unchecked")
+
+  set(CMAKE_JAVA_INCLUDE_PATH wpiutil.jar)
+
+  file(GLOB_RECURSE JAVA_SOURCES src/main/java/*.java)
+  add_jar(wpiutil_jar ${JAVA_SOURCES} OUTPUT_NAME wpiutil)
+
+  get_property(WPIUTIL_JAR_FILE TARGET wpiutil_jar PROPERTY JAR_FILE)
+  install(FILES ${WPIUTIL_JAR_FILE} DESTINATION "${java_lib_dest}")
+
+  set_property(TARGET wpiutil_jar PROPERTY FOLDER "java")
+
+endif()
+
+set(THREADS_PREFER_PTHREAD_FLAG ON)
+find_package(Threads REQUIRED)
+
+GENERATE_RESOURCES(src/main/native/resources generated/main/cpp WPI wpi wpiutil_resources_src)
+
+file(GLOB_RECURSE wpiutil_native_src src/main/native/cpp/*.cpp)
+
+file(GLOB uv_native_src src/main/native/libuv/*.cpp)
+
+file(GLOB uv_windows_src src/main/native/libuv/win/*.cpp)
+
+set(uv_unix_src
+    src/main/native/libuv/unix/async.cpp
+    src/main/native/libuv/unix/core.cpp
+    src/main/native/libuv/unix/dl.cpp
+    src/main/native/libuv/unix/fs.cpp
+    src/main/native/libuv/unix/getaddrinfo.cpp
+    src/main/native/libuv/unix/getnameinfo.cpp
+    src/main/native/libuv/unix/loop-watcher.cpp
+    src/main/native/libuv/unix/loop.cpp
+    src/main/native/libuv/unix/pipe.cpp
+    src/main/native/libuv/unix/poll.cpp
+    src/main/native/libuv/unix/process.cpp
+    src/main/native/libuv/unix/signal.cpp
+    src/main/native/libuv/unix/stream.cpp
+    src/main/native/libuv/unix/tcp.cpp
+    src/main/native/libuv/unix/thread.cpp
+    src/main/native/libuv/unix/timer.cpp
+    src/main/native/libuv/unix/tty.cpp
+    src/main/native/libuv/unix/udp.cpp
+)
+
+set(uv_darwin_src
+    src/main/native/libuv/unix/bsd-ifaddrs.cpp
+    src/main/native/libuv/unix/darwin.cpp
+    src/main/native/libuv/unix/darwin-proctitle.cpp
+    src/main/native/libuv/unix/fsevents.cpp
+    src/main/native/libuv/unix/kqueue.cpp
+    src/main/native/libuv/unix/proctitle.cpp
+)
+
+set(uv_linux_src
+    src/main/native/libuv/unix/linux-core.cpp
+    src/main/native/libuv/unix/linux-inotify.cpp
+    src/main/native/libuv/unix/linux-syscalls.cpp
+    src/main/native/libuv/unix/procfs-exepath.cpp
+    src/main/native/libuv/unix/proctitle.cpp
+    src/main/native/libuv/unix/sysinfo-loadavg.cpp
+    src/main/native/libuv/unix/sysinfo-memory.cpp
+)
+
+add_library(wpiutil ${wpiutil_native_src} ${uv_native_src} ${wpiutil_resources_src})
+set_target_properties(wpiutil PROPERTIES DEBUG_POSTFIX "d")
+
+set_property(TARGET wpiutil PROPERTY FOLDER "libraries")
+
+if(NOT MSVC)
+    target_sources(wpiutil PRIVATE ${uv_unix_src})
+    if (APPLE)
+        target_sources(wpiutil PRIVATE ${uv_darwin_src})
+    else()
+        target_sources(wpiutil PRIVATE ${uv_linux_src})
+    endif()
+    target_compile_options(wpiutil PUBLIC -std=c++14 -Wall -pedantic -Wextra -Wno-unused-parameter)
+    target_compile_options(wpiutil PRIVATE -D_GNU_SOURCE)
+else()
+    target_sources(wpiutil PRIVATE ${uv_windows_src})
+    target_compile_options(wpiutil PUBLIC -DNOMINMAX)
+    target_compile_options(wpiutil PRIVATE -D_CRT_SECURE_NO_WARNINGS)
+    if(BUILD_SHARED_LIBS)
+        target_compile_options(wpiutil PRIVATE -DBUILDING_UV_SHARED)
+    endif()
+endif()
+
+target_link_libraries(wpiutil Threads::Threads ${CMAKE_DL_LIBS})
+target_include_directories(wpiutil PUBLIC
+                            $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/src/main/native/include>
+                            $<INSTALL_INTERFACE:${include_dest}/wpiutil>)
+target_include_directories(wpiutil PRIVATE
+    src/main/native/libuv
+    src/main/native/include/uv-private
+)
+
+install(TARGETS wpiutil EXPORT wpiutil DESTINATION "${main_lib_dest}")
+install(DIRECTORY src/main/native/include/ DESTINATION "${include_dest}/wpiutil")
+
+if (NOT WITHOUT_JAVA AND MSVC)
+    install(TARGETS wpiutil RUNTIME DESTINATION "${jni_lib_dest}" COMPONENT Runtime)
+endif()
+
+if (MSVC)
+    set (wpiutil_config_dir ${wpilib_dest})
+else()
+    set (wpiutil_config_dir share/wpiutil)
+endif()
+
+install(FILES wpiutil-config.cmake DESTINATION ${wpiutil_config_dir})
+install(EXPORT wpiutil DESTINATION ${wpiutil_config_dir})
+
+SUBDIR_LIST(wpiutil_examples "${CMAKE_CURRENT_SOURCE_DIR}/examples")
+foreach(example ${wpiutil_examples})
+    file(GLOB wpiutil_example_src examples/${example}/*.cpp)
+    if(wpiutil_example_src)
+        add_executable(wpiutil_${example} ${wpiutil_example_src})
+        target_link_libraries(wpiutil_${example} wpiutil)
+    endif()
+endforeach()
+
+if (UNIX AND NOT APPLE)
+    set (LIBUTIL -lutil)
+else()
+    set (LIBUTIL)
+endif()
+file(GLOB netconsoleServer_src src/netconsoleServer/native/cpp/*.cpp)
+add_executable(netconsoleServer ${netconsoleServer_src})
+target_link_libraries(netconsoleServer wpiutil ${LIBUTIL})
+
+file(GLOB netconsoleTee_src src/netconsoleTee/native/cpp/*.cpp)
+add_executable(netconsoleTee ${netconsoleTee_src})
+target_link_libraries(netconsoleTee wpiutil)
diff --git a/third_party/allwpilib_2019/wpiutil/build.gradle b/third_party/allwpilib_2019/wpiutil/build.gradle
new file mode 100644
index 0000000..2c2cc7f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/build.gradle
@@ -0,0 +1,200 @@
+apply from: "${rootDir}/shared/resources.gradle"
+
+ext {
+    nativeName = 'wpiutil'
+    devMain = 'edu.wpi.first.wpiutil.DevMain'
+    def generateTask = createGenerateResourcesTask('main', 'WPI', 'wpi', project)
+    extraSetup = {
+        it.tasks.withType(CppCompile) {
+            dependsOn generateTask
+        }
+        it.sources {
+            libuvCpp(CppSourceSet) {
+                source {
+                    srcDirs 'src/main/native/libuv'
+                    include '*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/include', 'src/main/native/include/uv-private', 'src/main/native/libuv'
+                }
+            }
+            resourcesCpp(CppSourceSet) {
+                source {
+                    srcDirs "$buildDir/generated/main/cpp", "$rootDir/shared/singlelib"
+                    include '*.cpp'
+                }
+                exportedHeaders {
+                    srcDirs 'src/main/native/include'
+                }
+            }
+        }
+        if (it.targetPlatform.operatingSystem.name != 'windows') {
+            it.cppCompiler.define '_GNU_SOURCE'
+            it.sources {
+                libuvUnixCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/libuv/unix'
+                        includes = [
+                            'async.cpp',
+                            'core.cpp',
+                            'dl.cpp',
+                            'fs.cpp',
+                            'getaddrinfo.cpp',
+                            'getnameinfo.cpp',
+                            'loop-watcher.cpp',
+                            'loop.cpp',
+                            'pipe.cpp',
+                            'poll.cpp',
+                            'process.cpp',
+                            'signal.cpp',
+                            'stream.cpp',
+                            'tcp.cpp',
+                            'thread.cpp',
+                            'timer.cpp',
+                            'tty.cpp',
+                            'udp.cpp',
+                        ]
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/include/uv-private', 'src/main/native/libuv'
+                    }
+                }
+            }
+        }
+        if (it.targetPlatform.operatingSystem.name == 'windows') {
+            if (it in SharedLibraryBinarySpec) {
+                it.cppCompiler.define 'BUILDING_UV_SHARED'
+            }
+            it.sources {
+                libuvWindowsCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/libuv/win'
+                        include '*.cpp'
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/include/uv-private', 'src/main/native/libuv'
+                    }
+                }
+            }
+        } else if (it.targetPlatform.operatingSystem.name == 'osx') {
+            it.sources {
+                libuvMacCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/libuv/unix'
+                        includes = [
+                            'bsd-ifaddrs.cpp',
+                            'darwin.cpp',
+                            'darwin-proctitle.cpp',
+                            'fsevents.cpp',
+                            'kqueue.cpp',
+                            'proctitle.cpp'
+                        ]
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/include/uv-private', 'src/main/native/libuv'
+                    }
+                }
+            }
+        } else {
+            it.sources {
+                libuvLinuxCpp(CppSourceSet) {
+                    source {
+                        srcDirs 'src/main/native/libuv/unix'
+                        includes = [
+                            'linux-core.cpp',
+                            'linux-inotify.cpp',
+                            'linux-syscalls.cpp',
+                            'procfs-exepath.cpp',
+                            'proctitle.cpp',
+                            'sysinfo-loadavg.cpp',
+                            'sysinfo-memory.cpp',
+                        ]
+                    }
+                    exportedHeaders {
+                        srcDirs 'src/main/native/include', 'src/main/native/include/uv-private', 'src/main/native/libuv'
+                    }
+                }
+            }
+        }
+    }
+}
+
+def examplesMap = [:];
+file("$projectDir/examples").list(new FilenameFilter() {
+    @Override
+    public boolean accept(File current, String name) {
+        return new File(current, name).isDirectory();
+    }
+}).each {
+    examplesMap.put(it, [])
+}
+
+apply from: "${rootDir}/shared/javacpp/setupBuild.gradle"
+
+model {
+    // Exports config is a utility to enable exporting all symbols in a C++ library on windows to a DLL.
+    // This removes the need for DllExport on a library. However, the gradle C++ builder has a bug
+    // where some extra symbols are added that cannot be resolved at link time. This configuration
+    // lets you specify specific symbols to exlude from exporting.
+    exportsConfigs {
+        wpiutil(ExportsConfig) {
+            x86ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure', '_CT??_R0?AVout_of_range', '_CTA3?AVout_of_range',
+                                 '_TI3?AVout_of_range', '_CT??_R0?AVbad_cast']
+            x64ExcludeSymbols = ['_CT??_R0?AV_System_error', '_CT??_R0?AVexception', '_CT??_R0?AVfailure',
+                                 '_CT??_R0?AVruntime_error', '_CT??_R0?AVsystem_error', '_CTA5?AVfailure',
+                                 '_TI5?AVfailure', '_CT??_R0?AVout_of_range', '_CTA3?AVout_of_range',
+                                 '_TI3?AVout_of_range', '_CT??_R0?AVbad_cast']
+        }
+    }
+    components {
+        examplesMap.each { key, value ->
+            "${key}"(NativeExecutableSpec) {
+                targetBuildTypes 'debug'
+                binaries.all {
+                    lib library: 'wpiutil', linkage: 'shared'
+                }
+                sources {
+                    cpp {
+                        source {
+                            srcDirs 'examples/' + "${key}"
+                            include '**/*.cpp'
+                        }
+                    }
+                }
+            }
+        }
+        netconsoleServer(NativeExecutableSpec) {
+            targetBuildTypes 'release'
+            sources {
+                cpp {
+                    source {
+                        srcDirs = ['src/netconsoleServer/native/cpp']
+                        includes = ['**/*.cpp']
+                    }
+                }
+            }
+            binaries.all { binary ->
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+                if (binary.targetPlatform.operatingSystem.isLinux()) {
+                    linker.args "-lutil"
+                }
+            }
+        }
+        netconsoleTee(NativeExecutableSpec) {
+            targetBuildTypes 'release'
+            sources {
+                cpp {
+                    source {
+                        srcDirs = ['src/netconsoleTee/native/cpp']
+                        includes = ['**/*.cpp']
+                    }
+                }
+            }
+            binaries.all { binary ->
+                lib project: ':wpiutil', library: 'wpiutil', linkage: 'static'
+            }
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/examples/webserver/webserver.cpp b/third_party/allwpilib_2019/wpiutil/examples/webserver/webserver.cpp
new file mode 100644
index 0000000..e112d04
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/examples/webserver/webserver.cpp
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* 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 <cstdio>
+
+#include "wpi/EventLoopRunner.h"
+#include "wpi/HttpServerConnection.h"
+#include "wpi/UrlParser.h"
+#include "wpi/raw_ostream.h"
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/Tcp.h"
+
+namespace uv = wpi::uv;
+
+class MyHttpServerConnection : public wpi::HttpServerConnection {
+ public:
+  explicit MyHttpServerConnection(std::shared_ptr<uv::Stream> stream)
+      : HttpServerConnection(stream) {}
+
+ protected:
+  void ProcessRequest() override;
+};
+
+void MyHttpServerConnection::ProcessRequest() {
+  wpi::errs() << "HTTP request: '" << m_request.GetUrl() << "'\n";
+  wpi::UrlParser url{m_request.GetUrl(),
+                     m_request.GetMethod() == wpi::HTTP_CONNECT};
+  if (!url.IsValid()) {
+    // failed to parse URL
+    SendError(400);
+    return;
+  }
+
+  wpi::StringRef path;
+  if (url.HasPath()) path = url.GetPath();
+  wpi::errs() << "path: \"" << path << "\"\n";
+
+  wpi::StringRef query;
+  if (url.HasQuery()) query = url.GetQuery();
+  wpi::errs() << "query: \"" << query << "\"\n";
+
+  const bool isGET = m_request.GetMethod() == wpi::HTTP_GET;
+  if (isGET && path.equals("/")) {
+    // build HTML root page
+    wpi::SmallString<256> buf;
+    wpi::raw_svector_ostream os{buf};
+    os << "<html><head><title>WebServer Example</title></head>";
+    os << "<body><p>This is an example root page from the webserver.";
+    os << "</body></html>";
+    SendResponse(200, "OK", "text/html", os.str());
+  } else {
+    SendError(404, "Resource not found");
+  }
+}
+
+int main() {
+  // Kick off the event loop on a separate thread
+  wpi::EventLoopRunner loop;
+  loop.ExecAsync([](uv::Loop& loop) {
+    auto tcp = uv::Tcp::Create(loop);
+
+    // bind to listen address and port
+    tcp->Bind("", 8080);
+
+    // when we get a connection, accept it and start reading
+    tcp->connection.connect([srv = tcp.get()] {
+      auto tcp = srv->Accept();
+      if (!tcp) return;
+      wpi::errs() << "Got a connection\n";
+      auto conn = std::make_shared<MyHttpServerConnection>(tcp);
+      tcp->SetData(conn);
+    });
+
+    // start listening for incoming connections
+    tcp->Listen();
+
+    wpi::errs() << "Listening on port 8080\n";
+  });
+
+  // wait for a keypress to terminate
+  std::getchar();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/dev/java/edu/wpi/first/wpiutil/DevMain.java b/third_party/allwpilib_2019/wpiutil/src/dev/java/edu/wpi/first/wpiutil/DevMain.java
new file mode 100644
index 0000000..c5f1754
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/dev/java/edu/wpi/first/wpiutil/DevMain.java
@@ -0,0 +1,21 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpiutil;
+
+public final class DevMain {
+  /**
+   * Main entry point.
+   */
+  public static void main(String[] args) {
+    System.out.println("Hello World!");
+    System.out.println(RuntimeDetector.getPlatformPath());
+  }
+
+  private DevMain() {
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/dev/native/cpp/main.cpp b/third_party/allwpilib_2019/wpiutil/src/dev/native/cpp/main.cpp
new file mode 100644
index 0000000..9ac3bab
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/dev/native/cpp/main.cpp
@@ -0,0 +1,17 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 <iostream>
+
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include "wpi/hostname.h"
+
+int main() {
+  wpi::StringRef v1("Hello");
+  std::cout << v1.lower() << std::endl;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/java/edu/wpi/first/wpiutil/RuntimeDetector.java b/third_party/allwpilib_2019/wpiutil/src/main/java/edu/wpi/first/wpiutil/RuntimeDetector.java
new file mode 100644
index 0000000..bf3bce2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/java/edu/wpi/first/wpiutil/RuntimeDetector.java
@@ -0,0 +1,156 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpiutil;
+
+import java.io.BufferedReader;
+import java.io.File;
+import java.io.IOException;
+import java.nio.file.Files;
+import java.nio.file.Paths;
+
+public final class RuntimeDetector {
+  private static String filePrefix;
+  private static String fileExtension;
+  private static String filePath;
+
+  @SuppressWarnings("PMD.CyclomaticComplexity")
+  private static synchronized void computePlatform() {
+    if (fileExtension != null && filePath != null && filePrefix != null) {
+      return;
+    }
+
+
+    boolean intel32 = is32BitIntel();
+    boolean intel64 = is64BitIntel();
+
+    if (isWindows()) {
+      filePrefix = "";
+      fileExtension = ".dll";
+      if (intel32) {
+        filePath = "/windows/x86/";
+      } else {
+        filePath = "/windows/x86-64/";
+      }
+    } else if (isMac()) {
+      filePrefix = "lib";
+      fileExtension = ".dylib";
+      if (intel32) {
+        filePath = "/osx/x86";
+      } else {
+        filePath = "/osx/x86-64/";
+      }
+    } else if (isLinux()) {
+      filePrefix = "lib";
+      fileExtension = ".so";
+      if (intel32) {
+        filePath = "/linux/x86/";
+      } else if (intel64) {
+        filePath = "/linux/x86-64/";
+      } else if (isAthena()) {
+        filePath = "/linux/athena/";
+      } else if (isRaspbian()) {
+        filePath = "/linux/raspbian/";
+      } else {
+        filePath = "/linux/nativearm/";
+      }
+    } else {
+      throw new IllegalStateException("Failed to determine OS");
+    }
+  }
+
+  /**
+   * Get the file prefix for the current system.
+   */
+  public static synchronized String getFilePrefix() {
+    computePlatform();
+
+    return filePrefix;
+  }
+
+  /**
+   * Get the file extension for the current system.
+   */
+  public static synchronized String getFileExtension() {
+    computePlatform();
+
+    return fileExtension;
+  }
+
+  /**
+   * Get the platform path for the current system.
+   */
+  public static synchronized String getPlatformPath() {
+    computePlatform();
+
+    return filePath;
+  }
+
+  /**
+   * Get the path to the requested resource.
+   */
+  public static synchronized String getLibraryResource(String libName) {
+    computePlatform();
+
+    String toReturn = filePath + filePrefix + libName + fileExtension;
+    return toReturn;
+  }
+
+  /**
+   * Get the path to the hash to the requested resource.
+   */
+  public static synchronized String getHashLibraryResource(String libName) {
+    computePlatform();
+
+    String toReturn = filePath + libName + ".hash";
+    return toReturn;
+  }
+
+  public static boolean isAthena() {
+    File runRobotFile = new File("/usr/local/frc/bin/frcRunRobot.sh");
+    return runRobotFile.exists();
+  }
+
+  /** check if os is raspbian.
+   *
+   * @return if os is raspbian
+   */
+  public static boolean isRaspbian() {
+    try (BufferedReader reader = Files.newBufferedReader(Paths.get("/etc/os-release"))) {
+      String value = reader.readLine();
+      return value.contains("Raspbian");
+    } catch (IOException ex) {
+      return false;
+    }
+  }
+
+  public static boolean isLinux() {
+    return System.getProperty("os.name").startsWith("Linux");
+  }
+
+  public static boolean isWindows() {
+    return System.getProperty("os.name").startsWith("Windows");
+  }
+
+  public static boolean isMac() {
+    return System.getProperty("os.name").startsWith("Mac");
+  }
+
+  public static boolean is32BitIntel() {
+    String arch = System.getProperty("os.arch");
+    return "x86".equals(arch) || "i386".equals(arch);
+  }
+
+  public static boolean is64BitIntel() {
+    String arch = System.getProperty("os.arch");
+    return "amd64".equals(arch) || "x86_64".equals(arch);
+  }
+
+  private RuntimeDetector() {
+
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/java/edu/wpi/first/wpiutil/RuntimeLoader.java b/third_party/allwpilib_2019/wpiutil/src/main/java/edu/wpi/first/wpiutil/RuntimeLoader.java
new file mode 100644
index 0000000..b209fe8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/java/edu/wpi/first/wpiutil/RuntimeLoader.java
@@ -0,0 +1,172 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+package edu.wpi.first.wpiutil;
+
+import java.io.File;
+import java.io.IOException;
+import java.io.InputStream;
+import java.io.OutputStream;
+import java.nio.charset.StandardCharsets;
+import java.nio.file.Files;
+import java.nio.file.Paths;
+import java.security.DigestInputStream;
+import java.security.MessageDigest;
+import java.security.NoSuchAlgorithmException;
+import java.util.Locale;
+import java.util.Scanner;
+
+public final class RuntimeLoader<T> {
+  private static String defaultExtractionRoot;
+
+  /**
+   * Gets the default extration root location (~/.wpilib/nativecache).
+   */
+  public static synchronized String getDefaultExtractionRoot() {
+    if (defaultExtractionRoot != null) {
+      return defaultExtractionRoot;
+    }
+    String home = System.getProperty("user.home");
+    defaultExtractionRoot = Paths.get(home, ".wpilib", "nativecache").toString();
+    return defaultExtractionRoot;
+  }
+
+  private final String m_libraryName;
+  private final Class<T> m_loadClass;
+  private final String m_extractionRoot;
+
+  /**
+   * Creates a new library loader.
+   *
+   * <p>Resources loaded on disk from extractionRoot, and from classpath from the
+   * passed in class. Library name is the passed in name.
+   */
+  public RuntimeLoader(String libraryName, String extractionRoot, Class<T> cls) {
+    m_libraryName = libraryName;
+    m_loadClass = cls;
+    m_extractionRoot = extractionRoot;
+  }
+
+  private String getLoadErrorMessage() {
+    StringBuilder msg = new StringBuilder(256);
+    msg.append(m_libraryName)
+       .append(" could not be loaded from path or an embedded resource.\n"
+               + "\tattempted to load for platform ")
+       .append(RuntimeDetector.getPlatformPath())
+       .append('\n');
+    return msg.toString();
+  }
+
+  /**
+   * Loads a native library.
+   */
+  @SuppressWarnings("PMD.PreserveStackTrace")
+  public void loadLibrary() throws IOException {
+    try {
+      // First, try loading path
+      System.loadLibrary(m_libraryName);
+      return;
+    } catch (UnsatisfiedLinkError ule) {
+      // Then load the hash from the resources
+      String hashName = RuntimeDetector.getHashLibraryResource(m_libraryName);
+      String resname = RuntimeDetector.getLibraryResource(m_libraryName);
+      try (InputStream hashIs = m_loadClass.getResourceAsStream(hashName)) {
+        if (hashIs == null) {
+          throw new IOException(getLoadErrorMessage());
+        }
+        try (Scanner scanner = new Scanner(hashIs, StandardCharsets.UTF_8.name())) {
+          String hash = scanner.nextLine();
+          File jniLibrary = new File(m_extractionRoot, resname + "." + hash);
+          try {
+            // Try to load from an already extracted hash
+            System.load(jniLibrary.getAbsolutePath());
+          } catch (UnsatisfiedLinkError ule2) {
+            // If extraction failed, extract
+            try (InputStream resIs = m_loadClass.getResourceAsStream(resname)) {
+              if (resIs == null) {
+                throw new IOException(getLoadErrorMessage());
+              }
+              jniLibrary.getParentFile().mkdirs();
+              try (OutputStream os = Files.newOutputStream(jniLibrary.toPath())) {
+                byte[] buffer = new byte[0xFFFF]; // 64K copy buffer
+                int readBytes;
+                while ((readBytes = resIs.read(buffer)) != -1) { // NOPMD
+                  os.write(buffer, 0, readBytes);
+                }
+              }
+              System.load(jniLibrary.getAbsolutePath());
+            }
+          }
+        }
+      }
+    }
+  }
+
+  /**
+   * Load a native library by directly hashing the file.
+   */
+  @SuppressWarnings({"PMD.NPathComplexity", "PMD.PreserveStackTrace", "PMD.EmptyWhileStmt",
+                     "PMD.AvoidThrowingRawExceptionTypes", "PMD.CyclomaticComplexity"})
+  public void loadLibraryHashed() throws IOException {
+    try {
+      // First, try loading path
+      System.loadLibrary(m_libraryName);
+      return;
+    } catch (UnsatisfiedLinkError ule) {
+      // Then load the hash from the input file
+      String resname = RuntimeDetector.getLibraryResource(m_libraryName);
+      String hash = null;
+      try (InputStream is = m_loadClass.getResourceAsStream(resname)) {
+        if (is == null) {
+          throw new IOException(getLoadErrorMessage());
+        }
+        MessageDigest md = null;
+        try {
+          md = MessageDigest.getInstance("MD5");
+        } catch (NoSuchAlgorithmException nsae) {
+          throw new RuntimeException("Weird Hash Algorithm?");
+        }
+        try (DigestInputStream dis = new DigestInputStream(is, md)) {
+          // Read the entire buffer once to hash
+          byte[] buffer = new byte[0xFFFF];
+          while (dis.read(buffer) > -1) {}
+          MessageDigest digest = dis.getMessageDigest();
+          byte[] digestOutput = digest.digest();
+          StringBuilder builder = new StringBuilder();
+          for (byte b : digestOutput) {
+            builder.append(String.format("%02X", b));
+          }
+          hash = builder.toString().toLowerCase(Locale.ENGLISH);
+        }
+      }
+      if (hash == null) {
+        throw new IOException("Weird Hash?");
+      }
+      File jniLibrary = new File(m_extractionRoot, resname + "." + hash);
+      try {
+        // Try to load from an already extracted hash
+        System.load(jniLibrary.getAbsolutePath());
+      } catch (UnsatisfiedLinkError ule2) {
+        // If extraction failed, extract
+        try (InputStream resIs = m_loadClass.getResourceAsStream(resname)) {
+          if (resIs == null) {
+            throw new IOException(getLoadErrorMessage());
+          }
+          jniLibrary.getParentFile().mkdirs();
+          try (OutputStream os = Files.newOutputStream(jniLibrary.toPath())) {
+            byte[] buffer = new byte[0xFFFF]; // 64K copy buffer
+            int readBytes;
+            while ((readBytes = resIs.read(buffer)) != -1) { // NOPMD
+              os.write(buffer, 0, readBytes);
+            }
+          }
+          System.load(jniLibrary.getAbsolutePath());
+        }
+      }
+    }
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/Base64.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/Base64.cpp
new file mode 100644
index 0000000..35ac76c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/Base64.cpp
@@ -0,0 +1,170 @@
+/* ====================================================================
+ * Copyright (c) 1995-1999 The Apache Group.  All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ *
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in
+ *    the documentation and/or other materials provided with the
+ *    distribution.
+ *
+ * 3. All advertising materials mentioning features or use of this
+ *    software must display the following acknowledgment:
+ *    "This product includes software developed by the Apache Group
+ *    for use in the Apache HTTP server project (http://www.apache.org/)."
+ *
+ * 4. The names "Apache Server" and "Apache Group" must not be used to
+ *    endorse or promote products derived from this software without
+ *    prior written permission. For written permission, please contact
+ *    apache@apache.org.
+ *
+ * 5. Products derived from this software may not be called "Apache"
+ *    nor may "Apache" appear in their names without prior written
+ *    permission of the Apache Group.
+ *
+ * 6. Redistributions of any form whatsoever must retain the following
+ *    acknowledgment:
+ *    "This product includes software developed by the Apache Group
+ *    for use in the Apache HTTP server project (http://www.apache.org/)."
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE APACHE GROUP ``AS IS'' AND ANY
+ * EXPRESSED OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR
+ * PURPOSE ARE DISCLAIMED.  IN NO EVENT SHALL THE APACHE GROUP OR
+ * ITS CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+ * SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+ * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT,
+ * STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
+ * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED
+ * OF THE POSSIBILITY OF SUCH DAMAGE.
+ * ====================================================================
+ *
+ * This software consists of voluntary contributions made by many
+ * individuals on behalf of the Apache Group and was originally based
+ * on public domain software written at the National Center for
+ * Supercomputing Applications, University of Illinois, Urbana-Champaign.
+ * For more information on the Apache Group and the Apache HTTP server
+ * project, please see <http://www.apache.org/>.
+ *
+ */
+
+#include "wpi/Base64.h"
+
+#include "wpi/SmallVector.h"
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+// aaaack but it's fast and const should make it shared text page.
+static const unsigned char pr2six[256] = {
+    // ASCII table
+    64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 62, 64, 64, 64, 63, 52, 53, 54, 55, 56, 57, 58, 59, 60,
+    61, 64, 64, 64, 64, 64, 64, 64, 0,  1,  2,  3,  4,  5,  6,  7,  8,  9,  10,
+    11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 64, 64, 64, 64,
+    64, 64, 26, 27, 28, 29, 30, 31, 32, 33, 34, 35, 36, 37, 38, 39, 40, 41, 42,
+    43, 44, 45, 46, 47, 48, 49, 50, 51, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64, 64,
+    64, 64, 64, 64, 64, 64, 64, 64, 64};
+
+size_t Base64Decode(raw_ostream& os, StringRef encoded) {
+  const unsigned char* end = encoded.bytes_begin();
+  while (pr2six[*end] <= 63 && end != encoded.bytes_end()) ++end;
+  size_t nprbytes = end - encoded.bytes_begin();
+  if (nprbytes == 0) return 0;
+
+  const unsigned char* cur = encoded.bytes_begin();
+
+  while (nprbytes > 4) {
+    os << static_cast<unsigned char>(pr2six[cur[0]] << 2 | pr2six[cur[1]] >> 4);
+    os << static_cast<unsigned char>(pr2six[cur[1]] << 4 | pr2six[cur[2]] >> 2);
+    os << static_cast<unsigned char>(pr2six[cur[2]] << 6 | pr2six[cur[3]]);
+    cur += 4;
+    nprbytes -= 4;
+  }
+
+  // Note: (nprbytes == 1) would be an error, so just ignore that case
+  if (nprbytes > 1)
+    os << static_cast<unsigned char>(pr2six[cur[0]] << 2 | pr2six[cur[1]] >> 4);
+  if (nprbytes > 2)
+    os << static_cast<unsigned char>(pr2six[cur[1]] << 4 | pr2six[cur[2]] >> 2);
+  if (nprbytes > 3)
+    os << static_cast<unsigned char>(pr2six[cur[2]] << 6 | pr2six[cur[3]]);
+
+  return (end - encoded.bytes_begin()) + ((4 - nprbytes) & 3);
+}
+
+size_t Base64Decode(StringRef encoded, std::string* plain) {
+  plain->resize(0);
+  raw_string_ostream os(*plain);
+  size_t rv = Base64Decode(os, encoded);
+  os.flush();
+  return rv;
+}
+
+StringRef Base64Decode(StringRef encoded, size_t* num_read,
+                       SmallVectorImpl<char>& buf) {
+  buf.clear();
+  raw_svector_ostream os(buf);
+  *num_read = Base64Decode(os, encoded);
+  return os.str();
+}
+
+static const char basis_64[] =
+    "ABCDEFGHIJKLMNOPQRSTUVWXYZabcdefghijklmnopqrstuvwxyz0123456789+/";
+
+void Base64Encode(raw_ostream& os, StringRef plain) {
+  if (plain.empty()) return;
+  size_t len = plain.size();
+
+  size_t i;
+  for (i = 0; (i + 2) < len; i += 3) {
+    os << basis_64[(plain[i] >> 2) & 0x3F];
+    os << basis_64[((plain[i] & 0x3) << 4) |
+                   (static_cast<int>(plain[i + 1] & 0xF0) >> 4)];
+    os << basis_64[((plain[i + 1] & 0xF) << 2) |
+                   (static_cast<int>(plain[i + 2] & 0xC0) >> 6)];
+    os << basis_64[plain[i + 2] & 0x3F];
+  }
+  if (i < len) {
+    os << basis_64[(plain[i] >> 2) & 0x3F];
+    if (i == (len - 1)) {
+      os << basis_64[((plain[i] & 0x3) << 4)];
+      os << '=';
+    } else {
+      os << basis_64[((plain[i] & 0x3) << 4) |
+                     (static_cast<int>(plain[i + 1] & 0xF0) >> 4)];
+      os << basis_64[((plain[i + 1] & 0xF) << 2)];
+    }
+    os << '=';
+  }
+}
+
+void Base64Encode(StringRef plain, std::string* encoded) {
+  encoded->resize(0);
+  raw_string_ostream os(*encoded);
+  Base64Encode(os, plain);
+  os.flush();
+}
+
+StringRef Base64Encode(StringRef plain, SmallVectorImpl<char>& buf) {
+  buf.clear();
+  raw_svector_ostream os(buf);
+  Base64Encode(os, plain);
+  return os.str();
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/EventLoopRunner.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/EventLoopRunner.cpp
new file mode 100644
index 0000000..b885385
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/EventLoopRunner.cpp
@@ -0,0 +1,78 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/EventLoopRunner.h"
+
+#include "wpi/SmallVector.h"
+#include "wpi/condition_variable.h"
+#include "wpi/mutex.h"
+#include "wpi/uv/AsyncFunction.h"
+#include "wpi/uv/Loop.h"
+
+using namespace wpi;
+
+class EventLoopRunner::Thread : public SafeThread {
+ public:
+  using UvExecFunc = uv::AsyncFunction<void(LoopFunc)>;
+
+  Thread() : m_loop(uv::Loop::Create()) {
+    // set up async handles
+    if (!m_loop) return;
+
+    // run function
+    m_doExec = UvExecFunc::Create(
+        m_loop, [loop = m_loop.get()](auto out, LoopFunc func) {
+          func(*loop);
+          out.set_value();
+        });
+  }
+
+  void Main() {
+    if (m_loop) m_loop->Run();
+  }
+
+  // the loop
+  std::shared_ptr<uv::Loop> m_loop;
+
+  // run function
+  std::weak_ptr<UvExecFunc> m_doExec;
+};
+
+EventLoopRunner::EventLoopRunner() { m_owner.Start(); }
+
+EventLoopRunner::~EventLoopRunner() { Stop(); }
+
+void EventLoopRunner::Stop() {
+  ExecAsync([](uv::Loop& loop) {
+    // close all handles; this will (eventually) stop the loop
+    loop.Walk([](uv::Handle& h) { h.Close(); });
+  });
+  m_owner.Join();
+}
+
+void EventLoopRunner::ExecAsync(LoopFunc func) {
+  if (auto thr = m_owner.GetThread()) {
+    if (auto doExec = thr->m_doExec.lock()) {
+      doExec->Call(func);
+    }
+  }
+}
+
+void EventLoopRunner::ExecSync(LoopFunc func) {
+  wpi::future<void> f;
+  if (auto thr = m_owner.GetThread()) {
+    if (auto doExec = thr->m_doExec.lock()) {
+      f = doExec->Call(func);
+    }
+  }
+  if (f.valid()) f.wait();
+}
+
+std::shared_ptr<uv::Loop> EventLoopRunner::GetLoop() {
+  if (auto thr = m_owner.GetThread()) return thr->m_loop;
+  return nullptr;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpParser.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpParser.cpp
new file mode 100644
index 0000000..4560b38
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpParser.cpp
@@ -0,0 +1,176 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/HttpParser.h"
+
+using namespace wpi;
+
+uint32_t HttpParser::GetParserVersion() {
+  return static_cast<uint32_t>(http_parser_version());
+}
+
+HttpParser::HttpParser(Type type) {
+  http_parser_init(&m_parser,
+                   static_cast<http_parser_type>(static_cast<int>(type)));
+  m_parser.data = this;
+
+  http_parser_settings_init(&m_settings);
+
+  // Unlike the underlying http_parser library, we don't perform callbacks
+  // (other than body) with partial data; instead we buffer and call the user
+  // callback only when the data is complete.
+
+  // on_message_begin: initialize our state, call user callback
+  m_settings.on_message_begin = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.m_urlBuf.clear();
+    self.m_state = kStart;
+    self.messageBegin();
+    return self.m_aborted;
+  };
+
+  // on_url: collect into buffer
+  m_settings.on_url = [](http_parser* p, const char* at, size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    // append to buffer
+    if ((self.m_urlBuf.size() + length) > self.m_maxLength) return 1;
+    self.m_urlBuf += StringRef{at, length};
+    self.m_state = kUrl;
+    return 0;
+  };
+
+  // on_status: collect into buffer, call user URL callback
+  m_settings.on_status = [](http_parser* p, const char* at,
+                            size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    // use valueBuf for the status
+    if ((self.m_valueBuf.size() + length) > self.m_maxLength) return 1;
+    self.m_valueBuf += StringRef{at, length};
+    self.m_state = kStatus;
+    return 0;
+  };
+
+  // on_header_field: collect into buffer, call user header/status callback
+  m_settings.on_header_field = [](http_parser* p, const char* at,
+                                  size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+
+    // once we're in header, we know the URL is complete
+    if (self.m_state == kUrl) {
+      self.url(self.m_urlBuf);
+      if (self.m_aborted) return 1;
+    }
+
+    // once we're in header, we know the status is complete
+    if (self.m_state == kStatus) {
+      self.status(self.m_valueBuf);
+      if (self.m_aborted) return 1;
+    }
+
+    // if we previously were in value state, that means we finished a header
+    if (self.m_state == kValue) {
+      self.header(self.m_fieldBuf, self.m_valueBuf);
+      if (self.m_aborted) return 1;
+    }
+
+    // clear field and value when we enter this state
+    if (self.m_state != kField) {
+      self.m_state = kField;
+      self.m_fieldBuf.clear();
+      self.m_valueBuf.clear();
+    }
+
+    // append data to field buffer
+    if ((self.m_fieldBuf.size() + length) > self.m_maxLength) return 1;
+    self.m_fieldBuf += StringRef{at, length};
+    return 0;
+  };
+
+  // on_header_field: collect into buffer
+  m_settings.on_header_value = [](http_parser* p, const char* at,
+                                  size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+
+    // if we weren't previously in value state, clear the buffer
+    if (self.m_state != kValue) {
+      self.m_state = kValue;
+      self.m_valueBuf.clear();
+    }
+
+    // append data to value buffer
+    if ((self.m_valueBuf.size() + length) > self.m_maxLength) return 1;
+    self.m_valueBuf += StringRef{at, length};
+    return 0;
+  };
+
+  // on_headers_complete: call user status/header/complete callback
+  m_settings.on_headers_complete = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+
+    // if we previously were in url state, that means we finished the url
+    if (self.m_state == kUrl) {
+      self.url(self.m_urlBuf);
+      if (self.m_aborted) return 1;
+    }
+
+    // if we previously were in status state, that means we finished the status
+    if (self.m_state == kStatus) {
+      self.status(self.m_valueBuf);
+      if (self.m_aborted) return 1;
+    }
+
+    // if we previously were in value state, that means we finished a header
+    if (self.m_state == kValue) {
+      self.header(self.m_fieldBuf, self.m_valueBuf);
+      if (self.m_aborted) return 1;
+    }
+
+    self.headersComplete(self.ShouldKeepAlive());
+    return self.m_aborted;
+  };
+
+  // on_body: call user callback
+  m_settings.on_body = [](http_parser* p, const char* at,
+                          size_t length) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.body(StringRef{at, length}, self.IsBodyFinal());
+    return self.m_aborted;
+  };
+
+  // on_message_complete: call user callback
+  m_settings.on_message_complete = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.messageComplete(self.ShouldKeepAlive());
+    return self.m_aborted;
+  };
+
+  // on_chunk_header: call user callback
+  m_settings.on_chunk_header = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.chunkHeader(p->content_length);
+    return self.m_aborted;
+  };
+
+  // on_chunk_complete: call user callback
+  m_settings.on_chunk_complete = [](http_parser* p) -> int {
+    auto& self = *static_cast<HttpParser*>(p->data);
+    self.chunkComplete();
+    return self.m_aborted;
+  };
+}
+
+void HttpParser::Reset(Type type) {
+  http_parser_init(&m_parser,
+                   static_cast<http_parser_type>(static_cast<int>(type)));
+  m_parser.data = this;
+  m_maxLength = 1024;
+  m_state = kStart;
+  m_urlBuf.clear();
+  m_fieldBuf.clear();
+  m_valueBuf.clear();
+  m_aborted = false;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpServerConnection.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpServerConnection.cpp
new file mode 100644
index 0000000..9e65691
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpServerConnection.cpp
@@ -0,0 +1,162 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/HttpServerConnection.h"
+
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "wpi/raw_uv_ostream.h"
+
+using namespace wpi;
+
+HttpServerConnection::HttpServerConnection(std::shared_ptr<uv::Stream> stream)
+    : m_stream(*stream) {
+  // process HTTP messages
+  m_messageCompleteConn =
+      m_request.messageComplete.connect_connection([this](bool keepAlive) {
+        m_keepAlive = keepAlive;
+        ProcessRequest();
+      });
+
+  // look for Accept-Encoding headers to determine if gzip is acceptable
+  m_request.messageBegin.connect([this] { m_acceptGzip = false; });
+  m_request.header.connect([this](StringRef name, StringRef value) {
+    if (name.equals_lower("accept-encoding") && value.contains("gzip")) {
+      m_acceptGzip = true;
+    }
+  });
+
+  // pass incoming data to HTTP parser
+  m_dataConn =
+      stream->data.connect_connection([this](uv::Buffer& buf, size_t size) {
+        m_request.Execute(StringRef{buf.base, size});
+        if (m_request.HasError()) {
+          // could not parse; just close the connection
+          m_stream.Close();
+        }
+      });
+
+  // close when remote side closes
+  m_endConn =
+      stream->end.connect_connection([h = stream.get()] { h->Close(); });
+
+  // start reading
+  stream->StartRead();
+}
+
+void HttpServerConnection::BuildCommonHeaders(raw_ostream& os) {
+  os << "Server: WebServer/1.0\r\n"
+        "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
+        "post-check=0, max-age=0\r\n"
+        "Pragma: no-cache\r\n"
+        "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n";
+}
+
+void HttpServerConnection::BuildHeader(raw_ostream& os, int code,
+                                       const Twine& codeText,
+                                       const Twine& contentType,
+                                       uint64_t contentLength,
+                                       const Twine& extra) {
+  os << "HTTP/" << m_request.GetMajor() << '.' << m_request.GetMinor() << ' '
+     << code << ' ' << codeText << "\r\n";
+  if (contentLength == 0) m_keepAlive = false;
+  if (!m_keepAlive) os << "Connection: close\r\n";
+  BuildCommonHeaders(os);
+  os << "Content-Type: " << contentType << "\r\n";
+  if (contentLength != 0) os << "Content-Length: " << contentLength << "\r\n";
+  os << "Access-Control-Allow-Origin: *\r\nAccess-Control-Allow-Methods: *\r\n";
+  SmallString<128> extraBuf;
+  StringRef extraStr = extra.toStringRef(extraBuf);
+  if (!extraStr.empty()) os << extraStr;
+  os << "\r\n";  // header ends with a blank line
+}
+
+void HttpServerConnection::SendData(ArrayRef<uv::Buffer> bufs,
+                                    bool closeAfter) {
+  m_stream.Write(bufs, [ closeAfter, stream = &m_stream ](
+                           MutableArrayRef<uv::Buffer> bufs, uv::Error) {
+    for (auto&& buf : bufs) buf.Deallocate();
+    if (closeAfter) stream->Close();
+  });
+}
+
+void HttpServerConnection::SendResponse(int code, const Twine& codeText,
+                                        const Twine& contentType,
+                                        StringRef content,
+                                        const Twine& extraHeader) {
+  SmallVector<uv::Buffer, 4> toSend;
+  raw_uv_ostream os{toSend, 4096};
+  BuildHeader(os, code, codeText, contentType, content.size(), extraHeader);
+  os << content;
+  // close after write completes if we aren't keeping alive
+  SendData(os.bufs(), !m_keepAlive);
+}
+
+void HttpServerConnection::SendStaticResponse(int code, const Twine& codeText,
+                                              const Twine& contentType,
+                                              StringRef content, bool gzipped,
+                                              const Twine& extraHeader) {
+  // TODO: handle remote side not accepting gzip (very rare)
+
+  StringRef contentEncodingHeader;
+  if (gzipped /* && m_acceptGzip*/)
+    contentEncodingHeader = "Content-Encoding: gzip\r\n";
+
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os{bufs, 4096};
+  BuildHeader(os, code, codeText, contentType, content.size(),
+              extraHeader + contentEncodingHeader);
+  // can send content without copying
+  bufs.emplace_back(content);
+
+  m_stream.Write(bufs, [ closeAfter = !m_keepAlive, stream = &m_stream ](
+                           MutableArrayRef<uv::Buffer> bufs, uv::Error) {
+    // don't deallocate the static content
+    for (auto&& buf : bufs.drop_back()) buf.Deallocate();
+    if (closeAfter) stream->Close();
+  });
+}
+
+void HttpServerConnection::SendError(int code, const Twine& message) {
+  StringRef codeText, extra, baseMessage;
+  switch (code) {
+    case 401:
+      codeText = "Unauthorized";
+      extra = "WWW-Authenticate: Basic realm=\"CameraServer\"";
+      baseMessage = "401: Not Authenticated!";
+      break;
+    case 404:
+      codeText = "Not Found";
+      baseMessage = "404: Not Found!";
+      break;
+    case 500:
+      codeText = "Internal Server Error";
+      baseMessage = "500: Internal Server Error!";
+      break;
+    case 400:
+      codeText = "Bad Request";
+      baseMessage = "400: Not Found!";
+      break;
+    case 403:
+      codeText = "Forbidden";
+      baseMessage = "403: Forbidden!";
+      break;
+    case 503:
+      codeText = "Service Unavailable";
+      baseMessage = "503: Service Unavailable";
+      break;
+    default:
+      code = 501;
+      codeText = "Not Implemented";
+      baseMessage = "501: Not Implemented!";
+      break;
+  }
+  SmallString<256> content = baseMessage;
+  content += "\r\n";
+  message.toVector(content);
+  SendResponse(code, codeText, "text/plain", content, extra);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpUtil.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpUtil.cpp
new file mode 100644
index 0000000..37fea60
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/HttpUtil.cpp
@@ -0,0 +1,410 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 "wpi/HttpUtil.h"
+
+#include <cctype>
+
+#include "wpi/Base64.h"
+#include "wpi/STLExtras.h"
+#include "wpi/StringExtras.h"
+#include "wpi/TCPConnector.h"
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+StringRef UnescapeURI(const Twine& str, SmallVectorImpl<char>& buf,
+                      bool* error) {
+  SmallString<128> strBuf;
+  StringRef strStr = str.toStringRef(strBuf);
+  buf.clear();
+  for (auto i = strStr.begin(), end = strStr.end(); i != end; ++i) {
+    // pass non-escaped characters to output
+    if (*i != '%') {
+      // decode + to space
+      if (*i == '+')
+        buf.push_back(' ');
+      else
+        buf.push_back(*i);
+      continue;
+    }
+
+    // are there enough characters left?
+    if (i + 2 >= end) {
+      *error = true;
+      return StringRef{};
+    }
+
+    // replace %xx with the corresponding character
+    unsigned val1 = hexDigitValue(*++i);
+    if (val1 == -1U) {
+      *error = true;
+      return StringRef{};
+    }
+    unsigned val2 = hexDigitValue(*++i);
+    if (val2 == -1U) {
+      *error = true;
+      return StringRef{};
+    }
+    buf.push_back((val1 << 4) | val2);
+  }
+
+  *error = false;
+  return StringRef{buf.data(), buf.size()};
+}
+
+StringRef EscapeURI(const Twine& str, SmallVectorImpl<char>& buf,
+                    bool spacePlus) {
+  static const char* const hexLut = "0123456789ABCDEF";
+
+  SmallString<128> strBuf;
+  StringRef strStr = str.toStringRef(strBuf);
+  buf.clear();
+  for (auto i = strStr.begin(), end = strStr.end(); i != end; ++i) {
+    // pass unreserved characters to output
+    if (std::isalnum(*i) || *i == '-' || *i == '_' || *i == '.' || *i == '~') {
+      buf.push_back(*i);
+      continue;
+    }
+
+    // encode space to +
+    if (spacePlus && *i == ' ') {
+      buf.push_back('+');
+      continue;
+    }
+
+    // convert others to %xx
+    buf.push_back('%');
+    buf.push_back(hexLut[((*i) >> 4) & 0x0f]);
+    buf.push_back(hexLut[(*i) & 0x0f]);
+  }
+
+  return StringRef{buf.data(), buf.size()};
+}
+
+bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl<char>* contentType,
+                      SmallVectorImpl<char>* contentLength) {
+  if (contentType) contentType->clear();
+  if (contentLength) contentLength->clear();
+
+  bool inContentType = false;
+  bool inContentLength = false;
+  SmallString<64> lineBuf;
+  for (;;) {
+    StringRef line = is.getline(lineBuf, 1024).rtrim();
+    if (is.has_error()) return false;
+    if (line.empty()) return true;  // empty line signals end of headers
+
+    // header fields start at the beginning of the line
+    if (!std::isspace(line[0])) {
+      inContentType = false;
+      inContentLength = false;
+      StringRef field;
+      std::tie(field, line) = line.split(':');
+      field = field.rtrim();
+      if (field.equals_lower("content-type"))
+        inContentType = true;
+      else if (field.equals_lower("content-length"))
+        inContentLength = true;
+      else
+        continue;  // ignore other fields
+    }
+
+    // collapse whitespace
+    line = line.ltrim();
+
+    // save field data
+    if (inContentType && contentType)
+      contentType->append(line.begin(), line.end());
+    else if (inContentLength && contentLength)
+      contentLength->append(line.begin(), line.end());
+  }
+}
+
+bool FindMultipartBoundary(raw_istream& is, StringRef boundary,
+                           std::string* saveBuf) {
+  SmallString<64> searchBuf;
+  searchBuf.resize(boundary.size() + 2);
+  size_t searchPos = 0;
+
+  // Per the spec, the --boundary should be preceded by \r\n, so do a first
+  // pass of 1-byte reads to throw those away (common case) and keep the
+  // last non-\r\n character in searchBuf.
+  if (!saveBuf) {
+    do {
+      is.read(searchBuf.data(), 1);
+      if (is.has_error()) return false;
+    } while (searchBuf[0] == '\r' || searchBuf[0] == '\n');
+    searchPos = 1;
+  }
+
+  // Look for --boundary.  Read boundarysize+2 bytes at a time
+  // during the search to speed up the reads, then fast-scan for -,
+  // and only then match the entire boundary.  This will be slow if
+  // there's a bunch of continuous -'s in the output, but that's unlikely.
+  for (;;) {
+    is.read(searchBuf.data() + searchPos, searchBuf.size() - searchPos);
+    if (is.has_error()) return false;
+
+    // Did we find the boundary?
+    if (searchBuf[0] == '-' && searchBuf[1] == '-' &&
+        searchBuf.substr(2) == boundary)
+      return true;
+
+    // Fast-scan for '-'
+    size_t pos = searchBuf.find('-', searchBuf[0] == '-' ? 1 : 0);
+    if (pos == StringRef::npos) {
+      if (saveBuf) saveBuf->append(searchBuf.data(), searchBuf.size());
+    } else {
+      if (saveBuf) saveBuf->append(searchBuf.data(), pos);
+
+      // move '-' and following to start of buffer (next read will fill)
+      std::memmove(searchBuf.data(), searchBuf.data() + pos,
+                   searchBuf.size() - pos);
+      searchPos = searchBuf.size() - pos;
+    }
+  }
+}
+
+HttpLocation::HttpLocation(const Twine& url_, bool* error,
+                           std::string* errorMsg)
+    : url{url_.str()} {
+  // Split apart into components
+  StringRef query{url};
+
+  // scheme:
+  StringRef scheme;
+  std::tie(scheme, query) = query.split(':');
+  if (!scheme.equals_lower("http")) {
+    *errorMsg = "only supports http URLs";
+    *error = true;
+    return;
+  }
+
+  // "//"
+  if (!query.startswith("//")) {
+    *errorMsg = "expected http://...";
+    *error = true;
+    return;
+  }
+  query = query.drop_front(2);
+
+  // user:password@host:port/
+  StringRef authority;
+  std::tie(authority, query) = query.split('/');
+
+  StringRef userpass, hostport;
+  std::tie(userpass, hostport) = authority.split('@');
+  // split leaves the RHS empty if the split char isn't present...
+  if (hostport.empty()) {
+    hostport = userpass;
+    userpass = StringRef{};
+  }
+
+  if (!userpass.empty()) {
+    StringRef rawUser, rawPassword;
+    std::tie(rawUser, rawPassword) = userpass.split(':');
+    SmallString<64> userBuf, passBuf;
+    user = UnescapeURI(rawUser, userBuf, error);
+    if (*error) {
+      raw_string_ostream oss(*errorMsg);
+      oss << "could not unescape user \"" << rawUser << "\"";
+      oss.flush();
+      return;
+    }
+    password = UnescapeURI(rawPassword, passBuf, error);
+    if (*error) {
+      raw_string_ostream oss(*errorMsg);
+      oss << "could not unescape password \"" << rawPassword << "\"";
+      oss.flush();
+      return;
+    }
+  }
+
+  StringRef portStr;
+  std::tie(host, portStr) = hostport.rsplit(':');
+  if (host.empty()) {
+    *errorMsg = "host is empty";
+    *error = true;
+    return;
+  }
+  if (portStr.empty()) {
+    port = 80;
+  } else if (portStr.getAsInteger(10, port)) {
+    raw_string_ostream oss(*errorMsg);
+    oss << "port \"" << portStr << "\" is not an integer";
+    oss.flush();
+    *error = true;
+    return;
+  }
+
+  // path?query#fragment
+  std::tie(query, fragment) = query.split('#');
+  std::tie(path, query) = query.split('?');
+
+  // Split query string into parameters
+  while (!query.empty()) {
+    // split out next param and value
+    StringRef rawParam, rawValue;
+    std::tie(rawParam, query) = query.split('&');
+    if (rawParam.empty()) continue;  // ignore "&&"
+    std::tie(rawParam, rawValue) = rawParam.split('=');
+
+    // unescape param
+    *error = false;
+    SmallString<64> paramBuf;
+    StringRef param = UnescapeURI(rawParam, paramBuf, error);
+    if (*error) {
+      raw_string_ostream oss(*errorMsg);
+      oss << "could not unescape parameter \"" << rawParam << "\"";
+      oss.flush();
+      return;
+    }
+
+    // unescape value
+    SmallString<64> valueBuf;
+    StringRef value = UnescapeURI(rawValue, valueBuf, error);
+    if (*error) {
+      raw_string_ostream oss(*errorMsg);
+      oss << "could not unescape value \"" << rawValue << "\"";
+      oss.flush();
+      return;
+    }
+
+    params.emplace_back(std::make_pair(param, value));
+  }
+
+  *error = false;
+}
+
+void HttpRequest::SetAuth(const HttpLocation& loc) {
+  if (!loc.user.empty()) {
+    SmallString<64> userpass;
+    userpass += loc.user;
+    userpass += ':';
+    userpass += loc.password;
+    Base64Encode(userpass, &auth);
+  }
+}
+
+bool HttpConnection::Handshake(const HttpRequest& request,
+                               std::string* warnMsg) {
+  // send GET request
+  os << "GET /" << request.path << " HTTP/1.1\r\n";
+  os << "Host: " << request.host << "\r\n";
+  if (!request.auth.empty())
+    os << "Authorization: Basic " << request.auth << "\r\n";
+  os << "\r\n";
+  os.flush();
+
+  // read first line of response
+  SmallString<64> lineBuf;
+  StringRef line = is.getline(lineBuf, 1024).rtrim();
+  if (is.has_error()) {
+    *warnMsg = "disconnected before response";
+    return false;
+  }
+
+  // see if we got a HTTP 200 response
+  StringRef httpver, code, codeText;
+  std::tie(httpver, line) = line.split(' ');
+  std::tie(code, codeText) = line.split(' ');
+  if (!httpver.startswith("HTTP")) {
+    *warnMsg = "did not receive HTTP response";
+    return false;
+  }
+  if (code != "200") {
+    raw_string_ostream oss(*warnMsg);
+    oss << "received " << code << " " << codeText << " response";
+    oss.flush();
+    return false;
+  }
+
+  // Parse headers
+  if (!ParseHttpHeaders(is, &contentType, &contentLength)) {
+    *warnMsg = "disconnected during headers";
+    return false;
+  }
+
+  return true;
+}
+
+void HttpMultipartScanner::SetBoundary(StringRef boundary) {
+  m_boundaryWith = "\n--";
+  m_boundaryWith += boundary;
+  m_boundaryWithout = "\n";
+  m_boundaryWithout += boundary;
+  m_dashes = kUnknown;
+}
+
+void HttpMultipartScanner::Reset(bool saveSkipped) {
+  m_saveSkipped = saveSkipped;
+  m_state = kBoundary;
+  m_posWith = 0;
+  m_posWithout = 0;
+  m_buf.resize(0);
+}
+
+StringRef HttpMultipartScanner::Execute(StringRef in) {
+  if (m_state == kDone) Reset(m_saveSkipped);
+  if (m_saveSkipped) m_buf += in;
+
+  size_t pos = 0;
+  if (m_state == kBoundary) {
+    for (char ch : in) {
+      ++pos;
+      if (m_dashes != kWithout) {
+        if (ch == m_boundaryWith[m_posWith]) {
+          ++m_posWith;
+          if (m_posWith == m_boundaryWith.size()) {
+            // Found the boundary; transition to padding
+            m_state = kPadding;
+            m_dashes = kWith;  // no longer accept plain 'boundary'
+            break;
+          }
+        } else if (ch == m_boundaryWith[0]) {
+          m_posWith = 1;
+        } else {
+          m_posWith = 0;
+        }
+      }
+
+      if (m_dashes != kWith) {
+        if (ch == m_boundaryWithout[m_posWithout]) {
+          ++m_posWithout;
+          if (m_posWithout == m_boundaryWithout.size()) {
+            // Found the boundary; transition to padding
+            m_state = kPadding;
+            m_dashes = kWithout;  // no longer accept '--boundary'
+            break;
+          }
+        } else if (ch == m_boundaryWithout[0]) {
+          m_posWithout = 1;
+        } else {
+          m_posWithout = 0;
+        }
+      }
+    }
+  }
+
+  if (m_state == kPadding) {
+    for (char ch : in.drop_front(pos)) {
+      ++pos;
+      if (ch == '\n') {
+        // Found the LF; return remaining input buffer (following it)
+        m_state = kDone;
+        if (m_saveSkipped) m_buf.resize(m_buf.size() - in.size() + pos);
+        return in.drop_front(pos);
+      }
+    }
+  }
+
+  // We consumed the entire input
+  return StringRef{};
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/SafeThread.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/SafeThread.cpp
new file mode 100644
index 0000000..52ac700
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/SafeThread.cpp
@@ -0,0 +1,86 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "wpi/SafeThread.h"
+
+using namespace wpi;
+
+detail::SafeThreadProxyBase::SafeThreadProxyBase(
+    std::shared_ptr<SafeThread> thr)
+    : m_thread(std::move(thr)) {
+  if (!m_thread) return;
+  m_lock = std::unique_lock<wpi::mutex>(m_thread->m_mutex);
+  if (!m_thread->m_active) {
+    m_lock.unlock();
+    m_thread = nullptr;
+    return;
+  }
+}
+
+detail::SafeThreadOwnerBase::~SafeThreadOwnerBase() {
+  if (m_joinAtExit)
+    Join();
+  else
+    Stop();
+}
+
+void detail::SafeThreadOwnerBase::Start(std::shared_ptr<SafeThread> thr) {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (auto thr = m_thread.lock()) return;
+  m_stdThread = std::thread([=] { thr->Main(); });
+  m_thread = thr;
+}
+
+void detail::SafeThreadOwnerBase::Stop() {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  if (auto thr = m_thread.lock()) {
+    thr->m_active = false;
+    thr->m_cond.notify_all();
+    m_thread.reset();
+  }
+  if (m_stdThread.joinable()) m_stdThread.detach();
+}
+
+void detail::SafeThreadOwnerBase::Join() {
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  if (auto thr = m_thread.lock()) {
+    auto stdThread = std::move(m_stdThread);
+    m_thread.reset();
+    lock.unlock();
+    thr->m_active = false;
+    thr->m_cond.notify_all();
+    stdThread.join();
+  } else if (m_stdThread.joinable()) {
+    m_stdThread.detach();
+  }
+}
+
+void detail::swap(SafeThreadOwnerBase& lhs, SafeThreadOwnerBase& rhs) noexcept {
+  using std::swap;
+  if (&lhs == &rhs) return;
+  std::lock(lhs.m_mutex, rhs.m_mutex);
+  std::lock_guard<wpi::mutex> lock_lhs(lhs.m_mutex, std::adopt_lock);
+  std::lock_guard<wpi::mutex> lock_rhs(rhs.m_mutex, std::adopt_lock);
+  std::swap(lhs.m_stdThread, rhs.m_stdThread);
+  std::swap(lhs.m_thread, rhs.m_thread);
+}
+
+detail::SafeThreadOwnerBase::operator bool() const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return !m_thread.expired();
+}
+
+std::thread::native_handle_type
+detail::SafeThreadOwnerBase::GetNativeThreadHandle() {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return m_stdThread.native_handle();
+}
+
+std::shared_ptr<SafeThread> detail::SafeThreadOwnerBase::GetThread() const {
+  std::lock_guard<wpi::mutex> lock(m_mutex);
+  return m_thread.lock();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/SocketError.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/SocketError.cpp
new file mode 100644
index 0000000..1695846
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/SocketError.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "wpi/SocketError.h"
+
+#ifdef _WIN32
+#include <winsock2.h>
+#else
+#include <cerrno>
+#include <cstring>
+#endif
+
+namespace wpi {
+
+int SocketErrno() {
+#ifdef _WIN32
+  return WSAGetLastError();
+#else
+  return errno;
+#endif
+}
+
+std::string SocketStrerror(int code) {
+#ifdef _WIN32
+  LPSTR errstr = nullptr;
+  FormatMessage(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM, 0,
+                code, 0, (LPSTR)&errstr, 0, 0);
+  std::string rv(errstr);
+  LocalFree(errstr);
+  return rv;
+#else
+  return std::strerror(code);
+#endif
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPAcceptor.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPAcceptor.cpp
new file mode 100644
index 0000000..0abf862
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPAcceptor.cpp
@@ -0,0 +1,205 @@
+/*
+   TCPAcceptor.cpp
+
+   TCPAcceptor class definition. TCPAcceptor provides methods to passively
+   establish TCP/IP connections with clients.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
+*/
+
+#include "wpi/TCPAcceptor.h"
+
+#include <cstdio>
+#include <cstring>
+
+#ifdef _WIN32
+#include <WinSock2.h>
+#include <Ws2tcpip.h>
+#pragma comment(lib, "Ws2_32.lib")
+#else
+#include <arpa/inet.h>
+#include <fcntl.h>
+#include <netinet/in.h>
+#include <unistd.h>
+#endif
+
+#include "wpi/Logger.h"
+#include "wpi/SmallString.h"
+#include "wpi/SocketError.h"
+
+using namespace wpi;
+
+TCPAcceptor::TCPAcceptor(int port, const char* address, Logger& logger)
+    : m_lsd(0),
+      m_port(port),
+      m_address(address),
+      m_listening(false),
+      m_logger(logger) {
+  m_shutdown = false;
+#ifdef _WIN32
+  WSAData wsaData;
+  WORD wVersionRequested = MAKEWORD(2, 2);
+  WSAStartup(wVersionRequested, &wsaData);
+#endif
+}
+
+TCPAcceptor::~TCPAcceptor() {
+  if (m_lsd > 0) {
+    shutdown();
+#ifdef _WIN32
+    closesocket(m_lsd);
+#else
+    close(m_lsd);
+#endif
+  }
+#ifdef _WIN32
+  WSACleanup();
+#endif
+}
+
+int TCPAcceptor::start() {
+  if (m_listening) return 0;
+
+  m_lsd = socket(PF_INET, SOCK_STREAM, 0);
+  if (m_lsd < 0) {
+    WPI_ERROR(m_logger, "could not create socket");
+    return -1;
+  }
+  struct sockaddr_in address;
+
+  std::memset(&address, 0, sizeof(address));
+  address.sin_family = PF_INET;
+  if (m_address.size() > 0) {
+#ifdef _WIN32
+    SmallString<128> addr_copy(m_address);
+    addr_copy.push_back('\0');
+    int res = InetPton(PF_INET, addr_copy.data(), &(address.sin_addr));
+#else
+    int res = inet_pton(PF_INET, m_address.c_str(), &(address.sin_addr));
+#endif
+    if (res != 1) {
+      WPI_ERROR(m_logger, "could not resolve " << m_address << " address");
+      return -1;
+    }
+  } else {
+    address.sin_addr.s_addr = INADDR_ANY;
+  }
+  address.sin_port = htons(m_port);
+
+#ifdef _WIN32
+  int optval = 1;
+  setsockopt(m_lsd, SOL_SOCKET, SO_EXCLUSIVEADDRUSE,
+             reinterpret_cast<char*>(&optval), sizeof optval);
+#else
+  int optval = 1;
+  setsockopt(m_lsd, SOL_SOCKET, SO_REUSEADDR, reinterpret_cast<char*>(&optval),
+             sizeof optval);
+#endif
+
+  int result = bind(m_lsd, reinterpret_cast<struct sockaddr*>(&address),
+                    sizeof(address));
+  if (result != 0) {
+    WPI_ERROR(m_logger,
+              "bind() to port " << m_port << " failed: " << SocketStrerror());
+    return result;
+  }
+
+  result = listen(m_lsd, 5);
+  if (result != 0) {
+    WPI_ERROR(m_logger,
+              "listen() on port " << m_port << " failed: " << SocketStrerror());
+    return result;
+  }
+  m_listening = true;
+  return result;
+}
+
+void TCPAcceptor::shutdown() {
+  m_shutdown = true;
+#ifdef _WIN32
+  ::shutdown(m_lsd, SD_BOTH);
+
+  // this is ugly, but the easiest way to do this
+  // force wakeup of accept() with a non-blocking connect to ourselves
+  struct sockaddr_in address;
+
+  std::memset(&address, 0, sizeof(address));
+  address.sin_family = PF_INET;
+  SmallString<128> addr_copy;
+  if (m_address.size() > 0)
+    addr_copy = m_address;
+  else
+    addr_copy = "127.0.0.1";
+  addr_copy.push_back('\0');
+  int size = sizeof(address);
+  if (WSAStringToAddress(addr_copy.data(), PF_INET, nullptr,
+                         (struct sockaddr*)&address, &size) != 0)
+    return;
+  address.sin_port = htons(m_port);
+
+  fd_set sdset;
+  struct timeval tv;
+  int result = -1, valopt, sd = socket(AF_INET, SOCK_STREAM, 0);
+  if (sd < 0) return;
+
+  // Set socket to non-blocking
+  u_long mode = 1;
+  ioctlsocket(sd, FIONBIO, &mode);
+
+  // Try to connect
+  ::connect(sd, (struct sockaddr*)&address, sizeof(address));
+
+  // Close
+  ::closesocket(sd);
+
+#else
+  ::shutdown(m_lsd, SHUT_RDWR);
+  int nullfd = ::open("/dev/null", O_RDONLY);
+  if (nullfd >= 0) {
+    ::dup2(nullfd, m_lsd);
+    ::close(nullfd);
+  }
+#endif
+}
+
+std::unique_ptr<NetworkStream> TCPAcceptor::accept() {
+  if (!m_listening || m_shutdown) return nullptr;
+
+  struct sockaddr_in address;
+#ifdef _WIN32
+  int len = sizeof(address);
+#else
+  socklen_t len = sizeof(address);
+#endif
+  std::memset(&address, 0, sizeof(address));
+  int sd = ::accept(m_lsd, (struct sockaddr*)&address, &len);
+  if (sd < 0) {
+    if (!m_shutdown)
+      WPI_ERROR(m_logger, "accept() on port "
+                              << m_port << " failed: " << SocketStrerror());
+    return nullptr;
+  }
+  if (m_shutdown) {
+#ifdef _WIN32
+    closesocket(sd);
+#else
+    close(sd);
+#endif
+    return nullptr;
+  }
+  return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPConnector.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPConnector.cpp
new file mode 100644
index 0000000..6110133
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPConnector.cpp
@@ -0,0 +1,218 @@
+/*
+   TCPConnector.h
+
+   TCPConnector class definition. TCPConnector provides methods to actively
+   establish TCP/IP connections with a server.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License
+*/
+
+#include "wpi/TCPConnector.h"
+
+#include <fcntl.h>
+
+#include <cerrno>
+#include <cstdio>
+#include <cstring>
+
+#ifdef _WIN32
+#include <WS2tcpip.h>
+#include <WinSock2.h>
+#else
+#include <arpa/inet.h>
+#include <netdb.h>
+#include <netinet/in.h>
+#include <sys/select.h>
+#include <unistd.h>
+#endif
+
+#include "wpi/Logger.h"
+#include "wpi/SmallString.h"
+#include "wpi/SocketError.h"
+#include "wpi/TCPStream.h"
+
+using namespace wpi;
+
+static int ResolveHostName(const char* hostname, struct in_addr* addr) {
+  struct addrinfo hints;
+  struct addrinfo* res;
+
+  hints.ai_flags = 0;
+  hints.ai_family = AF_INET;
+  hints.ai_socktype = SOCK_STREAM;
+  hints.ai_protocol = 0;
+  hints.ai_addrlen = 0;
+  hints.ai_addr = nullptr;
+  hints.ai_canonname = nullptr;
+  hints.ai_next = nullptr;
+  int result = getaddrinfo(hostname, nullptr, &hints, &res);
+  if (result == 0) {
+    std::memcpy(
+        addr, &(reinterpret_cast<struct sockaddr_in*>(res->ai_addr)->sin_addr),
+        sizeof(struct in_addr));
+    freeaddrinfo(res);
+  }
+  return result;
+}
+
+std::unique_ptr<NetworkStream> TCPConnector::connect(const char* server,
+                                                     int port, Logger& logger,
+                                                     int timeout) {
+#ifdef _WIN32
+  struct WSAHelper {
+    WSAHelper() {
+      WSAData wsaData;
+      WORD wVersionRequested = MAKEWORD(2, 2);
+      WSAStartup(wVersionRequested, &wsaData);
+    }
+    ~WSAHelper() { WSACleanup(); }
+  };
+  static WSAHelper helper;
+#endif
+  struct sockaddr_in address;
+
+  std::memset(&address, 0, sizeof(address));
+  address.sin_family = AF_INET;
+  if (ResolveHostName(server, &(address.sin_addr)) != 0) {
+#ifdef _WIN32
+    SmallString<128> addr_copy(server);
+    addr_copy.push_back('\0');
+    int res = InetPton(PF_INET, addr_copy.data(), &(address.sin_addr));
+#else
+    int res = inet_pton(PF_INET, server, &(address.sin_addr));
+#endif
+    if (res != 1) {
+      WPI_ERROR(logger, "could not resolve " << server << " address");
+      return nullptr;
+    }
+  }
+  address.sin_port = htons(port);
+
+  if (timeout == 0) {
+    int sd = socket(AF_INET, SOCK_STREAM, 0);
+    if (sd < 0) {
+      WPI_ERROR(logger, "could not create socket");
+      return nullptr;
+    }
+    if (::connect(sd, (struct sockaddr*)&address, sizeof(address)) != 0) {
+      WPI_ERROR(logger, "connect() to " << server << " port " << port
+                                        << " failed: " << SocketStrerror());
+#ifdef _WIN32
+      closesocket(sd);
+#else
+      ::close(sd);
+#endif
+      return nullptr;
+    }
+    return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
+  }
+
+  fd_set sdset;
+  struct timeval tv;
+  socklen_t len;
+  int result = -1, valopt, sd = socket(AF_INET, SOCK_STREAM, 0);
+  if (sd < 0) {
+    WPI_ERROR(logger, "could not create socket");
+    return nullptr;
+  }
+
+// Set socket to non-blocking
+#ifdef _WIN32
+  u_long mode = 1;
+  if (ioctlsocket(sd, FIONBIO, &mode) == SOCKET_ERROR)
+    WPI_WARNING(logger,
+                "could not set socket to non-blocking: " << SocketStrerror());
+#else
+  int arg;
+  arg = fcntl(sd, F_GETFL, nullptr);
+  if (arg < 0) {
+    WPI_WARNING(logger,
+                "could not set socket to non-blocking: " << SocketStrerror());
+  } else {
+    arg |= O_NONBLOCK;
+    if (fcntl(sd, F_SETFL, arg) < 0)
+      WPI_WARNING(logger,
+                  "could not set socket to non-blocking: " << SocketStrerror());
+  }
+#endif
+
+  // Connect with time limit
+  if ((result = ::connect(sd, (struct sockaddr*)&address, sizeof(address))) <
+      0) {
+    int my_errno = SocketErrno();
+#ifdef _WIN32
+    if (my_errno == WSAEWOULDBLOCK || my_errno == WSAEINPROGRESS) {
+#else
+    if (my_errno == EWOULDBLOCK || my_errno == EINPROGRESS) {
+#endif
+      tv.tv_sec = timeout;
+      tv.tv_usec = 0;
+      FD_ZERO(&sdset);
+      FD_SET(sd, &sdset);
+      if (select(sd + 1, nullptr, &sdset, nullptr, &tv) > 0) {
+        len = sizeof(int);
+        getsockopt(sd, SOL_SOCKET, SO_ERROR, reinterpret_cast<char*>(&valopt),
+                   &len);
+        if (valopt) {
+          WPI_ERROR(logger, "select() to " << server << " port " << port
+                                           << " error " << valopt << " - "
+                                           << SocketStrerror(valopt));
+        }
+        // connection established
+        else
+          result = 0;
+      } else {
+        WPI_INFO(logger,
+                 "connect() to " << server << " port " << port << " timed out");
+      }
+    } else {
+      WPI_ERROR(logger, "connect() to " << server << " port " << port
+                                        << " error " << SocketErrno() << " - "
+                                        << SocketStrerror());
+    }
+  }
+
+// Return socket to blocking mode
+#ifdef _WIN32
+  mode = 0;
+  if (ioctlsocket(sd, FIONBIO, &mode) == SOCKET_ERROR)
+    WPI_WARNING(logger,
+                "could not set socket to blocking: " << SocketStrerror());
+#else
+  arg = fcntl(sd, F_GETFL, nullptr);
+  if (arg < 0) {
+    WPI_WARNING(logger,
+                "could not set socket to blocking: " << SocketStrerror());
+  } else {
+    arg &= (~O_NONBLOCK);
+    if (fcntl(sd, F_SETFL, arg) < 0)
+      WPI_WARNING(logger,
+                  "could not set socket to blocking: " << SocketStrerror());
+  }
+#endif
+
+  // Create stream object if connected, close if not.
+  if (result == -1) {
+#ifdef _WIN32
+    closesocket(sd);
+#else
+    ::close(sd);
+#endif
+    return nullptr;
+  }
+  return std::unique_ptr<NetworkStream>(new TCPStream(sd, &address));
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPConnector_parallel.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPConnector_parallel.cpp
new file mode 100644
index 0000000..e0a8a92
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPConnector_parallel.cpp
@@ -0,0 +1,129 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "wpi/TCPConnector.h"  // NOLINT(build/include_order)
+
+#include <atomic>
+#include <chrono>
+#include <thread>
+#include <tuple>
+
+#include "wpi/SmallSet.h"
+#include "wpi/condition_variable.h"
+#include "wpi/mutex.h"
+
+using namespace wpi;
+
+// MSVC < 1900 doesn't have support for thread_local
+#if !defined(_MSC_VER) || _MSC_VER >= 1900
+// clang check for availability of thread_local
+#if !defined(__has_feature) || __has_feature(cxx_thread_local)
+#define HAVE_THREAD_LOCAL
+#endif
+#endif
+
+std::unique_ptr<NetworkStream> TCPConnector::connect_parallel(
+    ArrayRef<std::pair<const char*, int>> servers, Logger& logger,
+    int timeout) {
+  if (servers.empty()) return nullptr;
+
+  // structure to make sure we don't start duplicate workers
+  struct GlobalState {
+    wpi::mutex mtx;
+#ifdef HAVE_THREAD_LOCAL
+    SmallSet<std::pair<std::string, int>, 16> active;
+#else
+    SmallSet<std::tuple<std::thread::id, std::string, int>, 16> active;
+#endif
+  };
+#ifdef HAVE_THREAD_LOCAL
+  thread_local auto global = std::make_shared<GlobalState>();
+#else
+  static auto global = std::make_shared<GlobalState>();
+  auto this_id = std::this_thread::get_id();
+#endif
+  auto local = global;  // copy to an automatic variable for lambda capture
+
+  // structure shared between threads and this function
+  struct Result {
+    wpi::mutex mtx;
+    wpi::condition_variable cv;
+    std::unique_ptr<NetworkStream> stream;
+    std::atomic<unsigned int> count{0};
+    std::atomic<bool> done{false};
+  };
+  auto result = std::make_shared<Result>();
+
+  // start worker threads; this is I/O bound so we don't limit to # of procs
+  Logger* plogger = &logger;
+  unsigned int num_workers = 0;
+  for (const auto& server : servers) {
+    std::pair<std::string, int> server_copy{std::string{server.first},
+                                            server.second};
+#ifdef HAVE_THREAD_LOCAL
+    const auto& active_tracker = server_copy;
+#else
+    std::tuple<std::thread::id, std::string, int> active_tracker{
+        this_id, server_copy.first, server_copy.second};
+#endif
+
+    // don't start a new worker if we had a previously still-active connection
+    // attempt to the same server
+    {
+      std::lock_guard<wpi::mutex> lock(local->mtx);
+      if (local->active.count(active_tracker) > 0) continue;  // already in set
+    }
+
+    ++num_workers;
+
+    // start the worker
+    std::thread([=]() {
+      if (!result->done) {
+        // add to global state
+        {
+          std::lock_guard<wpi::mutex> lock(local->mtx);
+          local->active.insert(active_tracker);
+        }
+
+        // try to connect
+        auto stream = connect(server_copy.first.c_str(), server_copy.second,
+                              *plogger, timeout);
+
+        // remove from global state
+        {
+          std::lock_guard<wpi::mutex> lock(local->mtx);
+          local->active.erase(active_tracker);
+        }
+
+        // successful connection
+        if (stream) {
+          std::lock_guard<wpi::mutex> lock(result->mtx);
+          if (!result->done.exchange(true)) result->stream = std::move(stream);
+        }
+      }
+      ++result->count;
+      result->cv.notify_all();
+    })
+        .detach();
+  }
+
+  // wait for a result, timeout, or all finished
+  std::unique_lock<wpi::mutex> lock(result->mtx);
+  if (timeout == 0) {
+    result->cv.wait(
+        lock, [&] { return result->stream || result->count >= num_workers; });
+  } else {
+    auto timeout_time =
+        std::chrono::steady_clock::now() + std::chrono::seconds(timeout);
+    result->cv.wait_until(lock, timeout_time, [&] {
+      return result->stream || result->count >= num_workers;
+    });
+  }
+
+  // no need to wait for remaining worker threads; shared_ptr will clean up
+  return std::move(result->stream);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPStream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPStream.cpp
new file mode 100644
index 0000000..d4e3671
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/TCPStream.cpp
@@ -0,0 +1,209 @@
+/*
+   TCPStream.h
+
+   TCPStream class definition. TCPStream provides methods to trasnfer
+   data between peers over a TCP/IP connection.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
+*/
+
+#include "wpi/TCPStream.h"
+
+#include <fcntl.h>
+
+#ifdef _WIN32
+#include <winsock2.h>
+#include <ws2tcpip.h>
+#else
+#include <arpa/inet.h>
+#include <netinet/tcp.h>
+#include <unistd.h>
+#endif
+
+#include <cerrno>
+
+using namespace wpi;
+
+TCPStream::TCPStream(int sd, sockaddr_in* address)
+    : m_sd(sd), m_blocking(true) {
+  char ip[50];
+#ifdef _WIN32
+  InetNtop(PF_INET, &(address->sin_addr.s_addr), ip, sizeof(ip) - 1);
+#else
+  inet_ntop(PF_INET, reinterpret_cast<in_addr*>(&(address->sin_addr.s_addr)),
+            ip, sizeof(ip) - 1);
+#ifdef SO_NOSIGPIPE
+  // disable SIGPIPE on Mac OS X
+  int set = 1;
+  setsockopt(m_sd, SOL_SOCKET, SO_NOSIGPIPE, reinterpret_cast<char*>(&set),
+             sizeof set);
+#endif
+#endif
+  m_peerIP = ip;
+  m_peerPort = ntohs(address->sin_port);
+}
+
+TCPStream::~TCPStream() { close(); }
+
+size_t TCPStream::send(const char* buffer, size_t len, Error* err) {
+  if (m_sd < 0) {
+    *err = kConnectionClosed;
+    return 0;
+  }
+#ifdef _WIN32
+  WSABUF wsaBuf;
+  wsaBuf.buf = const_cast<char*>(buffer);
+  wsaBuf.len = (ULONG)len;
+  DWORD rv;
+  bool result = true;
+  while (WSASend(m_sd, &wsaBuf, 1, &rv, 0, nullptr, nullptr) == SOCKET_ERROR) {
+    if (WSAGetLastError() != WSAEWOULDBLOCK) {
+      result = false;
+      break;
+    }
+    if (!m_blocking) {
+      *err = kWouldBlock;
+      return 0;
+    }
+    Sleep(1);
+  }
+  if (!result) {
+    char Buffer[128];
+#ifdef _MSC_VER
+    sprintf_s(Buffer, "Send() failed: WSA error=%d\n", WSAGetLastError());
+#else
+    std::snprintf(Buffer, sizeof(Buffer), "Send() failed: WSA error=%d\n",
+                  WSAGetLastError());
+#endif
+    OutputDebugStringA(Buffer);
+    *err = kConnectionReset;
+    return 0;
+  }
+#else
+#ifdef MSG_NOSIGNAL
+  // disable SIGPIPE on Linux
+  ssize_t rv = ::send(m_sd, buffer, len, MSG_NOSIGNAL);
+#else
+  ssize_t rv = ::send(m_sd, buffer, len, 0);
+#endif
+  if (rv < 0) {
+    if (!m_blocking && (errno == EAGAIN || errno == EWOULDBLOCK))
+      *err = kWouldBlock;
+    else
+      *err = kConnectionReset;
+    return 0;
+  }
+#endif
+  return static_cast<size_t>(rv);
+}
+
+size_t TCPStream::receive(char* buffer, size_t len, Error* err, int timeout) {
+  if (m_sd < 0) {
+    *err = kConnectionClosed;
+    return 0;
+  }
+#ifdef _WIN32
+  int rv;
+#else
+  ssize_t rv;
+#endif
+  if (timeout <= 0) {
+#ifdef _WIN32
+    rv = recv(m_sd, buffer, len, 0);
+#else
+    rv = read(m_sd, buffer, len);
+#endif
+  } else if (WaitForReadEvent(timeout)) {
+#ifdef _WIN32
+    rv = recv(m_sd, buffer, len, 0);
+#else
+    rv = read(m_sd, buffer, len);
+#endif
+  } else {
+    *err = kConnectionTimedOut;
+    return 0;
+  }
+  if (rv < 0) {
+#ifdef _WIN32
+    if (!m_blocking && WSAGetLastError() == WSAEWOULDBLOCK)
+#else
+    if (!m_blocking && (errno == EAGAIN || errno == EWOULDBLOCK))
+#endif
+      *err = kWouldBlock;
+    else
+      *err = kConnectionReset;
+    return 0;
+  }
+  return static_cast<size_t>(rv);
+}
+
+void TCPStream::close() {
+  if (m_sd >= 0) {
+#ifdef _WIN32
+    ::shutdown(m_sd, SD_BOTH);
+    closesocket(m_sd);
+#else
+    ::shutdown(m_sd, SHUT_RDWR);
+    ::close(m_sd);
+#endif
+  }
+  m_sd = -1;
+}
+
+StringRef TCPStream::getPeerIP() const { return m_peerIP; }
+
+int TCPStream::getPeerPort() const { return m_peerPort; }
+
+void TCPStream::setNoDelay() {
+  if (m_sd < 0) return;
+  int optval = 1;
+  setsockopt(m_sd, IPPROTO_TCP, TCP_NODELAY, reinterpret_cast<char*>(&optval),
+             sizeof optval);
+}
+
+bool TCPStream::setBlocking(bool enabled) {
+  if (m_sd < 0) return true;  // silently accept
+#ifdef _WIN32
+  u_long mode = enabled ? 0 : 1;
+  if (ioctlsocket(m_sd, FIONBIO, &mode) == SOCKET_ERROR) return false;
+#else
+  int flags = fcntl(m_sd, F_GETFL, nullptr);
+  if (flags < 0) return false;
+  if (enabled)
+    flags &= ~O_NONBLOCK;
+  else
+    flags |= O_NONBLOCK;
+  if (fcntl(m_sd, F_SETFL, flags) < 0) return false;
+#endif
+  return true;
+}
+
+int TCPStream::getNativeHandle() const { return m_sd; }
+
+bool TCPStream::WaitForReadEvent(int timeout) {
+  fd_set sdset;
+  struct timeval tv;
+
+  tv.tv_sec = timeout;
+  tv.tv_usec = 0;
+  FD_ZERO(&sdset);
+  FD_SET(m_sd, &sdset);
+  if (select(m_sd + 1, &sdset, NULL, NULL, &tv) > 0) {
+    return true;
+  }
+  return false;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/UDPClient.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/UDPClient.cpp
new file mode 100644
index 0000000..aafdf47
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/UDPClient.cpp
@@ -0,0 +1,237 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "wpi/UDPClient.h"
+
+#ifdef _WIN32
+#include <WinSock2.h>
+#include <Ws2tcpip.h>
+#pragma comment(lib, "Ws2_32.lib")
+#else
+#include <arpa/inet.h>
+#include <fcntl.h>
+#include <netinet/in.h>
+#include <unistd.h>
+#endif
+
+#include "wpi/Logger.h"
+#include "wpi/SocketError.h"
+
+using namespace wpi;
+
+UDPClient::UDPClient(Logger& logger) : UDPClient("", logger) {}
+
+UDPClient::UDPClient(const Twine& address, Logger& logger)
+    : m_lsd(0), m_port(0), m_address(address.str()), m_logger(logger) {}
+
+UDPClient::UDPClient(UDPClient&& other)
+    : m_lsd(other.m_lsd),
+      m_port(other.m_port),
+      m_address(std::move(other.m_address)),
+      m_logger(other.m_logger) {
+  other.m_lsd = 0;
+  other.m_port = 0;
+}
+
+UDPClient::~UDPClient() {
+  if (m_lsd > 0) {
+    shutdown();
+  }
+}
+
+UDPClient& UDPClient::operator=(UDPClient&& other) {
+  if (this == &other) return *this;
+  shutdown();
+  m_logger = other.m_logger;
+  m_lsd = other.m_lsd;
+  m_address = std::move(other.m_address);
+  m_port = other.m_port;
+  other.m_lsd = 0;
+  other.m_port = 0;
+  return *this;
+}
+
+int UDPClient::start() { return start(0); }
+
+int UDPClient::start(int port) {
+  if (m_lsd > 0) return 0;
+
+#ifdef _WIN32
+  WSAData wsaData;
+  WORD wVersionRequested = MAKEWORD(2, 2);
+  WSAStartup(wVersionRequested, &wsaData);
+#endif
+
+  m_lsd = socket(AF_INET, SOCK_DGRAM, 0);
+
+  if (m_lsd < 0) {
+    WPI_ERROR(m_logger, "could not create socket");
+    return -1;
+  }
+
+  struct sockaddr_in addr;
+  std::memset(&addr, 0, sizeof(addr));
+  addr.sin_family = AF_INET;
+  if (m_address.size() > 0) {
+#ifdef _WIN32
+    SmallString<128> addr_copy(m_address);
+    addr_copy.push_back('\0');
+    int res = InetPton(PF_INET, addr_copy.data(), &(addr.sin_addr));
+#else
+    int res = inet_pton(PF_INET, m_address.c_str(), &(addr.sin_addr));
+#endif
+    if (res != 1) {
+      WPI_ERROR(m_logger, "could not resolve " << m_address << " address");
+      return -1;
+    }
+  } else {
+    addr.sin_addr.s_addr = INADDR_ANY;
+  }
+  addr.sin_port = htons(port);
+
+  if (port != 0) {
+#ifdef _WIN32
+    int optval = 1;
+    setsockopt(m_lsd, SOL_SOCKET, SO_EXCLUSIVEADDRUSE,
+               reinterpret_cast<char*>(&optval), sizeof optval);
+#else
+    int optval = 1;
+    setsockopt(m_lsd, SOL_SOCKET, SO_REUSEADDR,
+               reinterpret_cast<char*>(&optval), sizeof optval);
+#endif
+  }
+
+  int result = bind(m_lsd, reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
+  if (result != 0) {
+    WPI_ERROR(m_logger, "bind() failed: " << SocketStrerror());
+    return result;
+  }
+  m_port = port;
+  return 0;
+}
+
+void UDPClient::shutdown() {
+  if (m_lsd > 0) {
+#ifdef _WIN32
+    ::shutdown(m_lsd, SD_BOTH);
+    closesocket(m_lsd);
+    WSACleanup();
+#else
+    ::shutdown(m_lsd, SHUT_RDWR);
+    close(m_lsd);
+#endif
+    m_lsd = 0;
+    m_port = 0;
+  }
+}
+
+int UDPClient::send(ArrayRef<uint8_t> data, const Twine& server, int port) {
+  // server must be a resolvable IP address
+  struct sockaddr_in addr;
+  std::memset(&addr, 0, sizeof(addr));
+  addr.sin_family = AF_INET;
+  SmallVector<char, 128> addr_store;
+  StringRef remoteAddr = server.toNullTerminatedStringRef(addr_store);
+  if (remoteAddr.empty()) {
+    WPI_ERROR(m_logger, "server must be passed");
+    return -1;
+  }
+
+#ifdef _WIN32
+  int res = InetPton(AF_INET, remoteAddr.data(), &(addr.sin_addr));
+#else
+  int res = inet_pton(AF_INET, remoteAddr.data(), &(addr.sin_addr));
+#endif
+  if (res != 1) {
+    WPI_ERROR(m_logger, "could not resolve " << server << " address");
+    return -1;
+  }
+  addr.sin_port = htons(port);
+
+  // sendto should not block
+  int result =
+      sendto(m_lsd, reinterpret_cast<const char*>(data.data()), data.size(), 0,
+             reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
+  return result;
+}
+
+int UDPClient::send(StringRef data, const Twine& server, int port) {
+  // server must be a resolvable IP address
+  struct sockaddr_in addr;
+  std::memset(&addr, 0, sizeof(addr));
+  addr.sin_family = AF_INET;
+  SmallVector<char, 128> addr_store;
+  StringRef remoteAddr = server.toNullTerminatedStringRef(addr_store);
+  if (remoteAddr.empty()) {
+    WPI_ERROR(m_logger, "server must be passed");
+    return -1;
+  }
+
+#ifdef _WIN32
+  int res = InetPton(AF_INET, remoteAddr.data(), &(addr.sin_addr));
+#else
+  int res = inet_pton(AF_INET, remoteAddr.data(), &(addr.sin_addr));
+#endif
+  if (res != 1) {
+    WPI_ERROR(m_logger, "could not resolve " << server << " address");
+    return -1;
+  }
+  addr.sin_port = htons(port);
+
+  // sendto should not block
+  int result = sendto(m_lsd, data.data(), data.size(), 0,
+                      reinterpret_cast<sockaddr*>(&addr), sizeof(addr));
+  return result;
+}
+
+int UDPClient::receive(uint8_t* data_received, int receive_len) {
+  if (m_port == 0) return -1;  // return if not receiving
+  return recv(m_lsd, reinterpret_cast<char*>(data_received), receive_len, 0);
+}
+
+int UDPClient::receive(uint8_t* data_received, int receive_len,
+                       SmallVectorImpl<char>* addr_received,
+                       int* port_received) {
+  if (m_port == 0) return -1;  // return if not receiving
+
+  struct sockaddr_in remote;
+  socklen_t remote_len = sizeof(remote);
+  std::memset(&remote, 0, sizeof(remote));
+
+  int result =
+      recvfrom(m_lsd, reinterpret_cast<char*>(data_received), receive_len, 0,
+               reinterpret_cast<sockaddr*>(&remote), &remote_len);
+
+  char ip[50];
+#ifdef _WIN32
+  InetNtop(PF_INET, &(remote.sin_addr.s_addr), ip, sizeof(ip) - 1);
+#else
+  inet_ntop(PF_INET, reinterpret_cast<in_addr*>(&(remote.sin_addr.s_addr)), ip,
+            sizeof(ip) - 1);
+#endif
+
+  ip[49] = '\0';
+  int addr_len = std::strlen(ip);
+  addr_received->clear();
+  addr_received->append(&ip[0], &ip[addr_len]);
+
+  *port_received = ntohs(remote.sin_port);
+
+  return result;
+}
+
+int UDPClient::set_timeout(double timeout) {
+  if (timeout < 0) return -1;
+  struct timeval tv;
+  tv.tv_sec = timeout;             // truncating will give seconds
+  timeout -= tv.tv_sec;            // remove seconds portion
+  tv.tv_usec = timeout * 1000000;  // fractions of a second to us
+  int ret = setsockopt(m_lsd, SOL_SOCKET, SO_RCVTIMEO,
+                       reinterpret_cast<char*>(&tv), sizeof(tv));
+  if (ret < 0) WPI_ERROR(m_logger, "set timeout failed");
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/WebSocket.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/WebSocket.cpp
new file mode 100644
index 0000000..a38be20
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/WebSocket.cpp
@@ -0,0 +1,565 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/WebSocket.h"
+
+#include <random>
+
+#include "wpi/Base64.h"
+#include "wpi/HttpParser.h"
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "wpi/raw_uv_ostream.h"
+#include "wpi/sha1.h"
+#include "wpi/uv/Stream.h"
+
+using namespace wpi;
+
+namespace {
+class WebSocketWriteReq : public uv::WriteReq {
+ public:
+  explicit WebSocketWriteReq(
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+    finish.connect([=](uv::Error err) {
+      MutableArrayRef<uv::Buffer> bufs{m_bufs};
+      for (auto&& buf : bufs.slice(0, m_startUser)) buf.Deallocate();
+      callback(bufs.slice(m_startUser), err);
+    });
+  }
+
+  SmallVector<uv::Buffer, 4> m_bufs;
+  size_t m_startUser;
+};
+}  // namespace
+
+class WebSocket::ClientHandshakeData {
+ public:
+  ClientHandshakeData() {
+    // key is a random nonce
+    static std::random_device rd;
+    static std::default_random_engine gen{rd()};
+    std::uniform_int_distribution<unsigned int> dist(0, 255);
+    char nonce[16];  // the nonce sent to the server
+    for (char& v : nonce) v = static_cast<char>(dist(gen));
+    raw_svector_ostream os(key);
+    Base64Encode(os, StringRef{nonce, 16});
+  }
+  ~ClientHandshakeData() {
+    if (auto t = timer.lock()) {
+      t->Stop();
+      t->Close();
+    }
+  }
+
+  SmallString<64> key;                       // the key sent to the server
+  SmallVector<std::string, 2> protocols;     // valid protocols
+  HttpParser parser{HttpParser::kResponse};  // server response parser
+  bool hasUpgrade = false;
+  bool hasConnection = false;
+  bool hasAccept = false;
+  bool hasProtocol = false;
+
+  std::weak_ptr<uv::Timer> timer;
+};
+
+static StringRef AcceptHash(StringRef key, SmallVectorImpl<char>& buf) {
+  SHA1 hash;
+  hash.Update(key);
+  hash.Update("258EAFA5-E914-47DA-95CA-C5AB0DC85B11");
+  SmallString<64> hashBuf;
+  return Base64Encode(hash.RawFinal(hashBuf), buf);
+}
+
+WebSocket::WebSocket(uv::Stream& stream, bool server, const private_init&)
+    : m_stream{stream}, m_server{server} {
+  // Connect closed and error signals to ourselves
+  m_stream.closed.connect([this]() { SetClosed(1006, "handle closed"); });
+  m_stream.error.connect([this](uv::Error err) {
+    Terminate(1006, "stream error: " + Twine(err.name()));
+  });
+
+  // Start reading
+  m_stream.StopRead();  // we may have been reading
+  m_stream.StartRead();
+  m_stream.data.connect(
+      [this](uv::Buffer& buf, size_t size) { HandleIncoming(buf, size); });
+  m_stream.end.connect(
+      [this]() { Terminate(1006, "remote end closed connection"); });
+}
+
+WebSocket::~WebSocket() {}
+
+std::shared_ptr<WebSocket> WebSocket::CreateClient(
+    uv::Stream& stream, const Twine& uri, const Twine& host,
+    ArrayRef<StringRef> protocols, const ClientOptions& options) {
+  auto ws = std::make_shared<WebSocket>(stream, false, private_init{});
+  stream.SetData(ws);
+  ws->StartClient(uri, host, protocols, options);
+  return ws;
+}
+
+std::shared_ptr<WebSocket> WebSocket::CreateServer(uv::Stream& stream,
+                                                   StringRef key,
+                                                   StringRef version,
+                                                   StringRef protocol) {
+  auto ws = std::make_shared<WebSocket>(stream, true, private_init{});
+  stream.SetData(ws);
+  ws->StartServer(key, version, protocol);
+  return ws;
+}
+
+void WebSocket::Close(uint16_t code, const Twine& reason) {
+  SendClose(code, reason);
+  if (m_state != FAILED && m_state != CLOSED) m_state = CLOSING;
+}
+
+void WebSocket::Fail(uint16_t code, const Twine& reason) {
+  if (m_state == FAILED || m_state == CLOSED) return;
+  SendClose(code, reason);
+  SetClosed(code, reason, true);
+  Shutdown();
+}
+
+void WebSocket::Terminate(uint16_t code, const Twine& reason) {
+  if (m_state == FAILED || m_state == CLOSED) return;
+  SetClosed(code, reason);
+  Shutdown();
+}
+
+void WebSocket::StartClient(const Twine& uri, const Twine& host,
+                            ArrayRef<StringRef> protocols,
+                            const ClientOptions& options) {
+  // Create client handshake data
+  m_clientHandshake = std::make_unique<ClientHandshakeData>();
+
+  // Build client request
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os{bufs, 4096};
+
+  os << "GET " << uri << " HTTP/1.1\r\n";
+  os << "Host: " << host << "\r\n";
+  os << "Upgrade: websocket\r\n";
+  os << "Connection: Upgrade\r\n";
+  os << "Sec-WebSocket-Key: " << m_clientHandshake->key << "\r\n";
+  os << "Sec-WebSocket-Version: 13\r\n";
+
+  // protocols (if provided)
+  if (!protocols.empty()) {
+    os << "Sec-WebSocket-Protocol: ";
+    bool first = true;
+    for (auto protocol : protocols) {
+      if (!first)
+        os << ", ";
+      else
+        first = false;
+      os << protocol;
+      // also save for later checking against server response
+      m_clientHandshake->protocols.emplace_back(protocol);
+    }
+    os << "\r\n";
+  }
+
+  // other headers
+  for (auto&& header : options.extraHeaders)
+    os << header.first << ": " << header.second << "\r\n";
+
+  // finish headers
+  os << "\r\n";
+
+  // Send client request
+  m_stream.Write(bufs, [](auto bufs, uv::Error) {
+    for (auto& buf : bufs) buf.Deallocate();
+  });
+
+  // Set up client response handling
+  m_clientHandshake->parser.status.connect([this](StringRef status) {
+    unsigned int code = m_clientHandshake->parser.GetStatusCode();
+    if (code != 101) Terminate(code, status);
+  });
+  m_clientHandshake->parser.header.connect(
+      [this](StringRef name, StringRef value) {
+        value = value.trim();
+        if (name.equals_lower("upgrade")) {
+          if (!value.equals_lower("websocket"))
+            return Terminate(1002, "invalid upgrade response value");
+          m_clientHandshake->hasUpgrade = true;
+        } else if (name.equals_lower("connection")) {
+          if (!value.equals_lower("upgrade"))
+            return Terminate(1002, "invalid connection response value");
+          m_clientHandshake->hasConnection = true;
+        } else if (name.equals_lower("sec-websocket-accept")) {
+          // Check against expected response
+          SmallString<64> acceptBuf;
+          if (!value.equals(AcceptHash(m_clientHandshake->key, acceptBuf)))
+            return Terminate(1002, "invalid accept key");
+          m_clientHandshake->hasAccept = true;
+        } else if (name.equals_lower("sec-websocket-extensions")) {
+          // No extensions are supported
+          if (!value.empty()) return Terminate(1010, "unsupported extension");
+        } else if (name.equals_lower("sec-websocket-protocol")) {
+          // Make sure it was one of the provided protocols
+          bool match = false;
+          for (auto&& protocol : m_clientHandshake->protocols) {
+            if (value.equals_lower(protocol)) {
+              match = true;
+              break;
+            }
+          }
+          if (!match) return Terminate(1003, "unsupported protocol");
+          m_clientHandshake->hasProtocol = true;
+          m_protocol = value;
+        }
+      });
+  m_clientHandshake->parser.headersComplete.connect([this](bool) {
+    if (!m_clientHandshake->hasUpgrade || !m_clientHandshake->hasConnection ||
+        !m_clientHandshake->hasAccept ||
+        (!m_clientHandshake->hasProtocol &&
+         !m_clientHandshake->protocols.empty())) {
+      return Terminate(1002, "invalid response");
+    }
+    if (m_state == CONNECTING) {
+      m_state = OPEN;
+      open(m_protocol);
+    }
+  });
+
+  // Start handshake timer if a timeout was specified
+  if (options.handshakeTimeout != uv::Timer::Time::max()) {
+    auto timer = uv::Timer::Create(m_stream.GetLoopRef());
+    timer->timeout.connect(
+        [this]() { Terminate(1006, "connection timed out"); });
+    timer->Start(options.handshakeTimeout);
+    m_clientHandshake->timer = timer;
+  }
+}
+
+void WebSocket::StartServer(StringRef key, StringRef version,
+                            StringRef protocol) {
+  m_protocol = protocol;
+
+  // Build server response
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os{bufs, 4096};
+
+  // Handle unsupported version
+  if (version != "13") {
+    os << "HTTP/1.1 426 Upgrade Required\r\n";
+    os << "Upgrade: WebSocket\r\n";
+    os << "Sec-WebSocket-Version: 13\r\n\r\n";
+    m_stream.Write(bufs, [this](auto bufs, uv::Error) {
+      for (auto& buf : bufs) buf.Deallocate();
+      // XXX: Should we support sending a new handshake on the same connection?
+      // XXX: "this->" is required by GCC 5.5 (bug)
+      this->Terminate(1003, "unsupported protocol version");
+    });
+    return;
+  }
+
+  os << "HTTP/1.1 101 Switching Protocols\r\n";
+  os << "Upgrade: websocket\r\n";
+  os << "Connection: Upgrade\r\n";
+
+  // accept hash
+  SmallString<64> acceptBuf;
+  os << "Sec-WebSocket-Accept: " << AcceptHash(key, acceptBuf) << "\r\n";
+
+  if (!protocol.empty()) os << "Sec-WebSocket-Protocol: " << protocol << "\r\n";
+
+  // end headers
+  os << "\r\n";
+
+  // Send server response
+  m_stream.Write(bufs, [this](auto bufs, uv::Error) {
+    for (auto& buf : bufs) buf.Deallocate();
+    if (m_state == CONNECTING) {
+      m_state = OPEN;
+      open(m_protocol);
+    }
+  });
+}
+
+void WebSocket::SendClose(uint16_t code, const Twine& reason) {
+  SmallVector<uv::Buffer, 4> bufs;
+  if (code != 1005) {
+    raw_uv_ostream os{bufs, 4096};
+    os << ArrayRef<uint8_t>{static_cast<uint8_t>((code >> 8) & 0xff),
+                            static_cast<uint8_t>(code & 0xff)};
+    reason.print(os);
+  }
+  Send(kFlagFin | kOpClose, bufs, [](auto bufs, uv::Error) {
+    for (auto&& buf : bufs) buf.Deallocate();
+  });
+}
+
+void WebSocket::SetClosed(uint16_t code, const Twine& reason, bool failed) {
+  if (m_state == FAILED || m_state == CLOSED) return;
+  m_state = failed ? FAILED : CLOSED;
+  SmallString<64> reasonBuf;
+  closed(code, reason.toStringRef(reasonBuf));
+}
+
+void WebSocket::Shutdown() {
+  m_stream.Shutdown([this] { m_stream.Close(); });
+}
+
+void WebSocket::HandleIncoming(uv::Buffer& buf, size_t size) {
+  // ignore incoming data if we're failed or closed
+  if (m_state == FAILED || m_state == CLOSED) return;
+
+  StringRef data{buf.base, size};
+
+  // Handle connecting state (mainly on client)
+  if (m_state == CONNECTING) {
+    if (m_clientHandshake) {
+      data = m_clientHandshake->parser.Execute(data);
+      // check for parser failure
+      if (m_clientHandshake->parser.HasError())
+        return Terminate(1003, "invalid response");
+      if (m_state != OPEN) return;  // not done with handshake yet
+
+      // we're done with the handshake, so release its memory
+      m_clientHandshake.reset();
+
+      // fall through to process additional data after handshake
+    } else {
+      return Terminate(1003, "got data on server before response");
+    }
+  }
+
+  // Message processing
+  while (!data.empty()) {
+    if (m_frameSize == UINT64_MAX) {
+      // Need at least two bytes to determine header length
+      if (m_header.size() < 2u) {
+        size_t toCopy = std::min(2u - m_header.size(), data.size());
+        m_header.append(data.bytes_begin(), data.bytes_begin() + toCopy);
+        data = data.drop_front(toCopy);
+        if (m_header.size() < 2u) return;  // need more data
+
+        // Validate RSV bits are zero
+        if ((m_header[0] & 0x70) != 0) return Fail(1002, "nonzero RSV");
+      }
+
+      // Once we have first two bytes, we can calculate the header size
+      if (m_headerSize == 0) {
+        m_headerSize = 2;
+        uint8_t len = m_header[1] & kLenMask;
+        if (len == 126)
+          m_headerSize += 2;
+        else if (len == 127)
+          m_headerSize += 8;
+        bool masking = (m_header[1] & kFlagMasking) != 0;
+        if (masking) m_headerSize += 4;  // masking key
+        // On server side, incoming messages MUST be masked
+        // On client side, incoming messages MUST NOT be masked
+        if (m_server && !masking) return Fail(1002, "client data not masked");
+        if (!m_server && masking) return Fail(1002, "server data masked");
+      }
+
+      // Need to complete header to calculate message size
+      if (m_header.size() < m_headerSize) {
+        size_t toCopy = std::min(m_headerSize - m_header.size(), data.size());
+        m_header.append(data.bytes_begin(), data.bytes_begin() + toCopy);
+        data = data.drop_front(toCopy);
+        if (m_header.size() < m_headerSize) return;  // need more data
+      }
+
+      if (m_header.size() >= m_headerSize) {
+        // get payload length
+        uint8_t len = m_header[1] & kLenMask;
+        if (len == 126)
+          m_frameSize = (static_cast<uint16_t>(m_header[2]) << 8) |
+                        static_cast<uint16_t>(m_header[3]);
+        else if (len == 127)
+          m_frameSize = (static_cast<uint64_t>(m_header[2]) << 56) |
+                        (static_cast<uint64_t>(m_header[3]) << 48) |
+                        (static_cast<uint64_t>(m_header[4]) << 40) |
+                        (static_cast<uint64_t>(m_header[5]) << 32) |
+                        (static_cast<uint64_t>(m_header[6]) << 24) |
+                        (static_cast<uint64_t>(m_header[7]) << 16) |
+                        (static_cast<uint64_t>(m_header[8]) << 8) |
+                        static_cast<uint64_t>(m_header[9]);
+        else
+          m_frameSize = len;
+
+        // limit maximum size
+        if ((m_payload.size() + m_frameSize) > m_maxMessageSize)
+          return Fail(1009, "message too large");
+      }
+    }
+
+    if (m_frameSize != UINT64_MAX) {
+      size_t need = m_frameStart + m_frameSize - m_payload.size();
+      size_t toCopy = std::min(need, data.size());
+      m_payload.append(data.bytes_begin(), data.bytes_begin() + toCopy);
+      data = data.drop_front(toCopy);
+      need -= toCopy;
+      if (need == 0) {
+        // We have a complete frame
+        // If the message had masking, unmask it
+        if ((m_header[1] & kFlagMasking) != 0) {
+          uint8_t key[4] = {
+              m_header[m_headerSize - 4], m_header[m_headerSize - 3],
+              m_header[m_headerSize - 2], m_header[m_headerSize - 1]};
+          int n = 0;
+          for (uint8_t& ch :
+               MutableArrayRef<uint8_t>{m_payload}.slice(m_frameStart)) {
+            ch ^= key[n++];
+            if (n >= 4) n = 0;
+          }
+        }
+
+        // Handle message
+        bool fin = (m_header[0] & kFlagFin) != 0;
+        uint8_t opcode = m_header[0] & kOpMask;
+        switch (opcode) {
+          case kOpCont:
+            switch (m_fragmentOpcode) {
+              case kOpText:
+                if (!m_combineFragments || fin)
+                  text(StringRef{reinterpret_cast<char*>(m_payload.data()),
+                                 m_payload.size()},
+                       fin);
+                break;
+              case kOpBinary:
+                if (!m_combineFragments || fin) binary(m_payload, fin);
+                break;
+              default:
+                // no preceding message?
+                return Fail(1002, "invalid continuation message");
+            }
+            if (fin) m_fragmentOpcode = 0;
+            break;
+          case kOpText:
+            if (m_fragmentOpcode != 0) return Fail(1002, "incomplete fragment");
+            if (!m_combineFragments || fin)
+              text(StringRef{reinterpret_cast<char*>(m_payload.data()),
+                             m_payload.size()},
+                   fin);
+            if (!fin) m_fragmentOpcode = opcode;
+            break;
+          case kOpBinary:
+            if (m_fragmentOpcode != 0) return Fail(1002, "incomplete fragment");
+            if (!m_combineFragments || fin) binary(m_payload, fin);
+            if (!fin) m_fragmentOpcode = opcode;
+            break;
+          case kOpClose: {
+            uint16_t code;
+            StringRef reason;
+            if (!fin) {
+              code = 1002;
+              reason = "cannot fragment control frames";
+            } else if (m_payload.size() < 2) {
+              code = 1005;
+            } else {
+              code = (static_cast<uint16_t>(m_payload[0]) << 8) |
+                     static_cast<uint16_t>(m_payload[1]);
+              reason = StringRef{reinterpret_cast<char*>(m_payload.data()),
+                                 m_payload.size()}
+                           .drop_front(2);
+            }
+            // Echo the close if we didn't previously send it
+            if (m_state != CLOSING) SendClose(code, reason);
+            SetClosed(code, reason);
+            // If we're the server, shutdown the connection.
+            if (m_server) Shutdown();
+            break;
+          }
+          case kOpPing:
+            if (!fin) return Fail(1002, "cannot fragment control frames");
+            ping(m_payload);
+            break;
+          case kOpPong:
+            if (!fin) return Fail(1002, "cannot fragment control frames");
+            pong(m_payload);
+            break;
+          default:
+            return Fail(1002, "invalid message opcode");
+        }
+
+        // Prepare for next message
+        m_header.clear();
+        m_headerSize = 0;
+        if (!m_combineFragments || fin) m_payload.clear();
+        m_frameStart = m_payload.size();
+        m_frameSize = UINT64_MAX;
+      }
+    }
+  }
+}
+
+void WebSocket::Send(
+    uint8_t opcode, ArrayRef<uv::Buffer> data,
+    std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+  // If we're not open, emit an error and don't send the data
+  if (m_state != OPEN) {
+    int err;
+    if (m_state == CONNECTING)
+      err = UV_EAGAIN;
+    else
+      err = UV_ESHUTDOWN;
+    SmallVector<uv::Buffer, 4> bufs{data.begin(), data.end()};
+    callback(bufs, uv::Error{err});
+    return;
+  }
+
+  auto req = std::make_shared<WebSocketWriteReq>(callback);
+  raw_uv_ostream os{req->m_bufs, 4096};
+
+  // opcode (includes FIN bit)
+  os << static_cast<unsigned char>(opcode);
+
+  // payload length
+  uint64_t size = 0;
+  for (auto&& buf : data) size += buf.len;
+  if (size < 126) {
+    os << static_cast<unsigned char>((m_server ? 0x00 : kFlagMasking) | size);
+  } else if (size <= 0xffff) {
+    os << static_cast<unsigned char>((m_server ? 0x00 : kFlagMasking) | 126);
+    os << ArrayRef<uint8_t>{static_cast<uint8_t>((size >> 8) & 0xff),
+                            static_cast<uint8_t>(size & 0xff)};
+  } else {
+    os << static_cast<unsigned char>((m_server ? 0x00 : kFlagMasking) | 127);
+    os << ArrayRef<uint8_t>{static_cast<uint8_t>((size >> 56) & 0xff),
+                            static_cast<uint8_t>((size >> 48) & 0xff),
+                            static_cast<uint8_t>((size >> 40) & 0xff),
+                            static_cast<uint8_t>((size >> 32) & 0xff),
+                            static_cast<uint8_t>((size >> 24) & 0xff),
+                            static_cast<uint8_t>((size >> 16) & 0xff),
+                            static_cast<uint8_t>((size >> 8) & 0xff),
+                            static_cast<uint8_t>(size & 0xff)};
+  }
+
+  // clients need to mask the input data
+  if (!m_server) {
+    // generate masking key
+    static std::random_device rd;
+    static std::default_random_engine gen{rd()};
+    std::uniform_int_distribution<unsigned int> dist(0, 255);
+    uint8_t key[4];
+    for (uint8_t& v : key) v = dist(gen);
+    os << ArrayRef<uint8_t>{key, 4};
+    // copy and mask data
+    int n = 0;
+    for (auto&& buf : data) {
+      for (auto&& ch : buf.data()) {
+        os << static_cast<unsigned char>(static_cast<uint8_t>(ch) ^ key[n++]);
+        if (n >= 4) n = 0;
+      }
+    }
+    req->m_startUser = req->m_bufs.size();
+    req->m_bufs.append(data.begin(), data.end());
+    // don't send the user bufs as we copied their data
+    m_stream.Write(ArrayRef<uv::Buffer>{req->m_bufs}.slice(0, req->m_startUser),
+                   req);
+  } else {
+    // servers can just send the buffers directly without masking
+    req->m_startUser = req->m_bufs.size();
+    req->m_bufs.append(data.begin(), data.end());
+    m_stream.Write(req->m_bufs, req);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/WebSocketServer.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/WebSocketServer.cpp
new file mode 100644
index 0000000..3ad5e0e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/WebSocketServer.cpp
@@ -0,0 +1,143 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/WebSocketServer.h"
+
+#include "wpi/raw_uv_ostream.h"
+#include "wpi/uv/Buffer.h"
+#include "wpi/uv/Stream.h"
+
+using namespace wpi;
+
+WebSocketServerHelper::WebSocketServerHelper(HttpParser& req) {
+  req.header.connect([this](StringRef name, StringRef value) {
+    if (name.equals_lower("host")) {
+      m_gotHost = true;
+    } else if (name.equals_lower("upgrade")) {
+      if (value.equals_lower("websocket")) m_websocket = true;
+    } else if (name.equals_lower("sec-websocket-key")) {
+      m_key = value;
+    } else if (name.equals_lower("sec-websocket-version")) {
+      m_version = value;
+    } else if (name.equals_lower("sec-websocket-protocol")) {
+      // Protocols are comma delimited, repeated headers add to list
+      SmallVector<StringRef, 2> protocols;
+      value.split(protocols, ",", -1, false);
+      for (auto protocol : protocols) {
+        protocol = protocol.trim();
+        if (!protocol.empty()) m_protocols.emplace_back(protocol);
+      }
+    }
+  });
+  req.headersComplete.connect([&req, this](bool) {
+    if (req.IsUpgrade() && IsUpgrade()) upgrade();
+  });
+}
+
+std::pair<bool, StringRef> WebSocketServerHelper::MatchProtocol(
+    ArrayRef<StringRef> protocols) {
+  if (protocols.empty() && m_protocols.empty())
+    return std::make_pair(true, StringRef{});
+  for (auto protocol : protocols) {
+    for (auto&& clientProto : m_protocols) {
+      if (protocol == clientProto) return std::make_pair(true, protocol);
+    }
+  }
+  return std::make_pair(false, StringRef{});
+}
+
+WebSocketServer::WebSocketServer(uv::Stream& stream,
+                                 ArrayRef<StringRef> protocols,
+                                 const ServerOptions& options,
+                                 const private_init&)
+    : m_stream{stream},
+      m_helper{m_req},
+      m_protocols{protocols.begin(), protocols.end()},
+      m_options{options} {
+  // Header handling
+  m_req.header.connect([this](StringRef name, StringRef value) {
+    if (name.equals_lower("host")) {
+      if (m_options.checkHost) {
+        if (!m_options.checkHost(value)) Abort(401, "Unrecognized Host");
+      }
+    }
+  });
+  m_req.url.connect([this](StringRef name) {
+    if (m_options.checkUrl) {
+      if (!m_options.checkUrl(name)) Abort(404, "Not Found");
+    }
+  });
+  m_req.headersComplete.connect([this](bool) {
+    // We only accept websocket connections
+    if (!m_helper.IsUpgrade() || !m_req.IsUpgrade())
+      Abort(426, "Upgrade Required");
+  });
+
+  // Handle upgrade event
+  m_helper.upgrade.connect([this] {
+    if (m_aborted) return;
+
+    // Negotiate sub-protocol
+    SmallVector<StringRef, 2> protocols{m_protocols.begin(), m_protocols.end()};
+    StringRef protocol = m_helper.MatchProtocol(protocols).second;
+
+    // Disconnect our header reader
+    m_dataConn.disconnect();
+
+    // Accepting the stream may destroy this (as it replaces the stream user
+    // data), so grab a shared pointer first.
+    auto self = shared_from_this();
+
+    // Accept the upgrade
+    auto ws = m_helper.Accept(m_stream, protocol);
+
+    // Connect the websocket open event to our connected event.
+    ws->open.connect_extended([ self, s = ws.get() ](auto conn, StringRef) {
+      self->connected(self->m_req.GetUrl(), *s);
+      conn.disconnect();  // one-shot
+    });
+  });
+
+  // Set up stream
+  stream.StartRead();
+  m_dataConn =
+      stream.data.connect_connection([this](uv::Buffer& buf, size_t size) {
+        if (m_aborted) return;
+        m_req.Execute(StringRef{buf.base, size});
+        if (m_req.HasError()) Abort(400, "Bad Request");
+      });
+  m_errorConn =
+      stream.error.connect_connection([this](uv::Error) { m_stream.Close(); });
+  m_endConn = stream.end.connect_connection([this] { m_stream.Close(); });
+}
+
+std::shared_ptr<WebSocketServer> WebSocketServer::Create(
+    uv::Stream& stream, ArrayRef<StringRef> protocols,
+    const ServerOptions& options) {
+  auto server = std::make_shared<WebSocketServer>(stream, protocols, options,
+                                                  private_init{});
+  stream.SetData(server);
+  return server;
+}
+
+void WebSocketServer::Abort(uint16_t code, StringRef reason) {
+  if (m_aborted) return;
+  m_aborted = true;
+
+  // Build response
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os{bufs, 1024};
+
+  // Handle unsupported version
+  os << "HTTP/1.1 " << code << ' ' << reason << "\r\n";
+  if (code == 426) os << "Upgrade: WebSocket\r\n";
+  os << "\r\n";
+  m_stream.Write(bufs, [this](auto bufs, uv::Error) {
+    for (auto& buf : bufs) buf.Deallocate();
+    m_stream.Shutdown([this] { m_stream.Close(); });
+  });
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/future.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/future.cpp
new file mode 100644
index 0000000..fb31658
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/future.cpp
@@ -0,0 +1,119 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/future.h"
+
+namespace wpi {
+namespace detail {
+
+PromiseFactoryBase::~PromiseFactoryBase() {
+  m_active = false;
+  m_resultCv.notify_all();  // wake up any waiters
+}
+
+void PromiseFactoryBase::IgnoreResult(uint64_t request) {
+  std::unique_lock<wpi::mutex> lock(m_resultMutex);
+  EraseRequest(request);
+}
+
+uint64_t PromiseFactoryBase::CreateRequest() {
+  std::unique_lock<wpi::mutex> lock(m_resultMutex);
+  uint64_t req = ++m_uid;
+  m_requests.push_back(req);
+  return req;
+}
+
+bool PromiseFactoryBase::EraseRequest(uint64_t request) {
+  if (request == 0) return false;
+  auto it = std::find_if(m_requests.begin(), m_requests.end(),
+                         [=](auto r) { return r == request; });
+  if (it == m_requests.end()) return false;  // no waiters
+  m_requests.erase(it);
+  return true;
+}
+
+}  // namespace detail
+
+future<void> PromiseFactory<void>::MakeReadyFuture() {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  uint64_t req = CreateErasedRequest();
+  m_results.emplace_back(req);
+  return future<void>{this, req};
+}
+
+void PromiseFactory<void>::SetValue(uint64_t request) {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  if (!EraseRequest(request)) return;
+  auto it = std::find_if(m_thens.begin(), m_thens.end(),
+                         [=](const auto& x) { return x.request == request; });
+  if (it != m_thens.end()) {
+    uint64_t outRequest = it->outRequest;
+    ThenFunction func = std::move(it->func);
+    m_thens.erase(it);
+    lock.unlock();
+    return func(outRequest);
+  }
+  m_results.emplace_back(request);
+  Notify();
+}
+
+void PromiseFactory<void>::SetThen(uint64_t request, uint64_t outRequest,
+                                   ThenFunction func) {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  auto it = std::find_if(m_results.begin(), m_results.end(),
+                         [=](const auto& r) { return r == request; });
+  if (it != m_results.end()) {
+    m_results.erase(it);
+    lock.unlock();
+    return func(outRequest);
+  }
+  m_thens.emplace_back(request, outRequest, func);
+}
+
+bool PromiseFactory<void>::IsReady(uint64_t request) noexcept {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  auto it = std::find_if(m_results.begin(), m_results.end(),
+                         [=](const auto& r) { return r == request; });
+  return it != m_results.end();
+}
+
+void PromiseFactory<void>::GetResult(uint64_t request) {
+  // wait for response
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  while (IsActive()) {
+    // Did we get a response to *our* request?
+    auto it = std::find_if(m_results.begin(), m_results.end(),
+                           [=](const auto& r) { return r == request; });
+    if (it != m_results.end()) {
+      // Yes, remove it from the vector and we're done.
+      m_results.erase(it);
+      return;
+    }
+    // No, keep waiting for a response
+    Wait(lock);
+  }
+}
+
+void PromiseFactory<void>::WaitResult(uint64_t request) {
+  // wait for response
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  while (IsActive()) {
+    // Did we get a response to *our* request?
+    auto it = std::find_if(m_results.begin(), m_results.end(),
+                           [=](const auto& r) { return r == request; });
+    if (it != m_results.end()) return;
+    // No, keep waiting for a response
+    Wait(lock);
+  }
+}
+
+PromiseFactory<void>& PromiseFactory<void>::GetInstance() {
+  static PromiseFactory<void> inst;
+  return inst;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/hostname.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/hostname.cpp
new file mode 100644
index 0000000..ffc5cad
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/hostname.cpp
@@ -0,0 +1,56 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "wpi/hostname.h"
+
+#include <cstdlib>
+#include <string>
+
+#include "uv.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+
+namespace wpi {
+
+std::string GetHostname() {
+  std::string rv;
+  char name[256];
+  size_t size = sizeof(name);
+
+  int err = uv_os_gethostname(name, &size);
+  if (err == 0) {
+    rv.assign(name, size);
+  } else if (err == UV_ENOBUFS) {
+    char* name2 = static_cast<char*>(std::malloc(size));
+    err = uv_os_gethostname(name2, &size);
+    if (err == 0) rv.assign(name2, size);
+    std::free(name2);
+  }
+
+  return rv;
+}
+
+StringRef GetHostname(SmallVectorImpl<char>& name) {
+  // Use a tmp array to not require the SmallVector to be too large.
+  char tmpName[256];
+  size_t size = sizeof(tmpName);
+
+  name.clear();
+
+  int err = uv_os_gethostname(tmpName, &size);
+  if (err == 0) {
+    name.append(tmpName, tmpName + size);
+  } else if (err == UV_ENOBUFS) {
+    name.resize(size);
+    err = uv_os_gethostname(name.data(), &size);
+    if (err != 0) size = 0;
+  }
+
+  return StringRef{name.data(), size};
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/http_parser.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/http_parser.cpp
new file mode 100644
index 0000000..0900219
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/http_parser.cpp
@@ -0,0 +1,2471 @@
+/* Copyright Joyent, Inc. and other Node contributors.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+#include "wpi/http_parser.h"
+#include <assert.h>
+#include <stddef.h>
+#include <ctype.h>
+#include <string.h>
+#include <limits.h>
+
+#ifndef ULLONG_MAX
+# define ULLONG_MAX ((uint64_t) -1) /* 2^64-1 */
+#endif
+
+#ifndef MIN
+# define MIN(a,b) ((a) < (b) ? (a) : (b))
+#endif
+
+#ifndef ARRAY_SIZE
+# define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0]))
+#endif
+
+#ifndef BIT_AT
+# define BIT_AT(a, i)                                                \
+  (!!((unsigned int) (a)[(unsigned int) (i) >> 3] &                  \
+   (1 << ((unsigned int) (i) & 7))))
+#endif
+
+#ifndef ELEM_AT
+# define ELEM_AT(a, i, v) ((unsigned int) (i) < ARRAY_SIZE(a) ? (a)[(i)] : (v))
+#endif
+
+#define SET_ERRNO(e)                                                 \
+do {                                                                 \
+  parser->nread = nread;                                             \
+  parser->http_errno = (e);                                          \
+} while(0)
+
+#define CURRENT_STATE() p_state
+#define UPDATE_STATE(V) p_state = (enum state) (V);
+#define RETURN(V)                                                    \
+do {                                                                 \
+  parser->nread = nread;                                             \
+  parser->state = CURRENT_STATE();                                   \
+  return (V);                                                        \
+} while (0);
+#define REEXECUTE()                                                  \
+  goto reexecute;                                                    \
+
+
+#ifdef __GNUC__
+# define LIKELY(X) __builtin_expect(!!(X), 1)
+# define UNLIKELY(X) __builtin_expect(!!(X), 0)
+#else
+# define LIKELY(X) (X)
+# define UNLIKELY(X) (X)
+#endif
+
+
+/* Run the notify callback FOR, returning ER if it fails */
+#define CALLBACK_NOTIFY_(FOR, ER)                                    \
+do {                                                                 \
+  assert(HTTP_PARSER_ERRNO(parser) == HPE_OK);                       \
+                                                                     \
+  if (LIKELY(settings->on_##FOR)) {                                  \
+    parser->state = CURRENT_STATE();                                 \
+    if (UNLIKELY(0 != settings->on_##FOR(parser))) {                 \
+      SET_ERRNO(HPE_CB_##FOR);                                       \
+    }                                                                \
+    UPDATE_STATE(parser->state);                                     \
+                                                                     \
+    /* We either errored above or got paused; get out */             \
+    if (UNLIKELY(HTTP_PARSER_ERRNO(parser) != HPE_OK)) {             \
+      return (ER);                                                   \
+    }                                                                \
+  }                                                                  \
+} while (0)
+
+/* Run the notify callback FOR and consume the current byte */
+#define CALLBACK_NOTIFY(FOR)            CALLBACK_NOTIFY_(FOR, p - data + 1)
+
+/* Run the notify callback FOR and don't consume the current byte */
+#define CALLBACK_NOTIFY_NOADVANCE(FOR)  CALLBACK_NOTIFY_(FOR, p - data)
+
+/* Run data callback FOR with LEN bytes, returning ER if it fails */
+#define CALLBACK_DATA_(FOR, LEN, ER)                                 \
+do {                                                                 \
+  assert(HTTP_PARSER_ERRNO(parser) == HPE_OK);                       \
+                                                                     \
+  if (FOR##_mark) {                                                  \
+    if (LIKELY(settings->on_##FOR)) {                                \
+      parser->state = CURRENT_STATE();                               \
+      if (UNLIKELY(0 !=                                              \
+                   settings->on_##FOR(parser, FOR##_mark, (LEN)))) { \
+        SET_ERRNO(HPE_CB_##FOR);                                     \
+      }                                                              \
+      UPDATE_STATE(parser->state);                                   \
+                                                                     \
+      /* We either errored above or got paused; get out */           \
+      if (UNLIKELY(HTTP_PARSER_ERRNO(parser) != HPE_OK)) {           \
+        return (ER);                                                 \
+      }                                                              \
+    }                                                                \
+    FOR##_mark = NULL;                                               \
+  }                                                                  \
+} while (0)
+
+/* Run the data callback FOR and consume the current byte */
+#define CALLBACK_DATA(FOR)                                           \
+    CALLBACK_DATA_(FOR, p - FOR##_mark, p - data + 1)
+
+/* Run the data callback FOR and don't consume the current byte */
+#define CALLBACK_DATA_NOADVANCE(FOR)                                 \
+    CALLBACK_DATA_(FOR, p - FOR##_mark, p - data)
+
+/* Set the mark FOR; non-destructive if mark is already set */
+#define MARK(FOR)                                                    \
+do {                                                                 \
+  if (!FOR##_mark) {                                                 \
+    FOR##_mark = p;                                                  \
+  }                                                                  \
+} while (0)
+
+/* Don't allow the total size of the HTTP headers (including the status
+ * line) to exceed HTTP_MAX_HEADER_SIZE.  This check is here to protect
+ * embedders against denial-of-service attacks where the attacker feeds
+ * us a never-ending header that the embedder keeps buffering.
+ *
+ * This check is arguably the responsibility of embedders but we're doing
+ * it on the embedder's behalf because most won't bother and this way we
+ * make the web a little safer.  HTTP_MAX_HEADER_SIZE is still far bigger
+ * than any reasonable request or response so this should never affect
+ * day-to-day operation.
+ */
+#define COUNT_HEADER_SIZE(V)                                         \
+do {                                                                 \
+  nread += (V);                                                      \
+  if (UNLIKELY(nread > (HTTP_MAX_HEADER_SIZE))) {                    \
+    SET_ERRNO(HPE_HEADER_OVERFLOW);                                  \
+    goto error;                                                      \
+  }                                                                  \
+} while (0)
+
+
+#define PROXY_CONNECTION "proxy-connection"
+#define CONNECTION "connection"
+#define CONTENT_LENGTH "content-length"
+#define TRANSFER_ENCODING "transfer-encoding"
+#define UPGRADE "upgrade"
+#define CHUNKED "chunked"
+#define KEEP_ALIVE "keep-alive"
+#define CLOSE "close"
+
+namespace wpi {
+
+
+static const char *method_strings[] =
+  {
+#define XX(num, name, string) #string,
+  HTTP_METHOD_MAP(XX)
+#undef XX
+  };
+
+
+/* Tokens as defined by rfc 2616. Also lowercases them.
+ *        token       = 1*<any CHAR except CTLs or separators>
+ *     separators     = "(" | ")" | "<" | ">" | "@"
+ *                    | "," | ";" | ":" | "\" | <">
+ *                    | "/" | "[" | "]" | "?" | "="
+ *                    | "{" | "}" | SP | HT
+ */
+static const char tokens[256] = {
+/*   0 nul    1 soh    2 stx    3 etx    4 eot    5 enq    6 ack    7 bel  */
+        0,       0,       0,       0,       0,       0,       0,       0,
+/*   8 bs     9 ht    10 nl    11 vt    12 np    13 cr    14 so    15 si   */
+        0,       0,       0,       0,       0,       0,       0,       0,
+/*  16 dle   17 dc1   18 dc2   19 dc3   20 dc4   21 nak   22 syn   23 etb */
+        0,       0,       0,       0,       0,       0,       0,       0,
+/*  24 can   25 em    26 sub   27 esc   28 fs    29 gs    30 rs    31 us  */
+        0,       0,       0,       0,       0,       0,       0,       0,
+/*  32 sp    33  !    34  "    35  #    36  $    37  %    38  &    39  '  */
+       ' ',     '!',      0,      '#',     '$',     '%',     '&',    '\'',
+/*  40  (    41  )    42  *    43  +    44  ,    45  -    46  .    47  /  */
+        0,       0,      '*',     '+',      0,      '-',     '.',      0,
+/*  48  0    49  1    50  2    51  3    52  4    53  5    54  6    55  7  */
+       '0',     '1',     '2',     '3',     '4',     '5',     '6',     '7',
+/*  56  8    57  9    58  :    59  ;    60  <    61  =    62  >    63  ?  */
+       '8',     '9',      0,       0,       0,       0,       0,       0,
+/*  64  @    65  A    66  B    67  C    68  D    69  E    70  F    71  G  */
+        0,      'a',     'b',     'c',     'd',     'e',     'f',     'g',
+/*  72  H    73  I    74  J    75  K    76  L    77  M    78  N    79  O  */
+       'h',     'i',     'j',     'k',     'l',     'm',     'n',     'o',
+/*  80  P    81  Q    82  R    83  S    84  T    85  U    86  V    87  W  */
+       'p',     'q',     'r',     's',     't',     'u',     'v',     'w',
+/*  88  X    89  Y    90  Z    91  [    92  \    93  ]    94  ^    95  _  */
+       'x',     'y',     'z',      0,       0,       0,      '^',     '_',
+/*  96  `    97  a    98  b    99  c   100  d   101  e   102  f   103  g  */
+       '`',     'a',     'b',     'c',     'd',     'e',     'f',     'g',
+/* 104  h   105  i   106  j   107  k   108  l   109  m   110  n   111  o  */
+       'h',     'i',     'j',     'k',     'l',     'm',     'n',     'o',
+/* 112  p   113  q   114  r   115  s   116  t   117  u   118  v   119  w  */
+       'p',     'q',     'r',     's',     't',     'u',     'v',     'w',
+/* 120  x   121  y   122  z   123  {   124  |   125  }   126  ~   127 del */
+       'x',     'y',     'z',      0,      '|',      0,      '~',       0 };
+
+
+static const int8_t unhex[256] =
+  {-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  , 0, 1, 2, 3, 4, 5, 6, 7, 8, 9,-1,-1,-1,-1,-1,-1
+  ,-1,10,11,12,13,14,15,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,10,11,12,13,14,15,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  ,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1,-1
+  };
+
+
+#if HTTP_PARSER_STRICT
+# define T(v) 0
+#else
+# define T(v) v
+#endif
+
+
+static const uint8_t normal_url_char[32] = {
+/*   0 nul    1 soh    2 stx    3 etx    4 eot    5 enq    6 ack    7 bel  */
+        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
+/*   8 bs     9 ht    10 nl    11 vt    12 np    13 cr    14 so    15 si   */
+        0    | T(2)   |   0    |   0    | T(16)  |   0    |   0    |   0,
+/*  16 dle   17 dc1   18 dc2   19 dc3   20 dc4   21 nak   22 syn   23 etb */
+        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
+/*  24 can   25 em    26 sub   27 esc   28 fs    29 gs    30 rs    31 us  */
+        0    |   0    |   0    |   0    |   0    |   0    |   0    |   0,
+/*  32 sp    33  !    34  "    35  #    36  $    37  %    38  &    39  '  */
+        0    |   2    |   4    |   0    |   16   |   32   |   64   |  128,
+/*  40  (    41  )    42  *    43  +    44  ,    45  -    46  .    47  /  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  48  0    49  1    50  2    51  3    52  4    53  5    54  6    55  7  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  56  8    57  9    58  :    59  ;    60  <    61  =    62  >    63  ?  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |   0,
+/*  64  @    65  A    66  B    67  C    68  D    69  E    70  F    71  G  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  72  H    73  I    74  J    75  K    76  L    77  M    78  N    79  O  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  80  P    81  Q    82  R    83  S    84  T    85  U    86  V    87  W  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  88  X    89  Y    90  Z    91  [    92  \    93  ]    94  ^    95  _  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/*  96  `    97  a    98  b    99  c   100  d   101  e   102  f   103  g  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/* 104  h   105  i   106  j   107  k   108  l   109  m   110  n   111  o  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/* 112  p   113  q   114  r   115  s   116  t   117  u   118  v   119  w  */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |  128,
+/* 120  x   121  y   122  z   123  {   124  |   125  }   126  ~   127 del */
+        1    |   2    |   4    |   8    |   16   |   32   |   64   |   0, };
+
+#undef T
+
+enum state
+  { s_dead = 1 /* important that this is > 0 */
+
+  , s_start_req_or_res
+  , s_res_or_resp_H
+  , s_start_res
+  , s_res_H
+  , s_res_HT
+  , s_res_HTT
+  , s_res_HTTP
+  , s_res_http_major
+  , s_res_http_dot
+  , s_res_http_minor
+  , s_res_http_end
+  , s_res_first_status_code
+  , s_res_status_code
+  , s_res_status_start
+  , s_res_status
+  , s_res_line_almost_done
+
+  , s_start_req
+
+  , s_req_method
+  , s_req_spaces_before_url
+  , s_req_schema
+  , s_req_schema_slash
+  , s_req_schema_slash_slash
+  , s_req_server_start
+  , s_req_server
+  , s_req_server_with_at
+  , s_req_path
+  , s_req_query_string_start
+  , s_req_query_string
+  , s_req_fragment_start
+  , s_req_fragment
+  , s_req_http_start
+  , s_req_http_H
+  , s_req_http_HT
+  , s_req_http_HTT
+  , s_req_http_HTTP
+  , s_req_http_major
+  , s_req_http_dot
+  , s_req_http_minor
+  , s_req_http_end
+  , s_req_line_almost_done
+
+  , s_header_field_start
+  , s_header_field
+  , s_header_value_discard_ws
+  , s_header_value_discard_ws_almost_done
+  , s_header_value_discard_lws
+  , s_header_value_start
+  , s_header_value
+  , s_header_value_lws
+
+  , s_header_almost_done
+
+  , s_chunk_size_start
+  , s_chunk_size
+  , s_chunk_parameters
+  , s_chunk_size_almost_done
+
+  , s_headers_almost_done
+  , s_headers_done
+
+  /* Important: 's_headers_done' must be the last 'header' state. All
+   * states beyond this must be 'body' states. It is used for overflow
+   * checking. See the PARSING_HEADER() macro.
+   */
+
+  , s_chunk_data
+  , s_chunk_data_almost_done
+  , s_chunk_data_done
+
+  , s_body_identity
+  , s_body_identity_eof
+
+  , s_message_done
+  };
+
+
+#define PARSING_HEADER(state) (state <= s_headers_done)
+
+
+enum header_states
+  { h_general = 0
+  , h_C
+  , h_CO
+  , h_CON
+
+  , h_matching_connection
+  , h_matching_proxy_connection
+  , h_matching_content_length
+  , h_matching_transfer_encoding
+  , h_matching_upgrade
+
+  , h_connection
+  , h_content_length
+  , h_content_length_num
+  , h_content_length_ws
+  , h_transfer_encoding
+  , h_upgrade
+
+  , h_matching_transfer_encoding_chunked
+  , h_matching_connection_token_start
+  , h_matching_connection_keep_alive
+  , h_matching_connection_close
+  , h_matching_connection_upgrade
+  , h_matching_connection_token
+
+  , h_transfer_encoding_chunked
+  , h_connection_keep_alive
+  , h_connection_close
+  , h_connection_upgrade
+  };
+
+enum http_host_state
+  {
+    s_http_host_dead = 1
+  , s_http_userinfo_start
+  , s_http_userinfo
+  , s_http_host_start
+  , s_http_host_v6_start
+  , s_http_host
+  , s_http_host_v6
+  , s_http_host_v6_end
+  , s_http_host_v6_zone_start
+  , s_http_host_v6_zone
+  , s_http_host_port_start
+  , s_http_host_port
+};
+
+/* Macros for character classes; depends on strict-mode  */
+#define CR                  '\r'
+#define LF                  '\n'
+#define LOWER(c)            (unsigned char)(c | 0x20)
+#define IS_ALPHA(c)         (LOWER(c) >= 'a' && LOWER(c) <= 'z')
+#define IS_NUM(c)           ((c) >= '0' && (c) <= '9')
+#define IS_ALPHANUM(c)      (IS_ALPHA(c) || IS_NUM(c))
+#define IS_HEX(c)           (IS_NUM(c) || (LOWER(c) >= 'a' && LOWER(c) <= 'f'))
+#define IS_MARK(c)          ((c) == '-' || (c) == '_' || (c) == '.' || \
+  (c) == '!' || (c) == '~' || (c) == '*' || (c) == '\'' || (c) == '(' || \
+  (c) == ')')
+#define IS_USERINFO_CHAR(c) (IS_ALPHANUM(c) || IS_MARK(c) || (c) == '%' || \
+  (c) == ';' || (c) == ':' || (c) == '&' || (c) == '=' || (c) == '+' || \
+  (c) == '$' || (c) == ',')
+
+#define STRICT_TOKEN(c)     ((c == ' ') ? 0 : tokens[(unsigned char)c])
+
+#if HTTP_PARSER_STRICT
+#define TOKEN(c)            STRICT_TOKEN(c)
+#define IS_URL_CHAR(c)      (BIT_AT(normal_url_char, (unsigned char)c))
+#define IS_HOST_CHAR(c)     (IS_ALPHANUM(c) || (c) == '.' || (c) == '-')
+#else
+#define TOKEN(c)            tokens[(unsigned char)c]
+#define IS_URL_CHAR(c)                                                         \
+  (BIT_AT(normal_url_char, (unsigned char)c) || ((c) & 0x80))
+#define IS_HOST_CHAR(c)                                                        \
+  (IS_ALPHANUM(c) || (c) == '.' || (c) == '-' || (c) == '_')
+#endif
+
+/**
+ * Verify that a char is a valid visible (printable) US-ASCII
+ * character or %x80-FF
+ **/
+#define IS_HEADER_CHAR(ch)                                                     \
+  (ch == CR || ch == LF || ch == 9 || ((unsigned char)ch > 31 && ch != 127))
+
+#define start_state (parser->type == HTTP_REQUEST ? s_start_req : s_start_res)
+
+
+#if HTTP_PARSER_STRICT
+# define STRICT_CHECK(cond)                                          \
+do {                                                                 \
+  if (cond) {                                                        \
+    SET_ERRNO(HPE_STRICT);                                           \
+    goto error;                                                      \
+  }                                                                  \
+} while (0)
+# define NEW_MESSAGE() (http_should_keep_alive(parser) ? start_state : s_dead)
+#else
+# define STRICT_CHECK(cond)
+# define NEW_MESSAGE() start_state
+#endif
+
+
+/* Map errno values to strings for human-readable output */
+#define HTTP_STRERROR_GEN(n, s) { "HPE_" #n, s },
+static struct {
+  const char *name;
+  const char *description;
+} http_strerror_tab[] = {
+  HTTP_ERRNO_MAP(HTTP_STRERROR_GEN)
+};
+#undef HTTP_STRERROR_GEN
+
+int http_message_needs_eof(const http_parser *parser);
+
+/* Our URL parser.
+ *
+ * This is designed to be shared by http_parser_execute() for URL validation,
+ * hence it has a state transition + byte-for-byte interface. In addition, it
+ * is meant to be embedded in http_parser_parse_url(), which does the dirty
+ * work of turning state transitions URL components for its API.
+ *
+ * This function should only be invoked with non-space characters. It is
+ * assumed that the caller cares about (and can detect) the transition between
+ * URL and non-URL states by looking for these.
+ */
+static enum state
+parse_url_char(enum state s, const char ch)
+{
+  if (ch == ' ' || ch == '\r' || ch == '\n') {
+    return s_dead;
+  }
+
+#if HTTP_PARSER_STRICT
+  if (ch == '\t' || ch == '\f') {
+    return s_dead;
+  }
+#endif
+
+  switch (s) {
+    case s_req_spaces_before_url:
+      /* Proxied requests are followed by scheme of an absolute URI (alpha).
+       * All methods except CONNECT are followed by '/' or '*'.
+       */
+
+      if (ch == '/' || ch == '*') {
+        return s_req_path;
+      }
+
+      if (IS_ALPHA(ch)) {
+        return s_req_schema;
+      }
+
+      break;
+
+    case s_req_schema:
+      if (IS_ALPHA(ch)) {
+        return s;
+      }
+
+      if (ch == ':') {
+        return s_req_schema_slash;
+      }
+
+      break;
+
+    case s_req_schema_slash:
+      if (ch == '/') {
+        return s_req_schema_slash_slash;
+      }
+
+      break;
+
+    case s_req_schema_slash_slash:
+      if (ch == '/') {
+        return s_req_server_start;
+      }
+
+      break;
+
+    case s_req_server_with_at:
+      if (ch == '@') {
+        return s_dead;
+      }
+
+    /* fall through */
+    case s_req_server_start:
+    case s_req_server:
+      if (ch == '/') {
+        return s_req_path;
+      }
+
+      if (ch == '?') {
+        return s_req_query_string_start;
+      }
+
+      if (ch == '@') {
+        return s_req_server_with_at;
+      }
+
+      if (IS_USERINFO_CHAR(ch) || ch == '[' || ch == ']') {
+        return s_req_server;
+      }
+
+      break;
+
+    case s_req_path:
+      if (IS_URL_CHAR(ch)) {
+        return s;
+      }
+
+      switch (ch) {
+        case '?':
+          return s_req_query_string_start;
+
+        case '#':
+          return s_req_fragment_start;
+      }
+
+      break;
+
+    case s_req_query_string_start:
+    case s_req_query_string:
+      if (IS_URL_CHAR(ch)) {
+        return s_req_query_string;
+      }
+
+      switch (ch) {
+        case '?':
+          /* allow extra '?' in query string */
+          return s_req_query_string;
+
+        case '#':
+          return s_req_fragment_start;
+      }
+
+      break;
+
+    case s_req_fragment_start:
+      if (IS_URL_CHAR(ch)) {
+        return s_req_fragment;
+      }
+
+      switch (ch) {
+        case '?':
+          return s_req_fragment;
+
+        case '#':
+          return s;
+      }
+
+      break;
+
+    case s_req_fragment:
+      if (IS_URL_CHAR(ch)) {
+        return s;
+      }
+
+      switch (ch) {
+        case '?':
+        case '#':
+          return s;
+      }
+
+      break;
+
+    default:
+      break;
+  }
+
+  /* We should never fall out of the switch above unless there's an error */
+  return s_dead;
+}
+
+size_t http_parser_execute (http_parser *parser,
+                            const http_parser_settings *settings,
+                            const char *data,
+                            size_t len)
+{
+  char c, ch;
+  int8_t unhex_val;
+  const char *p = data;
+  const char *header_field_mark = 0;
+  const char *header_value_mark = 0;
+  const char *url_mark = 0;
+  const char *body_mark = 0;
+  const char *status_mark = 0;
+  enum state p_state = (enum state) parser->state;
+  const unsigned int lenient = parser->lenient_http_headers;
+  uint32_t nread = parser->nread;
+
+  /* We're in an error state. Don't bother doing anything. */
+  if (HTTP_PARSER_ERRNO(parser) != HPE_OK) {
+    return 0;
+  }
+
+  if (len == 0) {
+    switch (CURRENT_STATE()) {
+      case s_body_identity_eof:
+        /* Use of CALLBACK_NOTIFY() here would erroneously return 1 byte read if
+         * we got paused.
+         */
+        CALLBACK_NOTIFY_NOADVANCE(message_complete);
+        return 0;
+
+      case s_dead:
+      case s_start_req_or_res:
+      case s_start_res:
+      case s_start_req:
+        return 0;
+
+      default:
+        SET_ERRNO(HPE_INVALID_EOF_STATE);
+        return 1;
+    }
+  }
+
+
+  if (CURRENT_STATE() == s_header_field)
+    header_field_mark = data;
+  if (CURRENT_STATE() == s_header_value)
+    header_value_mark = data;
+  switch (CURRENT_STATE()) {
+  case s_req_path:
+  case s_req_schema:
+  case s_req_schema_slash:
+  case s_req_schema_slash_slash:
+  case s_req_server_start:
+  case s_req_server:
+  case s_req_server_with_at:
+  case s_req_query_string_start:
+  case s_req_query_string:
+  case s_req_fragment_start:
+  case s_req_fragment:
+    url_mark = data;
+    break;
+  case s_res_status:
+    status_mark = data;
+    break;
+  default:
+    break;
+  }
+
+  for (p=data; p != data + len; p++) {
+    ch = *p;
+
+    if (PARSING_HEADER(CURRENT_STATE()))
+      COUNT_HEADER_SIZE(1);
+
+reexecute:
+    switch (CURRENT_STATE()) {
+
+      case s_dead:
+        /* this state is used after a 'Connection: close' message
+         * the parser will error out if it reads another message
+         */
+        if (LIKELY(ch == CR || ch == LF))
+          break;
+
+        SET_ERRNO(HPE_CLOSED_CONNECTION);
+        goto error;
+
+      case s_start_req_or_res:
+      {
+        if (ch == CR || ch == LF)
+          break;
+        parser->flags = 0;
+        parser->content_length = ULLONG_MAX;
+
+        if (ch == 'H') {
+          UPDATE_STATE(s_res_or_resp_H);
+
+          CALLBACK_NOTIFY(message_begin);
+        } else {
+          parser->type = HTTP_REQUEST;
+          UPDATE_STATE(s_start_req);
+          REEXECUTE();
+        }
+
+        break;
+      }
+
+      case s_res_or_resp_H:
+        if (ch == 'T') {
+          parser->type = HTTP_RESPONSE;
+          UPDATE_STATE(s_res_HT);
+        } else {
+          if (UNLIKELY(ch != 'E')) {
+            SET_ERRNO(HPE_INVALID_CONSTANT);
+            goto error;
+          }
+
+          parser->type = HTTP_REQUEST;
+          parser->method = HTTP_HEAD;
+          parser->index = 2;
+          UPDATE_STATE(s_req_method);
+        }
+        break;
+
+      case s_start_res:
+      {
+        parser->flags = 0;
+        parser->content_length = ULLONG_MAX;
+
+        switch (ch) {
+          case 'H':
+            UPDATE_STATE(s_res_H);
+            break;
+
+          case CR:
+          case LF:
+            break;
+
+          default:
+            SET_ERRNO(HPE_INVALID_CONSTANT);
+            goto error;
+        }
+
+        CALLBACK_NOTIFY(message_begin);
+        break;
+      }
+
+      case s_res_H:
+        STRICT_CHECK(ch != 'T');
+        UPDATE_STATE(s_res_HT);
+        break;
+
+      case s_res_HT:
+        STRICT_CHECK(ch != 'T');
+        UPDATE_STATE(s_res_HTT);
+        break;
+
+      case s_res_HTT:
+        STRICT_CHECK(ch != 'P');
+        UPDATE_STATE(s_res_HTTP);
+        break;
+
+      case s_res_HTTP:
+        STRICT_CHECK(ch != '/');
+        UPDATE_STATE(s_res_http_major);
+        break;
+
+      case s_res_http_major:
+        if (UNLIKELY(!IS_NUM(ch))) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        parser->http_major = ch - '0';
+        UPDATE_STATE(s_res_http_dot);
+        break;
+
+      case s_res_http_dot:
+      {
+        if (UNLIKELY(ch != '.')) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        UPDATE_STATE(s_res_http_minor);
+        break;
+      }
+
+      case s_res_http_minor:
+        if (UNLIKELY(!IS_NUM(ch))) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        parser->http_minor = ch - '0';
+        UPDATE_STATE(s_res_http_end);
+        break;
+
+      case s_res_http_end:
+      {
+        if (UNLIKELY(ch != ' ')) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        UPDATE_STATE(s_res_first_status_code);
+        break;
+      }
+
+      case s_res_first_status_code:
+      {
+        if (!IS_NUM(ch)) {
+          if (ch == ' ') {
+            break;
+          }
+
+          SET_ERRNO(HPE_INVALID_STATUS);
+          goto error;
+        }
+        parser->status_code = ch - '0';
+        UPDATE_STATE(s_res_status_code);
+        break;
+      }
+
+      case s_res_status_code:
+      {
+        if (!IS_NUM(ch)) {
+          switch (ch) {
+            case ' ':
+              UPDATE_STATE(s_res_status_start);
+              break;
+            case CR:
+            case LF:
+              UPDATE_STATE(s_res_status_start);
+              REEXECUTE();
+              break;
+            default:
+              SET_ERRNO(HPE_INVALID_STATUS);
+              goto error;
+          }
+          break;
+        }
+
+        parser->status_code *= 10;
+        parser->status_code += ch - '0';
+
+        if (UNLIKELY(parser->status_code > 999)) {
+          SET_ERRNO(HPE_INVALID_STATUS);
+          goto error;
+        }
+
+        break;
+      }
+
+      case s_res_status_start:
+      {
+        MARK(status);
+        UPDATE_STATE(s_res_status);
+        parser->index = 0;
+
+        if (ch == CR || ch == LF)
+          REEXECUTE();
+
+        break;
+      }
+
+      case s_res_status:
+        if (ch == CR) {
+          UPDATE_STATE(s_res_line_almost_done);
+          CALLBACK_DATA(status);
+          break;
+        }
+
+        if (ch == LF) {
+          UPDATE_STATE(s_header_field_start);
+          CALLBACK_DATA(status);
+          break;
+        }
+
+        break;
+
+      case s_res_line_almost_done:
+        STRICT_CHECK(ch != LF);
+        UPDATE_STATE(s_header_field_start);
+        break;
+
+      case s_start_req:
+      {
+        if (ch == CR || ch == LF)
+          break;
+        parser->flags = 0;
+        parser->content_length = ULLONG_MAX;
+
+        if (UNLIKELY(!IS_ALPHA(ch))) {
+          SET_ERRNO(HPE_INVALID_METHOD);
+          goto error;
+        }
+
+        parser->method = (enum http_method) 0;
+        parser->index = 1;
+        switch (ch) {
+          case 'A': parser->method = HTTP_ACL; break;
+          case 'B': parser->method = HTTP_BIND; break;
+          case 'C': parser->method = HTTP_CONNECT; /* or COPY, CHECKOUT */ break;
+          case 'D': parser->method = HTTP_DELETE; break;
+          case 'G': parser->method = HTTP_GET; break;
+          case 'H': parser->method = HTTP_HEAD; break;
+          case 'L': parser->method = HTTP_LOCK; /* or LINK */ break;
+          case 'M': parser->method = HTTP_MKCOL; /* or MOVE, MKACTIVITY, MERGE, M-SEARCH, MKCALENDAR */ break;
+          case 'N': parser->method = HTTP_NOTIFY; break;
+          case 'O': parser->method = HTTP_OPTIONS; break;
+          case 'P': parser->method = HTTP_POST;
+            /* or PROPFIND|PROPPATCH|PUT|PATCH|PURGE */
+            break;
+          case 'R': parser->method = HTTP_REPORT; /* or REBIND */ break;
+          case 'S': parser->method = HTTP_SUBSCRIBE; /* or SEARCH, SOURCE */ break;
+          case 'T': parser->method = HTTP_TRACE; break;
+          case 'U': parser->method = HTTP_UNLOCK; /* or UNSUBSCRIBE, UNBIND, UNLINK */ break;
+          default:
+            SET_ERRNO(HPE_INVALID_METHOD);
+            goto error;
+        }
+        UPDATE_STATE(s_req_method);
+
+        CALLBACK_NOTIFY(message_begin);
+
+        break;
+      }
+
+      case s_req_method:
+      {
+        const char *matcher;
+        if (UNLIKELY(ch == '\0')) {
+          SET_ERRNO(HPE_INVALID_METHOD);
+          goto error;
+        }
+
+        matcher = method_strings[parser->method];
+        if (ch == ' ' && matcher[parser->index] == '\0') {
+          UPDATE_STATE(s_req_spaces_before_url);
+        } else if (ch == matcher[parser->index]) {
+          ; /* nada */
+        } else if ((ch >= 'A' && ch <= 'Z') || ch == '-') {
+
+          switch (parser->method << 16 | parser->index << 8 | ch) {
+#define XX(meth, pos, ch, new_meth) \
+            case (HTTP_##meth << 16 | pos << 8 | ch): \
+              parser->method = HTTP_##new_meth; break;
+
+            XX(POST,      1, 'U', PUT)
+            XX(POST,      1, 'A', PATCH)
+            XX(POST,      1, 'R', PROPFIND)
+            XX(PUT,       2, 'R', PURGE)
+            XX(CONNECT,   1, 'H', CHECKOUT)
+            XX(CONNECT,   2, 'P', COPY)
+            XX(MKCOL,     1, 'O', MOVE)
+            XX(MKCOL,     1, 'E', MERGE)
+            XX(MKCOL,     1, '-', MSEARCH)
+            XX(MKCOL,     2, 'A', MKACTIVITY)
+            XX(MKCOL,     3, 'A', MKCALENDAR)
+            XX(SUBSCRIBE, 1, 'E', SEARCH)
+            XX(SUBSCRIBE, 1, 'O', SOURCE)
+            XX(REPORT,    2, 'B', REBIND)
+            XX(PROPFIND,  4, 'P', PROPPATCH)
+            XX(LOCK,      1, 'I', LINK)
+            XX(UNLOCK,    2, 'S', UNSUBSCRIBE)
+            XX(UNLOCK,    2, 'B', UNBIND)
+            XX(UNLOCK,    3, 'I', UNLINK)
+#undef XX
+            default:
+              SET_ERRNO(HPE_INVALID_METHOD);
+              goto error;
+          }
+        } else {
+          SET_ERRNO(HPE_INVALID_METHOD);
+          goto error;
+        }
+
+        ++parser->index;
+        break;
+      }
+
+      case s_req_spaces_before_url:
+      {
+        if (ch == ' ') break;
+
+        MARK(url);
+        if (parser->method == HTTP_CONNECT) {
+          UPDATE_STATE(s_req_server_start);
+        }
+
+        UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
+        if (UNLIKELY(CURRENT_STATE() == s_dead)) {
+          SET_ERRNO(HPE_INVALID_URL);
+          goto error;
+        }
+
+        break;
+      }
+
+      case s_req_schema:
+      case s_req_schema_slash:
+      case s_req_schema_slash_slash:
+      case s_req_server_start:
+      {
+        switch (ch) {
+          /* No whitespace allowed here */
+          case ' ':
+          case CR:
+          case LF:
+            SET_ERRNO(HPE_INVALID_URL);
+            goto error;
+          default:
+            UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
+            if (UNLIKELY(CURRENT_STATE() == s_dead)) {
+              SET_ERRNO(HPE_INVALID_URL);
+              goto error;
+            }
+        }
+
+        break;
+      }
+
+      case s_req_server:
+      case s_req_server_with_at:
+      case s_req_path:
+      case s_req_query_string_start:
+      case s_req_query_string:
+      case s_req_fragment_start:
+      case s_req_fragment:
+      {
+        switch (ch) {
+          case ' ':
+            UPDATE_STATE(s_req_http_start);
+            CALLBACK_DATA(url);
+            break;
+          case CR:
+          case LF:
+            parser->http_major = 0;
+            parser->http_minor = 9;
+            UPDATE_STATE((ch == CR) ?
+              s_req_line_almost_done :
+              s_header_field_start);
+            CALLBACK_DATA(url);
+            break;
+          default:
+            UPDATE_STATE(parse_url_char(CURRENT_STATE(), ch));
+            if (UNLIKELY(CURRENT_STATE() == s_dead)) {
+              SET_ERRNO(HPE_INVALID_URL);
+              goto error;
+            }
+        }
+        break;
+      }
+
+      case s_req_http_start:
+        switch (ch) {
+          case 'H':
+            UPDATE_STATE(s_req_http_H);
+            break;
+          case ' ':
+            break;
+          default:
+            SET_ERRNO(HPE_INVALID_CONSTANT);
+            goto error;
+        }
+        break;
+
+      case s_req_http_H:
+        STRICT_CHECK(ch != 'T');
+        UPDATE_STATE(s_req_http_HT);
+        break;
+
+      case s_req_http_HT:
+        STRICT_CHECK(ch != 'T');
+        UPDATE_STATE(s_req_http_HTT);
+        break;
+
+      case s_req_http_HTT:
+        STRICT_CHECK(ch != 'P');
+        UPDATE_STATE(s_req_http_HTTP);
+        break;
+
+      case s_req_http_HTTP:
+        STRICT_CHECK(ch != '/');
+        UPDATE_STATE(s_req_http_major);
+        break;
+
+      case s_req_http_major:
+        if (UNLIKELY(!IS_NUM(ch))) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        parser->http_major = ch - '0';
+        UPDATE_STATE(s_req_http_dot);
+        break;
+
+      case s_req_http_dot:
+      {
+        if (UNLIKELY(ch != '.')) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        UPDATE_STATE(s_req_http_minor);
+        break;
+      }
+
+      case s_req_http_minor:
+        if (UNLIKELY(!IS_NUM(ch))) {
+          SET_ERRNO(HPE_INVALID_VERSION);
+          goto error;
+        }
+
+        parser->http_minor = ch - '0';
+        UPDATE_STATE(s_req_http_end);
+        break;
+
+      case s_req_http_end:
+      {
+        if (ch == CR) {
+          UPDATE_STATE(s_req_line_almost_done);
+          break;
+        }
+
+        if (ch == LF) {
+          UPDATE_STATE(s_header_field_start);
+          break;
+        }
+
+        SET_ERRNO(HPE_INVALID_VERSION);
+        goto error;
+        break;
+      }
+
+      /* end of request line */
+      case s_req_line_almost_done:
+      {
+        if (UNLIKELY(ch != LF)) {
+          SET_ERRNO(HPE_LF_EXPECTED);
+          goto error;
+        }
+
+        UPDATE_STATE(s_header_field_start);
+        break;
+      }
+
+      case s_header_field_start:
+      {
+        if (ch == CR) {
+          UPDATE_STATE(s_headers_almost_done);
+          break;
+        }
+
+        if (ch == LF) {
+          /* they might be just sending \n instead of \r\n so this would be
+           * the second \n to denote the end of headers*/
+          UPDATE_STATE(s_headers_almost_done);
+          REEXECUTE();
+        }
+
+        c = TOKEN(ch);
+
+        if (UNLIKELY(!c)) {
+          SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
+          goto error;
+        }
+
+        MARK(header_field);
+
+        parser->index = 0;
+        UPDATE_STATE(s_header_field);
+
+        switch (c) {
+          case 'c':
+            parser->header_state = h_C;
+            break;
+
+          case 'p':
+            parser->header_state = h_matching_proxy_connection;
+            break;
+
+          case 't':
+            parser->header_state = h_matching_transfer_encoding;
+            break;
+
+          case 'u':
+            parser->header_state = h_matching_upgrade;
+            break;
+
+          default:
+            parser->header_state = h_general;
+            break;
+        }
+        break;
+      }
+
+      case s_header_field:
+      {
+        const char* start = p;
+        for (; p != data + len; p++) {
+          ch = *p;
+          c = TOKEN(ch);
+
+          if (!c)
+            break;
+
+          switch (parser->header_state) {
+            case h_general: {
+              size_t limit = data + len - p;
+              limit = MIN(limit, HTTP_MAX_HEADER_SIZE);
+              while (p+1 < data + limit && TOKEN(p[1])) {
+                p++;
+              }
+              break;
+            }
+
+            case h_C:
+              parser->index++;
+              parser->header_state = (c == 'o' ? h_CO : h_general);
+              break;
+
+            case h_CO:
+              parser->index++;
+              parser->header_state = (c == 'n' ? h_CON : h_general);
+              break;
+
+            case h_CON:
+              parser->index++;
+              switch (c) {
+                case 'n':
+                  parser->header_state = h_matching_connection;
+                  break;
+                case 't':
+                  parser->header_state = h_matching_content_length;
+                  break;
+                default:
+                  parser->header_state = h_general;
+                  break;
+              }
+              break;
+
+            /* connection */
+
+            case h_matching_connection:
+              parser->index++;
+              if (parser->index > sizeof(CONNECTION)-1
+                  || c != CONNECTION[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(CONNECTION)-2) {
+                parser->header_state = h_connection;
+              }
+              break;
+
+            /* proxy-connection */
+
+            case h_matching_proxy_connection:
+              parser->index++;
+              if (parser->index > sizeof(PROXY_CONNECTION)-1
+                  || c != PROXY_CONNECTION[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(PROXY_CONNECTION)-2) {
+                parser->header_state = h_connection;
+              }
+              break;
+
+            /* content-length */
+
+            case h_matching_content_length:
+              parser->index++;
+              if (parser->index > sizeof(CONTENT_LENGTH)-1
+                  || c != CONTENT_LENGTH[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(CONTENT_LENGTH)-2) {
+                parser->header_state = h_content_length;
+              }
+              break;
+
+            /* transfer-encoding */
+
+            case h_matching_transfer_encoding:
+              parser->index++;
+              if (parser->index > sizeof(TRANSFER_ENCODING)-1
+                  || c != TRANSFER_ENCODING[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(TRANSFER_ENCODING)-2) {
+                parser->header_state = h_transfer_encoding;
+              }
+              break;
+
+            /* upgrade */
+
+            case h_matching_upgrade:
+              parser->index++;
+              if (parser->index > sizeof(UPGRADE)-1
+                  || c != UPGRADE[parser->index]) {
+                parser->header_state = h_general;
+              } else if (parser->index == sizeof(UPGRADE)-2) {
+                parser->header_state = h_upgrade;
+              }
+              break;
+
+            case h_connection:
+            case h_content_length:
+            case h_transfer_encoding:
+            case h_upgrade:
+              if (ch != ' ') parser->header_state = h_general;
+              break;
+
+            default:
+              assert(0 && "Unknown header_state");
+              break;
+          }
+        }
+
+        if (p == data + len) {
+          --p;
+          COUNT_HEADER_SIZE(p - start);
+          break;
+        }
+
+        COUNT_HEADER_SIZE(p - start);
+
+        if (ch == ':') {
+          UPDATE_STATE(s_header_value_discard_ws);
+          CALLBACK_DATA(header_field);
+          break;
+        }
+
+        SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
+        goto error;
+      }
+
+      case s_header_value_discard_ws:
+        if (ch == ' ' || ch == '\t') break;
+
+        if (ch == CR) {
+          UPDATE_STATE(s_header_value_discard_ws_almost_done);
+          break;
+        }
+
+        if (ch == LF) {
+          UPDATE_STATE(s_header_value_discard_lws);
+          break;
+        }
+
+        /* fall through */
+
+      case s_header_value_start:
+      {
+        MARK(header_value);
+
+        UPDATE_STATE(s_header_value);
+        parser->index = 0;
+
+        c = LOWER(ch);
+
+        switch (parser->header_state) {
+          case h_upgrade:
+            parser->flags |= F_UPGRADE;
+            parser->header_state = h_general;
+            break;
+
+          case h_transfer_encoding:
+            /* looking for 'Transfer-Encoding: chunked' */
+            if ('c' == c) {
+              parser->header_state = h_matching_transfer_encoding_chunked;
+            } else {
+              parser->header_state = h_general;
+            }
+            break;
+
+          case h_content_length:
+            if (UNLIKELY(!IS_NUM(ch))) {
+              SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+              goto error;
+            }
+
+            if (parser->flags & F_CONTENTLENGTH) {
+              SET_ERRNO(HPE_UNEXPECTED_CONTENT_LENGTH);
+              goto error;
+            }
+
+            parser->flags |= F_CONTENTLENGTH;
+            parser->content_length = ch - '0';
+            parser->header_state = h_content_length_num;
+            break;
+
+          case h_connection:
+            /* looking for 'Connection: keep-alive' */
+            if (c == 'k') {
+              parser->header_state = h_matching_connection_keep_alive;
+            /* looking for 'Connection: close' */
+            } else if (c == 'c') {
+              parser->header_state = h_matching_connection_close;
+            } else if (c == 'u') {
+              parser->header_state = h_matching_connection_upgrade;
+            } else {
+              parser->header_state = h_matching_connection_token;
+            }
+            break;
+
+          /* Multi-value `Connection` header */
+          case h_matching_connection_token_start:
+            break;
+
+          default:
+            parser->header_state = h_general;
+            break;
+        }
+        break;
+      }
+
+      case s_header_value:
+      {
+        const char* start = p;
+        enum header_states h_state = (enum header_states) parser->header_state;
+        for (; p != data + len; p++) {
+          ch = *p;
+          if (ch == CR) {
+            UPDATE_STATE(s_header_almost_done);
+            parser->header_state = h_state;
+            CALLBACK_DATA(header_value);
+            break;
+          }
+
+          if (ch == LF) {
+            UPDATE_STATE(s_header_almost_done);
+            COUNT_HEADER_SIZE(p - start);
+            parser->header_state = h_state;
+            CALLBACK_DATA_NOADVANCE(header_value);
+            REEXECUTE();
+          }
+
+          if (!lenient && !IS_HEADER_CHAR(ch)) {
+            SET_ERRNO(HPE_INVALID_HEADER_TOKEN);
+            goto error;
+          }
+
+          c = LOWER(ch);
+
+          switch (h_state) {
+            case h_general:
+            {
+              const char* p_cr;
+              const char* p_lf;
+              size_t limit = data + len - p;
+
+              limit = MIN(limit, HTTP_MAX_HEADER_SIZE);
+
+              p_cr = (const char*) memchr(p, CR, limit);
+              p_lf = (const char*) memchr(p, LF, limit);
+              if (p_cr != NULL) {
+                if (p_lf != NULL && p_cr >= p_lf)
+                  p = p_lf;
+                else
+                  p = p_cr;
+              } else if (UNLIKELY(p_lf != NULL)) {
+                p = p_lf;
+              } else {
+                p = data + len;
+              }
+              --p;
+              break;
+            }
+
+            case h_connection:
+            case h_transfer_encoding:
+              assert(0 && "Shouldn't get here.");
+              break;
+
+            case h_content_length:
+              if (ch == ' ') break;
+              h_state = h_content_length_num;
+              /* fall through */
+
+            case h_content_length_num:
+            {
+              uint64_t t;
+
+              if (ch == ' ') {
+                h_state = h_content_length_ws;
+                break;
+              }
+
+              if (UNLIKELY(!IS_NUM(ch))) {
+                SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+                parser->header_state = h_state;
+                goto error;
+              }
+
+              t = parser->content_length;
+              t *= 10;
+              t += ch - '0';
+
+              /* Overflow? Test against a conservative limit for simplicity. */
+              if (UNLIKELY((ULLONG_MAX - 10) / 10 < parser->content_length)) {
+                SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+                parser->header_state = h_state;
+                goto error;
+              }
+
+              parser->content_length = t;
+              break;
+            }
+
+            case h_content_length_ws:
+              if (ch == ' ') break;
+              SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+              parser->header_state = h_state;
+              goto error;
+
+            /* Transfer-Encoding: chunked */
+            case h_matching_transfer_encoding_chunked:
+              parser->index++;
+              if (parser->index > sizeof(CHUNKED)-1
+                  || c != CHUNKED[parser->index]) {
+                h_state = h_general;
+              } else if (parser->index == sizeof(CHUNKED)-2) {
+                h_state = h_transfer_encoding_chunked;
+              }
+              break;
+
+            case h_matching_connection_token_start:
+              /* looking for 'Connection: keep-alive' */
+              if (c == 'k') {
+                h_state = h_matching_connection_keep_alive;
+              /* looking for 'Connection: close' */
+              } else if (c == 'c') {
+                h_state = h_matching_connection_close;
+              } else if (c == 'u') {
+                h_state = h_matching_connection_upgrade;
+              } else if (STRICT_TOKEN(c)) {
+                h_state = h_matching_connection_token;
+              } else if (c == ' ' || c == '\t') {
+                /* Skip lws */
+              } else {
+                h_state = h_general;
+              }
+              break;
+
+            /* looking for 'Connection: keep-alive' */
+            case h_matching_connection_keep_alive:
+              parser->index++;
+              if (parser->index > sizeof(KEEP_ALIVE)-1
+                  || c != KEEP_ALIVE[parser->index]) {
+                h_state = h_matching_connection_token;
+              } else if (parser->index == sizeof(KEEP_ALIVE)-2) {
+                h_state = h_connection_keep_alive;
+              }
+              break;
+
+            /* looking for 'Connection: close' */
+            case h_matching_connection_close:
+              parser->index++;
+              if (parser->index > sizeof(CLOSE)-1 || c != CLOSE[parser->index]) {
+                h_state = h_matching_connection_token;
+              } else if (parser->index == sizeof(CLOSE)-2) {
+                h_state = h_connection_close;
+              }
+              break;
+
+            /* looking for 'Connection: upgrade' */
+            case h_matching_connection_upgrade:
+              parser->index++;
+              if (parser->index > sizeof(UPGRADE) - 1 ||
+                  c != UPGRADE[parser->index]) {
+                h_state = h_matching_connection_token;
+              } else if (parser->index == sizeof(UPGRADE)-2) {
+                h_state = h_connection_upgrade;
+              }
+              break;
+
+            case h_matching_connection_token:
+              if (ch == ',') {
+                h_state = h_matching_connection_token_start;
+                parser->index = 0;
+              }
+              break;
+
+            case h_transfer_encoding_chunked:
+              if (ch != ' ') h_state = h_general;
+              break;
+
+            case h_connection_keep_alive:
+            case h_connection_close:
+            case h_connection_upgrade:
+              if (ch == ',') {
+                if (h_state == h_connection_keep_alive) {
+                  parser->flags |= F_CONNECTION_KEEP_ALIVE;
+                } else if (h_state == h_connection_close) {
+                  parser->flags |= F_CONNECTION_CLOSE;
+                } else if (h_state == h_connection_upgrade) {
+                  parser->flags |= F_CONNECTION_UPGRADE;
+                }
+                h_state = h_matching_connection_token_start;
+                parser->index = 0;
+              } else if (ch != ' ') {
+                h_state = h_matching_connection_token;
+              }
+              break;
+
+            default:
+              UPDATE_STATE(s_header_value);
+              h_state = h_general;
+              break;
+          }
+        }
+        parser->header_state = h_state;
+
+        if (p == data + len)
+          --p;
+
+        COUNT_HEADER_SIZE(p - start);
+        break;
+      }
+
+      case s_header_almost_done:
+      {
+        if (UNLIKELY(ch != LF)) {
+          SET_ERRNO(HPE_LF_EXPECTED);
+          goto error;
+        }
+
+        UPDATE_STATE(s_header_value_lws);
+        break;
+      }
+
+      case s_header_value_lws:
+      {
+        if (ch == ' ' || ch == '\t') {
+          UPDATE_STATE(s_header_value_start);
+          REEXECUTE();
+        }
+
+        /* finished the header */
+        switch (parser->header_state) {
+          case h_connection_keep_alive:
+            parser->flags |= F_CONNECTION_KEEP_ALIVE;
+            break;
+          case h_connection_close:
+            parser->flags |= F_CONNECTION_CLOSE;
+            break;
+          case h_transfer_encoding_chunked:
+            parser->flags |= F_CHUNKED;
+            break;
+          case h_connection_upgrade:
+            parser->flags |= F_CONNECTION_UPGRADE;
+            break;
+          default:
+            break;
+        }
+
+        UPDATE_STATE(s_header_field_start);
+        REEXECUTE();
+      }
+
+      case s_header_value_discard_ws_almost_done:
+      {
+        STRICT_CHECK(ch != LF);
+        UPDATE_STATE(s_header_value_discard_lws);
+        break;
+      }
+
+      case s_header_value_discard_lws:
+      {
+        if (ch == ' ' || ch == '\t') {
+          UPDATE_STATE(s_header_value_discard_ws);
+          break;
+        } else {
+          switch (parser->header_state) {
+            case h_connection_keep_alive:
+              parser->flags |= F_CONNECTION_KEEP_ALIVE;
+              break;
+            case h_connection_close:
+              parser->flags |= F_CONNECTION_CLOSE;
+              break;
+            case h_connection_upgrade:
+              parser->flags |= F_CONNECTION_UPGRADE;
+              break;
+            case h_transfer_encoding_chunked:
+              parser->flags |= F_CHUNKED;
+              break;
+            default:
+              break;
+          }
+
+          /* header value was empty */
+          MARK(header_value);
+          UPDATE_STATE(s_header_field_start);
+          CALLBACK_DATA_NOADVANCE(header_value);
+          REEXECUTE();
+        }
+      }
+
+      case s_headers_almost_done:
+      {
+        STRICT_CHECK(ch != LF);
+
+        if (parser->flags & F_TRAILING) {
+          /* End of a chunked request */
+          UPDATE_STATE(s_message_done);
+          CALLBACK_NOTIFY_NOADVANCE(chunk_complete);
+          REEXECUTE();
+        }
+
+        /* Cannot use chunked encoding and a content-length header together
+           per the HTTP specification. */
+        if ((parser->flags & F_CHUNKED) &&
+            (parser->flags & F_CONTENTLENGTH)) {
+          SET_ERRNO(HPE_UNEXPECTED_CONTENT_LENGTH);
+          goto error;
+        }
+
+        UPDATE_STATE(s_headers_done);
+
+        /* Set this here so that on_headers_complete() callbacks can see it */
+        if ((parser->flags & F_UPGRADE) &&
+            (parser->flags & F_CONNECTION_UPGRADE)) {
+          /* For responses, "Upgrade: foo" and "Connection: upgrade" are
+           * mandatory only when it is a 101 Switching Protocols response,
+           * otherwise it is purely informational, to announce support.
+           */
+          parser->upgrade =
+              (parser->type == HTTP_REQUEST || parser->status_code == 101);
+        } else {
+          parser->upgrade = (parser->method == HTTP_CONNECT);
+        }
+
+        /* Here we call the headers_complete callback. This is somewhat
+         * different than other callbacks because if the user returns 1, we
+         * will interpret that as saying that this message has no body. This
+         * is needed for the annoying case of recieving a response to a HEAD
+         * request.
+         *
+         * We'd like to use CALLBACK_NOTIFY_NOADVANCE() here but we cannot, so
+         * we have to simulate it by handling a change in errno below.
+         */
+        if (settings->on_headers_complete) {
+          switch (settings->on_headers_complete(parser)) {
+            case 0:
+              break;
+
+            case 2:
+              parser->upgrade = 1;
+
+              /* fall through */
+            case 1:
+              parser->flags |= F_SKIPBODY;
+              break;
+
+            default:
+              SET_ERRNO(HPE_CB_headers_complete);
+              RETURN(p - data); /* Error */
+          }
+        }
+
+        if (HTTP_PARSER_ERRNO(parser) != HPE_OK) {
+          RETURN(p - data);
+        }
+
+        REEXECUTE();
+      }
+
+      case s_headers_done:
+      {
+        int hasBody;
+        STRICT_CHECK(ch != LF);
+
+        parser->nread = 0;
+        nread = 0;
+
+        hasBody = parser->flags & F_CHUNKED ||
+          (parser->content_length > 0 && parser->content_length != ULLONG_MAX);
+        if (parser->upgrade && (parser->method == HTTP_CONNECT ||
+                                (parser->flags & F_SKIPBODY) || !hasBody)) {
+          /* Exit, the rest of the message is in a different protocol. */
+          UPDATE_STATE(NEW_MESSAGE());
+          CALLBACK_NOTIFY(message_complete);
+          RETURN((p - data) + 1);
+        }
+
+        if (parser->flags & F_SKIPBODY) {
+          UPDATE_STATE(NEW_MESSAGE());
+          CALLBACK_NOTIFY(message_complete);
+        } else if (parser->flags & F_CHUNKED) {
+          /* chunked encoding - ignore Content-Length header */
+          UPDATE_STATE(s_chunk_size_start);
+        } else {
+          if (parser->content_length == 0) {
+            /* Content-Length header given but zero: Content-Length: 0\r\n */
+            UPDATE_STATE(NEW_MESSAGE());
+            CALLBACK_NOTIFY(message_complete);
+          } else if (parser->content_length != ULLONG_MAX) {
+            /* Content-Length header given and non-zero */
+            UPDATE_STATE(s_body_identity);
+          } else {
+            if (!http_message_needs_eof(parser)) {
+              /* Assume content-length 0 - read the next */
+              UPDATE_STATE(NEW_MESSAGE());
+              CALLBACK_NOTIFY(message_complete);
+            } else {
+              /* Read body until EOF */
+              UPDATE_STATE(s_body_identity_eof);
+            }
+          }
+        }
+
+        break;
+      }
+
+      case s_body_identity:
+      {
+        uint64_t to_read = MIN(parser->content_length,
+                               (uint64_t) ((data + len) - p));
+
+        assert(parser->content_length != 0
+            && parser->content_length != ULLONG_MAX);
+
+        /* The difference between advancing content_length and p is because
+         * the latter will automaticaly advance on the next loop iteration.
+         * Further, if content_length ends up at 0, we want to see the last
+         * byte again for our message complete callback.
+         */
+        MARK(body);
+        parser->content_length -= to_read;
+        p += to_read - 1;
+
+        if (parser->content_length == 0) {
+          UPDATE_STATE(s_message_done);
+
+          /* Mimic CALLBACK_DATA_NOADVANCE() but with one extra byte.
+           *
+           * The alternative to doing this is to wait for the next byte to
+           * trigger the data callback, just as in every other case. The
+           * problem with this is that this makes it difficult for the test
+           * harness to distinguish between complete-on-EOF and
+           * complete-on-length. It's not clear that this distinction is
+           * important for applications, but let's keep it for now.
+           */
+          CALLBACK_DATA_(body, p - body_mark + 1, p - data);
+          REEXECUTE();
+        }
+
+        break;
+      }
+
+      /* read until EOF */
+      case s_body_identity_eof:
+        MARK(body);
+        p = data + len - 1;
+
+        break;
+
+      case s_message_done:
+        UPDATE_STATE(NEW_MESSAGE());
+        CALLBACK_NOTIFY(message_complete);
+        if (parser->upgrade) {
+          /* Exit, the rest of the message is in a different protocol. */
+          RETURN((p - data) + 1);
+        }
+        break;
+
+      case s_chunk_size_start:
+      {
+        assert(nread == 1);
+        assert(parser->flags & F_CHUNKED);
+
+        unhex_val = unhex[(unsigned char)ch];
+        if (UNLIKELY(unhex_val == -1)) {
+          SET_ERRNO(HPE_INVALID_CHUNK_SIZE);
+          goto error;
+        }
+
+        parser->content_length = unhex_val;
+        UPDATE_STATE(s_chunk_size);
+        break;
+      }
+
+      case s_chunk_size:
+      {
+        uint64_t t;
+
+        assert(parser->flags & F_CHUNKED);
+
+        if (ch == CR) {
+          UPDATE_STATE(s_chunk_size_almost_done);
+          break;
+        }
+
+        unhex_val = unhex[(unsigned char)ch];
+
+        if (unhex_val == -1) {
+          if (ch == ';' || ch == ' ') {
+            UPDATE_STATE(s_chunk_parameters);
+            break;
+          }
+
+          SET_ERRNO(HPE_INVALID_CHUNK_SIZE);
+          goto error;
+        }
+
+        t = parser->content_length;
+        t *= 16;
+        t += unhex_val;
+
+        /* Overflow? Test against a conservative limit for simplicity. */
+        if (UNLIKELY((ULLONG_MAX - 16) / 16 < parser->content_length)) {
+          SET_ERRNO(HPE_INVALID_CONTENT_LENGTH);
+          goto error;
+        }
+
+        parser->content_length = t;
+        break;
+      }
+
+      case s_chunk_parameters:
+      {
+        assert(parser->flags & F_CHUNKED);
+        /* just ignore this shit. TODO check for overflow */
+        if (ch == CR) {
+          UPDATE_STATE(s_chunk_size_almost_done);
+          break;
+        }
+        break;
+      }
+
+      case s_chunk_size_almost_done:
+      {
+        assert(parser->flags & F_CHUNKED);
+        STRICT_CHECK(ch != LF);
+
+        parser->nread = 0;
+        nread = 0;
+
+        if (parser->content_length == 0) {
+          parser->flags |= F_TRAILING;
+          UPDATE_STATE(s_header_field_start);
+        } else {
+          UPDATE_STATE(s_chunk_data);
+        }
+        CALLBACK_NOTIFY(chunk_header);
+        break;
+      }
+
+      case s_chunk_data:
+      {
+        uint64_t to_read = MIN(parser->content_length,
+                               (uint64_t) ((data + len) - p));
+
+        assert(parser->flags & F_CHUNKED);
+        assert(parser->content_length != 0
+            && parser->content_length != ULLONG_MAX);
+
+        /* See the explanation in s_body_identity for why the content
+         * length and data pointers are managed this way.
+         */
+        MARK(body);
+        parser->content_length -= to_read;
+        p += to_read - 1;
+
+        if (parser->content_length == 0) {
+          UPDATE_STATE(s_chunk_data_almost_done);
+        }
+
+        break;
+      }
+
+      case s_chunk_data_almost_done:
+        assert(parser->flags & F_CHUNKED);
+        assert(parser->content_length == 0);
+        STRICT_CHECK(ch != CR);
+        UPDATE_STATE(s_chunk_data_done);
+        CALLBACK_DATA(body);
+        break;
+
+      case s_chunk_data_done:
+        assert(parser->flags & F_CHUNKED);
+        STRICT_CHECK(ch != LF);
+        parser->nread = 0;
+        nread = 0;
+        UPDATE_STATE(s_chunk_size_start);
+        CALLBACK_NOTIFY(chunk_complete);
+        break;
+
+      default:
+        assert(0 && "unhandled state");
+        SET_ERRNO(HPE_INVALID_INTERNAL_STATE);
+        goto error;
+    }
+  }
+
+  /* Run callbacks for any marks that we have leftover after we ran our of
+   * bytes. There should be at most one of these set, so it's OK to invoke
+   * them in series (unset marks will not result in callbacks).
+   *
+   * We use the NOADVANCE() variety of callbacks here because 'p' has already
+   * overflowed 'data' and this allows us to correct for the off-by-one that
+   * we'd otherwise have (since CALLBACK_DATA() is meant to be run with a 'p'
+   * value that's in-bounds).
+   */
+
+  assert(((header_field_mark ? 1 : 0) +
+          (header_value_mark ? 1 : 0) +
+          (url_mark ? 1 : 0)  +
+          (body_mark ? 1 : 0) +
+          (status_mark ? 1 : 0)) <= 1);
+
+  CALLBACK_DATA_NOADVANCE(header_field);
+  CALLBACK_DATA_NOADVANCE(header_value);
+  CALLBACK_DATA_NOADVANCE(url);
+  CALLBACK_DATA_NOADVANCE(body);
+  CALLBACK_DATA_NOADVANCE(status);
+
+  RETURN(len);
+
+error:
+  if (HTTP_PARSER_ERRNO(parser) == HPE_OK) {
+    SET_ERRNO(HPE_UNKNOWN);
+  }
+
+  RETURN(p - data);
+}
+
+
+/* Does the parser need to see an EOF to find the end of the message? */
+int
+http_message_needs_eof (const http_parser *parser)
+{
+  if (parser->type == HTTP_REQUEST) {
+    return 0;
+  }
+
+  /* See RFC 2616 section 4.4 */
+  if (parser->status_code / 100 == 1 || /* 1xx e.g. Continue */
+      parser->status_code == 204 ||     /* No Content */
+      parser->status_code == 304 ||     /* Not Modified */
+      parser->flags & F_SKIPBODY) {     /* response to a HEAD request */
+    return 0;
+  }
+
+  if ((parser->flags & F_CHUNKED) || parser->content_length != ULLONG_MAX) {
+    return 0;
+  }
+
+  return 1;
+}
+
+
+int
+http_should_keep_alive (const http_parser *parser)
+{
+  if (parser->http_major > 0 && parser->http_minor > 0) {
+    /* HTTP/1.1 */
+    if (parser->flags & F_CONNECTION_CLOSE) {
+      return 0;
+    }
+  } else {
+    /* HTTP/1.0 or earlier */
+    if (!(parser->flags & F_CONNECTION_KEEP_ALIVE)) {
+      return 0;
+    }
+  }
+
+  return !http_message_needs_eof(parser);
+}
+
+
+const char *
+http_method_str (enum http_method m)
+{
+  return ELEM_AT(method_strings, m, "<unknown>");
+}
+
+const char *
+http_status_str (enum http_status s)
+{
+  switch (s) {
+#define XX(num, name, string) case HTTP_STATUS_##name: return #string;
+    HTTP_STATUS_MAP(XX)
+#undef XX
+    default: return "<unknown>";
+  }
+}
+
+void
+http_parser_init (http_parser *parser, enum http_parser_type t)
+{
+  void *data = parser->data; /* preserve application data */
+  memset(parser, 0, sizeof(*parser));
+  parser->data = data;
+  parser->type = t;
+  parser->state = (t == HTTP_REQUEST ? s_start_req : (t == HTTP_RESPONSE ? s_start_res : s_start_req_or_res));
+  parser->http_errno = HPE_OK;
+}
+
+void
+http_parser_settings_init(http_parser_settings *settings)
+{
+  memset(settings, 0, sizeof(*settings));
+}
+
+const char *
+http_errno_name(enum http_errno err) {
+  assert(((size_t) err) < ARRAY_SIZE(http_strerror_tab));
+  return http_strerror_tab[err].name;
+}
+
+const char *
+http_errno_description(enum http_errno err) {
+  assert(((size_t) err) < ARRAY_SIZE(http_strerror_tab));
+  return http_strerror_tab[err].description;
+}
+
+static enum http_host_state
+http_parse_host_char(enum http_host_state s, const char ch) {
+  switch(s) {
+    case s_http_userinfo:
+    case s_http_userinfo_start:
+      if (ch == '@') {
+        return s_http_host_start;
+      }
+
+      if (IS_USERINFO_CHAR(ch)) {
+        return s_http_userinfo;
+      }
+      break;
+
+    case s_http_host_start:
+      if (ch == '[') {
+        return s_http_host_v6_start;
+      }
+
+      if (IS_HOST_CHAR(ch)) {
+        return s_http_host;
+      }
+
+      break;
+
+    case s_http_host:
+      if (IS_HOST_CHAR(ch)) {
+        return s_http_host;
+      }
+
+    /* fall through */
+    case s_http_host_v6_end:
+      if (ch == ':') {
+        return s_http_host_port_start;
+      }
+
+      break;
+
+    case s_http_host_v6:
+      if (ch == ']') {
+        return s_http_host_v6_end;
+      }
+
+    /* fall through */
+    case s_http_host_v6_start:
+      if (IS_HEX(ch) || ch == ':' || ch == '.') {
+        return s_http_host_v6;
+      }
+
+      if (s == s_http_host_v6 && ch == '%') {
+        return s_http_host_v6_zone_start;
+      }
+      break;
+
+    case s_http_host_v6_zone:
+      if (ch == ']') {
+        return s_http_host_v6_end;
+      }
+
+    /* fall through */
+    case s_http_host_v6_zone_start:
+      /* RFC 6874 Zone ID consists of 1*( unreserved / pct-encoded) */
+      if (IS_ALPHANUM(ch) || ch == '%' || ch == '.' || ch == '-' || ch == '_' ||
+          ch == '~') {
+        return s_http_host_v6_zone;
+      }
+      break;
+
+    case s_http_host_port:
+    case s_http_host_port_start:
+      if (IS_NUM(ch)) {
+        return s_http_host_port;
+      }
+
+      break;
+
+    default:
+      break;
+  }
+  return s_http_host_dead;
+}
+
+static int
+http_parse_host(const char * buf, struct http_parser_url *u, int found_at) {
+  enum http_host_state s;
+
+  const char *p;
+  size_t buflen = u->field_data[UF_HOST].off + u->field_data[UF_HOST].len;
+
+  assert(u->field_set & (1 << UF_HOST));
+
+  u->field_data[UF_HOST].len = 0;
+
+  s = found_at ? s_http_userinfo_start : s_http_host_start;
+
+  for (p = buf + u->field_data[UF_HOST].off; p < buf + buflen; p++) {
+    enum http_host_state new_s = http_parse_host_char(s, *p);
+
+    if (new_s == s_http_host_dead) {
+      return 1;
+    }
+
+    switch(new_s) {
+      case s_http_host:
+        if (s != s_http_host) {
+          u->field_data[UF_HOST].off = p - buf;
+        }
+        u->field_data[UF_HOST].len++;
+        break;
+
+      case s_http_host_v6:
+        if (s != s_http_host_v6) {
+          u->field_data[UF_HOST].off = p - buf;
+        }
+        u->field_data[UF_HOST].len++;
+        break;
+
+      case s_http_host_v6_zone_start:
+      case s_http_host_v6_zone:
+        u->field_data[UF_HOST].len++;
+        break;
+
+      case s_http_host_port:
+        if (s != s_http_host_port) {
+          u->field_data[UF_PORT].off = p - buf;
+          u->field_data[UF_PORT].len = 0;
+          u->field_set |= (1 << UF_PORT);
+        }
+        u->field_data[UF_PORT].len++;
+        break;
+
+      case s_http_userinfo:
+        if (s != s_http_userinfo) {
+          u->field_data[UF_USERINFO].off = p - buf ;
+          u->field_data[UF_USERINFO].len = 0;
+          u->field_set |= (1 << UF_USERINFO);
+        }
+        u->field_data[UF_USERINFO].len++;
+        break;
+
+      default:
+        break;
+    }
+    s = new_s;
+  }
+
+  /* Make sure we don't end somewhere unexpected */
+  switch (s) {
+    case s_http_host_start:
+    case s_http_host_v6_start:
+    case s_http_host_v6:
+    case s_http_host_v6_zone_start:
+    case s_http_host_v6_zone:
+    case s_http_host_port_start:
+    case s_http_userinfo:
+    case s_http_userinfo_start:
+      return 1;
+    default:
+      break;
+  }
+
+  return 0;
+}
+
+void
+http_parser_url_init(struct http_parser_url *u) {
+  memset(u, 0, sizeof(*u));
+}
+
+int
+http_parser_parse_url(const char *buf, size_t buflen, int is_connect,
+                      struct http_parser_url *u)
+{
+  enum state s;
+  const char *p;
+  enum http_parser_url_fields uf, old_uf;
+  int found_at = 0;
+
+  if (buflen == 0) {
+    return 1;
+  }
+
+  u->port = u->field_set = 0;
+  s = is_connect ? s_req_server_start : s_req_spaces_before_url;
+  old_uf = UF_MAX;
+
+  for (p = buf; p < buf + buflen; p++) {
+    s = parse_url_char(s, *p);
+
+    /* Figure out the next field that we're operating on */
+    switch (s) {
+      case s_dead:
+        return 1;
+
+      /* Skip delimeters */
+      case s_req_schema_slash:
+      case s_req_schema_slash_slash:
+      case s_req_server_start:
+      case s_req_query_string_start:
+      case s_req_fragment_start:
+        continue;
+
+      case s_req_schema:
+        uf = UF_SCHEMA;
+        break;
+
+      case s_req_server_with_at:
+        found_at = 1;
+
+      /* fall through */
+      case s_req_server:
+        uf = UF_HOST;
+        break;
+
+      case s_req_path:
+        uf = UF_PATH;
+        break;
+
+      case s_req_query_string:
+        uf = UF_QUERY;
+        break;
+
+      case s_req_fragment:
+        uf = UF_FRAGMENT;
+        break;
+
+      default:
+        assert(!"Unexpected state");
+        return 1;
+    }
+
+    /* Nothing's changed; soldier on */
+    if (uf == old_uf) {
+      u->field_data[uf].len++;
+      continue;
+    }
+
+    u->field_data[uf].off = p - buf;
+    u->field_data[uf].len = 1;
+
+    u->field_set |= (1 << uf);
+    old_uf = uf;
+  }
+
+  /* host must be present if there is a schema */
+  /* parsing http:///toto will fail */
+  if ((u->field_set & (1 << UF_SCHEMA)) &&
+      (u->field_set & (1 << UF_HOST)) == 0) {
+    return 1;
+  }
+
+  if (u->field_set & (1 << UF_HOST)) {
+    if (http_parse_host(buf, u, found_at) != 0) {
+      return 1;
+    }
+  }
+
+  /* CONNECT requests can only contain "hostname:port" */
+  if (is_connect && u->field_set != ((1 << UF_HOST)|(1 << UF_PORT))) {
+    return 1;
+  }
+
+  if (u->field_set & (1 << UF_PORT)) {
+    uint16_t off;
+    uint16_t len;
+    const char* p;
+    const char* end;
+    unsigned long v;
+
+    off = u->field_data[UF_PORT].off;
+    len = u->field_data[UF_PORT].len;
+    end = buf + off + len;
+
+    /* NOTE: The characters are already validated and are in the [0-9] range */
+    assert(off + len <= buflen && "Port number overflow");
+    v = 0;
+    for (p = buf + off; p < end; p++) {
+      v *= 10;
+      v += *p - '0';
+
+      /* Ports have a max value of 2^16 */
+      if (v > 0xffff) {
+        return 1;
+      }
+    }
+
+    u->port = (uint16_t) v;
+  }
+
+  return 0;
+}
+
+void
+http_parser_pause(http_parser *parser, int paused) {
+  /* Users should only be pausing/unpausing a parser that is not in an error
+   * state. In non-debug builds, there's not much that we can do about this
+   * other than ignore it.
+   */
+  if (HTTP_PARSER_ERRNO(parser) == HPE_OK ||
+      HTTP_PARSER_ERRNO(parser) == HPE_PAUSED) {
+    uint32_t nread = parser->nread; /* used by the SET_ERRNO macro */
+    SET_ERRNO((paused) ? HPE_PAUSED : HPE_OK);
+  } else {
+    assert(0 && "Attempting to pause parser in error state");
+  }
+}
+
+int
+http_body_is_final(const struct http_parser *parser) {
+    return parser->state == s_message_done;
+}
+
+unsigned long
+http_parser_version(void) {
+  return HTTP_PARSER_VERSION_MAJOR * 0x10000 |
+         HTTP_PARSER_VERSION_MINOR * 0x00100 |
+         HTTP_PARSER_VERSION_PATCH * 0x00001;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json.cpp
new file mode 100644
index 0000000..9becfdd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json.cpp
@@ -0,0 +1,1493 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+namespace detail {
+
+exception::exception(int id_, const Twine& what_arg)
+    : id(id_), m(what_arg.str()) {}
+
+parse_error parse_error::create(int id_, std::size_t byte_, const Twine& what_arg)
+{
+    return parse_error(id_, byte_, "[json.exception.parse_error." + Twine(id_) + "] parse error" +
+                    (byte_ != 0 ? (" at " + Twine(byte_)) : Twine("")) +
+                    ": " + what_arg);
+}
+
+invalid_iterator invalid_iterator::create(int id_, const Twine& what_arg)
+{
+    return invalid_iterator(id_, "[json.exception.invalid_iterator." + Twine(id_) + "] " + what_arg);
+}
+
+type_error type_error::create(int id_, const Twine& what_arg)
+{
+    return type_error(id_, "[json.exception.type_error." + Twine(id_) + "] " + what_arg);
+}
+
+out_of_range out_of_range::create(int id_, const Twine& what_arg)
+{
+    return out_of_range(id_, "[json.exception.out_of_range." + Twine(id_) + "] " + what_arg);
+}
+
+other_error other_error::create(int id_, const Twine& what_arg)
+{
+    return other_error(id_, "[json.exception.other_error." + Twine(id_) + "] " + what_arg);
+}
+
+}  // namespace detail
+
+json::json_value::json_value(value_t t)
+{
+    switch (t)
+    {
+        case value_t::object:
+        {
+            object = create<object_t>();
+            break;
+        }
+
+        case value_t::array:
+        {
+            array = create<array_t>();
+            break;
+        }
+
+        case value_t::string:
+        {
+            string = create<std::string>("");
+            break;
+        }
+
+        case value_t::boolean:
+        {
+            boolean = false;
+            break;
+        }
+
+        case value_t::number_integer:
+        {
+            number_integer = 0;
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            number_unsigned = 0u;
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            number_float = 0.0;
+            break;
+        }
+
+        case value_t::null:
+        {
+            object = nullptr;  // silence warning, see #821
+            break;
+        }
+
+        default:
+        {
+            object = nullptr;  // silence warning, see #821
+            if (JSON_UNLIKELY(t == value_t::null))
+            {
+                JSON_THROW(other_error::create(500, "961c151d2e87f2686a955a9be24d316f1362bf21 3.1.2")); // LCOV_EXCL_LINE
+            }
+            break;
+        }
+    }
+}
+
+void json::json_value::destroy(value_t t) noexcept
+{
+    switch (t)
+    {
+        case value_t::object:
+        {
+            std::allocator<object_t> alloc;
+            alloc.destroy(object);
+            alloc.deallocate(object, 1);
+            break;
+        }
+
+        case value_t::array:
+        {
+            std::allocator<array_t> alloc;
+            alloc.destroy(array);
+            alloc.deallocate(array, 1);
+            break;
+        }
+
+        case value_t::string:
+        {
+            std::allocator<std::string> alloc;
+            alloc.destroy(string);
+            alloc.deallocate(string, 1);
+            break;
+        }
+
+        default:
+        {
+            break;
+        }
+    }
+}
+
+json::json(initializer_list_t init,
+           bool type_deduction,
+           value_t manual_type)
+{
+    // check if each element is an array with two elements whose first
+    // element is a string
+    bool is_an_object = std::all_of(init.begin(), init.end(),
+                                    [](const detail::json_ref<json>& element_ref)
+    {
+        return (element_ref->is_array() and element_ref->size() == 2 and (*element_ref)[0].is_string());
+    });
+
+    // adjust type if type deduction is not wanted
+    if (not type_deduction)
+    {
+        // if array is wanted, do not create an object though possible
+        if (manual_type == value_t::array)
+        {
+            is_an_object = false;
+        }
+
+        // if object is wanted but impossible, throw an exception
+        if (JSON_UNLIKELY(manual_type == value_t::object and not is_an_object))
+        {
+            JSON_THROW(type_error::create(301, "cannot create object from initializer list"));
+        }
+    }
+
+    if (is_an_object)
+    {
+        // the initializer list is a list of pairs -> create object
+        m_type = value_t::object;
+        m_value = value_t::object;
+
+        std::for_each(init.begin(), init.end(), [this](const detail::json_ref<json>& element_ref)
+        {
+            auto element = element_ref.moved_or_copied();
+            m_value.object->try_emplace(
+                *((*element.m_value.array)[0].m_value.string),
+                std::move((*element.m_value.array)[1]));
+        });
+    }
+    else
+    {
+        // the initializer list describes an array -> create array
+        m_type = value_t::array;
+        m_value.array = create<array_t>(init.begin(), init.end());
+    }
+
+    assert_invariant();
+}
+
+json::json(size_type cnt, const json& val)
+    : m_type(value_t::array)
+{
+    m_value.array = create<array_t>(cnt, val);
+    assert_invariant();
+}
+
+json::json(const json& other)
+    : m_type(other.m_type)
+{
+    // check of passed value is valid
+    other.assert_invariant();
+
+    switch (m_type)
+    {
+        case value_t::object:
+        {
+            m_value = *other.m_value.object;
+            break;
+        }
+
+        case value_t::array:
+        {
+            m_value = *other.m_value.array;
+            break;
+        }
+
+        case value_t::string:
+        {
+            m_value = *other.m_value.string;
+            break;
+        }
+
+        case value_t::boolean:
+        {
+            m_value = other.m_value.boolean;
+            break;
+        }
+
+        case value_t::number_integer:
+        {
+            m_value = other.m_value.number_integer;
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            m_value = other.m_value.number_unsigned;
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            m_value = other.m_value.number_float;
+            break;
+        }
+
+        default:
+            break;
+    }
+
+    assert_invariant();
+}
+
+json json::meta()
+{
+    json result;
+
+    result["copyright"] = "(C) 2013-2017 Niels Lohmann, (C) 2017-2018 FIRST";
+    result["name"] = "WPI version of JSON for Modern C++";
+    result["url"] = "https://github.com/wpilibsuite/allwpilib";
+    result["version"]["string"] =
+        std::to_string(NLOHMANN_JSON_VERSION_MAJOR) + "." +
+        std::to_string(NLOHMANN_JSON_VERSION_MINOR) + "." +
+        std::to_string(NLOHMANN_JSON_VERSION_PATCH);
+    result["version"]["major"] = NLOHMANN_JSON_VERSION_MAJOR;
+    result["version"]["minor"] = NLOHMANN_JSON_VERSION_MINOR;
+    result["version"]["patch"] = NLOHMANN_JSON_VERSION_PATCH;
+
+#ifdef _WIN32
+    result["platform"] = "win32";
+#elif defined __linux__
+    result["platform"] = "linux";
+#elif defined __APPLE__
+    result["platform"] = "apple";
+#elif defined __unix__
+    result["platform"] = "unix";
+#else
+    result["platform"] = "unknown";
+#endif
+
+#if defined(__ICC) || defined(__INTEL_COMPILER)
+    result["compiler"] = {{"family", "icc"}, {"version", __INTEL_COMPILER}};
+#elif defined(__clang__)
+    result["compiler"] = {{"family", "clang"}, {"version", __clang_version__}};
+#elif defined(__GNUC__) || defined(__GNUG__)
+    result["compiler"] = {{"family", "gcc"}, {"version", std::to_string(__GNUC__) + "." + std::to_string(__GNUC_MINOR__) + "." + std::to_string(__GNUC_PATCHLEVEL__)}};
+#elif defined(__HP_cc) || defined(__HP_aCC)
+    result["compiler"] = "hp"
+#elif defined(__IBMCPP__)
+    result["compiler"] = {{"family", "ilecpp"}, {"version", __IBMCPP__}};
+#elif defined(_MSC_VER)
+    result["compiler"] = {{"family", "msvc"}, {"version", _MSC_VER}};
+#elif defined(__PGI)
+    result["compiler"] = {{"family", "pgcpp"}, {"version", __PGI}};
+#elif defined(__SUNPRO_CC)
+    result["compiler"] = {{"family", "sunpro"}, {"version", __SUNPRO_CC}};
+#else
+    result["compiler"] = {{"family", "unknown"}, {"version", "unknown"}};
+#endif
+
+#ifdef __cplusplus
+    result["compiler"]["c++"] = std::to_string(__cplusplus);
+#else
+    result["compiler"]["c++"] = "unknown";
+#endif
+    return result;
+}
+
+json::reference json::at(size_type idx)
+{
+    // at only works for arrays
+    if (JSON_LIKELY(is_array()))
+    {
+        JSON_TRY
+        {
+            return m_value.array->at(idx);
+        }
+        JSON_CATCH (std::out_of_range&)
+        {
+            // create better exception explanation
+            JSON_THROW(out_of_range::create(401, "array index " + Twine(idx) + " is out of range"));
+        }
+    }
+    else
+    {
+        JSON_THROW(type_error::create(304, "cannot use at() with " + Twine(type_name())));
+    }
+}
+
+json::const_reference json::at(size_type idx) const
+{
+    // at only works for arrays
+    if (JSON_LIKELY(is_array()))
+    {
+        JSON_TRY
+        {
+            return m_value.array->at(idx);
+        }
+        JSON_CATCH (std::out_of_range&)
+        {
+            // create better exception explanation
+            JSON_THROW(out_of_range::create(401, "array index " + Twine(idx) + " is out of range"));
+        }
+    }
+    else
+    {
+        JSON_THROW(type_error::create(304, "cannot use at() with " + Twine(type_name())));
+    }
+}
+
+json::reference json::at(StringRef key)
+{
+    // at only works for objects
+    if (JSON_LIKELY(is_object()))
+    {
+        auto it = m_value.object->find(key);
+        if (it == m_value.object->end())
+        {
+            // create better exception explanation
+            JSON_THROW(out_of_range::create(403, "key '" + Twine(key) + "' not found"));
+        }
+        return it->second;
+    }
+    else
+    {
+        JSON_THROW(type_error::create(304, "cannot use at() with " + Twine(type_name())));
+    }
+}
+
+json::const_reference json::at(StringRef key) const
+{
+    // at only works for objects
+    if (JSON_LIKELY(is_object()))
+    {
+        auto it = m_value.object->find(key);
+        if (it == m_value.object->end())
+        {
+            // create better exception explanation
+            JSON_THROW(out_of_range::create(403, "key '" + Twine(key) + "' not found"));
+        }
+        return it->second;
+    }
+    else
+    {
+        JSON_THROW(type_error::create(304, "cannot use at() with " + Twine(type_name())));
+    }
+}
+
+json::reference json::operator[](size_type idx)
+{
+    // implicitly convert null value to an empty array
+    if (is_null())
+    {
+        m_type = value_t::array;
+        m_value.array = create<array_t>();
+        assert_invariant();
+    }
+
+    // operator[] only works for arrays
+    if (JSON_LIKELY(is_array()))
+    {
+        // fill up array with null values if given idx is outside range
+        if (idx >= m_value.array->size())
+        {
+            m_value.array->insert(m_value.array->end(),
+                                  idx - m_value.array->size() + 1,
+                                  json());
+        }
+
+        return m_value.array->operator[](idx);
+    }
+
+    JSON_THROW(type_error::create(305, "cannot use operator[] with " + Twine(type_name())));
+}
+
+json::const_reference json::operator[](size_type idx) const
+{
+    // const operator[] only works for arrays
+    if (JSON_LIKELY(is_array()))
+    {
+        return m_value.array->operator[](idx);
+    }
+
+    JSON_THROW(type_error::create(305, "cannot use operator[] with " + Twine(type_name())));
+}
+
+json::reference json::operator[](StringRef key)
+{
+    // implicitly convert null value to an empty object
+    if (is_null())
+    {
+        m_type = value_t::object;
+        m_value.object = create<object_t>();
+        assert_invariant();
+    }
+
+    // operator[] only works for objects
+    if (JSON_LIKELY(is_object()))
+    {
+        return m_value.object->operator[](key);
+    }
+
+    JSON_THROW(type_error::create(305, "cannot use operator[] with " + Twine(type_name())));
+}
+
+json::const_reference json::operator[](StringRef key) const
+{
+    // const operator[] only works for objects
+    if (JSON_LIKELY(is_object()))
+    {
+        assert(m_value.object->find(key) != m_value.object->end());
+        return m_value.object->find(key)->second;
+    }
+
+    JSON_THROW(type_error::create(305, "cannot use operator[] with " + Twine(type_name())));
+}
+
+json::size_type json::erase(StringRef key)
+{
+    // this erase only works for objects
+    if (JSON_LIKELY(is_object()))
+    {
+        return m_value.object->erase(key);
+    }
+
+    JSON_THROW(type_error::create(307, "cannot use erase() with " + Twine(type_name())));
+}
+
+void json::erase(const size_type idx)
+{
+    // this erase only works for arrays
+    if (JSON_LIKELY(is_array()))
+    {
+        if (JSON_UNLIKELY(idx >= size()))
+        {
+            JSON_THROW(out_of_range::create(401, "array index " + Twine(idx) + " is out of range"));
+        }
+
+        m_value.array->erase(m_value.array->begin() + static_cast<difference_type>(idx));
+    }
+    else
+    {
+        JSON_THROW(type_error::create(307, "cannot use erase() with " + Twine(type_name())));
+    }
+}
+
+json::iterator json::find(StringRef key)
+{
+    auto result = end();
+
+    if (is_object())
+    {
+        result.m_it.object_iterator = m_value.object->find(key);
+    }
+
+    return result;
+}
+
+json::const_iterator json::find(StringRef key) const
+{
+    auto result = cend();
+
+    if (is_object())
+    {
+        result.m_it.object_iterator = m_value.object->find(key);
+    }
+
+    return result;
+}
+
+json::size_type json::count(StringRef key) const
+{
+    // return 0 for all nonobject types
+    return is_object() ? m_value.object->count(key) : 0;
+}
+
+bool json::empty() const noexcept
+{
+    switch (m_type)
+    {
+        case value_t::null:
+        {
+            // null values are empty
+            return true;
+        }
+
+        case value_t::array:
+        {
+            // delegate call to array_t::empty()
+            return m_value.array->empty();
+        }
+
+        case value_t::object:
+        {
+            // delegate call to object_t::empty()
+            return m_value.object->empty();
+        }
+
+        default:
+        {
+            // all other types are nonempty
+            return false;
+        }
+    }
+}
+
+json::size_type json::size() const noexcept
+{
+    switch (m_type)
+    {
+        case value_t::null:
+        {
+            // null values are empty
+            return 0;
+        }
+
+        case value_t::array:
+        {
+            // delegate call to array_t::size()
+            return m_value.array->size();
+        }
+
+        case value_t::object:
+        {
+            // delegate call to object_t::size()
+            return m_value.object->size();
+        }
+
+        default:
+        {
+            // all other types have size 1
+            return 1;
+        }
+    }
+}
+
+json::size_type json::max_size() const noexcept
+{
+    switch (m_type)
+    {
+        case value_t::array:
+        {
+            // delegate call to array_t::max_size()
+            return m_value.array->max_size();
+        }
+
+        case value_t::object:
+        {
+            // delegate call to std::allocator<json>::max_size()
+            return std::allocator<json>().max_size();
+        }
+
+        default:
+        {
+            // all other types have max_size() == size()
+            return size();
+        }
+    }
+}
+
+void json::clear() noexcept
+{
+    switch (m_type)
+    {
+        case value_t::number_integer:
+        {
+            m_value.number_integer = 0;
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            m_value.number_unsigned = 0;
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            m_value.number_float = 0.0;
+            break;
+        }
+
+        case value_t::boolean:
+        {
+            m_value.boolean = false;
+            break;
+        }
+
+        case value_t::string:
+        {
+            m_value.string->clear();
+            break;
+        }
+
+        case value_t::array:
+        {
+            m_value.array->clear();
+            break;
+        }
+
+        case value_t::object:
+        {
+            m_value.object->clear();
+            break;
+        }
+
+        default:
+            break;
+    }
+}
+
+void json::push_back(json&& val)
+{
+    // push_back only works for null objects or arrays
+    if (JSON_UNLIKELY(not(is_null() or is_array())))
+    {
+        JSON_THROW(type_error::create(308, "cannot use push_back() with " + Twine(type_name())));
+    }
+
+    // transform null object into an array
+    if (is_null())
+    {
+        m_type = value_t::array;
+        m_value = value_t::array;
+        assert_invariant();
+    }
+
+    // add element to array (move semantics)
+    m_value.array->push_back(std::move(val));
+    // invalidate object
+    val.m_type = value_t::null;
+}
+
+void json::push_back(const json& val)
+{
+    // push_back only works for null objects or arrays
+    if (JSON_UNLIKELY(not(is_null() or is_array())))
+    {
+        JSON_THROW(type_error::create(308, "cannot use push_back() with " + Twine(type_name())));
+    }
+
+    // transform null object into an array
+    if (is_null())
+    {
+        m_type = value_t::array;
+        m_value = value_t::array;
+        assert_invariant();
+    }
+
+    // add element to array
+    m_value.array->push_back(val);
+}
+
+void json::push_back(initializer_list_t init)
+{
+    if (is_object() and init.size() == 2 and (*init.begin())->is_string())
+    {
+        std::string key = init.begin()->moved_or_copied();
+        push_back(std::pair<StringRef, json>(key, (init.begin() + 1)->moved_or_copied()));
+    }
+    else
+    {
+        push_back(json(init));
+    }
+}
+
+json::iterator json::insert(const_iterator pos, const json& val)
+{
+    // insert only works for arrays
+    if (JSON_LIKELY(is_array()))
+    {
+        // check if iterator pos fits to this JSON value
+        if (JSON_UNLIKELY(pos.m_object != this))
+        {
+            JSON_THROW(invalid_iterator::create(202, "iterator does not fit current value"));
+        }
+
+        // insert to array and return iterator
+        iterator result(this);
+        result.m_it.array_iterator = m_value.array->insert(pos.m_it.array_iterator, val);
+        return result;
+    }
+
+    JSON_THROW(type_error::create(309, "cannot use insert() with " + Twine(type_name())));
+}
+
+json::iterator json::insert(const_iterator pos, size_type cnt, const json& val)
+{
+    // insert only works for arrays
+    if (JSON_LIKELY(is_array()))
+    {
+        // check if iterator pos fits to this JSON value
+        if (JSON_UNLIKELY(pos.m_object != this))
+        {
+            JSON_THROW(invalid_iterator::create(202, "iterator does not fit current value"));
+        }
+
+        // insert to array and return iterator
+        iterator result(this);
+        result.m_it.array_iterator = m_value.array->insert(pos.m_it.array_iterator, cnt, val);
+        return result;
+    }
+
+    JSON_THROW(type_error::create(309, "cannot use insert() with " + Twine(type_name())));
+}
+
+json::iterator json::insert(const_iterator pos, const_iterator first, const_iterator last)
+{
+    // insert only works for arrays
+    if (JSON_UNLIKELY(not is_array()))
+    {
+        JSON_THROW(type_error::create(309, "cannot use insert() with " + Twine(type_name())));
+    }
+
+    // check if iterator pos fits to this JSON value
+    if (JSON_UNLIKELY(pos.m_object != this))
+    {
+        JSON_THROW(invalid_iterator::create(202, "iterator does not fit current value"));
+    }
+
+    // check if range iterators belong to the same JSON object
+    if (JSON_UNLIKELY(first.m_object != last.m_object))
+    {
+        JSON_THROW(invalid_iterator::create(210, "iterators do not fit"));
+    }
+
+    if (JSON_UNLIKELY(first.m_object == this))
+    {
+        JSON_THROW(invalid_iterator::create(211, "passed iterators may not belong to container"));
+    }
+
+    // insert to array and return iterator
+    iterator result(this);
+    result.m_it.array_iterator = m_value.array->insert(
+                                     pos.m_it.array_iterator,
+                                     first.m_it.array_iterator,
+                                     last.m_it.array_iterator);
+    return result;
+}
+
+json::iterator json::insert(const_iterator pos, initializer_list_t ilist)
+{
+    // insert only works for arrays
+    if (JSON_UNLIKELY(not is_array()))
+    {
+        JSON_THROW(type_error::create(309, "cannot use insert() with " + Twine(type_name())));
+    }
+
+    // check if iterator pos fits to this JSON value
+    if (JSON_UNLIKELY(pos.m_object != this))
+    {
+        JSON_THROW(invalid_iterator::create(202, "iterator does not fit current value"));
+    }
+
+    // insert to array and return iterator
+    iterator result(this);
+    result.m_it.array_iterator = m_value.array->insert(pos.m_it.array_iterator, ilist.begin(), ilist.end());
+    return result;
+}
+
+void json::insert(const_iterator first, const_iterator last)
+{
+    // insert only works for objects
+    if (JSON_UNLIKELY(not is_object()))
+    {
+        JSON_THROW(type_error::create(309, "cannot use insert() with " + Twine(type_name())));
+    }
+
+    // check if range iterators belong to the same JSON object
+    if (JSON_UNLIKELY(first.m_object != last.m_object))
+    {
+        JSON_THROW(invalid_iterator::create(210, "iterators do not fit"));
+    }
+
+    // passed iterators must belong to objects
+    if (JSON_UNLIKELY(not first.m_object->is_object()))
+    {
+        JSON_THROW(invalid_iterator::create(202, "iterators first and last must point to objects"));
+    }
+
+    for (auto it = first.m_it.object_iterator, end = last.m_it.object_iterator; it != end; ++it)
+    {
+        m_value.object->insert(std::make_pair(it->first(), it->second));
+    }
+}
+
+void json::update(const_reference j)
+{
+    // implicitly convert null value to an empty object
+    if (is_null())
+    {
+        m_type = value_t::object;
+        m_value.object = create<object_t>();
+        assert_invariant();
+    }
+
+    if (JSON_UNLIKELY(not is_object()))
+    {
+        JSON_THROW(type_error::create(312, "cannot use update() with " + Twine(type_name())));
+    }
+    if (JSON_UNLIKELY(not j.is_object()))
+    {
+        JSON_THROW(type_error::create(312, "cannot use update() with " + Twine(j.type_name())));
+    }
+
+    for (auto it = j.cbegin(); it != j.cend(); ++it)
+    {
+        m_value.object->operator[](it.key()) = it.value();
+    }
+}
+
+void json::update(const_iterator first, const_iterator last)
+{
+    // implicitly convert null value to an empty object
+    if (is_null())
+    {
+        m_type = value_t::object;
+        m_value.object = create<object_t>();
+        assert_invariant();
+    }
+
+    if (JSON_UNLIKELY(not is_object()))
+    {
+        JSON_THROW(type_error::create(312, "cannot use update() with " + Twine(type_name())));
+    }
+
+    // check if range iterators belong to the same JSON object
+    if (JSON_UNLIKELY(first.m_object != last.m_object))
+    {
+        JSON_THROW(invalid_iterator::create(210, "iterators do not fit"));
+    }
+
+    // passed iterators must belong to objects
+    if (JSON_UNLIKELY(not first.m_object->is_object()
+                      or not last.m_object->is_object()))
+    {
+        JSON_THROW(invalid_iterator::create(202, "iterators first and last must point to objects"));
+    }
+
+    for (auto it = first; it != last; ++it)
+    {
+        m_value.object->operator[](it.key()) = it.value();
+    }
+}
+
+bool operator==(json::const_reference lhs, json::const_reference rhs) noexcept
+{
+    const auto lhs_type = lhs.type();
+    const auto rhs_type = rhs.type();
+
+    if (lhs_type == rhs_type)
+    {
+        switch (lhs_type)
+        {
+            case json::value_t::array:
+                return (*lhs.m_value.array == *rhs.m_value.array);
+
+            case json::value_t::object:
+                return (*lhs.m_value.object == *rhs.m_value.object);
+
+            case json::value_t::null:
+                return true;
+
+            case json::value_t::string:
+                return (*lhs.m_value.string == *rhs.m_value.string);
+
+            case json::value_t::boolean:
+                return (lhs.m_value.boolean == rhs.m_value.boolean);
+
+            case json::value_t::number_integer:
+                return (lhs.m_value.number_integer == rhs.m_value.number_integer);
+
+            case json::value_t::number_unsigned:
+                return (lhs.m_value.number_unsigned == rhs.m_value.number_unsigned);
+
+            case json::value_t::number_float:
+                return (lhs.m_value.number_float == rhs.m_value.number_float);
+
+            default:
+                return false;
+        }
+    }
+    else if (lhs_type == json::value_t::number_integer and rhs_type == json::value_t::number_float)
+    {
+        return (static_cast<double>(lhs.m_value.number_integer) == rhs.m_value.number_float);
+    }
+    else if (lhs_type == json::value_t::number_float and rhs_type == json::value_t::number_integer)
+    {
+        return (lhs.m_value.number_float == static_cast<double>(rhs.m_value.number_integer));
+    }
+    else if (lhs_type == json::value_t::number_unsigned and rhs_type == json::value_t::number_float)
+    {
+        return (static_cast<double>(lhs.m_value.number_unsigned) == rhs.m_value.number_float);
+    }
+    else if (lhs_type == json::value_t::number_float and rhs_type == json::value_t::number_unsigned)
+    {
+        return (lhs.m_value.number_float == static_cast<double>(rhs.m_value.number_unsigned));
+    }
+    else if (lhs_type == json::value_t::number_unsigned and rhs_type == json::value_t::number_integer)
+    {
+        return (static_cast<int64_t>(lhs.m_value.number_unsigned) == rhs.m_value.number_integer);
+    }
+    else if (lhs_type == json::value_t::number_integer and rhs_type == json::value_t::number_unsigned)
+    {
+        return (lhs.m_value.number_integer == static_cast<int64_t>(rhs.m_value.number_unsigned));
+    }
+
+    return false;
+}
+
+bool operator<(json::const_reference lhs, json::const_reference rhs) noexcept
+{
+    const auto lhs_type = lhs.type();
+    const auto rhs_type = rhs.type();
+
+    if (lhs_type == rhs_type)
+    {
+        switch (lhs_type)
+        {
+            case json::value_t::array:
+                return (*lhs.m_value.array) < (*rhs.m_value.array);
+
+            case json::value_t::object:
+                return *lhs.m_value.object < *rhs.m_value.object;
+
+            case json::value_t::null:
+                return false;
+
+            case json::value_t::string:
+                return *lhs.m_value.string < *rhs.m_value.string;
+
+            case json::value_t::boolean:
+                return lhs.m_value.boolean < rhs.m_value.boolean;
+
+            case json::value_t::number_integer:
+                return lhs.m_value.number_integer < rhs.m_value.number_integer;
+
+            case json::value_t::number_unsigned:
+                return lhs.m_value.number_unsigned < rhs.m_value.number_unsigned;
+
+            case json::value_t::number_float:
+                return lhs.m_value.number_float < rhs.m_value.number_float;
+
+            default:
+                return false;
+        }
+    }
+    else if (lhs_type == json::value_t::number_integer and rhs_type == json::value_t::number_float)
+    {
+        return static_cast<double>(lhs.m_value.number_integer) < rhs.m_value.number_float;
+    }
+    else if (lhs_type == json::value_t::number_float and rhs_type == json::value_t::number_integer)
+    {
+        return lhs.m_value.number_float < static_cast<double>(rhs.m_value.number_integer);
+    }
+    else if (lhs_type == json::value_t::number_unsigned and rhs_type == json::value_t::number_float)
+    {
+        return static_cast<double>(lhs.m_value.number_unsigned) < rhs.m_value.number_float;
+    }
+    else if (lhs_type == json::value_t::number_float and rhs_type == json::value_t::number_unsigned)
+    {
+        return lhs.m_value.number_float < static_cast<double>(rhs.m_value.number_unsigned);
+    }
+    else if (lhs_type == json::value_t::number_integer and rhs_type == json::value_t::number_unsigned)
+    {
+        return lhs.m_value.number_integer < static_cast<int64_t>(rhs.m_value.number_unsigned);
+    }
+    else if (lhs_type == json::value_t::number_unsigned and rhs_type == json::value_t::number_integer)
+    {
+        return static_cast<int64_t>(lhs.m_value.number_unsigned) < rhs.m_value.number_integer;
+    }
+
+    // We only reach this line if we cannot compare values. In that case,
+    // we compare types. Note we have to call the operator explicitly,
+    // because MSVC has problems otherwise.
+    return operator<(lhs_type, rhs_type);
+}
+
+const char* json::type_name() const noexcept
+{
+    {
+        switch (m_type)
+        {
+            case value_t::null:
+                return "null";
+            case value_t::object:
+                return "object";
+            case value_t::array:
+                return "array";
+            case value_t::string:
+                return "string";
+            case value_t::boolean:
+                return "boolean";
+            case value_t::discarded:
+                return "discarded";
+            default:
+                return "number";
+        }
+    }
+}
+
+json json::patch(const json& json_patch) const
+{
+    // make a working copy to apply the patch to
+    json result = *this;
+
+    // the valid JSON Patch operations
+    enum class patch_operations {add, remove, replace, move, copy, test, invalid};
+
+    const auto get_op = [](const std::string & op)
+    {
+        if (op == "add")
+        {
+            return patch_operations::add;
+        }
+        if (op == "remove")
+        {
+            return patch_operations::remove;
+        }
+        if (op == "replace")
+        {
+            return patch_operations::replace;
+        }
+        if (op == "move")
+        {
+            return patch_operations::move;
+        }
+        if (op == "copy")
+        {
+            return patch_operations::copy;
+        }
+        if (op == "test")
+        {
+            return patch_operations::test;
+        }
+
+        return patch_operations::invalid;
+    };
+
+    // wrapper for "add" operation; add value at ptr
+    const auto operation_add = [&result](json_pointer & ptr, json val)
+    {
+        // adding to the root of the target document means replacing it
+        if (ptr.is_root())
+        {
+            result = val;
+        }
+        else
+        {
+            // make sure the top element of the pointer exists
+            json_pointer top_pointer = ptr.top();
+            if (top_pointer != ptr)
+            {
+                result.at(top_pointer);
+            }
+
+            // get reference to parent of JSON pointer ptr
+            const auto last_path = ptr.pop_back();
+            json& parent = result[ptr];
+
+            switch (parent.m_type)
+            {
+                case value_t::null:
+                case value_t::object:
+                {
+                    // use operator[] to add value
+                    parent[last_path] = val;
+                    break;
+                }
+
+                case value_t::array:
+                {
+                    if (last_path == "-")
+                    {
+                        // special case: append to back
+                        parent.push_back(val);
+                    }
+                    else
+                    {
+                        const auto idx = json_pointer::array_index(last_path);
+                        if (JSON_UNLIKELY(static_cast<size_type>(idx) > parent.size()))
+                        {
+                            // avoid undefined behavior
+                            JSON_THROW(out_of_range::create(401, "array index " + Twine(idx) + " is out of range"));
+                        }
+                        else
+                        {
+                            // default case: insert add offset
+                            parent.insert(parent.begin() + static_cast<difference_type>(idx), val);
+                        }
+                    }
+                    break;
+                }
+
+                default:
+                {
+                    // if there exists a parent it cannot be primitive
+                    assert(false);  // LCOV_EXCL_LINE
+                }
+            }
+        }
+    };
+
+    // wrapper for "remove" operation; remove value at ptr
+    const auto operation_remove = [&result](json_pointer & ptr)
+    {
+        // get reference to parent of JSON pointer ptr
+        const auto last_path = ptr.pop_back();
+        json& parent = result.at(ptr);
+
+        // remove child
+        if (parent.is_object())
+        {
+            // perform range check
+            auto it = parent.find(last_path);
+            if (JSON_LIKELY(it != parent.end()))
+            {
+                parent.erase(it);
+            }
+            else
+            {
+                JSON_THROW(out_of_range::create(403, "key '" + Twine(last_path) + "' not found"));
+            }
+        }
+        else if (parent.is_array())
+        {
+            // note erase performs range check
+            parent.erase(static_cast<size_type>(json_pointer::array_index(last_path)));
+        }
+    };
+
+    // type check: top level value must be an array
+    if (JSON_UNLIKELY(not json_patch.is_array()))
+    {
+        JSON_THROW(parse_error::create(104, 0, "JSON patch must be an array of objects"));
+    }
+
+    // iterate and apply the operations
+    for (const auto& val : json_patch)
+    {
+        // wrapper to get a value for an operation
+        const auto get_value = [&val](const std::string & op,
+                                      const std::string & member,
+                                      bool string_type) -> json &
+        {
+            // find value
+            auto it = val.m_value.object->find(member);
+
+            // context-sensitive error message
+            const auto error_msg = (op == "op") ? "operation" : "operation '" + op + "'";
+
+            // check if desired value is present
+            if (JSON_UNLIKELY(it == val.m_value.object->end()))
+            {
+                JSON_THROW(parse_error::create(105, 0, Twine(error_msg) + " must have member '" + Twine(member) + "'"));
+            }
+
+            // check if result is of type string
+            if (JSON_UNLIKELY(string_type and not it->second.is_string()))
+            {
+                JSON_THROW(parse_error::create(105, 0, Twine(error_msg) + " must have string member '" + Twine(member) + "'"));
+            }
+
+            // no error: return value
+            return it->second;
+        };
+
+        // type check: every element of the array must be an object
+        if (JSON_UNLIKELY(not val.is_object()))
+        {
+            JSON_THROW(parse_error::create(104, 0, "JSON patch must be an array of objects"));
+        }
+
+        // collect mandatory members
+        const std::string op = get_value("op", "op", true);
+        const std::string path = get_value(op, "path", true);
+        json_pointer ptr(path);
+
+        switch (get_op(op))
+        {
+            case patch_operations::add:
+            {
+                operation_add(ptr, get_value("add", "value", false));
+                break;
+            }
+
+            case patch_operations::remove:
+            {
+                operation_remove(ptr);
+                break;
+            }
+
+            case patch_operations::replace:
+            {
+                // the "path" location must exist - use at()
+                result.at(ptr) = get_value("replace", "value", false);
+                break;
+            }
+
+            case patch_operations::move:
+            {
+                const std::string from_path = get_value("move", "from", true);
+                json_pointer from_ptr(from_path);
+
+                // the "from" location must exist - use at()
+                json v = result.at(from_ptr);
+
+                // The move operation is functionally identical to a
+                // "remove" operation on the "from" location, followed
+                // immediately by an "add" operation at the target
+                // location with the value that was just removed.
+                operation_remove(from_ptr);
+                operation_add(ptr, v);
+                break;
+            }
+
+            case patch_operations::copy:
+            {
+                const std::string from_path = get_value("copy", "from", true);
+                const json_pointer from_ptr(from_path);
+
+                // the "from" location must exist - use at()
+                json v = result.at(from_ptr);
+
+                // The copy is functionally identical to an "add"
+                // operation at the target location using the value
+                // specified in the "from" member.
+                operation_add(ptr, v);
+                break;
+            }
+
+            case patch_operations::test:
+            {
+                bool success = false;
+                JSON_TRY
+                {
+                    // check if "value" matches the one at "path"
+                    // the "path" location must exist - use at()
+                    success = (result.at(ptr) == get_value("test", "value", false));
+                }
+                JSON_CATCH (out_of_range&)
+                {
+                    // ignore out of range errors: success remains false
+                }
+
+                // throw an exception if test fails
+                if (JSON_UNLIKELY(not success))
+                {
+                    JSON_THROW(other_error::create(501, "unsuccessful: " + Twine(val.dump())));
+                }
+
+                break;
+            }
+
+            case patch_operations::invalid:
+            {
+                // op must be "add", "remove", "replace", "move", "copy", or
+                // "test"
+                JSON_THROW(parse_error::create(105, 0, "operation value '" + Twine(op) + "' is invalid"));
+            }
+        }
+    }
+
+    return result;
+}
+
+json json::diff(const json& source, const json& target,
+                       const std::string& path)
+{
+    // the patch
+    json result(value_t::array);
+
+    // if the values are the same, return empty patch
+    if (source == target)
+    {
+        return result;
+    }
+
+    if (source.type() != target.type())
+    {
+        // different types: replace value
+        result.push_back(
+        {
+            {"op", "replace"}, {"path", path}, {"value", target}
+        });
+    }
+    else
+    {
+        switch (source.type())
+        {
+            case value_t::array:
+            {
+                // first pass: traverse common elements
+                std::size_t i = 0;
+                while (i < source.size() and i < target.size())
+                {
+                    // recursive call to compare array values at index i
+                    auto temp_diff = diff(source[i], target[i], path + "/" + std::to_string(i));
+                    result.insert(result.end(), temp_diff.begin(), temp_diff.end());
+                    ++i;
+                }
+
+                // i now reached the end of at least one array
+                // in a second pass, traverse the remaining elements
+
+                // remove my remaining elements
+                const auto end_index = static_cast<difference_type>(result.size());
+                while (i < source.size())
+                {
+                    // add operations in reverse order to avoid invalid
+                    // indices
+                    result.insert(result.begin() + end_index, object(
+                    {
+                        {"op", "remove"},
+                        {"path", path + "/" + std::to_string(i)}
+                    }));
+                    ++i;
+                }
+
+                // add other remaining elements
+                while (i < target.size())
+                {
+                    result.push_back(
+                    {
+                        {"op", "add"},
+                        {"path", path + "/" + std::to_string(i)},
+                        {"value", target[i]}
+                    });
+                    ++i;
+                }
+
+                break;
+            }
+
+            case value_t::object:
+            {
+                // first pass: traverse this object's elements
+                for (auto it = source.cbegin(); it != source.cend(); ++it)
+                {
+                    // escape the key name to be used in a JSON patch
+                    const auto key = json_pointer::escape(it.key());
+
+                    if (target.find(it.key()) != target.end())
+                    {
+                        // recursive call to compare object values at key it
+                        auto temp_diff = diff(it.value(), target[it.key()], path + "/" + key);
+                        result.insert(result.end(), temp_diff.begin(), temp_diff.end());
+                    }
+                    else
+                    {
+                        // found a key that is not in o -> remove it
+                        result.push_back(object(
+                        {
+                            {"op", "remove"}, {"path", path + "/" + key}
+                        }));
+                    }
+                }
+
+                // second pass: traverse other object's elements
+                for (auto it = target.cbegin(); it != target.cend(); ++it)
+                {
+                    if (source.find(it.key()) == source.end())
+                    {
+                        // found a key that is not in this -> add it
+                        const auto key = json_pointer::escape(it.key());
+                        result.push_back(
+                        {
+                            {"op", "add"}, {"path", path + "/" + key},
+                            {"value", it.value()}
+                        });
+                    }
+                }
+
+                break;
+            }
+
+            default:
+            {
+                // both primitive type: replace value
+                result.push_back(
+                {
+                    {"op", "replace"}, {"path", path}, {"value", target}
+                });
+                break;
+            }
+        }
+    }
+
+    return result;
+}
+
+void json::merge_patch(const json& patch)
+{
+    if (patch.is_object())
+    {
+        if (not is_object())
+        {
+            *this = object();
+        }
+        for (auto it = patch.begin(); it != patch.end(); ++it)
+        {
+            if (it.value().is_null())
+            {
+                erase(it.key());
+            }
+            else
+            {
+                operator[](it.key()).merge_patch(it.value());
+            }
+        }
+    }
+    else
+    {
+        *this = patch;
+    }
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_binary_reader.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_binary_reader.cpp
new file mode 100644
index 0000000..9298e92
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_binary_reader.cpp
@@ -0,0 +1,1413 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include <cmath>  // ldexp
+
+#include "wpi/raw_istream.h"
+
+namespace wpi {
+
+/*!
+@brief deserialization of CBOR and MessagePack values
+*/
+class json::binary_reader
+{
+  public:
+    /*!
+    @brief create a binary reader
+
+    @param[in] adapter  input adapter to read from
+    */
+    explicit binary_reader(raw_istream& s) : is(s)
+    {
+    }
+
+    /*!
+    @brief create a JSON value from CBOR input
+
+    @param[in] strict  whether to expect the input to be consumed completed
+    @return JSON value created from CBOR input
+
+    @throw parse_error.110 if input ended unexpectedly or the end of file was
+                           not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported byte was read
+    */
+    json parse_cbor(const bool strict)
+    {
+        const auto res = parse_cbor_internal();
+        if (strict)
+        {
+            get();
+            expect_eof();
+        }
+        return res;
+    }
+
+    /*!
+    @brief create a JSON value from MessagePack input
+
+    @param[in] strict  whether to expect the input to be consumed completed
+    @return JSON value created from MessagePack input
+
+    @throw parse_error.110 if input ended unexpectedly or the end of file was
+                           not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported byte was read
+    */
+    json parse_msgpack(const bool strict)
+    {
+        const auto res = parse_msgpack_internal();
+        if (strict)
+        {
+            get();
+            expect_eof();
+        }
+        return res;
+    }
+
+    /*!
+    @brief create a JSON value from UBJSON input
+
+    @param[in] strict  whether to expect the input to be consumed completed
+    @return JSON value created from UBJSON input
+
+    @throw parse_error.110 if input ended unexpectedly or the end of file was
+                           not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported byte was read
+    */
+    json parse_ubjson(const bool strict)
+    {
+        const auto res = parse_ubjson_internal();
+        if (strict)
+        {
+            get_ignore_noop();
+            expect_eof();
+        }
+        return res;
+    }
+
+    /*!
+    @brief determine system byte order
+
+    @return true if and only if system's byte order is little endian
+
+    @note from http://stackoverflow.com/a/1001328/266378
+    */
+    static bool little_endianess(int num = 1) noexcept
+    {
+        return (*reinterpret_cast<char*>(&num) == 1);
+    }
+
+  private:
+    /*!
+    @param[in] get_char  whether a new character should be retrieved from the
+                         input (true, default) or whether the last read
+                         character should be considered instead
+    */
+    json parse_cbor_internal(const bool get_char = true);
+
+    json parse_msgpack_internal();
+
+    /*!
+    @param[in] get_char  whether a new character should be retrieved from the
+                         input (true, default) or whether the last read
+                         character should be considered instead
+    */
+    json parse_ubjson_internal(const bool get_char = true)
+    {
+        return get_ubjson_value(get_char ? get_ignore_noop() : current);
+    }
+
+    /*!
+    @brief get next character from the input
+
+    This function provides the interface to the used input adapter. It does
+    not throw in case the input reached EOF, but returns a -'ve valued
+    `std::char_traits<char>::eof()` in that case.
+
+    @return character read from the input
+    */
+    int get()
+    {
+        ++chars_read;
+        unsigned char c;
+        is.read(c);
+        if (is.has_error())
+        {
+            current = std::char_traits<char>::eof();
+        }
+        else
+        {
+            current = c;
+        }
+        return current;
+    }
+
+    /*!
+    @return character read from the input after ignoring all 'N' entries
+    */
+    int get_ignore_noop()
+    {
+        do
+        {
+            get();
+        }
+        while (current == 'N');
+
+        return current;
+    }
+
+    /*
+    @brief read a number from the input
+
+    @tparam NumberType the type of the number
+
+    @return number of type @a NumberType
+
+    @note This function needs to respect the system's endianess, because
+          bytes in CBOR and MessagePack are stored in network order (big
+          endian) and therefore need reordering on little endian systems.
+
+    @throw parse_error.110 if input has less than `sizeof(NumberType)` bytes
+    */
+    template<typename NumberType> NumberType get_number()
+    {
+        // step 1: read input into array with system's byte order
+        std::array<uint8_t, sizeof(NumberType)> vec;
+        for (std::size_t i = 0; i < sizeof(NumberType); ++i)
+        {
+            get();
+            unexpect_eof();
+
+            // reverse byte order prior to conversion if necessary
+            if (is_little_endian)
+            {
+                vec[sizeof(NumberType) - i - 1] = static_cast<uint8_t>(current);
+            }
+            else
+            {
+                vec[i] = static_cast<uint8_t>(current); // LCOV_EXCL_LINE
+            }
+        }
+
+        // step 2: convert array into number of type T and return
+        NumberType result;
+        std::memcpy(&result, vec.data(), sizeof(NumberType));
+        return result;
+    }
+
+    /*!
+    @brief create a string by reading characters from the input
+
+    @param[in] len number of bytes to read
+
+    @note We can not reserve @a len bytes for the result, because @a len
+          may be too large. Usually, @ref unexpect_eof() detects the end of
+          the input before we run out of string memory.
+
+    @return string created by reading @a len bytes
+
+    @throw parse_error.110 if input has less than @a len bytes
+    */
+    template<typename NumberType>
+    std::string get_string(const NumberType len)
+    {
+        std::string result;
+        std::generate_n(std::back_inserter(result), len, [this]()
+        {
+            get();
+            unexpect_eof();
+            return static_cast<char>(current);
+        });
+        return result;
+    }
+
+    /*!
+    @brief reads a CBOR string
+
+    This function first reads starting bytes to determine the expected
+    string length and then copies this number of bytes into a string.
+    Additionally, CBOR's strings with indefinite lengths are supported.
+
+    @return string
+
+    @throw parse_error.110 if input ended
+    @throw parse_error.113 if an unexpected byte is read
+    */
+    std::string get_cbor_string();
+
+    template<typename NumberType>
+    json get_cbor_array(const NumberType len)
+    {
+        json result = value_t::array;
+        std::generate_n(std::back_inserter(*result.m_value.array), len, [this]()
+        {
+            return parse_cbor_internal();
+        });
+        return result;
+    }
+
+    template<typename NumberType>
+    json get_cbor_object(const NumberType len)
+    {
+        json result = value_t::object;
+        for (NumberType i = 0; i < len; ++i)
+        {
+            get();
+            auto key = get_cbor_string();
+            (*result.m_value.object)[key] = parse_cbor_internal();
+        }
+        return result;
+    }
+
+    /*!
+    @brief reads a MessagePack string
+
+    This function first reads starting bytes to determine the expected
+    string length and then copies this number of bytes into a string.
+
+    @return string
+
+    @throw parse_error.110 if input ended
+    @throw parse_error.113 if an unexpected byte is read
+    */
+    std::string get_msgpack_string();
+
+    template<typename NumberType>
+    json get_msgpack_array(const NumberType len)
+    {
+        json result = value_t::array;
+        std::generate_n(std::back_inserter(*result.m_value.array), len, [this]()
+        {
+            return parse_msgpack_internal();
+        });
+        return result;
+    }
+
+    template<typename NumberType>
+    json get_msgpack_object(const NumberType len)
+    {
+        json result = value_t::object;
+        for (NumberType i = 0; i < len; ++i)
+        {
+            get();
+            auto key = get_msgpack_string();
+            (*result.m_value.object)[key] = parse_msgpack_internal();
+        }
+        return result;
+    }
+
+    /*!
+    @brief reads a UBJSON string
+
+    This function is either called after reading the 'S' byte explicitly
+    indicating a string, or in case of an object key where the 'S' byte can be
+    left out.
+
+    @param[in] get_char  whether a new character should be retrieved from the
+                         input (true, default) or whether the last read
+                         character should be considered instead
+
+    @return string
+
+    @throw parse_error.110 if input ended
+    @throw parse_error.113 if an unexpected byte is read
+    */
+    std::string get_ubjson_string(const bool get_char = true);
+
+    /*!
+    @brief determine the type and size for a container
+
+    In the optimized UBJSON format, a type and a size can be provided to allow
+    for a more compact representation.
+
+    @return pair of the size and the type
+    */
+    std::pair<std::size_t, int> get_ubjson_size_type();
+
+    json get_ubjson_value(const int prefix);
+
+    json get_ubjson_array();
+
+    json get_ubjson_object();
+
+    /*!
+    @brief throw if end of input is not reached
+    @throw parse_error.110 if input not ended
+    */
+    void expect_eof() const
+    {
+        if (JSON_UNLIKELY(current != std::char_traits<char>::eof()))
+        {
+            JSON_THROW(parse_error::create(110, chars_read, "expected end of input"));
+        }
+    }
+
+    /*!
+    @briefthrow if end of input is reached
+    @throw parse_error.110 if input ended
+    */
+    void unexpect_eof() const
+    {
+        if (JSON_UNLIKELY(current == std::char_traits<char>::eof()))
+        {
+            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
+        }
+    }
+
+  private:
+    /// input adapter
+    raw_istream& is;
+
+    /// the current character
+    int current = std::char_traits<char>::eof();
+
+    /// the number of characters read
+    std::size_t chars_read = 0;
+
+    /// whether we can assume little endianess
+    const bool is_little_endian = little_endianess();
+};
+
+json json::binary_reader::parse_cbor_internal(const bool get_char)
+{
+    switch (get_char ? get() : current)
+    {
+        // EOF
+        case std::char_traits<char>::eof():
+            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
+
+        // Integer 0x00..0x17 (0..23)
+        case 0x00:
+        case 0x01:
+        case 0x02:
+        case 0x03:
+        case 0x04:
+        case 0x05:
+        case 0x06:
+        case 0x07:
+        case 0x08:
+        case 0x09:
+        case 0x0A:
+        case 0x0B:
+        case 0x0C:
+        case 0x0D:
+        case 0x0E:
+        case 0x0F:
+        case 0x10:
+        case 0x11:
+        case 0x12:
+        case 0x13:
+        case 0x14:
+        case 0x15:
+        case 0x16:
+        case 0x17:
+            return static_cast<uint64_t>(current);
+
+        case 0x18: // Unsigned integer (one-byte uint8_t follows)
+            return get_number<uint8_t>();
+
+        case 0x19: // Unsigned integer (two-byte uint16_t follows)
+            return get_number<uint16_t>();
+
+        case 0x1A: // Unsigned integer (four-byte uint32_t follows)
+            return get_number<uint32_t>();
+
+        case 0x1B: // Unsigned integer (eight-byte uint64_t follows)
+            return get_number<uint64_t>();
+
+        // Negative integer -1-0x00..-1-0x17 (-1..-24)
+        case 0x20:
+        case 0x21:
+        case 0x22:
+        case 0x23:
+        case 0x24:
+        case 0x25:
+        case 0x26:
+        case 0x27:
+        case 0x28:
+        case 0x29:
+        case 0x2A:
+        case 0x2B:
+        case 0x2C:
+        case 0x2D:
+        case 0x2E:
+        case 0x2F:
+        case 0x30:
+        case 0x31:
+        case 0x32:
+        case 0x33:
+        case 0x34:
+        case 0x35:
+        case 0x36:
+        case 0x37:
+            return static_cast<int8_t>(0x20 - 1 - current);
+
+        case 0x38: // Negative integer (one-byte uint8_t follows)
+        {
+            return static_cast<int64_t>(-1) - get_number<uint8_t>();
+        }
+
+        case 0x39: // Negative integer -1-n (two-byte uint16_t follows)
+        {
+            return static_cast<int64_t>(-1) - get_number<uint16_t>();
+        }
+
+        case 0x3A: // Negative integer -1-n (four-byte uint32_t follows)
+        {
+            return static_cast<int64_t>(-1) - get_number<uint32_t>();
+        }
+
+        case 0x3B: // Negative integer -1-n (eight-byte uint64_t follows)
+        {
+            return static_cast<int64_t>(-1) -
+                   static_cast<int64_t>(get_number<uint64_t>());
+        }
+
+        // UTF-8 string (0x00..0x17 bytes follow)
+        case 0x60:
+        case 0x61:
+        case 0x62:
+        case 0x63:
+        case 0x64:
+        case 0x65:
+        case 0x66:
+        case 0x67:
+        case 0x68:
+        case 0x69:
+        case 0x6A:
+        case 0x6B:
+        case 0x6C:
+        case 0x6D:
+        case 0x6E:
+        case 0x6F:
+        case 0x70:
+        case 0x71:
+        case 0x72:
+        case 0x73:
+        case 0x74:
+        case 0x75:
+        case 0x76:
+        case 0x77:
+        case 0x78: // UTF-8 string (one-byte uint8_t for n follows)
+        case 0x79: // UTF-8 string (two-byte uint16_t for n follow)
+        case 0x7A: // UTF-8 string (four-byte uint32_t for n follow)
+        case 0x7B: // UTF-8 string (eight-byte uint64_t for n follow)
+        case 0x7F: // UTF-8 string (indefinite length)
+        {
+            return get_cbor_string();
+        }
+
+        // array (0x00..0x17 data items follow)
+        case 0x80:
+        case 0x81:
+        case 0x82:
+        case 0x83:
+        case 0x84:
+        case 0x85:
+        case 0x86:
+        case 0x87:
+        case 0x88:
+        case 0x89:
+        case 0x8A:
+        case 0x8B:
+        case 0x8C:
+        case 0x8D:
+        case 0x8E:
+        case 0x8F:
+        case 0x90:
+        case 0x91:
+        case 0x92:
+        case 0x93:
+        case 0x94:
+        case 0x95:
+        case 0x96:
+        case 0x97:
+        {
+            return get_cbor_array(current & 0x1F);
+        }
+
+        case 0x98: // array (one-byte uint8_t for n follows)
+        {
+            return get_cbor_array(get_number<uint8_t>());
+        }
+
+        case 0x99: // array (two-byte uint16_t for n follow)
+        {
+            return get_cbor_array(get_number<uint16_t>());
+        }
+
+        case 0x9A: // array (four-byte uint32_t for n follow)
+        {
+            return get_cbor_array(get_number<uint32_t>());
+        }
+
+        case 0x9B: // array (eight-byte uint64_t for n follow)
+        {
+            return get_cbor_array(get_number<uint64_t>());
+        }
+
+        case 0x9F: // array (indefinite length)
+        {
+            json result = value_t::array;
+            while (get() != 0xFF)
+            {
+                result.push_back(parse_cbor_internal(false));
+            }
+            return result;
+        }
+
+        // map (0x00..0x17 pairs of data items follow)
+        case 0xA0:
+        case 0xA1:
+        case 0xA2:
+        case 0xA3:
+        case 0xA4:
+        case 0xA5:
+        case 0xA6:
+        case 0xA7:
+        case 0xA8:
+        case 0xA9:
+        case 0xAA:
+        case 0xAB:
+        case 0xAC:
+        case 0xAD:
+        case 0xAE:
+        case 0xAF:
+        case 0xB0:
+        case 0xB1:
+        case 0xB2:
+        case 0xB3:
+        case 0xB4:
+        case 0xB5:
+        case 0xB6:
+        case 0xB7:
+        {
+            return get_cbor_object(current & 0x1F);
+        }
+
+        case 0xB8: // map (one-byte uint8_t for n follows)
+        {
+            return get_cbor_object(get_number<uint8_t>());
+        }
+
+        case 0xB9: // map (two-byte uint16_t for n follow)
+        {
+            return get_cbor_object(get_number<uint16_t>());
+        }
+
+        case 0xBA: // map (four-byte uint32_t for n follow)
+        {
+            return get_cbor_object(get_number<uint32_t>());
+        }
+
+        case 0xBB: // map (eight-byte uint64_t for n follow)
+        {
+            return get_cbor_object(get_number<uint64_t>());
+        }
+
+        case 0xBF: // map (indefinite length)
+        {
+            json result = value_t::object;
+            while (get() != 0xFF)
+            {
+                auto key = get_cbor_string();
+                result[key] = parse_cbor_internal();
+            }
+            return result;
+        }
+
+        case 0xF4: // false
+        {
+            return false;
+        }
+
+        case 0xF5: // true
+        {
+            return true;
+        }
+
+        case 0xF6: // null
+        {
+            return value_t::null;
+        }
+
+        case 0xF9: // Half-Precision Float (two-byte IEEE 754)
+        {
+            const int byte1 = get();
+            unexpect_eof();
+            const int byte2 = get();
+            unexpect_eof();
+
+            // code from RFC 7049, Appendix D, Figure 3:
+            // As half-precision floating-point numbers were only added
+            // to IEEE 754 in 2008, today's programming platforms often
+            // still only have limited support for them. It is very
+            // easy to include at least decoding support for them even
+            // without such support. An example of a small decoder for
+            // half-precision floating-point numbers in the C language
+            // is shown in Fig. 3.
+            const int half = (byte1 << 8) + byte2;
+            const int exp = (half >> 10) & 0x1F;
+            const int mant = half & 0x3FF;
+            double val;
+            if (exp == 0)
+            {
+                val = std::ldexp(mant, -24);
+            }
+            else if (exp != 31)
+            {
+                val = std::ldexp(mant + 1024, exp - 25);
+            }
+            else
+            {
+                val = (mant == 0) ? std::numeric_limits<double>::infinity()
+                      : std::numeric_limits<double>::quiet_NaN();
+            }
+            return (half & 0x8000) != 0 ? -val : val;
+        }
+
+        case 0xFA: // Single-Precision Float (four-byte IEEE 754)
+        {
+            return get_number<float>();
+        }
+
+        case 0xFB: // Double-Precision Float (eight-byte IEEE 754)
+        {
+            return get_number<double>();
+        }
+
+        default: // anything else (0xFF is handled inside the other types)
+        {
+            JSON_THROW(parse_error::create(112, chars_read, "error reading CBOR; last byte: 0x" + Twine::utohexstr(current)));
+        }
+    }
+}
+
+json json::binary_reader::parse_msgpack_internal()
+{
+    switch (get())
+    {
+        // EOF
+        case std::char_traits<char>::eof():
+            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
+
+        // positive fixint
+        case 0x00:
+        case 0x01:
+        case 0x02:
+        case 0x03:
+        case 0x04:
+        case 0x05:
+        case 0x06:
+        case 0x07:
+        case 0x08:
+        case 0x09:
+        case 0x0A:
+        case 0x0B:
+        case 0x0C:
+        case 0x0D:
+        case 0x0E:
+        case 0x0F:
+        case 0x10:
+        case 0x11:
+        case 0x12:
+        case 0x13:
+        case 0x14:
+        case 0x15:
+        case 0x16:
+        case 0x17:
+        case 0x18:
+        case 0x19:
+        case 0x1A:
+        case 0x1B:
+        case 0x1C:
+        case 0x1D:
+        case 0x1E:
+        case 0x1F:
+        case 0x20:
+        case 0x21:
+        case 0x22:
+        case 0x23:
+        case 0x24:
+        case 0x25:
+        case 0x26:
+        case 0x27:
+        case 0x28:
+        case 0x29:
+        case 0x2A:
+        case 0x2B:
+        case 0x2C:
+        case 0x2D:
+        case 0x2E:
+        case 0x2F:
+        case 0x30:
+        case 0x31:
+        case 0x32:
+        case 0x33:
+        case 0x34:
+        case 0x35:
+        case 0x36:
+        case 0x37:
+        case 0x38:
+        case 0x39:
+        case 0x3A:
+        case 0x3B:
+        case 0x3C:
+        case 0x3D:
+        case 0x3E:
+        case 0x3F:
+        case 0x40:
+        case 0x41:
+        case 0x42:
+        case 0x43:
+        case 0x44:
+        case 0x45:
+        case 0x46:
+        case 0x47:
+        case 0x48:
+        case 0x49:
+        case 0x4A:
+        case 0x4B:
+        case 0x4C:
+        case 0x4D:
+        case 0x4E:
+        case 0x4F:
+        case 0x50:
+        case 0x51:
+        case 0x52:
+        case 0x53:
+        case 0x54:
+        case 0x55:
+        case 0x56:
+        case 0x57:
+        case 0x58:
+        case 0x59:
+        case 0x5A:
+        case 0x5B:
+        case 0x5C:
+        case 0x5D:
+        case 0x5E:
+        case 0x5F:
+        case 0x60:
+        case 0x61:
+        case 0x62:
+        case 0x63:
+        case 0x64:
+        case 0x65:
+        case 0x66:
+        case 0x67:
+        case 0x68:
+        case 0x69:
+        case 0x6A:
+        case 0x6B:
+        case 0x6C:
+        case 0x6D:
+        case 0x6E:
+        case 0x6F:
+        case 0x70:
+        case 0x71:
+        case 0x72:
+        case 0x73:
+        case 0x74:
+        case 0x75:
+        case 0x76:
+        case 0x77:
+        case 0x78:
+        case 0x79:
+        case 0x7A:
+        case 0x7B:
+        case 0x7C:
+        case 0x7D:
+        case 0x7E:
+        case 0x7F:
+            return static_cast<uint64_t>(current);
+
+        // fixmap
+        case 0x80:
+        case 0x81:
+        case 0x82:
+        case 0x83:
+        case 0x84:
+        case 0x85:
+        case 0x86:
+        case 0x87:
+        case 0x88:
+        case 0x89:
+        case 0x8A:
+        case 0x8B:
+        case 0x8C:
+        case 0x8D:
+        case 0x8E:
+        case 0x8F:
+        {
+            return get_msgpack_object(current & 0x0F);
+        }
+
+        // fixarray
+        case 0x90:
+        case 0x91:
+        case 0x92:
+        case 0x93:
+        case 0x94:
+        case 0x95:
+        case 0x96:
+        case 0x97:
+        case 0x98:
+        case 0x99:
+        case 0x9A:
+        case 0x9B:
+        case 0x9C:
+        case 0x9D:
+        case 0x9E:
+        case 0x9F:
+        {
+            return get_msgpack_array(current & 0x0F);
+        }
+
+        // fixstr
+        case 0xA0:
+        case 0xA1:
+        case 0xA2:
+        case 0xA3:
+        case 0xA4:
+        case 0xA5:
+        case 0xA6:
+        case 0xA7:
+        case 0xA8:
+        case 0xA9:
+        case 0xAA:
+        case 0xAB:
+        case 0xAC:
+        case 0xAD:
+        case 0xAE:
+        case 0xAF:
+        case 0xB0:
+        case 0xB1:
+        case 0xB2:
+        case 0xB3:
+        case 0xB4:
+        case 0xB5:
+        case 0xB6:
+        case 0xB7:
+        case 0xB8:
+        case 0xB9:
+        case 0xBA:
+        case 0xBB:
+        case 0xBC:
+        case 0xBD:
+        case 0xBE:
+        case 0xBF:
+            return get_msgpack_string();
+
+        case 0xC0: // nil
+            return value_t::null;
+
+        case 0xC2: // false
+            return false;
+
+        case 0xC3: // true
+            return true;
+
+        case 0xCA: // float 32
+            return get_number<float>();
+
+        case 0xCB: // float 64
+            return get_number<double>();
+
+        case 0xCC: // uint 8
+            return get_number<uint8_t>();
+
+        case 0xCD: // uint 16
+            return get_number<uint16_t>();
+
+        case 0xCE: // uint 32
+            return get_number<uint32_t>();
+
+        case 0xCF: // uint 64
+            return get_number<uint64_t>();
+
+        case 0xD0: // int 8
+            return get_number<int8_t>();
+
+        case 0xD1: // int 16
+            return get_number<int16_t>();
+
+        case 0xD2: // int 32
+            return get_number<int32_t>();
+
+        case 0xD3: // int 64
+            return get_number<int64_t>();
+
+        case 0xD9: // str 8
+        case 0xDA: // str 16
+        case 0xDB: // str 32
+            return get_msgpack_string();
+
+        case 0xDC: // array 16
+        {
+            return get_msgpack_array(get_number<uint16_t>());
+        }
+
+        case 0xDD: // array 32
+        {
+            return get_msgpack_array(get_number<uint32_t>());
+        }
+
+        case 0xDE: // map 16
+        {
+            return get_msgpack_object(get_number<uint16_t>());
+        }
+
+        case 0xDF: // map 32
+        {
+            return get_msgpack_object(get_number<uint32_t>());
+        }
+
+        // positive fixint
+        case 0xE0:
+        case 0xE1:
+        case 0xE2:
+        case 0xE3:
+        case 0xE4:
+        case 0xE5:
+        case 0xE6:
+        case 0xE7:
+        case 0xE8:
+        case 0xE9:
+        case 0xEA:
+        case 0xEB:
+        case 0xEC:
+        case 0xED:
+        case 0xEE:
+        case 0xEF:
+        case 0xF0:
+        case 0xF1:
+        case 0xF2:
+        case 0xF3:
+        case 0xF4:
+        case 0xF5:
+        case 0xF6:
+        case 0xF7:
+        case 0xF8:
+        case 0xF9:
+        case 0xFA:
+        case 0xFB:
+        case 0xFC:
+        case 0xFD:
+        case 0xFE:
+        case 0xFF:
+            return static_cast<int8_t>(current);
+
+        default: // anything else
+        {
+            JSON_THROW(parse_error::create(112, chars_read,
+                                           "error reading MessagePack; last byte: 0x" + Twine::utohexstr(current)));
+        }
+    }
+}
+
+std::string json::binary_reader::get_cbor_string()
+{
+    unexpect_eof();
+
+    switch (current)
+    {
+        // UTF-8 string (0x00..0x17 bytes follow)
+        case 0x60:
+        case 0x61:
+        case 0x62:
+        case 0x63:
+        case 0x64:
+        case 0x65:
+        case 0x66:
+        case 0x67:
+        case 0x68:
+        case 0x69:
+        case 0x6A:
+        case 0x6B:
+        case 0x6C:
+        case 0x6D:
+        case 0x6E:
+        case 0x6F:
+        case 0x70:
+        case 0x71:
+        case 0x72:
+        case 0x73:
+        case 0x74:
+        case 0x75:
+        case 0x76:
+        case 0x77:
+        {
+            return get_string(current & 0x1F);
+        }
+
+        case 0x78: // UTF-8 string (one-byte uint8_t for n follows)
+        {
+            return get_string(get_number<uint8_t>());
+        }
+
+        case 0x79: // UTF-8 string (two-byte uint16_t for n follow)
+        {
+            return get_string(get_number<uint16_t>());
+        }
+
+        case 0x7A: // UTF-8 string (four-byte uint32_t for n follow)
+        {
+            return get_string(get_number<uint32_t>());
+        }
+
+        case 0x7B: // UTF-8 string (eight-byte uint64_t for n follow)
+        {
+            return get_string(get_number<uint64_t>());
+        }
+
+        case 0x7F: // UTF-8 string (indefinite length)
+        {
+            std::string result;
+            while (get() != 0xFF)
+            {
+                result.append(get_cbor_string());
+            }
+            return result;
+        }
+
+        default:
+        {
+            JSON_THROW(parse_error::create(113, chars_read, "expected a CBOR string; last byte: 0x" + Twine::utohexstr(current)));
+        }
+    }
+}
+
+std::string json::binary_reader::get_msgpack_string()
+{
+    unexpect_eof();
+
+    switch (current)
+    {
+        // fixstr
+        case 0xA0:
+        case 0xA1:
+        case 0xA2:
+        case 0xA3:
+        case 0xA4:
+        case 0xA5:
+        case 0xA6:
+        case 0xA7:
+        case 0xA8:
+        case 0xA9:
+        case 0xAA:
+        case 0xAB:
+        case 0xAC:
+        case 0xAD:
+        case 0xAE:
+        case 0xAF:
+        case 0xB0:
+        case 0xB1:
+        case 0xB2:
+        case 0xB3:
+        case 0xB4:
+        case 0xB5:
+        case 0xB6:
+        case 0xB7:
+        case 0xB8:
+        case 0xB9:
+        case 0xBA:
+        case 0xBB:
+        case 0xBC:
+        case 0xBD:
+        case 0xBE:
+        case 0xBF:
+        {
+            return get_string(current & 0x1F);
+        }
+
+        case 0xD9: // str 8
+        {
+            return get_string(get_number<uint8_t>());
+        }
+
+        case 0xDA: // str 16
+        {
+            return get_string(get_number<uint16_t>());
+        }
+
+        case 0xDB: // str 32
+        {
+            return get_string(get_number<uint32_t>());
+        }
+
+        default:
+        {
+            JSON_THROW(parse_error::create(113, chars_read,
+                                           "expected a MessagePack string; last byte: 0x" + Twine::utohexstr(current)));
+        }
+    }
+}
+
+std::string json::binary_reader::get_ubjson_string(const bool get_char)
+{
+    if (get_char)
+    {
+        get();  // TODO: may we ignore N here?
+    }
+
+    unexpect_eof();
+
+    switch (current)
+    {
+        case 'U':
+            return get_string(get_number<uint8_t>());
+        case 'i':
+            return get_string(get_number<int8_t>());
+        case 'I':
+            return get_string(get_number<int16_t>());
+        case 'l':
+            return get_string(get_number<int32_t>());
+        case 'L':
+            return get_string(get_number<int64_t>());
+        default:
+            JSON_THROW(parse_error::create(113, chars_read,
+                                           "expected a UBJSON string; last byte: 0x" + Twine::utohexstr(current)));
+    }
+}
+
+std::pair<std::size_t, int> json::binary_reader::get_ubjson_size_type()
+{
+    std::size_t sz = std::string::npos;
+    int tc = 0;
+
+    get_ignore_noop();
+
+    if (current == '$')
+    {
+        tc = get();  // must not ignore 'N', because 'N' maybe the type
+        unexpect_eof();
+
+        get_ignore_noop();
+        if (current != '#')
+        {
+            JSON_THROW(parse_error::create(112, chars_read,
+                                           "expected '#' after UBJSON type information; last byte: 0x" + Twine::utohexstr(current)));
+        }
+        sz = parse_ubjson_internal();
+    }
+    else if (current == '#')
+    {
+        sz = parse_ubjson_internal();
+    }
+
+    return std::make_pair(sz, tc);
+}
+
+json json::binary_reader::get_ubjson_value(const int prefix)
+{
+    switch (prefix)
+    {
+        case std::char_traits<char>::eof():  // EOF
+            JSON_THROW(parse_error::create(110, chars_read, "unexpected end of input"));
+
+        case 'T':  // true
+            return true;
+        case 'F':  // false
+            return false;
+
+        case 'Z':  // null
+            return nullptr;
+
+        case 'U':
+            return get_number<uint8_t>();
+        case 'i':
+            return get_number<int8_t>();
+        case 'I':
+            return get_number<int16_t>();
+        case 'l':
+            return get_number<int32_t>();
+        case 'L':
+            return get_number<int64_t>();
+        case 'd':
+            return get_number<float>();
+        case 'D':
+            return get_number<double>();
+
+        case 'C':  // char
+        {
+            get();
+            unexpect_eof();
+            if (JSON_UNLIKELY(current > 127))
+            {
+                JSON_THROW(parse_error::create(113, chars_read,
+                                               "byte after 'C' must be in range 0x00..0x7F; last byte: 0x" + Twine::utohexstr(current)));
+            }
+            return std::string(1, static_cast<char>(current));
+        }
+
+        case 'S':  // string
+            return get_ubjson_string();
+
+        case '[':  // array
+            return get_ubjson_array();
+
+        case '{':  // object
+            return get_ubjson_object();
+
+        default: // anything else
+            JSON_THROW(parse_error::create(112, chars_read,
+                                           "error reading UBJSON; last byte: 0x" + Twine::utohexstr(current)));
+    }
+}
+
+json json::binary_reader::get_ubjson_array()
+{
+    json result = value_t::array;
+    const auto size_and_type = get_ubjson_size_type();
+
+    if (size_and_type.first != std::string::npos)
+    {
+        if (JSON_UNLIKELY(size_and_type.first > result.max_size()))
+        {
+            JSON_THROW(out_of_range::create(408,
+                                            "excessive array size: " + Twine(size_and_type.first)));
+        }
+
+        if (size_and_type.second != 0)
+        {
+            if (size_and_type.second != 'N')
+            {
+                std::generate_n(std::back_inserter(*result.m_value.array),
+                                size_and_type.first, [this, size_and_type]()
+                {
+                    return get_ubjson_value(size_and_type.second);
+                });
+            }
+        }
+        else
+        {
+            std::generate_n(std::back_inserter(*result.m_value.array),
+                            size_and_type.first, [this]()
+            {
+                return parse_ubjson_internal();
+            });
+        }
+    }
+    else
+    {
+        while (current != ']')
+        {
+            result.push_back(parse_ubjson_internal(false));
+            get_ignore_noop();
+        }
+    }
+
+    return result;
+}
+
+json json::binary_reader::get_ubjson_object()
+{
+    json result = value_t::object;
+    const auto size_and_type = get_ubjson_size_type();
+
+    if (size_and_type.first != std::string::npos)
+    {
+        if (JSON_UNLIKELY(size_and_type.first > result.max_size()))
+        {
+            JSON_THROW(out_of_range::create(408,
+                                            "excessive object size: " + Twine(size_and_type.first)));
+        }
+
+        if (size_and_type.second != 0)
+        {
+            for (size_t i = 0; i < size_and_type.first; ++i)
+            {
+                auto key = get_ubjson_string();
+                (*result.m_value.object)[key] = get_ubjson_value(size_and_type.second);
+            }
+        }
+        else
+        {
+            for (size_t i = 0; i < size_and_type.first; ++i)
+            {
+                auto key = get_ubjson_string();
+                (*result.m_value.object)[key] = parse_ubjson_internal();
+            }
+        }
+    }
+    else
+    {
+        while (current != '}')
+        {
+            auto key = get_ubjson_string(false);
+            result[std::move(key)] = parse_ubjson_internal();
+            get_ignore_noop();
+        }
+    }
+
+    return result;
+}
+
+json json::from_cbor(raw_istream& is, const bool strict)
+{
+    return binary_reader(is).parse_cbor(strict);
+}
+
+json json::from_cbor(ArrayRef<uint8_t> arr, const bool strict)
+{
+    raw_mem_istream is(arr);
+    return from_cbor(is, strict);
+}
+
+json json::from_msgpack(raw_istream& is, const bool strict)
+{
+    return binary_reader(is).parse_msgpack(strict);
+}
+
+json json::from_msgpack(ArrayRef<uint8_t> arr, const bool strict)
+{
+    raw_mem_istream is(arr);
+    return from_msgpack(is, strict);
+}
+
+json json::from_ubjson(raw_istream& is, const bool strict)
+{
+    return binary_reader(is).parse_ubjson(strict);
+}
+
+json json::from_ubjson(ArrayRef<uint8_t> arr, const bool strict)
+{
+    raw_mem_istream is(arr);
+    return from_ubjson(is, strict);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_binary_writer.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_binary_writer.cpp
new file mode 100644
index 0000000..75c39aa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_binary_writer.cpp
@@ -0,0 +1,1090 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+/*!
+@brief serialization to CBOR and MessagePack values
+*/
+class json::binary_writer
+{
+    using CharType = unsigned char;
+
+  public:
+    /*!
+    @brief create a binary writer
+
+    @param[in] adapter  output adapter to write to
+    */
+    explicit binary_writer(raw_ostream& s) : o(s)
+    {
+    }
+
+    /*!
+    @brief[in] j  JSON value to serialize
+    */
+    void write_cbor(const json& j);
+
+    /*!
+    @brief[in] j  JSON value to serialize
+    */
+    void write_msgpack(const json& j);
+
+    /*!
+    @param[in] j  JSON value to serialize
+    @param[in] use_count   whether to use '#' prefixes (optimized format)
+    @param[in] use_type    whether to use '$' prefixes (optimized format)
+    @param[in] add_prefix  whether prefixes need to be used for this value
+    */
+    void write_ubjson(const json& j, const bool use_count,
+                      const bool use_type, const bool add_prefix = true);
+
+  private:
+    void write_cbor_string(StringRef str);
+
+    void write_msgpack_string(StringRef str);
+
+    /*
+    @brief write a number to output input
+
+    @param[in] n number of type @a NumberType
+    @tparam NumberType the type of the number
+
+    @note This function needs to respect the system's endianess, because bytes
+          in CBOR, MessagePack, and UBJSON are stored in network order (big
+          endian) and therefore need reordering on little endian systems.
+    */
+    template<typename NumberType>
+    void write_number(const NumberType n);
+
+    // UBJSON: write number (floating point)
+    template<typename NumberType, typename std::enable_if<
+                 std::is_floating_point<NumberType>::value, int>::type = 0>
+    void write_number_with_ubjson_prefix(const NumberType n,
+                                         const bool add_prefix)
+    {
+        if (add_prefix)
+        {
+            o << get_ubjson_float_prefix(n);
+        }
+        write_number(n);
+    }
+
+    // UBJSON: write number (unsigned integer)
+    template<typename NumberType, typename std::enable_if<
+                 std::is_unsigned<NumberType>::value, int>::type = 0>
+    void write_number_with_ubjson_prefix(const NumberType n,
+                                         const bool add_prefix);
+
+    // UBJSON: write number (signed integer)
+    template<typename NumberType, typename std::enable_if<
+                 std::is_signed<NumberType>::value and
+                 not std::is_floating_point<NumberType>::value, int>::type = 0>
+    void write_number_with_ubjson_prefix(const NumberType n,
+                                         const bool add_prefix);
+
+    /*!
+    @brief determine the type prefix of container values
+
+    @note This function does not need to be 100% accurate when it comes to
+          integer limits. In case a number exceeds the limits of int64_t,
+          this will be detected by a later call to function
+          write_number_with_ubjson_prefix. Therefore, we return 'L' for any
+          value that does not fit the previous limits.
+    */
+    CharType ubjson_prefix(const json& j) const noexcept;
+
+    static constexpr CharType get_cbor_float_prefix(float)
+    {
+        return static_cast<CharType>(0xFA);  // Single-Precision Float
+    }
+
+    static constexpr CharType get_cbor_float_prefix(double)
+    {
+        return static_cast<CharType>(0xFB);  // Double-Precision Float
+    }
+
+    static constexpr CharType get_msgpack_float_prefix(float)
+    {
+        return static_cast<CharType>(0xCA);  // float 32
+    }
+
+    static constexpr CharType get_msgpack_float_prefix(double)
+    {
+        return static_cast<CharType>(0xCB);  // float 64
+    }
+
+    static constexpr CharType get_ubjson_float_prefix(float)
+    {
+        return 'd';  // float 32
+    }
+
+    static constexpr CharType get_ubjson_float_prefix(double)
+    {
+        return 'D';  // float 64
+    }
+
+  private:
+    static bool little_endianess(int num = 1) noexcept
+    {
+        return (*reinterpret_cast<char*>(&num) == 1);
+    }
+
+    /// whether we can assume little endianess
+    const bool is_little_endian = little_endianess();
+
+    /// the output
+    raw_ostream& o;
+};
+
+void json::binary_writer::write_cbor(const json& j)
+{
+    switch (j.type())
+    {
+        case value_t::null:
+        {
+            o << static_cast<CharType>(0xF6);
+            break;
+        }
+
+        case value_t::boolean:
+        {
+            o << static_cast<CharType>(j.m_value.boolean ? 0xF5 : 0xF4);
+            break;
+        }
+
+        case value_t::number_integer:
+        {
+            if (j.m_value.number_integer >= 0)
+            {
+                // CBOR does not differentiate between positive signed
+                // integers and unsigned integers. Therefore, we used the
+                // code from the value_t::number_unsigned case here.
+                if (j.m_value.number_integer <= 0x17)
+                {
+                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer <= (std::numeric_limits<uint8_t>::max)())
+                {
+                    o << static_cast<CharType>(0x18);
+                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer <= (std::numeric_limits<uint16_t>::max)())
+                {
+                    o << static_cast<CharType>(0x19);
+                    write_number(static_cast<uint16_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer <= (std::numeric_limits<uint32_t>::max)())
+                {
+                    o << static_cast<CharType>(0x1A);
+                    write_number(static_cast<uint32_t>(j.m_value.number_integer));
+                }
+                else
+                {
+                    o << static_cast<CharType>(0x1B);
+                    write_number(static_cast<uint64_t>(j.m_value.number_integer));
+                }
+            }
+            else
+            {
+                // The conversions below encode the sign in the first
+                // byte, and the value is converted to a positive number.
+                const auto positive_number = -1 - j.m_value.number_integer;
+                if (j.m_value.number_integer >= -24)
+                {
+                    write_number(static_cast<uint8_t>(0x20 + positive_number));
+                }
+                else if (positive_number <= (std::numeric_limits<uint8_t>::max)())
+                {
+                    o << static_cast<CharType>(0x38);
+                    write_number(static_cast<uint8_t>(positive_number));
+                }
+                else if (positive_number <= (std::numeric_limits<uint16_t>::max)())
+                {
+                    o << static_cast<CharType>(0x39);
+                    write_number(static_cast<uint16_t>(positive_number));
+                }
+                else if (positive_number <= (std::numeric_limits<uint32_t>::max)())
+                {
+                    o << static_cast<CharType>(0x3A);
+                    write_number(static_cast<uint32_t>(positive_number));
+                }
+                else
+                {
+                    o << static_cast<CharType>(0x3B);
+                    write_number(static_cast<uint64_t>(positive_number));
+                }
+            }
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            if (j.m_value.number_unsigned <= 0x17)
+            {
+                write_number(static_cast<uint8_t>(j.m_value.number_unsigned));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
+            {
+                o << static_cast<CharType>(0x18);
+                write_number(static_cast<uint8_t>(j.m_value.number_unsigned));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
+            {
+                o << static_cast<CharType>(0x19);
+                write_number(static_cast<uint16_t>(j.m_value.number_unsigned));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
+            {
+                o << static_cast<CharType>(0x1A);
+                write_number(static_cast<uint32_t>(j.m_value.number_unsigned));
+            }
+            else
+            {
+                o << static_cast<CharType>(0x1B);
+                write_number(static_cast<uint64_t>(j.m_value.number_unsigned));
+            }
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            o << get_cbor_float_prefix(j.m_value.number_float);
+            write_number(j.m_value.number_float);
+            break;
+        }
+
+        case value_t::string:
+        {
+            write_cbor_string(*j.m_value.string);
+            break;
+        }
+
+        case value_t::array:
+        {
+            // step 1: write control byte and the array size
+            const auto N = j.m_value.array->size();
+            if (N <= 0x17)
+            {
+                write_number(static_cast<uint8_t>(0x80 + N));
+            }
+            else if (N <= (std::numeric_limits<uint8_t>::max)())
+            {
+                o << static_cast<CharType>(0x98);
+                write_number(static_cast<uint8_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint16_t>::max)())
+            {
+                o << static_cast<CharType>(0x99);
+                write_number(static_cast<uint16_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint32_t>::max)())
+            {
+                o << static_cast<CharType>(0x9A);
+                write_number(static_cast<uint32_t>(N));
+            }
+            // LCOV_EXCL_START
+            else if (N <= (std::numeric_limits<uint64_t>::max)())
+            {
+                o << static_cast<CharType>(0x9B);
+                write_number(static_cast<uint64_t>(N));
+            }
+            // LCOV_EXCL_STOP
+
+            // step 2: write each element
+            for (const auto& el : *j.m_value.array)
+            {
+                write_cbor(el);
+            }
+            break;
+        }
+
+        case value_t::object:
+        {
+            // step 1: write control byte and the object size
+            const auto N = j.m_value.object->size();
+            if (N <= 0x17)
+            {
+                write_number(static_cast<uint8_t>(0xA0 + N));
+            }
+            else if (N <= (std::numeric_limits<uint8_t>::max)())
+            {
+                o << static_cast<CharType>(0xB8);
+                write_number(static_cast<uint8_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint16_t>::max)())
+            {
+                o << static_cast<CharType>(0xB9);
+                write_number(static_cast<uint16_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint32_t>::max)())
+            {
+                o << static_cast<CharType>(0xBA);
+                write_number(static_cast<uint32_t>(N));
+            }
+            // LCOV_EXCL_START
+            else /*if (N <= (std::numeric_limits<uint64_t>::max)())*/
+            {
+                o << static_cast<CharType>(0xBB);
+                write_number(static_cast<uint64_t>(N));
+            }
+            // LCOV_EXCL_STOP
+
+            // step 2: write each element
+            for (const auto& el : *j.m_value.object)
+            {
+                write_cbor_string(el.first());
+                write_cbor(el.second);
+            }
+            break;
+        }
+
+        default:
+            break;
+    }
+}
+
+void json::binary_writer::write_msgpack(const json& j)
+{
+    switch (j.type())
+    {
+        case value_t::null: // nil
+        {
+            o << static_cast<CharType>(0xC0);
+            break;
+        }
+
+        case value_t::boolean: // true and false
+        {
+            o << static_cast<CharType>(j.m_value.boolean ? 0xC3 : 0xC2);
+            break;
+        }
+
+        case value_t::number_integer:
+        {
+            if (j.m_value.number_integer >= 0)
+            {
+                // MessagePack does not differentiate between positive
+                // signed integers and unsigned integers. Therefore, we used
+                // the code from the value_t::number_unsigned case here.
+                if (j.m_value.number_unsigned < 128)
+                {
+                    // positive fixnum
+                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
+                {
+                    // uint 8
+                    o << static_cast<CharType>(0xCC);
+                    write_number(static_cast<uint8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
+                {
+                    // uint 16
+                    o << static_cast<CharType>(0xCD);
+                    write_number(static_cast<uint16_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
+                {
+                    // uint 32
+                    o << static_cast<CharType>(0xCE);
+                    write_number(static_cast<uint32_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_unsigned <= (std::numeric_limits<uint64_t>::max)())
+                {
+                    // uint 64
+                    o << static_cast<CharType>(0xCF);
+                    write_number(static_cast<uint64_t>(j.m_value.number_integer));
+                }
+            }
+            else
+            {
+                if (j.m_value.number_integer >= -32)
+                {
+                    // negative fixnum
+                    write_number(static_cast<int8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer >= (std::numeric_limits<int8_t>::min)() and
+                         j.m_value.number_integer <= (std::numeric_limits<int8_t>::max)())
+                {
+                    // int 8
+                    o << static_cast<CharType>(0xD0);
+                    write_number(static_cast<int8_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer >= (std::numeric_limits<int16_t>::min)() and
+                         j.m_value.number_integer <= (std::numeric_limits<int16_t>::max)())
+                {
+                    // int 16
+                    o << static_cast<CharType>(0xD1);
+                    write_number(static_cast<int16_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer >= (std::numeric_limits<int32_t>::min)() and
+                         j.m_value.number_integer <= (std::numeric_limits<int32_t>::max)())
+                {
+                    // int 32
+                    o << static_cast<CharType>(0xD2);
+                    write_number(static_cast<int32_t>(j.m_value.number_integer));
+                }
+                else if (j.m_value.number_integer >= (std::numeric_limits<int64_t>::min)() and
+                         j.m_value.number_integer <= (std::numeric_limits<int64_t>::max)())
+                {
+                    // int 64
+                    o << static_cast<CharType>(0xD3);
+                    write_number(static_cast<int64_t>(j.m_value.number_integer));
+                }
+            }
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            if (j.m_value.number_unsigned < 128)
+            {
+                // positive fixnum
+                write_number(static_cast<uint8_t>(j.m_value.number_integer));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
+            {
+                // uint 8
+                o << static_cast<CharType>(0xCC);
+                write_number(static_cast<uint8_t>(j.m_value.number_integer));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint16_t>::max)())
+            {
+                // uint 16
+                o << static_cast<CharType>(0xCD);
+                write_number(static_cast<uint16_t>(j.m_value.number_integer));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint32_t>::max)())
+            {
+                // uint 32
+                o << static_cast<CharType>(0xCE);
+                write_number(static_cast<uint32_t>(j.m_value.number_integer));
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint64_t>::max)())
+            {
+                // uint 64
+                o << static_cast<CharType>(0xCF);
+                write_number(static_cast<uint64_t>(j.m_value.number_integer));
+            }
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            o << get_msgpack_float_prefix(j.m_value.number_float);
+            write_number(j.m_value.number_float);
+            break;
+        }
+
+        case value_t::string:
+        {
+            write_msgpack_string(*j.m_value.string);
+            break;
+        }
+
+        case value_t::array:
+        {
+            // step 1: write control byte and the array size
+            const auto N = j.m_value.array->size();
+            if (N <= 15)
+            {
+                // fixarray
+                write_number(static_cast<uint8_t>(0x90 | N));
+            }
+            else if (N <= (std::numeric_limits<uint16_t>::max)())
+            {
+                // array 16
+                o << static_cast<CharType>(0xDC);
+                write_number(static_cast<uint16_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint32_t>::max)())
+            {
+                // array 32
+                o << static_cast<CharType>(0xDD);
+                write_number(static_cast<uint32_t>(N));
+            }
+
+            // step 2: write each element
+            for (const auto& el : *j.m_value.array)
+            {
+                write_msgpack(el);
+            }
+            break;
+        }
+
+        case value_t::object:
+        {
+            // step 1: write control byte and the object size
+            const auto N = j.m_value.object->size();
+            if (N <= 15)
+            {
+                // fixmap
+                write_number(static_cast<uint8_t>(0x80 | (N & 0xF)));
+            }
+            else if (N <= (std::numeric_limits<uint16_t>::max)())
+            {
+                // map 16
+                o << static_cast<CharType>(0xDE);
+                write_number(static_cast<uint16_t>(N));
+            }
+            else if (N <= (std::numeric_limits<uint32_t>::max)())
+            {
+                // map 32
+                o << static_cast<CharType>(0xDF);
+                write_number(static_cast<uint32_t>(N));
+            }
+
+            // step 2: write each element
+            for (const auto& el : *j.m_value.object)
+            {
+                write_msgpack_string(el.first());
+                write_msgpack(el.second);
+            }
+            break;
+        }
+
+        default:
+            break;
+    }
+}
+
+void json::binary_writer::write_ubjson(const json& j, const bool use_count,
+                  const bool use_type, const bool add_prefix)
+{
+    switch (j.type())
+    {
+        case value_t::null:
+        {
+            if (add_prefix)
+            {
+                o << static_cast<CharType>('Z');
+            }
+            break;
+        }
+
+        case value_t::boolean:
+        {
+            if (add_prefix)
+                o << static_cast<CharType>(j.m_value.boolean ? 'T' : 'F');
+            break;
+        }
+
+        case value_t::number_integer:
+        {
+            write_number_with_ubjson_prefix(j.m_value.number_integer, add_prefix);
+            break;
+        }
+
+        case value_t::number_unsigned:
+        {
+            write_number_with_ubjson_prefix(j.m_value.number_unsigned, add_prefix);
+            break;
+        }
+
+        case value_t::number_float:
+        {
+            write_number_with_ubjson_prefix(j.m_value.number_float, add_prefix);
+            break;
+        }
+
+        case value_t::string:
+        {
+            if (add_prefix)
+            {
+                o << static_cast<CharType>('S');
+            }
+            write_number_with_ubjson_prefix(j.m_value.string->size(), true);
+            o << j.m_value.string;
+            break;
+        }
+
+        case value_t::array:
+        {
+            if (add_prefix)
+            {
+                o << static_cast<CharType>('[');
+            }
+
+            bool prefix_required = true;
+            if (use_type and not j.m_value.array->empty())
+            {
+                assert(use_count);
+                const CharType first_prefix = ubjson_prefix(j.front());
+                const bool same_prefix = std::all_of(j.begin() + 1, j.end(),
+                                                     [this, first_prefix](const json & v)
+                {
+                    return ubjson_prefix(v) == first_prefix;
+                });
+
+                if (same_prefix)
+                {
+                    prefix_required = false;
+                    o << static_cast<CharType>('$');
+                    o << first_prefix;
+                }
+            }
+
+            if (use_count)
+            {
+                o << static_cast<CharType>('#');
+                write_number_with_ubjson_prefix(j.m_value.array->size(), true);
+            }
+
+            for (const auto& el : *j.m_value.array)
+            {
+                write_ubjson(el, use_count, use_type, prefix_required);
+            }
+
+            if (not use_count)
+            {
+                o << static_cast<CharType>(']');
+            }
+
+            break;
+        }
+
+        case value_t::object:
+        {
+            if (add_prefix)
+            {
+                o << static_cast<CharType>('{');
+            }
+
+            bool prefix_required = true;
+            if (use_type and not j.m_value.object->empty())
+            {
+                assert(use_count);
+                const CharType first_prefix = ubjson_prefix(j.front());
+                const bool same_prefix = std::all_of(j.begin(), j.end(),
+                                                     [this, first_prefix](const json & v)
+                {
+                    return ubjson_prefix(v) == first_prefix;
+                });
+
+                if (same_prefix)
+                {
+                    prefix_required = false;
+                    o << static_cast<CharType>('$');
+                    o << first_prefix;
+                }
+            }
+
+            if (use_count)
+            {
+                o << static_cast<CharType>('#');
+                write_number_with_ubjson_prefix(j.m_value.object->size(), true);
+            }
+
+            for (const auto& el : *j.m_value.object)
+            {
+                write_number_with_ubjson_prefix(el.first().size(), true);
+                o << el.first();
+                write_ubjson(el.second, use_count, use_type, prefix_required);
+            }
+
+            if (not use_count)
+            {
+                o << static_cast<CharType>('}');
+            }
+
+            break;
+        }
+
+        default:
+            break;
+    }
+}
+
+void json::binary_writer::write_cbor_string(StringRef str)
+{
+    // step 1: write control byte and the string length
+    const auto N = str.size();
+    if (N <= 0x17)
+    {
+        write_number(static_cast<uint8_t>(0x60 + N));
+    }
+    else if (N <= (std::numeric_limits<uint8_t>::max)())
+    {
+        o << static_cast<CharType>(0x78);
+        write_number(static_cast<uint8_t>(N));
+    }
+    else if (N <= (std::numeric_limits<uint16_t>::max)())
+    {
+        o << static_cast<CharType>(0x79);
+        write_number(static_cast<uint16_t>(N));
+    }
+    else if (N <= (std::numeric_limits<uint32_t>::max)())
+    {
+        o << static_cast<CharType>(0x7A);
+        write_number(static_cast<uint32_t>(N));
+    }
+    // LCOV_EXCL_START
+    else if (N <= (std::numeric_limits<uint64_t>::max)())
+    {
+        o << static_cast<CharType>(0x7B);
+        write_number(static_cast<uint64_t>(N));
+    }
+    // LCOV_EXCL_STOP
+
+    // step 2: write the string
+    o << str;
+}
+
+void json::binary_writer::write_msgpack_string(StringRef str)
+{
+    // step 1: write control byte and the string length
+    const auto N = str.size();
+    if (N <= 31)
+    {
+        // fixstr
+        write_number(static_cast<uint8_t>(0xA0 | N));
+    }
+    else if (N <= (std::numeric_limits<uint8_t>::max)())
+    {
+        // str 8
+        o << static_cast<CharType>(0xD9);
+        write_number(static_cast<uint8_t>(N));
+    }
+    else if (N <= (std::numeric_limits<uint16_t>::max)())
+    {
+        // str 16
+        o << static_cast<CharType>(0xDA);
+        write_number(static_cast<uint16_t>(N));
+    }
+    else if (N <= (std::numeric_limits<uint32_t>::max)())
+    {
+        // str 32
+        o << static_cast<CharType>(0xDB);
+        write_number(static_cast<uint32_t>(N));
+    }
+
+    // step 2: write the string
+    o << str;
+}
+
+template<typename NumberType>
+void json::binary_writer::write_number(const NumberType n)
+{
+    // step 1: write number to array of length NumberType
+    std::array<uint8_t, sizeof(NumberType)> vec;
+    std::memcpy(vec.data(), &n, sizeof(NumberType));
+
+    // step 2: write array to output (with possible reordering)
+    if (is_little_endian)
+    {
+        // reverse byte order prior to conversion if necessary
+        std::reverse(vec.begin(), vec.end());
+    }
+
+    o << ArrayRef<uint8_t>(vec.data(), sizeof(NumberType));
+}
+
+template<typename NumberType, typename std::enable_if<
+             std::is_unsigned<NumberType>::value, int>::type>
+void json::binary_writer::write_number_with_ubjson_prefix(const NumberType n,
+                                     const bool add_prefix)
+{
+    if (n <= static_cast<uint64_t>((std::numeric_limits<int8_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('i');  // int8
+        }
+        write_number(static_cast<uint8_t>(n));
+    }
+    else if (n <= (std::numeric_limits<uint8_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('U');  // uint8
+        }
+        write_number(static_cast<uint8_t>(n));
+    }
+    else if (n <= static_cast<uint64_t>((std::numeric_limits<int16_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('I');  // int16
+        }
+        write_number(static_cast<int16_t>(n));
+    }
+    else if (n <= static_cast<uint64_t>((std::numeric_limits<int32_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('l');  // int32
+        }
+        write_number(static_cast<int32_t>(n));
+    }
+    else if (n <= static_cast<uint64_t>((std::numeric_limits<int64_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('L');  // int64
+        }
+        write_number(static_cast<int64_t>(n));
+    }
+    else
+    {
+        JSON_THROW(out_of_range::create(407, "number overflow serializing " + Twine(n)));
+    }
+}
+
+template<typename NumberType, typename std::enable_if<
+             std::is_signed<NumberType>::value and
+             not std::is_floating_point<NumberType>::value, int>::type>
+void json::binary_writer::write_number_with_ubjson_prefix(const NumberType n,
+                                     const bool add_prefix)
+{
+    if ((std::numeric_limits<int8_t>::min)() <= n and n <= (std::numeric_limits<int8_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('i');  // int8
+        }
+        write_number(static_cast<int8_t>(n));
+    }
+    else if (static_cast<int64_t>((std::numeric_limits<uint8_t>::min)()) <= n and n <= static_cast<int64_t>((std::numeric_limits<uint8_t>::max)()))
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('U');  // uint8
+        }
+        write_number(static_cast<uint8_t>(n));
+    }
+    else if ((std::numeric_limits<int16_t>::min)() <= n and n <= (std::numeric_limits<int16_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('I');  // int16
+        }
+        write_number(static_cast<int16_t>(n));
+    }
+    else if ((std::numeric_limits<int32_t>::min)() <= n and n <= (std::numeric_limits<int32_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('l');  // int32
+        }
+        write_number(static_cast<int32_t>(n));
+    }
+    else if ((std::numeric_limits<int64_t>::min)() <= n and n <= (std::numeric_limits<int64_t>::max)())
+    {
+        if (add_prefix)
+        {
+            o << static_cast<CharType>('L');  // int64
+        }
+        write_number(static_cast<int64_t>(n));
+    }
+    // LCOV_EXCL_START
+    else
+    {
+        JSON_THROW(out_of_range::create(407, "number overflow serializing " + Twine(n)));
+    }
+    // LCOV_EXCL_STOP
+}
+
+json::binary_writer::CharType json::binary_writer::ubjson_prefix(const json& j) const noexcept
+{
+    switch (j.type())
+    {
+        case value_t::null:
+            return 'Z';
+
+        case value_t::boolean:
+            return j.m_value.boolean ? 'T' : 'F';
+
+        case value_t::number_integer:
+        {
+            if ((std::numeric_limits<int8_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int8_t>::max)())
+            {
+                return 'i';
+            }
+            else if ((std::numeric_limits<uint8_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<uint8_t>::max)())
+            {
+                return 'U';
+            }
+            else if ((std::numeric_limits<int16_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int16_t>::max)())
+            {
+                return 'I';
+            }
+            else if ((std::numeric_limits<int32_t>::min)() <= j.m_value.number_integer and j.m_value.number_integer <= (std::numeric_limits<int32_t>::max)())
+            {
+                return 'l';
+            }
+            else  // no check and assume int64_t (see note above)
+            {
+                return 'L';
+            }
+        }
+
+        case value_t::number_unsigned:
+        {
+            if (j.m_value.number_unsigned <= (std::numeric_limits<int8_t>::max)())
+            {
+                return 'i';
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<uint8_t>::max)())
+            {
+                return 'U';
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<int16_t>::max)())
+            {
+                return 'I';
+            }
+            else if (j.m_value.number_unsigned <= (std::numeric_limits<int32_t>::max)())
+            {
+                return 'l';
+            }
+            else  // no check and assume int64_t (see note above)
+            {
+                return 'L';
+            }
+        }
+
+        case value_t::number_float:
+            return get_ubjson_float_prefix(j.m_value.number_float);
+
+        case value_t::string:
+            return 'S';
+
+        case value_t::array:
+            return '[';
+
+        case value_t::object:
+            return '{';
+
+        default:  // discarded values
+            return 'N';
+    }
+}
+
+std::vector<uint8_t> json::to_cbor(const json& j)
+{
+    std::vector<uint8_t> result;
+    raw_uvector_ostream os(result);
+    to_cbor(os, j);
+    return result;
+}
+
+ArrayRef<uint8_t> json::to_cbor(const json& j, std::vector<uint8_t>& buf)
+{
+    buf.clear();
+    raw_uvector_ostream os(buf);
+    to_cbor(os, j);
+    return os.array();
+}
+
+ArrayRef<uint8_t> json::to_cbor(const json& j, SmallVectorImpl<uint8_t>& buf)
+{
+    buf.clear();
+    raw_usvector_ostream os(buf);
+    to_cbor(os, j);
+    return os.array();
+}
+
+void json::to_cbor(raw_ostream& os, const json& j)
+{
+    binary_writer(os).write_cbor(j);
+}
+
+std::vector<uint8_t> json::to_msgpack(const json& j)
+{
+    std::vector<uint8_t> result;
+    raw_uvector_ostream os(result);
+    to_msgpack(os, j);
+    return result;
+}
+
+ArrayRef<uint8_t> json::to_msgpack(const json& j, std::vector<uint8_t>& buf)
+{
+    buf.clear();
+    raw_uvector_ostream os(buf);
+    to_msgpack(os, j);
+    return os.array();
+}
+
+ArrayRef<uint8_t> json::to_msgpack(const json& j, SmallVectorImpl<uint8_t>& buf)
+{
+    buf.clear();
+    raw_usvector_ostream os(buf);
+    to_msgpack(os, j);
+    return os.array();
+}
+
+void json::to_msgpack(raw_ostream& os, const json& j)
+{
+    binary_writer(os).write_msgpack(j);
+}
+
+std::vector<uint8_t> json::to_ubjson(const json& j,
+                                     const bool use_size,
+                                     const bool use_type)
+{
+    std::vector<uint8_t> result;
+    raw_uvector_ostream os(result);
+    to_ubjson(os, j, use_size, use_type);
+    return result;
+}
+
+ArrayRef<uint8_t> json::to_ubjson(const json& j, std::vector<uint8_t>& buf,
+                                  const bool use_size, const bool use_type)
+{
+    buf.clear();
+    raw_uvector_ostream os(buf);
+    to_ubjson(os, j, use_size, use_type);
+    return os.array();
+}
+
+ArrayRef<uint8_t> json::to_ubjson(const json& j, SmallVectorImpl<uint8_t>& buf,
+                                  const bool use_size, const bool use_type)
+{
+    buf.clear();
+    raw_usvector_ostream os(buf);
+    to_ubjson(os, j, use_size, use_type);
+    return os.array();
+}
+
+void json::to_ubjson(raw_ostream& os, const json& j,
+                     const bool use_size, const bool use_type)
+{
+    binary_writer(os).write_ubjson(j, use_size, use_type);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_parser.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_parser.cpp
new file mode 100644
index 0000000..e0d7db3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_parser.cpp
@@ -0,0 +1,1968 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include <clocale>
+#include <cmath>
+#include <cstdlib>
+
+#include "wpi/Format.h"
+#include "wpi/SmallString.h"
+#include "wpi/raw_istream.h"
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+/*!
+@brief lexical analysis
+
+This class organizes the lexical analysis during JSON deserialization.
+*/
+class json::lexer
+{
+  public:
+    /// token types for the parser
+    enum class token_type
+    {
+        uninitialized,    ///< indicating the scanner is uninitialized
+        literal_true,     ///< the `true` literal
+        literal_false,    ///< the `false` literal
+        literal_null,     ///< the `null` literal
+        value_string,     ///< a string -- use get_string() for actual value
+        value_unsigned,   ///< an unsigned integer -- use get_number_unsigned() for actual value
+        value_integer,    ///< a signed integer -- use get_number_integer() for actual value
+        value_float,      ///< an floating point number -- use get_number_float() for actual value
+        begin_array,      ///< the character for array begin `[`
+        begin_object,     ///< the character for object begin `{`
+        end_array,        ///< the character for array end `]`
+        end_object,       ///< the character for object end `}`
+        name_separator,   ///< the name separator `:`
+        value_separator,  ///< the value separator `,`
+        parse_error,      ///< indicating a parse error
+        end_of_input,     ///< indicating the end of the input buffer
+        literal_or_value  ///< a literal or the begin of a value (only for diagnostics)
+    };
+
+    /// return name of values of type token_type (only used for errors)
+    static const char* token_type_name(const token_type t) noexcept;
+
+    explicit lexer(raw_istream& s);
+
+    // delete because of pointer members
+    lexer(const lexer&) = delete;
+    lexer& operator=(lexer&) = delete;
+
+  private:
+    /////////////////////
+    // locales
+    /////////////////////
+
+    /// return the locale-dependent decimal point
+    static char get_decimal_point() noexcept
+    {
+        const auto loc = localeconv();
+        assert(loc != nullptr);
+        return (loc->decimal_point == nullptr) ? '.' : *(loc->decimal_point);
+    }
+
+    /////////////////////
+    // scan functions
+    /////////////////////
+
+    /*!
+    @brief get codepoint from 4 hex characters following `\u`
+
+    For input "\u c1 c2 c3 c4" the codepoint is:
+      (c1 * 0x1000) + (c2 * 0x0100) + (c3 * 0x0010) + c4
+    = (c1 << 12) + (c2 << 8) + (c3 << 4) + (c4 << 0)
+
+    Furthermore, the possible characters '0'..'9', 'A'..'F', and 'a'..'f'
+    must be converted to the integers 0x0..0x9, 0xA..0xF, 0xA..0xF, resp. The
+    conversion is done by subtracting the offset (0x30, 0x37, and 0x57)
+    between the ASCII value of the character and the desired integer value.
+
+    @return codepoint (0x0000..0xFFFF) or -1 in case of an error (e.g. EOF or
+            non-hex character)
+    */
+    int get_codepoint();
+
+    /*!
+    @brief check if the next byte(s) are inside a given range
+
+    Adds the current byte and, for each passed range, reads a new byte and
+    checks if it is inside the range. If a violation was detected, set up an
+    error message and return false. Otherwise, return true.
+
+    @param[in] ranges  list of integers; interpreted as list of pairs of
+                       inclusive lower and upper bound, respectively
+
+    @pre The passed list @a ranges must have 2, 4, or 6 elements; that is,
+         1, 2, or 3 pairs. This precondition is enforced by an assertion.
+
+    @return true if and only if no range violation was detected
+    */
+    bool next_byte_in_range(std::initializer_list<int> ranges)
+    {
+        assert(ranges.size() == 2 or ranges.size() == 4 or ranges.size() == 6);
+        add(current);
+
+        for (auto range = ranges.begin(); range != ranges.end(); ++range)
+        {
+            get();
+            if (JSON_LIKELY(*range <= current and current <= *(++range)))
+            {
+                add(current);
+            }
+            else
+            {
+                error_message = "invalid string: ill-formed UTF-8 byte";
+                return false;
+            }
+        }
+
+        return true;
+    }
+
+    /*!
+    @brief scan a string literal
+
+    This function scans a string according to Sect. 7 of RFC 7159. While
+    scanning, bytes are escaped and copied into buffer token_buffer. Then the
+    function returns successfully, token_buffer is *not* null-terminated (as it
+    may contain \0 bytes), and token_buffer.size() is the number of bytes in the
+    string.
+
+    @return token_type::value_string if string could be successfully scanned,
+            token_type::parse_error otherwise
+
+    @note In case of errors, variable error_message contains a textual
+          description.
+    */
+    token_type scan_string();
+
+    static void strtof(float& f, const char* str, char** endptr) noexcept
+    {
+        f = std::strtof(str, endptr);
+    }
+
+    static void strtof(double& f, const char* str, char** endptr) noexcept
+    {
+        f = std::strtod(str, endptr);
+    }
+
+    static void strtof(long double& f, const char* str, char** endptr) noexcept
+    {
+        f = std::strtold(str, endptr);
+    }
+
+    /*!
+    @brief scan a number literal
+
+    This function scans a string according to Sect. 6 of RFC 7159.
+
+    The function is realized with a deterministic finite state machine derived
+    from the grammar described in RFC 7159. Starting in state "init", the
+    input is read and used to determined the next state. Only state "done"
+    accepts the number. State "error" is a trap state to model errors. In the
+    table below, "anything" means any character but the ones listed before.
+
+    state    | 0        | 1-9      | e E      | +       | -       | .        | anything
+    ---------|----------|----------|----------|---------|---------|----------|-----------
+    init     | zero     | any1     | [error]  | [error] | minus   | [error]  | [error]
+    minus    | zero     | any1     | [error]  | [error] | [error] | [error]  | [error]
+    zero     | done     | done     | exponent | done    | done    | decimal1 | done
+    any1     | any1     | any1     | exponent | done    | done    | decimal1 | done
+    decimal1 | decimal2 | [error]  | [error]  | [error] | [error] | [error]  | [error]
+    decimal2 | decimal2 | decimal2 | exponent | done    | done    | done     | done
+    exponent | any2     | any2     | [error]  | sign    | sign    | [error]  | [error]
+    sign     | any2     | any2     | [error]  | [error] | [error] | [error]  | [error]
+    any2     | any2     | any2     | done     | done    | done    | done     | done
+
+    The state machine is realized with one label per state (prefixed with
+    "scan_number_") and `goto` statements between them. The state machine
+    contains cycles, but any cycle can be left when EOF is read. Therefore,
+    the function is guaranteed to terminate.
+
+    During scanning, the read bytes are stored in token_buffer. This string is
+    then converted to a signed integer, an unsigned integer, or a
+    floating-point number.
+
+    @return token_type::value_unsigned, token_type::value_integer, or
+            token_type::value_float if number could be successfully scanned,
+            token_type::parse_error otherwise
+
+    @note The scanner is independent of the current locale. Internally, the
+          locale's decimal point is used instead of `.` to work with the
+          locale-dependent converters.
+    */
+    token_type scan_number();
+
+    /*!
+    @param[in] literal_text  the literal text to expect
+    @param[in] length        the length of the passed literal text
+    @param[in] return_type   the token type to return on success
+    */
+    token_type scan_literal(const char* literal_text, const std::size_t length,
+                            token_type return_type);
+
+    /////////////////////
+    // input management
+    /////////////////////
+
+    /// reset token_buffer; current character is beginning of token
+    void reset() noexcept
+    {
+        token_buffer.clear();
+        token_string.clear();
+        token_string.push_back(std::char_traits<char>::to_char_type(current));
+    }
+
+    /*
+    @brief get next character from the input
+
+    This function provides the interface to the used input adapter. It does
+    not throw in case the input reached EOF, but returns a
+    `std::char_traits<char>::eof()` in that case.  Stores the scanned characters
+    for use in error messages.
+
+    @return character read from the input
+    */
+    std::char_traits<char>::int_type get()
+    {
+        ++chars_read;
+        if (JSON_UNLIKELY(!unget_chars.empty()))
+        {
+            current = unget_chars.back();
+            unget_chars.pop_back();
+            token_string.push_back(current);
+            return current;
+        }
+        char c;
+        is.read(c);
+        if (JSON_UNLIKELY(is.has_error()))
+        {
+            current = std::char_traits<char>::eof();
+        }
+        else
+        {
+            current = std::char_traits<char>::to_int_type(c);
+            token_string.push_back(c);
+        }
+        return current;
+    }
+
+    /// unget current character (return it again on next get)
+    void unget()
+    {
+        --chars_read;
+        if (JSON_LIKELY(current != std::char_traits<char>::eof()))
+        {
+            unget_chars.emplace_back(current);
+            assert(token_string.size() != 0);
+            token_string.pop_back();
+            if (!token_string.empty())
+            {
+                current = token_string.back();
+            }
+        }
+    }
+
+    /// put back character (returned on next get)
+    void putback(std::char_traits<char>::int_type c)
+    {
+        --chars_read;
+        unget_chars.emplace_back(c);
+    }
+
+    /// add a character to token_buffer
+    void add(int c)
+    {
+        token_buffer.push_back(std::char_traits<char>::to_char_type(c));
+    }
+
+  public:
+    /////////////////////
+    // value getters
+    /////////////////////
+
+    /// return integer value
+    int64_t get_number_integer() const noexcept
+    {
+        return value_integer;
+    }
+
+    /// return unsigned integer value
+    uint64_t get_number_unsigned() const noexcept
+    {
+        return value_unsigned;
+    }
+
+    /// return floating-point value
+    double get_number_float() const noexcept
+    {
+        return value_float;
+    }
+
+    /// return current string value
+    StringRef get_string()
+    {
+        return token_buffer;
+    }
+
+    /////////////////////
+    // diagnostics
+    /////////////////////
+
+    /// return position of last read token
+    std::size_t get_position() const noexcept
+    {
+        return chars_read;
+    }
+
+    /// return the last read token (for errors only).  Will never contain EOF
+    /// (an arbitrary value that is not a valid char value, often -1), because
+    /// 255 may legitimately occur.  May contain NUL, which should be escaped.
+    std::string get_token_string() const;
+
+    /// return syntax error message
+    const char* get_error_message() const noexcept
+    {
+        return error_message;
+    }
+
+    /////////////////////
+    // actual scanner
+    /////////////////////
+
+    token_type scan();
+
+  private:
+    /// input adapter
+    raw_istream& is;
+
+    /// the current character
+    std::char_traits<char>::int_type current = std::char_traits<char>::eof();
+
+    /// unget characters
+    SmallVector<std::char_traits<char>::int_type, 4> unget_chars;
+
+    /// the number of characters read
+    std::size_t chars_read = 0;
+
+    /// raw input token string (for error messages)
+    SmallString<128> token_string {};
+
+    /// buffer for variable-length tokens (numbers, strings)
+    SmallString<128> token_buffer {};
+
+    /// a description of occurred lexer errors
+    const char* error_message = "";
+
+    // number values
+    int64_t value_integer = 0;
+    uint64_t value_unsigned = 0;
+    double value_float = 0;
+
+    /// the decimal point
+    const char decimal_point_char = '.';
+};
+
+////////////
+// parser //
+////////////
+
+/*!
+@brief syntax analysis
+
+This class implements a recursive decent parser.
+*/
+class json::parser
+{
+    using lexer_t = json::lexer;
+    using token_type = typename lexer_t::token_type;
+
+  public:
+    /// a parser reading from an input adapter
+    explicit parser(raw_istream& s,
+                    const parser_callback_t cb = nullptr,
+                    const bool allow_exceptions_ = true)
+        : callback(cb), m_lexer(s), allow_exceptions(allow_exceptions_)
+    {}
+
+    /*!
+    @brief public parser interface
+
+    @param[in] strict      whether to expect the last token to be EOF
+    @param[in,out] result  parsed JSON value
+
+    @throw parse_error.101 in case of an unexpected token
+    @throw parse_error.102 if to_unicode fails or surrogate error
+    @throw parse_error.103 if to_unicode fails
+    */
+    void parse(const bool strict, json& result);
+
+    /*!
+    @brief public accept interface
+
+    @param[in] strict  whether to expect the last token to be EOF
+    @return whether the input is a proper JSON text
+    */
+    bool accept(const bool strict = true)
+    {
+        // read first token
+        get_token();
+
+        if (not accept_internal())
+        {
+            return false;
+        }
+
+        // strict => last token must be EOF
+        return not strict or (get_token() == token_type::end_of_input);
+    }
+
+  private:
+    /*!
+    @brief the actual parser
+    @throw parse_error.101 in case of an unexpected token
+    @throw parse_error.102 if to_unicode fails or surrogate error
+    @throw parse_error.103 if to_unicode fails
+    */
+    void parse_internal(bool keep, json& result);
+
+    /*!
+    @brief the actual acceptor
+
+    @invariant 1. The last token is not yet processed. Therefore, the caller
+                  of this function must make sure a token has been read.
+               2. When this function returns, the last token is processed.
+                  That is, the last read character was already considered.
+
+    This invariant makes sure that no token needs to be "unput".
+    */
+    bool accept_internal();
+
+    /// get next token from lexer
+    token_type get_token()
+    {
+        return (last_token = m_lexer.scan());
+    }
+
+    /*!
+    @throw parse_error.101 if expected token did not occur
+    */
+    bool expect(token_type t)
+    {
+        if (JSON_UNLIKELY(t != last_token))
+        {
+            errored = true;
+            expected = t;
+            if (allow_exceptions)
+            {
+                throw_exception();
+            }
+            else
+            {
+                return false;
+            }
+        }
+
+        return true;
+    }
+
+    [[noreturn]] void throw_exception() const;
+
+  private:
+    /// current level of recursion
+    int depth = 0;
+    /// callback function
+    const parser_callback_t callback = nullptr;
+    /// the type of the last read token
+    token_type last_token = token_type::uninitialized;
+    /// the lexer
+    lexer_t m_lexer;
+    /// whether a syntax error occurred
+    bool errored = false;
+    /// possible reason for the syntax error
+    token_type expected = token_type::uninitialized;
+    /// whether to throw exceptions in case of errors
+    const bool allow_exceptions = true;
+};
+
+const char* json::lexer::token_type_name(const token_type t) noexcept
+{
+    switch (t)
+    {
+        case token_type::uninitialized:
+            return "<uninitialized>";
+        case token_type::literal_true:
+            return "true literal";
+        case token_type::literal_false:
+            return "false literal";
+        case token_type::literal_null:
+            return "null literal";
+        case token_type::value_string:
+            return "string literal";
+        case lexer::token_type::value_unsigned:
+        case lexer::token_type::value_integer:
+        case lexer::token_type::value_float:
+            return "number literal";
+        case token_type::begin_array:
+            return "'['";
+        case token_type::begin_object:
+            return "'{'";
+        case token_type::end_array:
+            return "']'";
+        case token_type::end_object:
+            return "'}'";
+        case token_type::name_separator:
+            return "':'";
+        case token_type::value_separator:
+            return "','";
+        case token_type::parse_error:
+            return "<parse error>";
+        case token_type::end_of_input:
+            return "end of input";
+        case token_type::literal_or_value:
+            return "'[', '{', or a literal";
+        default: // catch non-enum values
+            return "unknown token"; // LCOV_EXCL_LINE
+    }
+}
+
+json::lexer::lexer(raw_istream& s)
+    : is(s), decimal_point_char(get_decimal_point())
+{
+    // skip byte order mark
+    std::char_traits<char>::int_type c;
+    if ((c = get()) == 0xEF)
+    {
+        if ((c = get()) == 0xBB)
+        {
+            if ((c = get()) == 0xBF)
+            {
+                chars_read = 0;
+                return; // Ignore BOM
+            }
+            else if (c != std::char_traits<char>::eof())
+            {
+                unget();
+            }
+            putback('\xBB');
+        }
+        else if (c != std::char_traits<char>::eof())
+        {
+            unget();
+        }
+        putback('\xEF');
+    }
+    unget(); // no byte order mark; process as usual
+}
+
+int json::lexer::get_codepoint()
+{
+    // this function only makes sense after reading `\u`
+    assert(current == 'u');
+    int codepoint = 0;
+
+    const auto factors = { 12, 8, 4, 0 };
+    for (const auto factor : factors)
+    {
+        get();
+
+        if (current >= '0' and current <= '9')
+        {
+            codepoint += ((current - 0x30) << factor);
+        }
+        else if (current >= 'A' and current <= 'F')
+        {
+            codepoint += ((current - 0x37) << factor);
+        }
+        else if (current >= 'a' and current <= 'f')
+        {
+            codepoint += ((current - 0x57) << factor);
+        }
+        else
+        {
+            return -1;
+        }
+    }
+
+    assert(0x0000 <= codepoint and codepoint <= 0xFFFF);
+    return codepoint;
+}
+
+json::lexer::token_type json::lexer::scan_string()
+{
+    // reset token_buffer (ignore opening quote)
+    reset();
+
+    // we entered the function by reading an open quote
+    assert(current == '\"');
+
+    while (true)
+    {
+        // get next character
+        switch (get())
+        {
+            // end of file while parsing string
+            case std::char_traits<char>::eof():
+            {
+                error_message = "invalid string: missing closing quote";
+                return token_type::parse_error;
+            }
+
+            // closing quote
+            case '\"':
+            {
+                return token_type::value_string;
+            }
+
+            // escapes
+            case '\\':
+            {
+                switch (get())
+                {
+                    // quotation mark
+                    case '\"':
+                        add('\"');
+                        break;
+                    // reverse solidus
+                    case '\\':
+                        add('\\');
+                        break;
+                    // solidus
+                    case '/':
+                        add('/');
+                        break;
+                    // backspace
+                    case 'b':
+                        add('\b');
+                        break;
+                    // form feed
+                    case 'f':
+                        add('\f');
+                        break;
+                    // line feed
+                    case 'n':
+                        add('\n');
+                        break;
+                    // carriage return
+                    case 'r':
+                        add('\r');
+                        break;
+                    // tab
+                    case 't':
+                        add('\t');
+                        break;
+
+                    // unicode escapes
+                    case 'u':
+                    {
+                        const int codepoint1 = get_codepoint();
+                        int codepoint = codepoint1; // start with codepoint1
+
+                        if (JSON_UNLIKELY(codepoint1 == -1))
+                        {
+                            error_message = "invalid string: '\\u' must be followed by 4 hex digits";
+                            return token_type::parse_error;
+                        }
+
+                        // check if code point is a high surrogate
+                        if (0xD800 <= codepoint1 and codepoint1 <= 0xDBFF)
+                        {
+                            // expect next \uxxxx entry
+                            if (JSON_LIKELY(get() == '\\' and get() == 'u'))
+                            {
+                                const int codepoint2 = get_codepoint();
+
+                                if (JSON_UNLIKELY(codepoint2 == -1))
+                                {
+                                    error_message = "invalid string: '\\u' must be followed by 4 hex digits";
+                                    return token_type::parse_error;
+                                }
+
+                                // check if codepoint2 is a low surrogate
+                                if (JSON_LIKELY(0xDC00 <= codepoint2 and codepoint2 <= 0xDFFF))
+                                {
+                                    // overwrite codepoint
+                                    codepoint =
+                                        // high surrogate occupies the most significant 22 bits
+                                        (codepoint1 << 10)
+                                        // low surrogate occupies the least significant 15 bits
+                                        + codepoint2
+                                        // there is still the 0xD800, 0xDC00 and 0x10000 noise
+                                        // in the result so we have to subtract with:
+                                        // (0xD800 << 10) + DC00 - 0x10000 = 0x35FDC00
+                                        - 0x35FDC00;
+                                }
+                                else
+                                {
+                                    error_message = "invalid string: surrogate U+DC00..U+DFFF must be followed by U+DC00..U+DFFF";
+                                    return token_type::parse_error;
+                                }
+                            }
+                            else
+                            {
+                                error_message = "invalid string: surrogate U+DC00..U+DFFF must be followed by U+DC00..U+DFFF";
+                                return token_type::parse_error;
+                            }
+                        }
+                        else
+                        {
+                            if (JSON_UNLIKELY(0xDC00 <= codepoint1 and codepoint1 <= 0xDFFF))
+                            {
+                                error_message = "invalid string: surrogate U+DC00..U+DFFF must follow U+D800..U+DBFF";
+                                return token_type::parse_error;
+                            }
+                        }
+
+                        // result of the above calculation yields a proper codepoint
+                        assert(0x00 <= codepoint and codepoint <= 0x10FFFF);
+
+                        // translate codepoint into bytes
+                        if (codepoint < 0x80)
+                        {
+                            // 1-byte characters: 0xxxxxxx (ASCII)
+                            add(codepoint);
+                        }
+                        else if (codepoint <= 0x7FF)
+                        {
+                            // 2-byte characters: 110xxxxx 10xxxxxx
+                            add(0xC0 | (codepoint >> 6));
+                            add(0x80 | (codepoint & 0x3F));
+                        }
+                        else if (codepoint <= 0xFFFF)
+                        {
+                            // 3-byte characters: 1110xxxx 10xxxxxx 10xxxxxx
+                            add(0xE0 | (codepoint >> 12));
+                            add(0x80 | ((codepoint >> 6) & 0x3F));
+                            add(0x80 | (codepoint & 0x3F));
+                        }
+                        else
+                        {
+                            // 4-byte characters: 11110xxx 10xxxxxx 10xxxxxx 10xxxxxx
+                            add(0xF0 | (codepoint >> 18));
+                            add(0x80 | ((codepoint >> 12) & 0x3F));
+                            add(0x80 | ((codepoint >> 6) & 0x3F));
+                            add(0x80 | (codepoint & 0x3F));
+                        }
+
+                        break;
+                    }
+
+                    // other characters after escape
+                    default:
+                        error_message = "invalid string: forbidden character after backslash";
+                        return token_type::parse_error;
+                }
+
+                break;
+            }
+
+            // invalid control characters
+            case 0x00:
+            case 0x01:
+            case 0x02:
+            case 0x03:
+            case 0x04:
+            case 0x05:
+            case 0x06:
+            case 0x07:
+            case 0x08:
+            case 0x09:
+            case 0x0A:
+            case 0x0B:
+            case 0x0C:
+            case 0x0D:
+            case 0x0E:
+            case 0x0F:
+            case 0x10:
+            case 0x11:
+            case 0x12:
+            case 0x13:
+            case 0x14:
+            case 0x15:
+            case 0x16:
+            case 0x17:
+            case 0x18:
+            case 0x19:
+            case 0x1A:
+            case 0x1B:
+            case 0x1C:
+            case 0x1D:
+            case 0x1E:
+            case 0x1F:
+            {
+                error_message = "invalid string: control character must be escaped";
+                return token_type::parse_error;
+            }
+
+            // U+0020..U+007F (except U+0022 (quote) and U+005C (backspace))
+            case 0x20:
+            case 0x21:
+            case 0x23:
+            case 0x24:
+            case 0x25:
+            case 0x26:
+            case 0x27:
+            case 0x28:
+            case 0x29:
+            case 0x2A:
+            case 0x2B:
+            case 0x2C:
+            case 0x2D:
+            case 0x2E:
+            case 0x2F:
+            case 0x30:
+            case 0x31:
+            case 0x32:
+            case 0x33:
+            case 0x34:
+            case 0x35:
+            case 0x36:
+            case 0x37:
+            case 0x38:
+            case 0x39:
+            case 0x3A:
+            case 0x3B:
+            case 0x3C:
+            case 0x3D:
+            case 0x3E:
+            case 0x3F:
+            case 0x40:
+            case 0x41:
+            case 0x42:
+            case 0x43:
+            case 0x44:
+            case 0x45:
+            case 0x46:
+            case 0x47:
+            case 0x48:
+            case 0x49:
+            case 0x4A:
+            case 0x4B:
+            case 0x4C:
+            case 0x4D:
+            case 0x4E:
+            case 0x4F:
+            case 0x50:
+            case 0x51:
+            case 0x52:
+            case 0x53:
+            case 0x54:
+            case 0x55:
+            case 0x56:
+            case 0x57:
+            case 0x58:
+            case 0x59:
+            case 0x5A:
+            case 0x5B:
+            case 0x5D:
+            case 0x5E:
+            case 0x5F:
+            case 0x60:
+            case 0x61:
+            case 0x62:
+            case 0x63:
+            case 0x64:
+            case 0x65:
+            case 0x66:
+            case 0x67:
+            case 0x68:
+            case 0x69:
+            case 0x6A:
+            case 0x6B:
+            case 0x6C:
+            case 0x6D:
+            case 0x6E:
+            case 0x6F:
+            case 0x70:
+            case 0x71:
+            case 0x72:
+            case 0x73:
+            case 0x74:
+            case 0x75:
+            case 0x76:
+            case 0x77:
+            case 0x78:
+            case 0x79:
+            case 0x7A:
+            case 0x7B:
+            case 0x7C:
+            case 0x7D:
+            case 0x7E:
+            case 0x7F:
+            {
+                add(current);
+                break;
+            }
+
+            // U+0080..U+07FF: bytes C2..DF 80..BF
+            case 0xC2:
+            case 0xC3:
+            case 0xC4:
+            case 0xC5:
+            case 0xC6:
+            case 0xC7:
+            case 0xC8:
+            case 0xC9:
+            case 0xCA:
+            case 0xCB:
+            case 0xCC:
+            case 0xCD:
+            case 0xCE:
+            case 0xCF:
+            case 0xD0:
+            case 0xD1:
+            case 0xD2:
+            case 0xD3:
+            case 0xD4:
+            case 0xD5:
+            case 0xD6:
+            case 0xD7:
+            case 0xD8:
+            case 0xD9:
+            case 0xDA:
+            case 0xDB:
+            case 0xDC:
+            case 0xDD:
+            case 0xDE:
+            case 0xDF:
+            {
+                if (JSON_UNLIKELY(not next_byte_in_range({0x80, 0xBF})))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+0800..U+0FFF: bytes E0 A0..BF 80..BF
+            case 0xE0:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0xA0, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+1000..U+CFFF: bytes E1..EC 80..BF 80..BF
+            // U+E000..U+FFFF: bytes EE..EF 80..BF 80..BF
+            case 0xE1:
+            case 0xE2:
+            case 0xE3:
+            case 0xE4:
+            case 0xE5:
+            case 0xE6:
+            case 0xE7:
+            case 0xE8:
+            case 0xE9:
+            case 0xEA:
+            case 0xEB:
+            case 0xEC:
+            case 0xEE:
+            case 0xEF:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+D000..U+D7FF: bytes ED 80..9F 80..BF
+            case 0xED:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0x9F, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+10000..U+3FFFF F0 90..BF 80..BF 80..BF
+            case 0xF0:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x90, 0xBF, 0x80, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+40000..U+FFFFF F1..F3 80..BF 80..BF 80..BF
+            case 0xF1:
+            case 0xF2:
+            case 0xF3:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0xBF, 0x80, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // U+100000..U+10FFFF F4 80..8F 80..BF 80..BF
+            case 0xF4:
+            {
+                if (JSON_UNLIKELY(not (next_byte_in_range({0x80, 0x8F, 0x80, 0xBF, 0x80, 0xBF}))))
+                {
+                    return token_type::parse_error;
+                }
+                break;
+            }
+
+            // remaining bytes (80..C1 and F5..FF) are ill-formed
+            default:
+            {
+                error_message = "invalid string: ill-formed UTF-8 byte";
+                return token_type::parse_error;
+            }
+        }
+    }
+}
+
+json::lexer::token_type json::lexer::scan_number()
+{
+    // reset token_buffer to store the number's bytes
+    reset();
+
+    // the type of the parsed number; initially set to unsigned; will be
+    // changed if minus sign, decimal point or exponent is read
+    token_type number_type = token_type::value_unsigned;
+
+    // state (init): we just found out we need to scan a number
+    switch (current)
+    {
+        case '-':
+        {
+            add(current);
+            goto scan_number_minus;
+        }
+
+        case '0':
+        {
+            add(current);
+            goto scan_number_zero;
+        }
+
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any1;
+        }
+
+        default:
+        {
+            // all other characters are rejected outside scan_number()
+            assert(false); // LCOV_EXCL_LINE
+        }
+    }
+
+scan_number_minus:
+    // state: we just parsed a leading minus sign
+    number_type = token_type::value_integer;
+    switch (get())
+    {
+        case '0':
+        {
+            add(current);
+            goto scan_number_zero;
+        }
+
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any1;
+        }
+
+        default:
+        {
+            error_message = "invalid number; expected digit after '-'";
+            return token_type::parse_error;
+        }
+    }
+
+scan_number_zero:
+    // state: we just parse a zero (maybe with a leading minus sign)
+    switch (get())
+    {
+        case '.':
+        {
+            add(decimal_point_char);
+            goto scan_number_decimal1;
+        }
+
+        case 'e':
+        case 'E':
+        {
+            add(current);
+            goto scan_number_exponent;
+        }
+
+        default:
+            goto scan_number_done;
+    }
+
+scan_number_any1:
+    // state: we just parsed a number 0-9 (maybe with a leading minus sign)
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any1;
+        }
+
+        case '.':
+        {
+            add(decimal_point_char);
+            goto scan_number_decimal1;
+        }
+
+        case 'e':
+        case 'E':
+        {
+            add(current);
+            goto scan_number_exponent;
+        }
+
+        default:
+            goto scan_number_done;
+    }
+
+scan_number_decimal1:
+    // state: we just parsed a decimal point
+    number_type = token_type::value_float;
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_decimal2;
+        }
+
+        default:
+        {
+            error_message = "invalid number; expected digit after '.'";
+            return token_type::parse_error;
+        }
+    }
+
+scan_number_decimal2:
+    // we just parsed at least one number after a decimal point
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_decimal2;
+        }
+
+        case 'e':
+        case 'E':
+        {
+            add(current);
+            goto scan_number_exponent;
+        }
+
+        default:
+            goto scan_number_done;
+    }
+
+scan_number_exponent:
+    // we just parsed an exponent
+    number_type = token_type::value_float;
+    switch (get())
+    {
+        case '+':
+        case '-':
+        {
+            add(current);
+            goto scan_number_sign;
+        }
+
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any2;
+        }
+
+        default:
+        {
+            error_message =
+                "invalid number; expected '+', '-', or digit after exponent";
+            return token_type::parse_error;
+        }
+    }
+
+scan_number_sign:
+    // we just parsed an exponent sign
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any2;
+        }
+
+        default:
+        {
+            error_message = "invalid number; expected digit after exponent sign";
+            return token_type::parse_error;
+        }
+    }
+
+scan_number_any2:
+    // we just parsed a number after the exponent or exponent sign
+    switch (get())
+    {
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+        {
+            add(current);
+            goto scan_number_any2;
+        }
+
+        default:
+            goto scan_number_done;
+    }
+
+scan_number_done:
+    // unget the character after the number (we only read it to know that
+    // we are done scanning a number)
+    unget();
+
+    char* endptr = nullptr;
+    errno = 0;
+
+    // try to parse integers first and fall back to floats
+    if (number_type == token_type::value_unsigned)
+    {
+        const auto x = std::strtoull(token_buffer.c_str(), &endptr, 10);
+
+        // we checked the number format before
+        assert(endptr == token_buffer.data() + token_buffer.size());
+
+        if (errno == 0)
+        {
+            value_unsigned = static_cast<uint64_t>(x);
+            if (value_unsigned == x)
+            {
+                return token_type::value_unsigned;
+            }
+        }
+    }
+    else if (number_type == token_type::value_integer)
+    {
+        const auto x = std::strtoll(token_buffer.c_str(), &endptr, 10);
+
+        // we checked the number format before
+        assert(endptr == token_buffer.data() + token_buffer.size());
+
+        if (errno == 0)
+        {
+            value_integer = static_cast<int64_t>(x);
+            if (value_integer == x)
+            {
+                return token_type::value_integer;
+            }
+        }
+    }
+
+    // this code is reached if we parse a floating-point number or if an
+    // integer conversion above failed
+    strtof(value_float, token_buffer.c_str(), &endptr);
+
+    // we checked the number format before
+    assert(endptr == token_buffer.data() + token_buffer.size());
+
+    return token_type::value_float;
+}
+
+json::lexer::token_type json::lexer::scan_literal(const char* literal_text, const std::size_t length,
+                        token_type return_type)
+{
+    assert(current == literal_text[0]);
+    for (std::size_t i = 1; i < length; ++i)
+    {
+        if (JSON_UNLIKELY(get() != literal_text[i]))
+        {
+            error_message = "invalid literal";
+            return token_type::parse_error;
+        }
+    }
+    return return_type;
+}
+
+std::string json::lexer::get_token_string() const
+{
+    // escape control characters
+    std::string result;
+    raw_string_ostream ss(result);
+    for (const unsigned char c : token_string)
+    {
+        if (c <= '\x1F')
+        {
+            // escape control characters
+            ss << "<U+" << format_hex_no_prefix(c, 4, true) << '>';
+        }
+        else
+        {
+            // add character as is
+            ss << c;
+        }
+    }
+
+    ss.flush();
+    return result;
+}
+
+json::lexer::token_type json::lexer::scan()
+{
+    // read next character and ignore whitespace
+    do
+    {
+        get();
+    }
+    while (current == ' ' or current == '\t' or current == '\n' or current == '\r');
+
+    switch (current)
+    {
+        // structural characters
+        case '[':
+            return token_type::begin_array;
+        case ']':
+            return token_type::end_array;
+        case '{':
+            return token_type::begin_object;
+        case '}':
+            return token_type::end_object;
+        case ':':
+            return token_type::name_separator;
+        case ',':
+            return token_type::value_separator;
+
+        // literals
+        case 't':
+            return scan_literal("true", 4, token_type::literal_true);
+        case 'f':
+            return scan_literal("false", 5, token_type::literal_false);
+        case 'n':
+            return scan_literal("null", 4, token_type::literal_null);
+
+        // string
+        case '\"':
+            return scan_string();
+
+        // number
+        case '-':
+        case '0':
+        case '1':
+        case '2':
+        case '3':
+        case '4':
+        case '5':
+        case '6':
+        case '7':
+        case '8':
+        case '9':
+            return scan_number();
+
+        // end of input (the null byte is needed when parsing from
+        // string literals)
+        case '\0':
+        case std::char_traits<char>::eof():
+            return token_type::end_of_input;
+
+        // error
+        default:
+            error_message = "invalid literal";
+            return token_type::parse_error;
+    }
+}
+
+void json::parser::parse(const bool strict, json& result)
+{
+    // read first token
+    get_token();
+
+    parse_internal(true, result);
+    result.assert_invariant();
+
+    // in strict mode, input must be completely read
+    if (strict)
+    {
+        get_token();
+        expect(token_type::end_of_input);
+    }
+
+    // in case of an error, return discarded value
+    if (errored)
+    {
+        result = value_t::discarded;
+        return;
+    }
+
+    // set top-level value to null if it was discarded by the callback
+    // function
+    if (result.is_discarded())
+    {
+        result = nullptr;
+    }
+}
+
+void json::parser::parse_internal(bool keep, json& result)
+{
+    // never parse after a parse error was detected
+    assert(not errored);
+
+    // start with a discarded value
+    if (not result.is_discarded())
+    {
+        result.m_value.destroy(result.m_type);
+        result.m_type = value_t::discarded;
+    }
+
+    switch (last_token)
+    {
+        case token_type::begin_object:
+        {
+            if (keep)
+            {
+                if (callback)
+                {
+                    keep = callback(depth++, parse_event_t::object_start, result);
+                }
+
+                if (not callback or keep)
+                {
+                    // explicitly set result to object to cope with {}
+                    result.m_type = value_t::object;
+                    result.m_value = value_t::object;
+                }
+            }
+
+            // read next token
+            get_token();
+
+            // closing } -> we are done
+            if (last_token == token_type::end_object)
+            {
+                if (keep and callback and not callback(--depth, parse_event_t::object_end, result))
+                {
+                    result.m_value.destroy(result.m_type);
+                    result.m_type = value_t::discarded;
+                }
+                break;
+            }
+
+            // parse values
+            SmallString<128> key;
+            json value;
+            while (true)
+            {
+                // store key
+                if (not expect(token_type::value_string))
+                {
+                    return;
+                }
+                key = m_lexer.get_string();
+
+                bool keep_tag = false;
+                if (keep)
+                {
+                    if (callback)
+                    {
+                        json k(key);
+                        keep_tag = callback(depth, parse_event_t::key, k);
+                    }
+                    else
+                    {
+                        keep_tag = true;
+                    }
+                }
+
+                // parse separator (:)
+                get_token();
+                if (not expect(token_type::name_separator))
+                {
+                    return;
+                }
+
+                // parse and add value
+                get_token();
+                value.m_value.destroy(value.m_type);
+                value.m_type = value_t::discarded;
+                parse_internal(keep, value);
+
+                if (JSON_UNLIKELY(errored))
+                {
+                    return;
+                }
+
+                if (keep and keep_tag and not value.is_discarded())
+                {
+                    result.m_value.object->try_emplace(StringRef(key.data(), key.size()), std::move(value));
+                }
+
+                // comma -> next value
+                get_token();
+                if (last_token == token_type::value_separator)
+                {
+                    get_token();
+                    continue;
+                }
+
+                // closing }
+                if (not expect(token_type::end_object))
+                {
+                    return;
+                }
+                break;
+            }
+
+            if (keep and callback and not callback(--depth, parse_event_t::object_end, result))
+            {
+                result.m_value.destroy(result.m_type);
+                result.m_type = value_t::discarded;
+            }
+            break;
+        }
+
+        case token_type::begin_array:
+        {
+            if (keep)
+            {
+                if (callback)
+                {
+                    keep = callback(depth++, parse_event_t::array_start, result);
+                }
+
+                if (not callback or keep)
+                {
+                    // explicitly set result to array to cope with []
+                    result.m_type = value_t::array;
+                    result.m_value = value_t::array;
+                }
+            }
+
+            // read next token
+            get_token();
+
+            // closing ] -> we are done
+            if (last_token == token_type::end_array)
+            {
+                if (callback and not callback(--depth, parse_event_t::array_end, result))
+                {
+                    result.m_value.destroy(result.m_type);
+                    result.m_type = value_t::discarded;
+                }
+                break;
+            }
+
+            // parse values
+            json value;
+            while (true)
+            {
+                // parse value
+                value.m_value.destroy(value.m_type);
+                value.m_type = value_t::discarded;
+                parse_internal(keep, value);
+
+                if (JSON_UNLIKELY(errored))
+                {
+                    return;
+                }
+
+                if (keep and not value.is_discarded())
+                {
+                    result.m_value.array->push_back(std::move(value));
+                }
+
+                // comma -> next value
+                get_token();
+                if (last_token == token_type::value_separator)
+                {
+                    get_token();
+                    continue;
+                }
+
+                // closing ]
+                if (not expect(token_type::end_array))
+                {
+                    return;
+                }
+                break;
+            }
+
+            if (keep and callback and not callback(--depth, parse_event_t::array_end, result))
+            {
+                result.m_value.destroy(result.m_type);
+                result.m_type = value_t::discarded;
+            }
+            break;
+        }
+
+        case token_type::literal_null:
+        {
+            result.m_type = value_t::null;
+            break;
+        }
+
+        case token_type::value_string:
+        {
+            result.m_type = value_t::string;
+            result.m_value = m_lexer.get_string();
+            break;
+        }
+
+        case token_type::literal_true:
+        {
+            result.m_type = value_t::boolean;
+            result.m_value = true;
+            break;
+        }
+
+        case token_type::literal_false:
+        {
+            result.m_type = value_t::boolean;
+            result.m_value = false;
+            break;
+        }
+
+        case token_type::value_unsigned:
+        {
+            result.m_type = value_t::number_unsigned;
+            result.m_value = m_lexer.get_number_unsigned();
+            break;
+        }
+
+        case token_type::value_integer:
+        {
+            result.m_type = value_t::number_integer;
+            result.m_value = m_lexer.get_number_integer();
+            break;
+        }
+
+        case token_type::value_float:
+        {
+            result.m_type = value_t::number_float;
+            result.m_value = m_lexer.get_number_float();
+
+            // throw in case of infinity or NAN
+            if (JSON_UNLIKELY(not std::isfinite(result.m_value.number_float)))
+            {
+                if (allow_exceptions)
+                {
+                    JSON_THROW(out_of_range::create(406, "number overflow parsing '" +
+                                                    Twine(m_lexer.get_token_string()) + "'"));
+                }
+                expect(token_type::uninitialized);
+            }
+            break;
+        }
+
+        case token_type::parse_error:
+        {
+            // using "uninitialized" to avoid "expected" message
+            if (not expect(token_type::uninitialized))
+            {
+                return;
+            }
+            break; // LCOV_EXCL_LINE
+        }
+
+        default:
+        {
+            // the last token was unexpected; we expected a value
+            if (not expect(token_type::literal_or_value))
+            {
+                return;
+            }
+            break; // LCOV_EXCL_LINE
+        }
+    }
+
+    if (keep and callback and not callback(depth, parse_event_t::value, result))
+    {
+        result.m_value.destroy(result.m_type);
+        result.m_type = value_t::discarded;
+    }
+}
+
+bool json::parser::accept_internal()
+{
+    switch (last_token)
+    {
+        case token_type::begin_object:
+        {
+            // read next token
+            get_token();
+
+            // closing } -> we are done
+            if (last_token == token_type::end_object)
+            {
+                return true;
+            }
+
+            // parse values
+            while (true)
+            {
+                // parse key
+                if (last_token != token_type::value_string)
+                {
+                    return false;
+                }
+
+                // parse separator (:)
+                get_token();
+                if (last_token != token_type::name_separator)
+                {
+                    return false;
+                }
+
+                // parse value
+                get_token();
+                if (not accept_internal())
+                {
+                    return false;
+                }
+
+                // comma -> next value
+                get_token();
+                if (last_token == token_type::value_separator)
+                {
+                    get_token();
+                    continue;
+                }
+
+                // closing }
+                return (last_token == token_type::end_object);
+            }
+        }
+
+        case token_type::begin_array:
+        {
+            // read next token
+            get_token();
+
+            // closing ] -> we are done
+            if (last_token == token_type::end_array)
+            {
+                return true;
+            }
+
+            // parse values
+            while (true)
+            {
+                // parse value
+                if (not accept_internal())
+                {
+                    return false;
+                }
+
+                // comma -> next value
+                get_token();
+                if (last_token == token_type::value_separator)
+                {
+                    get_token();
+                    continue;
+                }
+
+                // closing ]
+                return (last_token == token_type::end_array);
+            }
+        }
+
+        case token_type::value_float:
+        {
+            // reject infinity or NAN
+            return std::isfinite(m_lexer.get_number_float());
+        }
+
+        case token_type::literal_false:
+        case token_type::literal_null:
+        case token_type::literal_true:
+        case token_type::value_integer:
+        case token_type::value_string:
+        case token_type::value_unsigned:
+            return true;
+
+        default: // the last token was unexpected
+            return false;
+    }
+}
+
+void json::parser::throw_exception() const
+{
+    std::string error_msg = "syntax error - ";
+    if (last_token == token_type::parse_error)
+    {
+        error_msg += std::string(m_lexer.get_error_message()) + "; last read: '" +
+                     m_lexer.get_token_string() + "'";
+    }
+    else
+    {
+        error_msg += "unexpected " + std::string(lexer_t::token_type_name(last_token));
+    }
+
+    if (expected != token_type::uninitialized)
+    {
+        error_msg += "; expected " + std::string(lexer_t::token_type_name(expected));
+    }
+
+    JSON_THROW(parse_error::create(101, m_lexer.get_position(), error_msg));
+}
+
+json json::parse(StringRef s,
+                        const parser_callback_t cb,
+                        const bool allow_exceptions)
+{
+    raw_mem_istream is(makeArrayRef(s.data(), s.size()));
+    return parse(is, cb, allow_exceptions);
+}
+
+json json::parse(ArrayRef<uint8_t> arr,
+                        const parser_callback_t cb,
+                        const bool allow_exceptions)
+{
+    raw_mem_istream is(arr);
+    return parse(is, cb, allow_exceptions);
+}
+
+json json::parse(raw_istream& i,
+                        const parser_callback_t cb,
+                        const bool allow_exceptions)
+{
+    json result;
+    parser(i, cb, allow_exceptions).parse(true, result);
+    return result;
+}
+
+bool json::accept(StringRef s)
+{
+    raw_mem_istream is(makeArrayRef(s.data(), s.size()));
+    return parser(is).accept(true);
+}
+
+bool json::accept(ArrayRef<uint8_t> arr)
+{
+    raw_mem_istream is(arr);
+    return parser(is).accept(true);
+}
+
+bool json::accept(raw_istream& i)
+{
+    return parser(i).accept(true);
+}
+
+raw_istream& operator>>(raw_istream& i, json& j)
+{
+    json::parser(i).parse(false, j);
+    return i;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_pointer.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_pointer.cpp
new file mode 100644
index 0000000..9cb1ec4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_pointer.cpp
@@ -0,0 +1,544 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include <numeric> // accumulate
+
+#include "wpi/SmallString.h"
+
+namespace wpi {
+
+std::string json_pointer::to_string() const noexcept
+{
+    return std::accumulate(reference_tokens.begin(), reference_tokens.end(),
+                           std::string{},
+                           [](const std::string & a, const std::string & b)
+    {
+        return a + "/" + escape(b);
+    });
+}
+
+int json_pointer::array_index(const Twine& s)
+{
+    SmallString<128> buf;
+    StringRef str = s.toNullTerminatedStringRef(buf);
+    std::size_t processed_chars = 0;
+    const int res = std::stoi(str, &processed_chars);
+
+    // check if the string was completely read
+    if (JSON_UNLIKELY(processed_chars != str.size()))
+    {
+        JSON_THROW(detail::out_of_range::create(404, "unresolved reference token '" + Twine(s) + "'"));
+    }
+
+    return res;
+}
+
+json& json_pointer::get_and_create(json& j) const
+{
+    using size_type = typename json::size_type;
+    auto result = &j;
+
+    // in case no reference tokens exist, return a reference to the JSON value
+    // j which will be overwritten by a primitive value
+    for (const auto& reference_token : reference_tokens)
+    {
+        switch (result->m_type)
+        {
+            case detail::value_t::null:
+            {
+                if (reference_token == "0")
+                {
+                    // start a new array if reference token is 0
+                    result = &result->operator[](0);
+                }
+                else
+                {
+                    // start a new object otherwise
+                    result = &result->operator[](reference_token);
+                }
+                break;
+            }
+
+            case detail::value_t::object:
+            {
+                // create an entry in the object
+                result = &result->operator[](reference_token);
+                break;
+            }
+
+            case detail::value_t::array:
+            {
+                // create an entry in the array
+                JSON_TRY
+                {
+                    result = &result->operator[](static_cast<size_type>(array_index(reference_token)));
+                }
+                JSON_CATCH(std::invalid_argument&)
+                {
+                    JSON_THROW(detail::parse_error::create(109, 0, "array index '" + Twine(reference_token) + "' is not a number"));
+                }
+                break;
+            }
+
+            /*
+            The following code is only reached if there exists a reference
+            token _and_ the current value is primitive. In this case, we have
+            an error situation, because primitive values may only occur as
+            single value; that is, with an empty list of reference tokens.
+            */
+            default:
+                JSON_THROW(detail::type_error::create(313, "invalid value to unflatten"));
+        }
+    }
+
+    return *result;
+}
+
+json& json_pointer::get_unchecked(json* ptr) const
+{
+    using size_type = typename json::size_type;
+    for (const auto& reference_token : reference_tokens)
+    {
+        // convert null values to arrays or objects before continuing
+        if (ptr->m_type == detail::value_t::null)
+        {
+            // check if reference token is a number
+            const bool nums =
+                std::all_of(reference_token.begin(), reference_token.end(),
+                            [](const char x)
+            {
+                return (x >= '0' and x <= '9');
+            });
+
+            // change value to array for numbers or "-" or to object otherwise
+            *ptr = (nums or reference_token == "-")
+                   ? detail::value_t::array
+                   : detail::value_t::object;
+        }
+
+        switch (ptr->m_type)
+        {
+            case detail::value_t::object:
+            {
+                // use unchecked object access
+                ptr = &ptr->operator[](reference_token);
+                break;
+            }
+
+            case detail::value_t::array:
+            {
+                // error condition (cf. RFC 6901, Sect. 4)
+                if (JSON_UNLIKELY(reference_token.size() > 1 and reference_token[0] == '0'))
+                {
+                    JSON_THROW(detail::parse_error::create(106, 0,
+                                                           "array index '" + Twine(reference_token) +
+                                                           "' must not begin with '0'"));
+                }
+
+                if (reference_token == "-")
+                {
+                    // explicitly treat "-" as index beyond the end
+                    ptr = &ptr->operator[](ptr->m_value.array->size());
+                }
+                else
+                {
+                    // convert array index to number; unchecked access
+                    JSON_TRY
+                    {
+                        ptr = &ptr->operator[](
+                            static_cast<size_type>(array_index(reference_token)));
+                    }
+                    JSON_CATCH(std::invalid_argument&)
+                    {
+                        JSON_THROW(detail::parse_error::create(109, 0, "array index '" + Twine(reference_token) + "' is not a number"));
+                    }
+                }
+                break;
+            }
+
+            default:
+                JSON_THROW(detail::out_of_range::create(404, "unresolved reference token '" + Twine(reference_token) + "'"));
+        }
+    }
+
+    return *ptr;
+}
+
+json& json_pointer::get_checked(json* ptr) const
+{
+    using size_type = typename json::size_type;
+    for (const auto& reference_token : reference_tokens)
+    {
+        switch (ptr->m_type)
+        {
+            case detail::value_t::object:
+            {
+                // note: at performs range check
+                ptr = &ptr->at(reference_token);
+                break;
+            }
+
+            case detail::value_t::array:
+            {
+                if (JSON_UNLIKELY(reference_token == "-"))
+                {
+                    // "-" always fails the range check
+                    JSON_THROW(detail::out_of_range::create(402,
+                                                            "array index '-' (" + Twine(ptr->m_value.array->size()) +
+                                                            ") is out of range"));
+                }
+
+                // error condition (cf. RFC 6901, Sect. 4)
+                if (JSON_UNLIKELY(reference_token.size() > 1 and reference_token[0] == '0'))
+                {
+                    JSON_THROW(detail::parse_error::create(106, 0,
+                                                           "array index '" + Twine(reference_token) +
+                                                           "' must not begin with '0'"));
+                }
+
+                // note: at performs range check
+                JSON_TRY
+                {
+                    ptr = &ptr->at(static_cast<size_type>(array_index(reference_token)));
+                }
+                JSON_CATCH(std::invalid_argument&)
+                {
+                    JSON_THROW(detail::parse_error::create(109, 0, "array index '" + Twine(reference_token) + "' is not a number"));
+                }
+                break;
+            }
+
+            default:
+                JSON_THROW(detail::out_of_range::create(404, "unresolved reference token '" + Twine(reference_token) + "'"));
+        }
+    }
+
+    return *ptr;
+}
+
+const json& json_pointer::get_unchecked(const json* ptr) const
+{
+    using size_type = typename json::size_type;
+    for (const auto& reference_token : reference_tokens)
+    {
+        switch (ptr->m_type)
+        {
+            case detail::value_t::object:
+            {
+                // use unchecked object access
+                ptr = &ptr->operator[](reference_token);
+                break;
+            }
+
+            case detail::value_t::array:
+            {
+                if (JSON_UNLIKELY(reference_token == "-"))
+                {
+                    // "-" cannot be used for const access
+                    JSON_THROW(detail::out_of_range::create(402,
+                                                            "array index '-' (" + Twine(ptr->m_value.array->size()) +
+                                                            ") is out of range"));
+                }
+
+                // error condition (cf. RFC 6901, Sect. 4)
+                if (JSON_UNLIKELY(reference_token.size() > 1 and reference_token[0] == '0'))
+                {
+                    JSON_THROW(detail::parse_error::create(106, 0,
+                                                           "array index '" + Twine(reference_token) +
+                                                           "' must not begin with '0'"));
+                }
+
+                // use unchecked array access
+                JSON_TRY
+                {
+                    ptr = &ptr->operator[](
+                        static_cast<size_type>(array_index(reference_token)));
+                }
+                JSON_CATCH(std::invalid_argument&)
+                {
+                    JSON_THROW(detail::parse_error::create(109, 0, "array index '" + Twine(reference_token) + "' is not a number"));
+                }
+                break;
+            }
+
+            default:
+                JSON_THROW(detail::out_of_range::create(404, "unresolved reference token '" + Twine(reference_token) + "'"));
+        }
+    }
+
+    return *ptr;
+}
+
+const json& json_pointer::get_checked(const json* ptr) const
+{
+    using size_type = typename json::size_type;
+    for (const auto& reference_token : reference_tokens)
+    {
+        switch (ptr->m_type)
+        {
+            case detail::value_t::object:
+            {
+                // note: at performs range check
+                ptr = &ptr->at(reference_token);
+                break;
+            }
+
+            case detail::value_t::array:
+            {
+                if (JSON_UNLIKELY(reference_token == "-"))
+                {
+                    // "-" always fails the range check
+                    JSON_THROW(detail::out_of_range::create(402,
+                                                            "array index '-' (" + Twine(ptr->m_value.array->size()) +
+                                                            ") is out of range"));
+                }
+
+                // error condition (cf. RFC 6901, Sect. 4)
+                if (JSON_UNLIKELY(reference_token.size() > 1 and reference_token[0] == '0'))
+                {
+                    JSON_THROW(detail::parse_error::create(106, 0,
+                                                           "array index '" + Twine(reference_token) +
+                                                           "' must not begin with '0'"));
+                }
+
+                // note: at performs range check
+                JSON_TRY
+                {
+                    ptr = &ptr->at(static_cast<size_type>(array_index(reference_token)));
+                }
+                JSON_CATCH(std::invalid_argument&)
+                {
+                    JSON_THROW(detail::parse_error::create(109, 0, "array index '" + Twine(reference_token) + "' is not a number"));
+                }
+                break;
+            }
+
+            default:
+                JSON_THROW(detail::out_of_range::create(404, "unresolved reference token '" + Twine(reference_token) + "'"));
+        }
+    }
+
+    return *ptr;
+}
+
+std::vector<std::string> json_pointer::split(const Twine& reference_string)
+{
+    SmallString<128> ref_str_buf;
+    StringRef ref_str = reference_string.toStringRef(ref_str_buf);
+    std::vector<std::string> result;
+
+    // special case: empty reference string -> no reference tokens
+    if (ref_str.empty())
+    {
+        return result;
+    }
+
+    // check if nonempty reference string begins with slash
+    if (JSON_UNLIKELY(ref_str[0] != '/'))
+    {
+        JSON_THROW(detail::parse_error::create(107, 1,
+                                               "JSON pointer must be empty or begin with '/' - was: '" +
+                                               Twine(ref_str) + "'"));
+    }
+
+    // extract the reference tokens:
+    // - slash: position of the last read slash (or end of string)
+    // - start: position after the previous slash
+    for (
+        // search for the first slash after the first character
+        std::size_t slash = ref_str.find_first_of('/', 1),
+        // set the beginning of the first reference token
+        start = 1;
+        // we can stop if start == string::npos+1 = 0
+        start != 0;
+        // set the beginning of the next reference token
+        // (will eventually be 0 if slash == std::string::npos)
+        start = slash + 1,
+        // find next slash
+        slash = ref_str.find_first_of('/', start))
+    {
+        // use the text between the beginning of the reference token
+        // (start) and the last slash (slash).
+        auto reference_token = ref_str.slice(start, slash);
+
+        // check reference tokens are properly escaped
+        for (std::size_t pos = reference_token.find_first_of('~');
+                pos != StringRef::npos;
+                pos = reference_token.find_first_of('~', pos + 1))
+        {
+            assert(reference_token[pos] == '~');
+
+            // ~ must be followed by 0 or 1
+            if (JSON_UNLIKELY(pos == reference_token.size() - 1 or
+                              (reference_token[pos + 1] != '0' and
+                               reference_token[pos + 1] != '1')))
+            {
+                JSON_THROW(detail::parse_error::create(108, 0, "escape character '~' must be followed with '0' or '1'"));
+            }
+        }
+
+        // finally, store the reference token
+        std::string ref_tok = reference_token;
+        unescape(ref_tok);
+        result.emplace_back(std::move(ref_tok));
+    }
+
+    return result;
+}
+
+void json_pointer::replace_substring(std::string& s, const std::string& f,
+                              const std::string& t)
+{
+    assert(not f.empty());
+    for (auto pos = s.find(f);                // find first occurrence of f
+            pos != std::string::npos;         // make sure f was found
+            s.replace(pos, f.size(), t),      // replace with t, and
+            pos = s.find(f, pos + t.size()))  // find next occurrence of f
+    {}
+}
+
+std::string json_pointer::escape(std::string s)
+{
+    replace_substring(s, "~", "~0");
+    replace_substring(s, "/", "~1");
+    return s;
+}
+
+/// unescape "~1" to tilde and "~0" to slash (order is important!)
+void json_pointer::unescape(std::string& s)
+{
+    replace_substring(s, "~1", "/");
+    replace_substring(s, "~0", "~");
+}
+
+void json_pointer::flatten(const Twine& reference_string,
+                    const json& value,
+                    json& result)
+{
+    switch (value.m_type)
+    {
+        case detail::value_t::array:
+        {
+            if (value.m_value.array->empty())
+            {
+                // flatten empty array as null
+                SmallString<64> buf;
+                result[reference_string.toStringRef(buf)] = nullptr;
+            }
+            else
+            {
+                // iterate array and use index as reference string
+                for (std::size_t i = 0; i < value.m_value.array->size(); ++i)
+                {
+                    flatten(reference_string + "/" + Twine(i),
+                            value.m_value.array->operator[](i), result);
+                }
+            }
+            break;
+        }
+
+        case detail::value_t::object:
+        {
+            if (value.m_value.object->empty())
+            {
+                // flatten empty object as null
+                SmallString<64> buf;
+                result[reference_string.toStringRef(buf)] = nullptr;
+            }
+            else
+            {
+                // iterate object and use keys as reference string
+                for (const auto& element : *value.m_value.object)
+                {
+                    flatten(reference_string + "/" + Twine(escape(element.first())), element.second, result);
+                }
+            }
+            break;
+        }
+
+        default:
+        {
+            // add primitive value with its reference string
+            SmallString<64> buf;
+            result[reference_string.toStringRef(buf)] = value;
+            break;
+        }
+    }
+}
+
+json
+json_pointer::unflatten(const json& value)
+{
+    if (JSON_UNLIKELY(not value.is_object()))
+    {
+        JSON_THROW(detail::type_error::create(314, "only objects can be unflattened"));
+    }
+
+    // we need to iterate over the object values in sorted key order
+    SmallVector<StringMapConstIterator<json>, 64> sorted;
+    for (auto i = value.m_value.object->begin(),
+         end = value.m_value.object->end(); i != end; ++i)
+    {
+        if (!i->second.is_primitive())
+        {
+            JSON_THROW(detail::type_error::create(315, "values in object must be primitive"));
+        }
+        sorted.push_back(i);
+    }
+    std::sort(sorted.begin(), sorted.end(),
+              [](const StringMapConstIterator<json>& a,
+                 const StringMapConstIterator<json>& b) {
+                return a->getKey() < b->getKey();
+              });
+
+    json result;
+
+    // iterate the sorted JSON object values
+    for (const auto& element : sorted)
+    {
+
+        // assign value to reference pointed to by JSON pointer; Note
+        // that if the JSON pointer is "" (i.e., points to the whole
+        // value), function get_and_create returns a reference to
+        // result itself. An assignment will then create a primitive
+        // value.
+        json_pointer(element->first()).get_and_create(result) = element->second;
+    }
+
+    return result;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_serializer.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_serializer.cpp
new file mode 100644
index 0000000..8ab92b1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_serializer.cpp
@@ -0,0 +1,1532 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#define WPI_JSON_IMPLEMENTATION
+#include "wpi/json.h"
+
+#include "wpi/Format.h"
+#include "wpi/SmallString.h"
+#include "wpi/StringExtras.h"
+#include "wpi/raw_os_ostream.h"
+
+#include "json_serializer.h"
+
+namespace wpi {
+
+namespace {
+
+/*!
+@brief implements the Grisu2 algorithm for binary to decimal floating-point
+conversion.
+
+This implementation is a slightly modified version of the reference
+implementation which may be obtained from
+http://florian.loitsch.com/publications (bench.tar.gz).
+
+The code is distributed under the MIT license, Copyright (c) 2009 Florian Loitsch.
+
+For a detailed description of the algorithm see:
+
+[1] Loitsch, "Printing Floating-Point Numbers Quickly and Accurately with
+    Integers", Proceedings of the ACM SIGPLAN 2010 Conference on Programming
+    Language Design and Implementation, PLDI 2010
+[2] Burger, Dybvig, "Printing Floating-Point Numbers Quickly and Accurately",
+    Proceedings of the ACM SIGPLAN 1996 Conference on Programming Language
+    Design and Implementation, PLDI 1996
+*/
+namespace dtoa_impl
+{
+
+template <typename Target, typename Source>
+Target reinterpret_bits(const Source source)
+{
+    static_assert(sizeof(Target) == sizeof(Source), "size mismatch");
+
+    Target target;
+    std::memcpy(&target, &source, sizeof(Source));
+    return target;
+}
+
+struct diyfp // f * 2^e
+{
+    static constexpr int kPrecision = 64; // = q
+
+    uint64_t f;
+    int e;
+
+    constexpr diyfp() noexcept : f(0), e(0) {}
+    constexpr diyfp(uint64_t f_, int e_) noexcept : f(f_), e(e_) {}
+
+    /*!
+    @brief returns x - y
+    @pre x.e == y.e and x.f >= y.f
+    */
+    static diyfp sub(const diyfp& x, const diyfp& y) noexcept
+    {
+        assert(x.e == y.e);
+        assert(x.f >= y.f);
+
+        return diyfp(x.f - y.f, x.e);
+    }
+
+    /*!
+    @brief returns x * y
+    @note The result is rounded. (Only the upper q bits are returned.)
+    */
+    static diyfp mul(const diyfp& x, const diyfp& y) noexcept
+    {
+        static_assert(kPrecision == 64, "internal error");
+
+        // Computes:
+        //  f = round((x.f * y.f) / 2^q)
+        //  e = x.e + y.e + q
+
+        // Emulate the 64-bit * 64-bit multiplication:
+        //
+        // p = u * v
+        //   = (u_lo + 2^32 u_hi) (v_lo + 2^32 v_hi)
+        //   = (u_lo v_lo         ) + 2^32 ((u_lo v_hi         ) + (u_hi v_lo         )) + 2^64 (u_hi v_hi         )
+        //   = (p0                ) + 2^32 ((p1                ) + (p2                )) + 2^64 (p3                )
+        //   = (p0_lo + 2^32 p0_hi) + 2^32 ((p1_lo + 2^32 p1_hi) + (p2_lo + 2^32 p2_hi)) + 2^64 (p3                )
+        //   = (p0_lo             ) + 2^32 (p0_hi + p1_lo + p2_lo                      ) + 2^64 (p1_hi + p2_hi + p3)
+        //   = (p0_lo             ) + 2^32 (Q                                          ) + 2^64 (H                 )
+        //   = (p0_lo             ) + 2^32 (Q_lo + 2^32 Q_hi                           ) + 2^64 (H                 )
+        //
+        // (Since Q might be larger than 2^32 - 1)
+        //
+        //   = (p0_lo + 2^32 Q_lo) + 2^64 (Q_hi + H)
+        //
+        // (Q_hi + H does not overflow a 64-bit int)
+        //
+        //   = p_lo + 2^64 p_hi
+
+        const uint64_t u_lo = x.f & 0xFFFFFFFF;
+        const uint64_t u_hi = x.f >> 32;
+        const uint64_t v_lo = y.f & 0xFFFFFFFF;
+        const uint64_t v_hi = y.f >> 32;
+
+        const uint64_t p0 = u_lo * v_lo;
+        const uint64_t p1 = u_lo * v_hi;
+        const uint64_t p2 = u_hi * v_lo;
+        const uint64_t p3 = u_hi * v_hi;
+
+        const uint64_t p0_hi = p0 >> 32;
+        const uint64_t p1_lo = p1 & 0xFFFFFFFF;
+        const uint64_t p1_hi = p1 >> 32;
+        const uint64_t p2_lo = p2 & 0xFFFFFFFF;
+        const uint64_t p2_hi = p2 >> 32;
+
+        uint64_t Q = p0_hi + p1_lo + p2_lo;
+
+        // The full product might now be computed as
+        //
+        // p_hi = p3 + p2_hi + p1_hi + (Q >> 32)
+        // p_lo = p0_lo + (Q << 32)
+        //
+        // But in this particular case here, the full p_lo is not required.
+        // Effectively we only need to add the highest bit in p_lo to p_hi (and
+        // Q_hi + 1 does not overflow).
+
+        Q += uint64_t{1} << (64 - 32 - 1); // round, ties up
+
+        const uint64_t h = p3 + p2_hi + p1_hi + (Q >> 32);
+
+        return diyfp(h, x.e + y.e + 64);
+    }
+
+    /*!
+    @brief normalize x such that the significand is >= 2^(q-1)
+    @pre x.f != 0
+    */
+    static diyfp normalize(diyfp x) noexcept
+    {
+        assert(x.f != 0);
+
+        while ((x.f >> 63) == 0)
+        {
+            x.f <<= 1;
+            x.e--;
+        }
+
+        return x;
+    }
+
+    /*!
+    @brief normalize x such that the result has the exponent E
+    @pre e >= x.e and the upper e - x.e bits of x.f must be zero.
+    */
+    static diyfp normalize_to(const diyfp& x, const int target_exponent) noexcept
+    {
+        const int delta = x.e - target_exponent;
+
+        assert(delta >= 0);
+        assert(((x.f << delta) >> delta) == x.f);
+
+        return diyfp(x.f << delta, target_exponent);
+    }
+};
+
+struct boundaries
+{
+    diyfp w;
+    diyfp minus;
+    diyfp plus;
+};
+
+/*!
+Compute the (normalized) diyfp representing the input number 'value' and its
+boundaries.
+
+@pre value must be finite and positive
+*/
+template <typename FloatType>
+boundaries compute_boundaries(FloatType value)
+{
+    assert(std::isfinite(value));
+    assert(value > 0);
+
+    // Convert the IEEE representation into a diyfp.
+    //
+    // If v is denormal:
+    //      value = 0.F * 2^(1 - bias) = (          F) * 2^(1 - bias - (p-1))
+    // If v is normalized:
+    //      value = 1.F * 2^(E - bias) = (2^(p-1) + F) * 2^(E - bias - (p-1))
+
+    static_assert(std::numeric_limits<FloatType>::is_iec559,
+                  "internal error: dtoa_short requires an IEEE-754 floating-point implementation");
+
+    constexpr int      kPrecision = std::numeric_limits<FloatType>::digits; // = p (includes the hidden bit)
+    constexpr int      kBias      = std::numeric_limits<FloatType>::max_exponent - 1 + (kPrecision - 1);
+    constexpr int      kMinExp    = 1 - kBias;
+    constexpr uint64_t kHiddenBit = uint64_t{1} << (kPrecision - 1); // = 2^(p-1)
+
+    using bits_type = typename std::conditional< kPrecision == 24, uint32_t, uint64_t >::type;
+
+    const uint64_t bits = reinterpret_bits<bits_type>(value);
+    const uint64_t E = bits >> (kPrecision - 1);
+    const uint64_t F = bits & (kHiddenBit - 1);
+
+    const bool is_denormal = (E == 0);
+    const diyfp v = is_denormal
+                    ? diyfp(F, kMinExp)
+                    : diyfp(F + kHiddenBit, static_cast<int>(E) - kBias);
+
+    // Compute the boundaries m- and m+ of the floating-point value
+    // v = f * 2^e.
+    //
+    // Determine v- and v+, the floating-point predecessor and successor if v,
+    // respectively.
+    //
+    //      v- = v - 2^e        if f != 2^(p-1) or e == e_min                (A)
+    //         = v - 2^(e-1)    if f == 2^(p-1) and e > e_min                (B)
+    //
+    //      v+ = v + 2^e
+    //
+    // Let m- = (v- + v) / 2 and m+ = (v + v+) / 2. All real numbers _strictly_
+    // between m- and m+ round to v, regardless of how the input rounding
+    // algorithm breaks ties.
+    //
+    //      ---+-------------+-------------+-------------+-------------+---  (A)
+    //         v-            m-            v             m+            v+
+    //
+    //      -----------------+------+------+-------------+-------------+---  (B)
+    //                       v-     m-     v             m+            v+
+
+    const bool lower_boundary_is_closer = (F == 0 and E > 1);
+    const diyfp m_plus = diyfp(2 * v.f + 1, v.e - 1);
+    const diyfp m_minus = lower_boundary_is_closer
+                          ? diyfp(4 * v.f - 1, v.e - 2)  // (B)
+                          : diyfp(2 * v.f - 1, v.e - 1); // (A)
+
+    // Determine the normalized w+ = m+.
+    const diyfp w_plus = diyfp::normalize(m_plus);
+
+    // Determine w- = m- such that e_(w-) = e_(w+).
+    const diyfp w_minus = diyfp::normalize_to(m_minus, w_plus.e);
+
+    return {diyfp::normalize(v), w_minus, w_plus};
+}
+
+// Given normalized diyfp w, Grisu needs to find a (normalized) cached
+// power-of-ten c, such that the exponent of the product c * w = f * 2^e lies
+// within a certain range [alpha, gamma] (Definition 3.2 from [1])
+//
+//      alpha <= e = e_c + e_w + q <= gamma
+//
+// or
+//
+//      f_c * f_w * 2^alpha <= f_c 2^(e_c) * f_w 2^(e_w) * 2^q
+//                          <= f_c * f_w * 2^gamma
+//
+// Since c and w are normalized, i.e. 2^(q-1) <= f < 2^q, this implies
+//
+//      2^(q-1) * 2^(q-1) * 2^alpha <= c * w * 2^q < 2^q * 2^q * 2^gamma
+//
+// or
+//
+//      2^(q - 2 + alpha) <= c * w < 2^(q + gamma)
+//
+// The choice of (alpha,gamma) determines the size of the table and the form of
+// the digit generation procedure. Using (alpha,gamma)=(-60,-32) works out well
+// in practice:
+//
+// The idea is to cut the number c * w = f * 2^e into two parts, which can be
+// processed independently: An integral part p1, and a fractional part p2:
+//
+//      f * 2^e = ( (f div 2^-e) * 2^-e + (f mod 2^-e) ) * 2^e
+//              = (f div 2^-e) + (f mod 2^-e) * 2^e
+//              = p1 + p2 * 2^e
+//
+// The conversion of p1 into decimal form requires a series of divisions and
+// modulos by (a power of) 10. These operations are faster for 32-bit than for
+// 64-bit integers, so p1 should ideally fit into a 32-bit integer. This can be
+// achieved by choosing
+//
+//      -e >= 32   or   e <= -32 := gamma
+//
+// In order to convert the fractional part
+//
+//      p2 * 2^e = p2 / 2^-e = d[-1] / 10^1 + d[-2] / 10^2 + ...
+//
+// into decimal form, the fraction is repeatedly multiplied by 10 and the digits
+// d[-i] are extracted in order:
+//
+//      (10 * p2) div 2^-e = d[-1]
+//      (10 * p2) mod 2^-e = d[-2] / 10^1 + ...
+//
+// The multiplication by 10 must not overflow. It is sufficient to choose
+//
+//      10 * p2 < 16 * p2 = 2^4 * p2 <= 2^64.
+//
+// Since p2 = f mod 2^-e < 2^-e,
+//
+//      -e <= 60   or   e >= -60 := alpha
+
+constexpr int kAlpha = -60;
+constexpr int kGamma = -32;
+
+struct cached_power // c = f * 2^e ~= 10^k
+{
+    uint64_t f;
+    int e;
+    int k;
+};
+
+/*!
+For a normalized diyfp w = f * 2^e, this function returns a (normalized) cached
+power-of-ten c = f_c * 2^e_c, such that the exponent of the product w * c
+satisfies (Definition 3.2 from [1])
+
+     alpha <= e_c + e + q <= gamma.
+*/
+inline cached_power get_cached_power_for_binary_exponent(int e)
+{
+    // Now
+    //
+    //      alpha <= e_c + e + q <= gamma                                    (1)
+    //      ==> f_c * 2^alpha <= c * 2^e * 2^q
+    //
+    // and since the c's are normalized, 2^(q-1) <= f_c,
+    //
+    //      ==> 2^(q - 1 + alpha) <= c * 2^(e + q)
+    //      ==> 2^(alpha - e - 1) <= c
+    //
+    // If c were an exakt power of ten, i.e. c = 10^k, one may determine k as
+    //
+    //      k = ceil( log_10( 2^(alpha - e - 1) ) )
+    //        = ceil( (alpha - e - 1) * log_10(2) )
+    //
+    // From the paper:
+    // "In theory the result of the procedure could be wrong since c is rounded,
+    //  and the computation itself is approximated [...]. In practice, however,
+    //  this simple function is sufficient."
+    //
+    // For IEEE double precision floating-point numbers converted into
+    // normalized diyfp's w = f * 2^e, with q = 64,
+    //
+    //      e >= -1022      (min IEEE exponent)
+    //           -52        (p - 1)
+    //           -52        (p - 1, possibly normalize denormal IEEE numbers)
+    //           -11        (normalize the diyfp)
+    //         = -1137
+    //
+    // and
+    //
+    //      e <= +1023      (max IEEE exponent)
+    //           -52        (p - 1)
+    //           -11        (normalize the diyfp)
+    //         = 960
+    //
+    // This binary exponent range [-1137,960] results in a decimal exponent
+    // range [-307,324]. One does not need to store a cached power for each
+    // k in this range. For each such k it suffices to find a cached power
+    // such that the exponent of the product lies in [alpha,gamma].
+    // This implies that the difference of the decimal exponents of adjacent
+    // table entries must be less than or equal to
+    //
+    //      floor( (gamma - alpha) * log_10(2) ) = 8.
+    //
+    // (A smaller distance gamma-alpha would require a larger table.)
+
+    // NB:
+    // Actually this function returns c, such that -60 <= e_c + e + 64 <= -34.
+
+    constexpr int kCachedPowersSize = 79;
+    constexpr int kCachedPowersMinDecExp = -300;
+    constexpr int kCachedPowersDecStep = 8;
+
+    static constexpr cached_power kCachedPowers[] =
+    {
+        { 0xAB70FE17C79AC6CA, -1060, -300 },
+        { 0xFF77B1FCBEBCDC4F, -1034, -292 },
+        { 0xBE5691EF416BD60C, -1007, -284 },
+        { 0x8DD01FAD907FFC3C,  -980, -276 },
+        { 0xD3515C2831559A83,  -954, -268 },
+        { 0x9D71AC8FADA6C9B5,  -927, -260 },
+        { 0xEA9C227723EE8BCB,  -901, -252 },
+        { 0xAECC49914078536D,  -874, -244 },
+        { 0x823C12795DB6CE57,  -847, -236 },
+        { 0xC21094364DFB5637,  -821, -228 },
+        { 0x9096EA6F3848984F,  -794, -220 },
+        { 0xD77485CB25823AC7,  -768, -212 },
+        { 0xA086CFCD97BF97F4,  -741, -204 },
+        { 0xEF340A98172AACE5,  -715, -196 },
+        { 0xB23867FB2A35B28E,  -688, -188 },
+        { 0x84C8D4DFD2C63F3B,  -661, -180 },
+        { 0xC5DD44271AD3CDBA,  -635, -172 },
+        { 0x936B9FCEBB25C996,  -608, -164 },
+        { 0xDBAC6C247D62A584,  -582, -156 },
+        { 0xA3AB66580D5FDAF6,  -555, -148 },
+        { 0xF3E2F893DEC3F126,  -529, -140 },
+        { 0xB5B5ADA8AAFF80B8,  -502, -132 },
+        { 0x87625F056C7C4A8B,  -475, -124 },
+        { 0xC9BCFF6034C13053,  -449, -116 },
+        { 0x964E858C91BA2655,  -422, -108 },
+        { 0xDFF9772470297EBD,  -396, -100 },
+        { 0xA6DFBD9FB8E5B88F,  -369,  -92 },
+        { 0xF8A95FCF88747D94,  -343,  -84 },
+        { 0xB94470938FA89BCF,  -316,  -76 },
+        { 0x8A08F0F8BF0F156B,  -289,  -68 },
+        { 0xCDB02555653131B6,  -263,  -60 },
+        { 0x993FE2C6D07B7FAC,  -236,  -52 },
+        { 0xE45C10C42A2B3B06,  -210,  -44 },
+        { 0xAA242499697392D3,  -183,  -36 },
+        { 0xFD87B5F28300CA0E,  -157,  -28 },
+        { 0xBCE5086492111AEB,  -130,  -20 },
+        { 0x8CBCCC096F5088CC,  -103,  -12 },
+        { 0xD1B71758E219652C,   -77,   -4 },
+        { 0x9C40000000000000,   -50,    4 },
+        { 0xE8D4A51000000000,   -24,   12 },
+        { 0xAD78EBC5AC620000,     3,   20 },
+        { 0x813F3978F8940984,    30,   28 },
+        { 0xC097CE7BC90715B3,    56,   36 },
+        { 0x8F7E32CE7BEA5C70,    83,   44 },
+        { 0xD5D238A4ABE98068,   109,   52 },
+        { 0x9F4F2726179A2245,   136,   60 },
+        { 0xED63A231D4C4FB27,   162,   68 },
+        { 0xB0DE65388CC8ADA8,   189,   76 },
+        { 0x83C7088E1AAB65DB,   216,   84 },
+        { 0xC45D1DF942711D9A,   242,   92 },
+        { 0x924D692CA61BE758,   269,  100 },
+        { 0xDA01EE641A708DEA,   295,  108 },
+        { 0xA26DA3999AEF774A,   322,  116 },
+        { 0xF209787BB47D6B85,   348,  124 },
+        { 0xB454E4A179DD1877,   375,  132 },
+        { 0x865B86925B9BC5C2,   402,  140 },
+        { 0xC83553C5C8965D3D,   428,  148 },
+        { 0x952AB45CFA97A0B3,   455,  156 },
+        { 0xDE469FBD99A05FE3,   481,  164 },
+        { 0xA59BC234DB398C25,   508,  172 },
+        { 0xF6C69A72A3989F5C,   534,  180 },
+        { 0xB7DCBF5354E9BECE,   561,  188 },
+        { 0x88FCF317F22241E2,   588,  196 },
+        { 0xCC20CE9BD35C78A5,   614,  204 },
+        { 0x98165AF37B2153DF,   641,  212 },
+        { 0xE2A0B5DC971F303A,   667,  220 },
+        { 0xA8D9D1535CE3B396,   694,  228 },
+        { 0xFB9B7CD9A4A7443C,   720,  236 },
+        { 0xBB764C4CA7A44410,   747,  244 },
+        { 0x8BAB8EEFB6409C1A,   774,  252 },
+        { 0xD01FEF10A657842C,   800,  260 },
+        { 0x9B10A4E5E9913129,   827,  268 },
+        { 0xE7109BFBA19C0C9D,   853,  276 },
+        { 0xAC2820D9623BF429,   880,  284 },
+        { 0x80444B5E7AA7CF85,   907,  292 },
+        { 0xBF21E44003ACDD2D,   933,  300 },
+        { 0x8E679C2F5E44FF8F,   960,  308 },
+        { 0xD433179D9C8CB841,   986,  316 },
+        { 0x9E19DB92B4E31BA9,  1013,  324 },
+    };
+
+    // This computation gives exactly the same results for k as
+    //      k = ceil((kAlpha - e - 1) * 0.30102999566398114)
+    // for |e| <= 1500, but doesn't require floating-point operations.
+    // NB: log_10(2) ~= 78913 / 2^18
+    assert(e >= -1500);
+    assert(e <=  1500);
+    const int f = kAlpha - e - 1;
+    const int k = (f * 78913) / (1 << 18) + (f > 0);
+
+    const int index = (-kCachedPowersMinDecExp + k + (kCachedPowersDecStep - 1)) / kCachedPowersDecStep;
+    assert(index >= 0);
+    assert(index < kCachedPowersSize);
+    static_cast<void>(kCachedPowersSize); // Fix warning.
+
+    const cached_power cached = kCachedPowers[index];
+    assert(kAlpha <= cached.e + e + 64);
+    assert(kGamma >= cached.e + e + 64);
+
+    return cached;
+}
+
+/*!
+For n != 0, returns k, such that pow10 := 10^(k-1) <= n < 10^k.
+For n == 0, returns 1 and sets pow10 := 1.
+*/
+inline int find_largest_pow10(const uint32_t n, uint32_t& pow10)
+{
+    // LCOV_EXCL_START
+    if (n >= 1000000000)
+    {
+        pow10 = 1000000000;
+        return 10;
+    }
+    // LCOV_EXCL_STOP
+    else if (n >= 100000000)
+    {
+        pow10 = 100000000;
+        return  9;
+    }
+    else if (n >= 10000000)
+    {
+        pow10 = 10000000;
+        return  8;
+    }
+    else if (n >= 1000000)
+    {
+        pow10 = 1000000;
+        return  7;
+    }
+    else if (n >= 100000)
+    {
+        pow10 = 100000;
+        return  6;
+    }
+    else if (n >= 10000)
+    {
+        pow10 = 10000;
+        return  5;
+    }
+    else if (n >= 1000)
+    {
+        pow10 = 1000;
+        return  4;
+    }
+    else if (n >= 100)
+    {
+        pow10 = 100;
+        return  3;
+    }
+    else if (n >= 10)
+    {
+        pow10 = 10;
+        return  2;
+    }
+    else
+    {
+        pow10 = 1;
+        return 1;
+    }
+}
+
+inline void grisu2_round(char* buf, int len, uint64_t dist, uint64_t delta,
+                         uint64_t rest, uint64_t ten_k)
+{
+    assert(len >= 1);
+    assert(dist <= delta);
+    assert(rest <= delta);
+    assert(ten_k > 0);
+
+    //               <--------------------------- delta ---->
+    //                                  <---- dist --------->
+    // --------------[------------------+-------------------]--------------
+    //               M-                 w                   M+
+    //
+    //                                  ten_k
+    //                                <------>
+    //                                       <---- rest ---->
+    // --------------[------------------+----+--------------]--------------
+    //                                  w    V
+    //                                       = buf * 10^k
+    //
+    // ten_k represents a unit-in-the-last-place in the decimal representation
+    // stored in buf.
+    // Decrement buf by ten_k while this takes buf closer to w.
+
+    // The tests are written in this order to avoid overflow in unsigned
+    // integer arithmetic.
+
+    while (rest < dist
+            and delta - rest >= ten_k
+            and (rest + ten_k < dist or dist - rest > rest + ten_k - dist))
+    {
+        assert(buf[len - 1] != '0');
+        buf[len - 1]--;
+        rest += ten_k;
+    }
+}
+
+/*!
+Generates V = buffer * 10^decimal_exponent, such that M- <= V <= M+.
+M- and M+ must be normalized and share the same exponent -60 <= e <= -32.
+*/
+inline void grisu2_digit_gen(char* buffer, int& length, int& decimal_exponent,
+                             diyfp M_minus, diyfp w, diyfp M_plus)
+{
+    static_assert(kAlpha >= -60, "internal error");
+    static_assert(kGamma <= -32, "internal error");
+
+    // Generates the digits (and the exponent) of a decimal floating-point
+    // number V = buffer * 10^decimal_exponent in the range [M-, M+]. The diyfp's
+    // w, M- and M+ share the same exponent e, which satisfies alpha <= e <= gamma.
+    //
+    //               <--------------------------- delta ---->
+    //                                  <---- dist --------->
+    // --------------[------------------+-------------------]--------------
+    //               M-                 w                   M+
+    //
+    // Grisu2 generates the digits of M+ from left to right and stops as soon as
+    // V is in [M-,M+].
+
+    assert(M_plus.e >= kAlpha);
+    assert(M_plus.e <= kGamma);
+
+    uint64_t delta = diyfp::sub(M_plus, M_minus).f; // (significand of (M+ - M-), implicit exponent is e)
+    uint64_t dist  = diyfp::sub(M_plus, w      ).f; // (significand of (M+ - w ), implicit exponent is e)
+
+    // Split M+ = f * 2^e into two parts p1 and p2 (note: e < 0):
+    //
+    //      M+ = f * 2^e
+    //         = ((f div 2^-e) * 2^-e + (f mod 2^-e)) * 2^e
+    //         = ((p1        ) * 2^-e + (p2        )) * 2^e
+    //         = p1 + p2 * 2^e
+
+    const diyfp one(uint64_t{1} << -M_plus.e, M_plus.e);
+
+    uint32_t p1 = static_cast<uint32_t>(M_plus.f >> -one.e); // p1 = f div 2^-e (Since -e >= 32, p1 fits into a 32-bit int.)
+    uint64_t p2 = M_plus.f & (one.f - 1);                    // p2 = f mod 2^-e
+
+    // 1)
+    //
+    // Generate the digits of the integral part p1 = d[n-1]...d[1]d[0]
+
+    assert(p1 > 0);
+
+    uint32_t pow10;
+    const int k = find_largest_pow10(p1, pow10);
+
+    //      10^(k-1) <= p1 < 10^k, pow10 = 10^(k-1)
+    //
+    //      p1 = (p1 div 10^(k-1)) * 10^(k-1) + (p1 mod 10^(k-1))
+    //         = (d[k-1]         ) * 10^(k-1) + (p1 mod 10^(k-1))
+    //
+    //      M+ = p1                                             + p2 * 2^e
+    //         = d[k-1] * 10^(k-1) + (p1 mod 10^(k-1))          + p2 * 2^e
+    //         = d[k-1] * 10^(k-1) + ((p1 mod 10^(k-1)) * 2^-e + p2) * 2^e
+    //         = d[k-1] * 10^(k-1) + (                         rest) * 2^e
+    //
+    // Now generate the digits d[n] of p1 from left to right (n = k-1,...,0)
+    //
+    //      p1 = d[k-1]...d[n] * 10^n + d[n-1]...d[0]
+    //
+    // but stop as soon as
+    //
+    //      rest * 2^e = (d[n-1]...d[0] * 2^-e + p2) * 2^e <= delta * 2^e
+
+    int n = k;
+    while (n > 0)
+    {
+        // Invariants:
+        //      M+ = buffer * 10^n + (p1 + p2 * 2^e)    (buffer = 0 for n = k)
+        //      pow10 = 10^(n-1) <= p1 < 10^n
+        //
+        const uint32_t d = p1 / pow10;  // d = p1 div 10^(n-1)
+        const uint32_t r = p1 % pow10;  // r = p1 mod 10^(n-1)
+        //
+        //      M+ = buffer * 10^n + (d * 10^(n-1) + r) + p2 * 2^e
+        //         = (buffer * 10 + d) * 10^(n-1) + (r + p2 * 2^e)
+        //
+        assert(d <= 9);
+        buffer[length++] = static_cast<char>('0' + d); // buffer := buffer * 10 + d
+        //
+        //      M+ = buffer * 10^(n-1) + (r + p2 * 2^e)
+        //
+        p1 = r;
+        n--;
+        //
+        //      M+ = buffer * 10^n + (p1 + p2 * 2^e)
+        //      pow10 = 10^n
+        //
+
+        // Now check if enough digits have been generated.
+        // Compute
+        //
+        //      p1 + p2 * 2^e = (p1 * 2^-e + p2) * 2^e = rest * 2^e
+        //
+        // Note:
+        // Since rest and delta share the same exponent e, it suffices to
+        // compare the significands.
+        const uint64_t rest = (uint64_t{p1} << -one.e) + p2;
+        if (rest <= delta)
+        {
+            // V = buffer * 10^n, with M- <= V <= M+.
+
+            decimal_exponent += n;
+
+            // We may now just stop. But instead look if the buffer could be
+            // decremented to bring V closer to w.
+            //
+            // pow10 = 10^n is now 1 ulp in the decimal representation V.
+            // The rounding procedure works with diyfp's with an implicit
+            // exponent of e.
+            //
+            //      10^n = (10^n * 2^-e) * 2^e = ulp * 2^e
+            //
+            const uint64_t ten_n = uint64_t{pow10} << -one.e;
+            grisu2_round(buffer, length, dist, delta, rest, ten_n);
+
+            return;
+        }
+
+        pow10 /= 10;
+        //
+        //      pow10 = 10^(n-1) <= p1 < 10^n
+        // Invariants restored.
+    }
+
+    // 2)
+    //
+    // The digits of the integral part have been generated:
+    //
+    //      M+ = d[k-1]...d[1]d[0] + p2 * 2^e
+    //         = buffer            + p2 * 2^e
+    //
+    // Now generate the digits of the fractional part p2 * 2^e.
+    //
+    // Note:
+    // No decimal point is generated: the exponent is adjusted instead.
+    //
+    // p2 actually represents the fraction
+    //
+    //      p2 * 2^e
+    //          = p2 / 2^-e
+    //          = d[-1] / 10^1 + d[-2] / 10^2 + ...
+    //
+    // Now generate the digits d[-m] of p1 from left to right (m = 1,2,...)
+    //
+    //      p2 * 2^e = d[-1]d[-2]...d[-m] * 10^-m
+    //                      + 10^-m * (d[-m-1] / 10^1 + d[-m-2] / 10^2 + ...)
+    //
+    // using
+    //
+    //      10^m * p2 = ((10^m * p2) div 2^-e) * 2^-e + ((10^m * p2) mod 2^-e)
+    //                = (                   d) * 2^-e + (                   r)
+    //
+    // or
+    //      10^m * p2 * 2^e = d + r * 2^e
+    //
+    // i.e.
+    //
+    //      M+ = buffer + p2 * 2^e
+    //         = buffer + 10^-m * (d + r * 2^e)
+    //         = (buffer * 10^m + d) * 10^-m + 10^-m * r * 2^e
+    //
+    // and stop as soon as 10^-m * r * 2^e <= delta * 2^e
+
+    assert(p2 > delta);
+
+    int m = 0;
+    for (;;)
+    {
+        // Invariant:
+        //      M+ = buffer * 10^-m + 10^-m * (d[-m-1] / 10 + d[-m-2] / 10^2 + ...) * 2^e
+        //         = buffer * 10^-m + 10^-m * (p2                                 ) * 2^e
+        //         = buffer * 10^-m + 10^-m * (1/10 * (10 * p2)                   ) * 2^e
+        //         = buffer * 10^-m + 10^-m * (1/10 * ((10*p2 div 2^-e) * 2^-e + (10*p2 mod 2^-e)) * 2^e
+        //
+        assert(p2 <= UINT64_MAX / 10);
+        p2 *= 10;
+        const uint64_t d = p2 >> -one.e;     // d = (10 * p2) div 2^-e
+        const uint64_t r = p2 & (one.f - 1); // r = (10 * p2) mod 2^-e
+        //
+        //      M+ = buffer * 10^-m + 10^-m * (1/10 * (d * 2^-e + r) * 2^e
+        //         = buffer * 10^-m + 10^-m * (1/10 * (d + r * 2^e))
+        //         = (buffer * 10 + d) * 10^(-m-1) + 10^(-m-1) * r * 2^e
+        //
+        assert(d <= 9);
+        buffer[length++] = static_cast<char>('0' + d); // buffer := buffer * 10 + d
+        //
+        //      M+ = buffer * 10^(-m-1) + 10^(-m-1) * r * 2^e
+        //
+        p2 = r;
+        m++;
+        //
+        //      M+ = buffer * 10^-m + 10^-m * p2 * 2^e
+        // Invariant restored.
+
+        // Check if enough digits have been generated.
+        //
+        //      10^-m * p2 * 2^e <= delta * 2^e
+        //              p2 * 2^e <= 10^m * delta * 2^e
+        //                    p2 <= 10^m * delta
+        delta *= 10;
+        dist  *= 10;
+        if (p2 <= delta)
+        {
+            break;
+        }
+    }
+
+    // V = buffer * 10^-m, with M- <= V <= M+.
+
+    decimal_exponent -= m;
+
+    // 1 ulp in the decimal representation is now 10^-m.
+    // Since delta and dist are now scaled by 10^m, we need to do the
+    // same with ulp in order to keep the units in sync.
+    //
+    //      10^m * 10^-m = 1 = 2^-e * 2^e = ten_m * 2^e
+    //
+    const uint64_t ten_m = one.f;
+    grisu2_round(buffer, length, dist, delta, p2, ten_m);
+
+    // By construction this algorithm generates the shortest possible decimal
+    // number (Loitsch, Theorem 6.2) which rounds back to w.
+    // For an input number of precision p, at least
+    //
+    //      N = 1 + ceil(p * log_10(2))
+    //
+    // decimal digits are sufficient to identify all binary floating-point
+    // numbers (Matula, "In-and-Out conversions").
+    // This implies that the algorithm does not produce more than N decimal
+    // digits.
+    //
+    //      N = 17 for p = 53 (IEEE double precision)
+    //      N = 9  for p = 24 (IEEE single precision)
+}
+
+/*!
+v = buf * 10^decimal_exponent
+len is the length of the buffer (number of decimal digits)
+The buffer must be large enough, i.e. >= max_digits10.
+*/
+inline void grisu2(char* buf, int& len, int& decimal_exponent,
+                   diyfp m_minus, diyfp v, diyfp m_plus)
+{
+    assert(m_plus.e == m_minus.e);
+    assert(m_plus.e == v.e);
+
+    //  --------(-----------------------+-----------------------)--------    (A)
+    //          m-                      v                       m+
+    //
+    //  --------------------(-----------+-----------------------)--------    (B)
+    //                      m-          v                       m+
+    //
+    // First scale v (and m- and m+) such that the exponent is in the range
+    // [alpha, gamma].
+
+    const cached_power cached = get_cached_power_for_binary_exponent(m_plus.e);
+
+    const diyfp c_minus_k(cached.f, cached.e); // = c ~= 10^-k
+
+    // The exponent of the products is = v.e + c_minus_k.e + q and is in the range [alpha,gamma]
+    const diyfp w       = diyfp::mul(v,       c_minus_k);
+    const diyfp w_minus = diyfp::mul(m_minus, c_minus_k);
+    const diyfp w_plus  = diyfp::mul(m_plus,  c_minus_k);
+
+    //  ----(---+---)---------------(---+---)---------------(---+---)----
+    //          w-                      w                       w+
+    //          = c*m-                  = c*v                   = c*m+
+    //
+    // diyfp::mul rounds its result and c_minus_k is approximated too. w, w- and
+    // w+ are now off by a small amount.
+    // In fact:
+    //
+    //      w - v * 10^k < 1 ulp
+    //
+    // To account for this inaccuracy, add resp. subtract 1 ulp.
+    //
+    //  --------+---[---------------(---+---)---------------]---+--------
+    //          w-  M-                  w                   M+  w+
+    //
+    // Now any number in [M-, M+] (bounds included) will round to w when input,
+    // regardless of how the input rounding algorithm breaks ties.
+    //
+    // And digit_gen generates the shortest possible such number in [M-, M+].
+    // Note that this does not mean that Grisu2 always generates the shortest
+    // possible number in the interval (m-, m+).
+    const diyfp M_minus(w_minus.f + 1, w_minus.e);
+    const diyfp M_plus (w_plus.f  - 1, w_plus.e );
+
+    decimal_exponent = -cached.k; // = -(-k) = k
+
+    grisu2_digit_gen(buf, len, decimal_exponent, M_minus, w, M_plus);
+}
+
+/*!
+v = buf * 10^decimal_exponent
+len is the length of the buffer (number of decimal digits)
+The buffer must be large enough, i.e. >= max_digits10.
+*/
+template <typename FloatType>
+void grisu2(char* buf, int& len, int& decimal_exponent, FloatType value)
+{
+    static_assert(diyfp::kPrecision >= std::numeric_limits<FloatType>::digits + 3,
+                  "internal error: not enough precision");
+
+    assert(std::isfinite(value));
+    assert(value > 0);
+
+    // If the neighbors (and boundaries) of 'value' are always computed for double-precision
+    // numbers, all float's can be recovered using strtod (and strtof). However, the resulting
+    // decimal representations are not exactly "short".
+    //
+    // The documentation for 'std::to_chars' (http://en.cppreference.com/w/cpp/utility/to_chars)
+    // says "value is converted to a string as if by std::sprintf in the default ("C") locale"
+    // and since sprintf promotes float's to double's, I think this is exactly what 'std::to_chars'
+    // does.
+    // On the other hand, the documentation for 'std::to_chars' requires that "parsing the
+    // representation using the corresponding std::from_chars function recovers value exactly". That
+    // indicates that single precision floating-point numbers should be recovered using
+    // 'std::strtof'.
+    //
+    // NB: If the neighbors are computed for single-precision numbers, there is a single float
+    //     (7.0385307e-26f) which can't be recovered using strtod. The resulting double precision
+    //     value is off by 1 ulp.
+#if 0
+    const boundaries w = compute_boundaries(static_cast<double>(value));
+#else
+    const boundaries w = compute_boundaries(value);
+#endif
+
+    grisu2(buf, len, decimal_exponent, w.minus, w.w, w.plus);
+}
+
+/*!
+@brief appends a decimal representation of e to buf
+@return a pointer to the element following the exponent.
+@pre -1000 < e < 1000
+*/
+inline char* append_exponent(char* buf, int e)
+{
+    assert(e > -1000);
+    assert(e <  1000);
+
+    if (e < 0)
+    {
+        e = -e;
+        *buf++ = '-';
+    }
+    else
+    {
+        *buf++ = '+';
+    }
+
+    uint32_t k = static_cast<uint32_t>(e);
+    if (k < 10)
+    {
+        // Always print at least two digits in the exponent.
+        // This is for compatibility with printf("%g").
+        *buf++ = '0';
+        *buf++ = static_cast<char>('0' + k);
+    }
+    else if (k < 100)
+    {
+        *buf++ = static_cast<char>('0' + k / 10);
+        k %= 10;
+        *buf++ = static_cast<char>('0' + k);
+    }
+    else
+    {
+        *buf++ = static_cast<char>('0' + k / 100);
+        k %= 100;
+        *buf++ = static_cast<char>('0' + k / 10);
+        k %= 10;
+        *buf++ = static_cast<char>('0' + k);
+    }
+
+    return buf;
+}
+
+/*!
+@brief prettify v = buf * 10^decimal_exponent
+
+If v is in the range [10^min_exp, 10^max_exp) it will be printed in fixed-point
+notation. Otherwise it will be printed in exponential notation.
+
+@pre min_exp < 0
+@pre max_exp > 0
+*/
+inline char* format_buffer(char* buf, int len, int decimal_exponent,
+                           int min_exp, int max_exp)
+{
+    assert(min_exp < 0);
+    assert(max_exp > 0);
+
+    const int k = len;
+    const int n = len + decimal_exponent;
+
+    // v = buf * 10^(n-k)
+    // k is the length of the buffer (number of decimal digits)
+    // n is the position of the decimal point relative to the start of the buffer.
+
+    if (k <= n and n <= max_exp)
+    {
+        // digits[000]
+        // len <= max_exp + 2
+
+        std::memset(buf + k, '0', static_cast<size_t>(n - k));
+        // Make it look like a floating-point number (#362, #378)
+        buf[n + 0] = '.';
+        buf[n + 1] = '0';
+        return buf + (n + 2);
+    }
+
+    if (0 < n and n <= max_exp)
+    {
+        // dig.its
+        // len <= max_digits10 + 1
+
+        assert(k > n);
+
+        std::memmove(buf + (n + 1), buf + n, static_cast<size_t>(k - n));
+        buf[n] = '.';
+        return buf + (k + 1);
+    }
+
+    if (min_exp < n and n <= 0)
+    {
+        // 0.[000]digits
+        // len <= 2 + (-min_exp - 1) + max_digits10
+
+        std::memmove(buf + (2 + -n), buf, static_cast<size_t>(k));
+        buf[0] = '0';
+        buf[1] = '.';
+        std::memset(buf + 2, '0', static_cast<size_t>(-n));
+        return buf + (2 + (-n) + k);
+    }
+
+    if (k == 1)
+    {
+        // dE+123
+        // len <= 1 + 5
+
+        buf += 1;
+    }
+    else
+    {
+        // d.igitsE+123
+        // len <= max_digits10 + 1 + 5
+
+        std::memmove(buf + 2, buf + 1, static_cast<size_t>(k - 1));
+        buf[1] = '.';
+        buf += 1 + k;
+    }
+
+    *buf++ = 'e';
+    return append_exponent(buf, n - 1);
+}
+
+} // namespace dtoa_impl
+
+/*!
+@brief generates a decimal representation of the floating-point number value in [first, last).
+
+The format of the resulting decimal representation is similar to printf's %g
+format. Returns an iterator pointing past-the-end of the decimal representation.
+
+@note The input number must be finite, i.e. NaN's and Inf's are not supported.
+@note The buffer must be large enough.
+@note The result is NOT null-terminated.
+*/
+template <typename FloatType>
+char* to_chars(char* first, char* last, FloatType value)
+{
+    static_cast<void>(last); // maybe unused - fix warning
+    assert(std::isfinite(value));
+
+    // Use signbit(value) instead of (value < 0) since signbit works for -0.
+    if (std::signbit(value))
+    {
+        value = -value;
+        *first++ = '-';
+    }
+
+    if (value == 0) // +-0
+    {
+        *first++ = '0';
+        // Make it look like a floating-point number (#362, #378)
+        *first++ = '.';
+        *first++ = '0';
+        return first;
+    }
+
+    assert(last - first >= std::numeric_limits<FloatType>::max_digits10);
+
+    // Compute v = buffer * 10^decimal_exponent.
+    // The decimal digits are stored in the buffer, which needs to be interpreted
+    // as an unsigned decimal integer.
+    // len is the length of the buffer, i.e. the number of decimal digits.
+    int len = 0;
+    int decimal_exponent = 0;
+    dtoa_impl::grisu2(first, len, decimal_exponent, value);
+
+    assert(len <= std::numeric_limits<FloatType>::max_digits10);
+
+    // Format the buffer like printf("%.*g", prec, value)
+    constexpr int kMinExp = -4;
+    // Use digits10 here to increase compatibility with version 2.
+    constexpr int kMaxExp = std::numeric_limits<FloatType>::digits10;
+
+    assert(last - first >= kMaxExp + 2);
+    assert(last - first >= 2 + (-kMinExp - 1) + std::numeric_limits<FloatType>::max_digits10);
+    assert(last - first >= std::numeric_limits<FloatType>::max_digits10 + 6);
+
+    return dtoa_impl::format_buffer(first, len, decimal_exponent, kMinExp, kMaxExp);
+}
+
+}  // namespace
+
+void json::serializer::dump(const json& val, const bool pretty_print,
+          const bool ensure_ascii,
+          const unsigned int indent_step,
+          const unsigned int current_indent)
+{
+    switch (val.m_type)
+    {
+        case value_t::object:
+        {
+            if (val.m_value.object->empty())
+            {
+                o << "{}";
+                return;
+            }
+
+            // we need to iterate over the object values in sorted key order
+            SmallVector<StringMapConstIterator<json>, 64> sorted;
+            for (auto i = val.m_value.object->begin(),
+                 end = val.m_value.object->end(); i != end; ++i)
+            {
+                sorted.push_back(i);
+            }
+            std::sort(sorted.begin(), sorted.end(),
+                      [](const StringMapConstIterator<json>& a,
+                         const StringMapConstIterator<json>& b) {
+                        return a->getKey() < b->getKey();
+                      });
+
+            if (pretty_print)
+            {
+                o << "{\n";
+
+                // variable to hold indentation for recursive calls
+                const auto new_indent = current_indent + indent_step;
+                if (JSON_UNLIKELY(indent_string.size() < new_indent))
+                {
+                    indent_string.resize(indent_string.size() * 2, indent_char);
+                }
+
+                // first n-1 elements
+                auto i = sorted.begin();
+                for (std::size_t cnt = 0; cnt < sorted.size() - 1; ++cnt, ++i)
+                {
+                    o.write(indent_string.c_str(), new_indent);
+                    o << '\"';
+                    dump_escaped((*i)->first(), ensure_ascii);
+                    o << "\": ";
+                    dump((*i)->second, true, ensure_ascii, indent_step, new_indent);
+                    o << ",\n";
+                }
+
+                // last element
+                assert(i != sorted.end());
+                //assert(std::next(i) == val.m_value.object->end());
+                o.write(indent_string.c_str(), new_indent);
+                o << '\"';
+                dump_escaped((*i)->first(), ensure_ascii);
+                o << "\": ";
+                dump((*i)->second, true, ensure_ascii, indent_step, new_indent);
+
+                o << '\n';
+                o.write(indent_string.c_str(), current_indent);
+                o << '}';
+            }
+            else
+            {
+                o << '{';
+
+                // first n-1 elements
+                auto i = sorted.begin();
+                for (std::size_t cnt = 0; cnt < sorted.size() - 1; ++cnt, ++i)
+                {
+                    o << '\"';
+                    dump_escaped((*i)->first(), ensure_ascii);
+                    o << "\":";
+                    dump((*i)->second, false, ensure_ascii, indent_step, current_indent);
+                    o << ',';
+                }
+
+                // last element
+                assert(i != sorted.end());
+                //assert(std::next(i) == val.m_value.object->end());
+                o << '\"';
+                dump_escaped((*i)->first(), ensure_ascii);
+                o << "\":";
+                dump((*i)->second, false, ensure_ascii, indent_step, current_indent);
+
+                o << '}';
+            }
+
+            return;
+        }
+
+        case value_t::array:
+        {
+            if (val.m_value.array->empty())
+            {
+                o << "[]";
+                return;
+            }
+
+            if (pretty_print)
+            {
+                o << "[\n";
+
+                // variable to hold indentation for recursive calls
+                const auto new_indent = current_indent + indent_step;
+                if (JSON_UNLIKELY(indent_string.size() < new_indent))
+                {
+                    indent_string.resize(indent_string.size() * 2, indent_char);
+                }
+
+                // first n-1 elements
+                for (auto i = val.m_value.array->cbegin();
+                        i != val.m_value.array->cend() - 1; ++i)
+                {
+                    o.write(indent_string.c_str(), new_indent);
+                    dump(*i, true, ensure_ascii, indent_step, new_indent);
+                    o << ",\n";
+                }
+
+                // last element
+                assert(not val.m_value.array->empty());
+                o.write(indent_string.c_str(), new_indent);
+                dump(val.m_value.array->back(), true, ensure_ascii, indent_step, new_indent);
+
+                o << '\n';
+                o.write(indent_string.c_str(), current_indent);
+                o << ']';
+            }
+            else
+            {
+                o << '[';
+
+                // first n-1 elements
+                for (auto i = val.m_value.array->cbegin();
+                        i != val.m_value.array->cend() - 1; ++i)
+                {
+                    dump(*i, false, ensure_ascii, indent_step, current_indent);
+                    o << ',';
+                }
+
+                // last element
+                assert(not val.m_value.array->empty());
+                dump(val.m_value.array->back(), false, ensure_ascii, indent_step, current_indent);
+
+                o << ']';
+            }
+
+            return;
+        }
+
+        case value_t::string:
+        {
+            o << '\"';
+            dump_escaped(*val.m_value.string, ensure_ascii);
+            o << '\"';
+            return;
+        }
+
+        case value_t::boolean:
+        {
+            if (val.m_value.boolean)
+            {
+                o << "true";
+            }
+            else
+            {
+                o << "false";
+            }
+            return;
+        }
+
+        case value_t::number_integer:
+        {
+            dump_integer(val.m_value.number_integer);
+            return;
+        }
+
+        case value_t::number_unsigned:
+        {
+            dump_integer(val.m_value.number_unsigned);
+            return;
+        }
+
+        case value_t::number_float:
+        {
+            dump_float(val.m_value.number_float);
+            return;
+        }
+
+        case value_t::discarded:
+        {
+            o << "<discarded>";
+            return;
+        }
+
+        case value_t::null:
+        {
+            o << "null";
+            return;
+        }
+    }
+}
+
+void json::serializer::dump_escaped(StringRef s, const bool ensure_ascii)
+{
+    uint32_t codepoint;
+    uint8_t state = UTF8_ACCEPT;
+
+    for (std::size_t i = 0; i < s.size(); ++i)
+    {
+        const auto byte = static_cast<uint8_t>(s[i]);
+
+        switch (decode(state, codepoint, byte))
+        {
+            case UTF8_ACCEPT:  // decode found a new code point
+            {
+                switch (codepoint)
+                {
+                    case 0x08: // backspace
+                    {
+                        o << '\\' << 'b';
+                        break;
+                    }
+
+                    case 0x09: // horizontal tab
+                    {
+                        o << '\\' << 't';
+                        break;
+                    }
+
+                    case 0x0A: // newline
+                    {
+                        o << '\\' << 'n';
+                        break;
+                    }
+
+                    case 0x0C: // formfeed
+                    {
+                        o << '\\' << 'f';
+                        break;
+                    }
+
+                    case 0x0D: // carriage return
+                    {
+                        o << '\\' << 'r';
+                        break;
+                    }
+
+                    case 0x22: // quotation mark
+                    {
+                        o << '\\' << '\"';
+                        break;
+                    }
+
+                    case 0x5C: // reverse solidus
+                    {
+                        o << '\\' << '\\';
+                        break;
+                    }
+
+                    default:
+                    {
+                        // escape control characters (0x00..0x1F) or, if
+                        // ensure_ascii parameter is used, non-ASCII characters
+                        if ((codepoint <= 0x1F) or (ensure_ascii and (codepoint >= 0x7F)))
+                        {
+                            if (codepoint <= 0xFFFF)
+                            {
+                                o << '\\' << 'u' << format_hex_no_prefix(codepoint, 4);
+                            }
+                            else
+                            {
+                                o << '\\' << 'u' << format_hex_no_prefix(0xD7C0 + (codepoint >> 10), 4);
+                                o << '\\' << 'u' << format_hex_no_prefix(0xDC00 + (codepoint & 0x3FF), 4);
+                            }
+                        }
+                        else
+                        {
+                            // copy byte to buffer (all previous bytes
+                            // been copied have in default case above)
+                            o << s[i];
+                        }
+                        break;
+                    }
+                }
+                break;
+            }
+
+            case UTF8_REJECT:  // decode found invalid UTF-8 byte
+            {
+                JSON_THROW(type_error::create(316, "invalid UTF-8 byte at index " + Twine(i) + ": 0x" + Twine::utohexstr(byte)));
+            }
+
+            default:  // decode found yet incomplete multi-byte code point
+            {
+                if (not ensure_ascii)
+                {
+                    // code point will not be escaped - copy byte to buffer
+                    o << s[i];
+                }
+                break;
+            }
+        }
+    }
+
+    if (JSON_UNLIKELY(state != UTF8_ACCEPT))
+    {
+        // we finish reading, but do not accept: string was incomplete
+        JSON_THROW(type_error::create(316, "incomplete UTF-8 string; last byte: 0x" + Twine::utohexstr(static_cast<uint8_t>(s.back()))));
+    }
+}
+
+void json::serializer::dump_float(double x)
+{
+    // NaN / inf
+    if (not std::isfinite(x))
+    {
+        o << "null";
+        return;
+    }
+
+    // use the Grisu2 algorithm to produce short numbers which are
+    // guaranteed to round-trip, using strtof and strtod, resp.
+    char* begin = number_buffer.data();
+    char* end = to_chars(begin, begin + number_buffer.size(), x);
+
+    o.write(begin, static_cast<size_t>(end - begin));
+}
+
+uint8_t json::serializer::decode(uint8_t& state, uint32_t& codep, const uint8_t byte) noexcept
+{
+    static const std::array<uint8_t, 400> utf8d =
+    {
+        {
+            0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // 00..1F
+            0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // 20..3F
+            0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // 40..5F
+            0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, // 60..7F
+            1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, 9, // 80..9F
+            7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, 7, // A0..BF
+            8, 8, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, 2, // C0..DF
+            0xA, 0x3, 0x3, 0x3, 0x3, 0x3, 0x3, 0x3, 0x3, 0x3, 0x3, 0x3, 0x3, 0x4, 0x3, 0x3, // E0..EF
+            0xB, 0x6, 0x6, 0x6, 0x5, 0x8, 0x8, 0x8, 0x8, 0x8, 0x8, 0x8, 0x8, 0x8, 0x8, 0x8, // F0..FF
+            0x0, 0x1, 0x2, 0x3, 0x5, 0x8, 0x7, 0x1, 0x1, 0x1, 0x4, 0x6, 0x1, 0x1, 0x1, 0x1, // s0..s0
+            1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 0, 1, 1, 1, 1, 1, 0, 1, 0, 1, 1, 1, 1, 1, 1, // s1..s2
+            1, 2, 1, 1, 1, 1, 1, 2, 1, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 2, 1, 1, 1, 1, 1, 1, 1, 1, // s3..s4
+            1, 2, 1, 1, 1, 1, 1, 1, 1, 2, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 3, 1, 3, 1, 1, 1, 1, 1, 1, // s5..s6
+            1, 3, 1, 1, 1, 1, 1, 3, 1, 3, 1, 1, 1, 1, 1, 1, 1, 3, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1, 1 // s7..s8
+        }
+    };
+
+    const uint8_t type = utf8d[byte];
+
+    codep = (state != UTF8_ACCEPT)
+            ? (byte & 0x3fu) | (codep << 6)
+            : static_cast<uint32_t>(0xff >> type) & (byte);
+
+    state = utf8d[256u + state * 16u + type];
+    return state;
+}
+
+std::string json::dump(const int indent, const char indent_char,
+                 const bool ensure_ascii) const
+{
+    std::string result;
+    raw_string_ostream os(result);
+    dump(os, indent, indent_char, ensure_ascii);
+    return result;
+}
+
+void json::dump(raw_ostream& os, int indent, const char indent_char,
+          const bool ensure_ascii) const
+{
+    serializer s(os, indent_char);
+
+    if (indent >= 0)
+    {
+        s.dump(*this, true, ensure_ascii, static_cast<unsigned int>(indent));
+    }
+    else
+    {
+        s.dump(*this, false, ensure_ascii, 0);
+    }
+
+    os.flush();
+}
+
+raw_ostream& operator<<(raw_ostream& o, const json& j)
+{
+    j.dump(o, 0);
+    return o;
+}
+
+std::ostream& operator<<(std::ostream& o, const json& j)
+{
+    raw_os_ostream os(o);
+    j.dump(os, 0);
+    return o;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_serializer.h b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_serializer.h
new file mode 100644
index 0000000..a9b36d2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/json_serializer.h
@@ -0,0 +1,206 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+#include "wpi/json.h"
+
+#include <clocale> // lconv, localeconv
+#include <cmath>  // labs, isfinite, isnan, signbit, ldexp
+#include <locale> // locale
+
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+class json::serializer
+{
+    static constexpr uint8_t UTF8_ACCEPT = 0;
+    static constexpr uint8_t UTF8_REJECT = 1;
+
+  public:
+    /*!
+    @param[in] s  output stream to serialize to
+    @param[in] ichar  indentation character to use
+    */
+    serializer(raw_ostream& s, const char ichar)
+        : o(s), loc(std::localeconv()),
+          thousands_sep(loc->thousands_sep == nullptr ? '\0' : * (loc->thousands_sep)),
+          decimal_point(loc->decimal_point == nullptr ? '\0' : * (loc->decimal_point)),
+          indent_char(ichar), indent_string(512, indent_char)
+    {}
+
+    // delete because of pointer members
+    serializer(const serializer&) = delete;
+    serializer& operator=(const serializer&) = delete;
+
+    /*!
+    @brief internal implementation of the serialization function
+
+    This function is called by the public member function dump and organizes
+    the serialization internally. The indentation level is propagated as
+    additional parameter. In case of arrays and objects, the function is
+    called recursively.
+
+    - strings and object keys are escaped using `escape_string()`
+    - integer numbers are converted implicitly via `operator<<`
+    - floating-point numbers are converted to a string using `"%g"` format
+
+    @param[in] val             value to serialize
+    @param[in] pretty_print    whether the output shall be pretty-printed
+    @param[in] indent_step     the indent level
+    @param[in] current_indent  the current indent level (only used internally)
+    */
+    void dump(const json& val, const bool pretty_print,
+              const bool ensure_ascii,
+              const unsigned int indent_step,
+              const unsigned int current_indent = 0);
+
+  private:
+    /*!
+    @brief dump escaped string
+
+    Escape a string by replacing certain special characters by a sequence of an
+    escape character (backslash) and another character and other control
+    characters by a sequence of "\u" followed by a four-digit hex
+    representation. The escaped string is written to output stream @a o.
+
+    @param[in] s  the string to escape
+    @param[in] ensure_ascii  whether to escape non-ASCII characters with
+                             \uXXXX sequences
+
+    @complexity Linear in the length of string @a s.
+    */
+    void dump_escaped(StringRef s, const bool ensure_ascii);
+
+    /*!
+    @brief dump an integer
+
+    Dump a given integer to output stream @a o. Works internally with
+    @a number_buffer.
+
+    @param[in] x  integer number (signed or unsigned) to dump
+    @tparam NumberType either @a int64_t or @a uint64_t
+    */
+    template<typename NumberType, detail::enable_if_t<
+                 std::is_same<NumberType, uint64_t>::value or
+                 std::is_same<NumberType, int64_t>::value,
+                 int> = 0>
+    void dump_integer(NumberType x)
+    {
+        // special case for "0"
+        if (x == 0)
+        {
+            o << '0';
+            return;
+        }
+
+        const bool is_negative = (x <= 0) and (x != 0);  // see issue #755
+        std::size_t i = 0;
+
+        while (x != 0)
+        {
+            // spare 1 byte for '\0'
+            assert(i < number_buffer.size() - 1);
+
+            const auto digit = std::labs(static_cast<long>(x % 10));
+            number_buffer[i++] = static_cast<char>('0' + digit);
+            x /= 10;
+        }
+
+        if (is_negative)
+        {
+            // make sure there is capacity for the '-'
+            assert(i < number_buffer.size() - 2);
+            number_buffer[i++] = '-';
+        }
+
+        std::reverse(number_buffer.begin(), number_buffer.begin() + i);
+        o.write(number_buffer.data(), i);
+    }
+
+    /*!
+    @brief dump a floating-point number
+
+    Dump a given floating-point number to output stream @a o. Works internally
+    with @a number_buffer.
+
+    @param[in] x  floating-point number to dump
+    */
+    void dump_float(double x);
+
+    /*!
+    @brief check whether a string is UTF-8 encoded
+
+    The function checks each byte of a string whether it is UTF-8 encoded. The
+    result of the check is stored in the @a state parameter. The function must
+    be called initially with state 0 (accept). State 1 means the string must
+    be rejected, because the current byte is not allowed. If the string is
+    completely processed, but the state is non-zero, the string ended
+    prematurely; that is, the last byte indicated more bytes should have
+    followed.
+
+    @param[in,out] state  the state of the decoding
+    @param[in,out] codep  codepoint (valid only if resulting state is UTF8_ACCEPT)
+    @param[in] byte       next byte to decode
+    @return               new state
+
+    @note The function has been edited: a std::array is used.
+
+    @copyright Copyright (c) 2008-2009 Bjoern Hoehrmann <bjoern@hoehrmann.de>
+    @sa http://bjoern.hoehrmann.de/utf-8/decoder/dfa/
+    */
+    static uint8_t decode(uint8_t& state, uint32_t& codep, const uint8_t byte) noexcept;
+
+  private:
+    /// the output of the serializer
+    raw_ostream& o;
+
+    /// a (hopefully) large enough character buffer
+    std::array<char, 64> number_buffer{{}};
+
+    /// the locale
+    const std::lconv* loc = nullptr;
+    /// the locale's thousand separator character
+    const char thousands_sep = '\0';
+    /// the locale's decimal point character
+    const char decimal_point = '\0';
+
+    /// string buffer
+    std::array<char, 512> string_buffer{{}};
+
+    /// the indentation character
+    const char indent_char;
+    /// the indentation string
+    std::string indent_string;
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/leb128.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/leb128.cpp
new file mode 100644
index 0000000..ce68ed8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/leb128.cpp
@@ -0,0 +1,81 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "wpi/leb128.h"
+
+#include "wpi/raw_istream.h"
+
+namespace wpi {
+
+uint64_t SizeUleb128(uint64_t val) {
+  size_t count = 0;
+  do {
+    val >>= 7;
+    ++count;
+  } while (val != 0);
+  return count;
+}
+
+uint64_t WriteUleb128(SmallVectorImpl<char>& dest, uint64_t val) {
+  size_t count = 0;
+
+  do {
+    unsigned char byte = val & 0x7f;
+    val >>= 7;
+
+    if (val != 0)
+      byte |= 0x80;  // mark this byte to show that more bytes will follow
+
+    dest.push_back(byte);
+    count++;
+  } while (val != 0);
+
+  return count;
+}
+
+uint64_t ReadUleb128(const char* addr, uint64_t* ret) {
+  uint32_t result = 0;
+  int shift = 0;
+  size_t count = 0;
+
+  while (1) {
+    unsigned char byte = *reinterpret_cast<const unsigned char*>(addr);
+    addr++;
+    count++;
+
+    result |= (byte & 0x7f) << shift;
+    shift += 7;
+
+    if (!(byte & 0x80)) break;
+  }
+
+  *ret = result;
+
+  return count;
+}
+
+bool ReadUleb128(raw_istream& is, uint64_t* ret) {
+  uint32_t result = 0;
+  int shift = 0;
+
+  while (1) {
+    unsigned char byte;
+    is.read(reinterpret_cast<char*>(&byte), 1);
+    if (is.has_error()) return false;
+
+    result |= (byte & 0x7f) << shift;
+    shift += 7;
+
+    if (!(byte & 0x80)) break;
+  }
+
+  *ret = result;
+
+  return true;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ConvertUTF.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ConvertUTF.cpp
new file mode 100644
index 0000000..bf51c36
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ConvertUTF.cpp
@@ -0,0 +1,739 @@
+/*===--- ConvertUTF.c - Universal Character Names conversions ---------------===
+ *
+ *                     The LLVM Compiler Infrastructure
+ *
+ * This file is distributed under the University of Illinois Open Source
+ * License. See LICENSE.TXT for details.
+ *
+ *===------------------------------------------------------------------------=*/
+/*
+ * Copyright 2001-2004 Unicode, Inc.
+ * 
+ * Disclaimer
+ * 
+ * This source code is provided as is by Unicode, Inc. No claims are
+ * made as to fitness for any particular purpose. No warranties of any
+ * kind are expressed or implied. The recipient agrees to determine
+ * applicability of information provided. If this file has been
+ * purchased on magnetic or optical media from Unicode, Inc., the
+ * sole remedy for any claim will be exchange of defective media
+ * within 90 days of receipt.
+ * 
+ * Limitations on Rights to Redistribute This Code
+ * 
+ * Unicode, Inc. hereby grants the right to freely use the information
+ * supplied in this file in the creation of products supporting the
+ * Unicode Standard, and to make copies of this file in any form
+ * for internal or external distribution as long as this notice
+ * remains attached.
+ */
+
+/* ---------------------------------------------------------------------
+
+    Conversions between UTF32, UTF-16, and UTF-8. Source code file.
+    Author: Mark E. Davis, 1994.
+    Rev History: Rick McGowan, fixes & updates May 2001.
+    Sept 2001: fixed const & error conditions per
+        mods suggested by S. Parent & A. Lillich.
+    June 2002: Tim Dodd added detection and handling of incomplete
+        source sequences, enhanced error detection, added casts
+        to eliminate compiler warnings.
+    July 2003: slight mods to back out aggressive FFFE detection.
+    Jan 2004: updated switches in from-UTF8 conversions.
+    Oct 2004: updated to use UNI_MAX_LEGAL_UTF32 in UTF-32 conversions.
+
+    See the header file "ConvertUTF.h" for complete documentation.
+
+------------------------------------------------------------------------ */
+
+#include "wpi/ConvertUTF.h"
+#ifdef CVTUTF_DEBUG
+#include <stdio.h>
+#endif
+#include <assert.h>
+
+/*
+ * This code extensively uses fall-through switches.
+ * Keep the compiler from warning about that.
+ */
+#if defined(__clang__) && defined(__has_warning)
+# if __has_warning("-Wimplicit-fallthrough")
+#  define ConvertUTF_DISABLE_WARNINGS \
+    _Pragma("clang diagnostic push")  \
+    _Pragma("clang diagnostic ignored \"-Wimplicit-fallthrough\"")
+#  define ConvertUTF_RESTORE_WARNINGS \
+    _Pragma("clang diagnostic pop")
+# endif
+#elif defined(__GNUC__) && __GNUC__ > 6
+# define ConvertUTF_DISABLE_WARNINGS \
+   _Pragma("GCC diagnostic push")    \
+   _Pragma("GCC diagnostic ignored \"-Wimplicit-fallthrough\"")
+# define ConvertUTF_RESTORE_WARNINGS \
+   _Pragma("GCC diagnostic pop")
+#endif
+#ifndef ConvertUTF_DISABLE_WARNINGS
+# define ConvertUTF_DISABLE_WARNINGS
+#endif
+#ifndef ConvertUTF_RESTORE_WARNINGS
+# define ConvertUTF_RESTORE_WARNINGS
+#endif
+
+ConvertUTF_DISABLE_WARNINGS
+
+namespace wpi {
+
+static const int halfShift  = 10; /* used for shifting by 10 bits */
+
+static const UTF32 halfBase = 0x0010000UL;
+static const UTF32 halfMask = 0x3FFUL;
+
+#define UNI_SUR_HIGH_START  (UTF32)0xD800
+#define UNI_SUR_HIGH_END    (UTF32)0xDBFF
+#define UNI_SUR_LOW_START   (UTF32)0xDC00
+#define UNI_SUR_LOW_END     (UTF32)0xDFFF
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Index into the table below with the first byte of a UTF-8 sequence to
+ * get the number of trailing bytes that are supposed to follow it.
+ * Note that *legal* UTF-8 values can't have 4 or 5-bytes. The table is
+ * left as-is for anyone who may want to do such conversion, which was
+ * allowed in earlier algorithms.
+ */
+static const char trailingBytesForUTF8[256] = {
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0, 0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,
+    1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1, 1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,1,
+    2,2,2,2,2,2,2,2,2,2,2,2,2,2,2,2, 3,3,3,3,3,3,3,3,4,4,4,4,5,5,5,5
+};
+
+/*
+ * Magic values subtracted from a buffer value during UTF8 conversion.
+ * This table contains as many values as there might be trailing bytes
+ * in a UTF-8 sequence.
+ */
+static const UTF32 offsetsFromUTF8[6] = { 0x00000000UL, 0x00003080UL, 0x000E2080UL, 
+                     0x03C82080UL, 0xFA082080UL, 0x82082080UL };
+
+/*
+ * Once the bits are split out into bytes of UTF-8, this is a mask OR-ed
+ * into the first byte, depending on how many bytes follow.  There are
+ * as many entries in this table as there are UTF-8 sequence types.
+ * (I.e., one byte sequence, two byte... etc.). Remember that sequencs
+ * for *legal* UTF-8 will be 4 or fewer bytes total.
+ */
+static const UTF8 firstByteMark[7] = { 0x00, 0x00, 0xC0, 0xE0, 0xF0, 0xF8, 0xFC };
+
+/* --------------------------------------------------------------------- */
+
+/* The interface converts a whole buffer to avoid function-call overhead.
+ * Constants have been gathered. Loops & conditionals have been removed as
+ * much as possible for efficiency, in favor of drop-through switches.
+ * (See "Note A" at the bottom of the file for equivalent code.)
+ * If your compiler supports it, the "isLegalUTF8" call can be turned
+ * into an inline function.
+ */
+
+
+/* --------------------------------------------------------------------- */
+
+ConversionResult ConvertUTF32toUTF16 (
+        const UTF32** sourceStart, const UTF32* sourceEnd, 
+        UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF32* source = *sourceStart;
+    UTF16* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch;
+        if (target >= targetEnd) {
+            result = targetExhausted; break;
+        }
+        ch = *source++;
+        if (ch <= UNI_MAX_BMP) { /* Target is a character <= 0xFFFF */
+            /* UTF-16 surrogate values are illegal in UTF-32; 0xffff or 0xfffe are both reserved values */
+            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
+                if (flags == strictConversion) {
+                    --source; /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                } else {
+                    *target++ = UNI_REPLACEMENT_CHAR;
+                }
+            } else {
+                *target++ = (UTF16)ch; /* normal case */
+            }
+        } else if (ch > UNI_MAX_LEGAL_UTF32) {
+            if (flags == strictConversion) {
+                result = sourceIllegal;
+            } else {
+                *target++ = UNI_REPLACEMENT_CHAR;
+            }
+        } else {
+            /* target is a character in range 0xFFFF - 0x10FFFF. */
+            if (target + 1 >= targetEnd) {
+                --source; /* Back up source pointer! */
+                result = targetExhausted; break;
+            }
+            ch -= halfBase;
+            *target++ = (UTF16)((ch >> halfShift) + UNI_SUR_HIGH_START);
+            *target++ = (UTF16)((ch & halfMask) + UNI_SUR_LOW_START);
+        }
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+/* --------------------------------------------------------------------- */
+
+ConversionResult ConvertUTF16toUTF32 (
+        const UTF16** sourceStart, const UTF16* sourceEnd, 
+        UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF16* source = *sourceStart;
+    UTF32* target = *targetStart;
+    UTF32 ch, ch2;
+    while (source < sourceEnd) {
+        const UTF16* oldSource = source; /*  In case we have to back up because of target overflow. */
+        ch = *source++;
+        /* If we have a surrogate pair, convert to UTF32 first. */
+        if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_HIGH_END) {
+            /* If the 16 bits following the high surrogate are in the source buffer... */
+            if (source < sourceEnd) {
+                ch2 = *source;
+                /* If it's a low surrogate, convert to UTF32. */
+                if (ch2 >= UNI_SUR_LOW_START && ch2 <= UNI_SUR_LOW_END) {
+                    ch = ((ch - UNI_SUR_HIGH_START) << halfShift)
+                        + (ch2 - UNI_SUR_LOW_START) + halfBase;
+                    ++source;
+                } else if (flags == strictConversion) { /* it's an unpaired high surrogate */
+                    --source; /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                }
+            } else { /* We don't have the 16 bits following the high surrogate. */
+                --source; /* return to the high surrogate */
+                result = sourceExhausted;
+                break;
+            }
+        } else if (flags == strictConversion) {
+            /* UTF-16 surrogate values are illegal in UTF-32 */
+            if (ch >= UNI_SUR_LOW_START && ch <= UNI_SUR_LOW_END) {
+                --source; /* return to the illegal value itself */
+                result = sourceIllegal;
+                break;
+            }
+        }
+        if (target >= targetEnd) {
+            source = oldSource; /* Back up source pointer! */
+            result = targetExhausted; break;
+        }
+        *target++ = ch;
+    }
+    *sourceStart = source;
+    *targetStart = target;
+#ifdef CVTUTF_DEBUG
+if (result == sourceIllegal) {
+    fprintf(stderr, "ConvertUTF16toUTF32 illegal seq 0x%04x,%04x\n", ch, ch2);
+    fflush(stderr);
+}
+#endif
+    return result;
+}
+ConversionResult ConvertUTF16toUTF8 (
+        const UTF16** sourceStart, const UTF16* sourceEnd, 
+        UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF16* source = *sourceStart;
+    UTF8* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch;
+        unsigned short bytesToWrite = 0;
+        const UTF32 byteMask = 0xBF;
+        const UTF32 byteMark = 0x80; 
+        const UTF16* oldSource = source; /* In case we have to back up because of target overflow. */
+        ch = *source++;
+        /* If we have a surrogate pair, convert to UTF32 first. */
+        if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_HIGH_END) {
+            /* If the 16 bits following the high surrogate are in the source buffer... */
+            if (source < sourceEnd) {
+                UTF32 ch2 = *source;
+                /* If it's a low surrogate, convert to UTF32. */
+                if (ch2 >= UNI_SUR_LOW_START && ch2 <= UNI_SUR_LOW_END) {
+                    ch = ((ch - UNI_SUR_HIGH_START) << halfShift)
+                        + (ch2 - UNI_SUR_LOW_START) + halfBase;
+                    ++source;
+                } else if (flags == strictConversion) { /* it's an unpaired high surrogate */
+                    --source; /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                }
+            } else { /* We don't have the 16 bits following the high surrogate. */
+                --source; /* return to the high surrogate */
+                result = sourceExhausted;
+                break;
+            }
+        } else if (flags == strictConversion) {
+            /* UTF-16 surrogate values are illegal in UTF-32 */
+            if (ch >= UNI_SUR_LOW_START && ch <= UNI_SUR_LOW_END) {
+                --source; /* return to the illegal value itself */
+                result = sourceIllegal;
+                break;
+            }
+        }
+        /* Figure out how many bytes the result will require */
+        if (ch < (UTF32)0x80) {      bytesToWrite = 1;
+        } else if (ch < (UTF32)0x800) {     bytesToWrite = 2;
+        } else if (ch < (UTF32)0x10000) {   bytesToWrite = 3;
+        } else if (ch < (UTF32)0x110000) {  bytesToWrite = 4;
+        } else {                            bytesToWrite = 3;
+                                            ch = UNI_REPLACEMENT_CHAR;
+        }
+
+        target += bytesToWrite;
+        if (target > targetEnd) {
+            source = oldSource; /* Back up source pointer! */
+            target -= bytesToWrite; result = targetExhausted; break;
+        }
+        switch (bytesToWrite) { /* note: everything falls through. */
+            case 4: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 3: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 2: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 1: *--target =  (UTF8)(ch | firstByteMark[bytesToWrite]);
+        }
+        target += bytesToWrite;
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+/* --------------------------------------------------------------------- */
+
+ConversionResult ConvertUTF32toUTF8 (
+        const UTF32** sourceStart, const UTF32* sourceEnd, 
+        UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF32* source = *sourceStart;
+    UTF8* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch;
+        unsigned short bytesToWrite = 0;
+        const UTF32 byteMask = 0xBF;
+        const UTF32 byteMark = 0x80; 
+        ch = *source++;
+        if (flags == strictConversion ) {
+            /* UTF-16 surrogate values are illegal in UTF-32 */
+            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
+                --source; /* return to the illegal value itself */
+                result = sourceIllegal;
+                break;
+            }
+        }
+        /*
+         * Figure out how many bytes the result will require. Turn any
+         * illegally large UTF32 things (> Plane 17) into replacement chars.
+         */
+        if (ch < (UTF32)0x80) {      bytesToWrite = 1;
+        } else if (ch < (UTF32)0x800) {     bytesToWrite = 2;
+        } else if (ch < (UTF32)0x10000) {   bytesToWrite = 3;
+        } else if (ch <= UNI_MAX_LEGAL_UTF32) {  bytesToWrite = 4;
+        } else {                            bytesToWrite = 3;
+                                            ch = UNI_REPLACEMENT_CHAR;
+                                            result = sourceIllegal;
+        }
+        
+        target += bytesToWrite;
+        if (target > targetEnd) {
+            --source; /* Back up source pointer! */
+            target -= bytesToWrite; result = targetExhausted; break;
+        }
+        switch (bytesToWrite) { /* note: everything falls through. */
+            case 4: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 3: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 2: *--target = (UTF8)((ch | byteMark) & byteMask); ch >>= 6;
+            case 1: *--target = (UTF8) (ch | firstByteMark[bytesToWrite]);
+        }
+        target += bytesToWrite;
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Utility routine to tell whether a sequence of bytes is legal UTF-8.
+ * This must be called with the length pre-determined by the first byte.
+ * If not calling this from ConvertUTF8to*, then the length can be set by:
+ *  length = trailingBytesForUTF8[*source]+1;
+ * and the sequence is illegal right away if there aren't that many bytes
+ * available.
+ * If presented with a length > 4, this returns false.  The Unicode
+ * definition of UTF-8 goes up to 4-byte sequences.
+ */
+
+static Boolean isLegalUTF8(const UTF8 *source, int length) {
+    UTF8 a;
+    const UTF8 *srcptr = source+length;
+    switch (length) {
+    default: return false;
+        /* Everything else falls through when "true"... */
+    case 4: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
+    case 3: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
+    case 2: if ((a = (*--srcptr)) < 0x80 || a > 0xBF) return false;
+
+        switch (*source) {
+            /* no fall-through in this inner switch */
+            case 0xE0: if (a < 0xA0) return false; break;
+            case 0xED: if (a > 0x9F) return false; break;
+            case 0xF0: if (a < 0x90) return false; break;
+            case 0xF4: if (a > 0x8F) return false; break;
+            default:   if (a < 0x80) return false;
+        }
+
+    case 1: if (*source >= 0x80 && *source < 0xC2) return false;
+    }
+    if (*source > 0xF4) return false;
+    return true;
+}
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Exported function to return whether a UTF-8 sequence is legal or not.
+ * This is not used here; it's just exported.
+ */
+Boolean isLegalUTF8Sequence(const UTF8 *source, const UTF8 *sourceEnd) {
+    int length = trailingBytesForUTF8[*source]+1;
+    if (length > sourceEnd - source) {
+        return false;
+    }
+    return isLegalUTF8(source, length);
+}
+
+/* --------------------------------------------------------------------- */
+
+static unsigned
+findMaximalSubpartOfIllFormedUTF8Sequence(const UTF8 *source,
+                                          const UTF8 *sourceEnd) {
+  UTF8 b1, b2, b3;
+
+  assert(!isLegalUTF8Sequence(source, sourceEnd));
+
+  /*
+   * Unicode 6.3.0, D93b:
+   *
+   *   Maximal subpart of an ill-formed subsequence: The longest code unit
+   *   subsequence starting at an unconvertible offset that is either:
+   *   a. the initial subsequence of a well-formed code unit sequence, or
+   *   b. a subsequence of length one.
+   */
+
+  if (source == sourceEnd)
+    return 0;
+
+  /*
+   * Perform case analysis.  See Unicode 6.3.0, Table 3-7. Well-Formed UTF-8
+   * Byte Sequences.
+   */
+
+  b1 = *source;
+  ++source;
+  if (b1 >= 0xC2 && b1 <= 0xDF) {
+    /*
+     * First byte is valid, but we know that this code unit sequence is
+     * invalid, so the maximal subpart has to end after the first byte.
+     */
+    return 1;
+  }
+
+  if (source == sourceEnd)
+    return 1;
+
+  b2 = *source;
+  ++source;
+
+  if (b1 == 0xE0) {
+    return (b2 >= 0xA0 && b2 <= 0xBF) ? 2 : 1;
+  }
+  if (b1 >= 0xE1 && b1 <= 0xEC) {
+    return (b2 >= 0x80 && b2 <= 0xBF) ? 2 : 1;
+  }
+  if (b1 == 0xED) {
+    return (b2 >= 0x80 && b2 <= 0x9F) ? 2 : 1;
+  }
+  if (b1 >= 0xEE && b1 <= 0xEF) {
+    return (b2 >= 0x80 && b2 <= 0xBF) ? 2 : 1;
+  }
+  if (b1 == 0xF0) {
+    if (b2 >= 0x90 && b2 <= 0xBF) {
+      if (source == sourceEnd)
+        return 2;
+
+      b3 = *source;
+      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
+    }
+    return 1;
+  }
+  if (b1 >= 0xF1 && b1 <= 0xF3) {
+    if (b2 >= 0x80 && b2 <= 0xBF) {
+      if (source == sourceEnd)
+        return 2;
+
+      b3 = *source;
+      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
+    }
+    return 1;
+  }
+  if (b1 == 0xF4) {
+    if (b2 >= 0x80 && b2 <= 0x8F) {
+      if (source == sourceEnd)
+        return 2;
+
+      b3 = *source;
+      return (b3 >= 0x80 && b3 <= 0xBF) ? 3 : 2;
+    }
+    return 1;
+  }
+
+  assert((b1 >= 0x80 && b1 <= 0xC1) || b1 >= 0xF5);
+  /*
+   * There are no valid sequences that start with these bytes.  Maximal subpart
+   * is defined to have length 1 in these cases.
+   */
+  return 1;
+}
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Exported function to return the total number of bytes in a codepoint
+ * represented in UTF-8, given the value of the first byte.
+ */
+unsigned getNumBytesForUTF8(UTF8 first) {
+  return trailingBytesForUTF8[first] + 1;
+}
+
+/* --------------------------------------------------------------------- */
+
+/*
+ * Exported function to return whether a UTF-8 string is legal or not.
+ * This is not used here; it's just exported.
+ */
+Boolean isLegalUTF8String(const UTF8 **source, const UTF8 *sourceEnd) {
+    while (*source != sourceEnd) {
+        int length = trailingBytesForUTF8[**source] + 1;
+        if (length > sourceEnd - *source || !isLegalUTF8(*source, length))
+            return false;
+        *source += length;
+    }
+    return true;
+}
+
+/* --------------------------------------------------------------------- */
+
+ConversionResult ConvertUTF8toUTF16 (
+        const UTF8** sourceStart, const UTF8* sourceEnd, 
+        UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags) {
+    ConversionResult result = conversionOK;
+    const UTF8* source = *sourceStart;
+    UTF16* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch = 0;
+        unsigned short extraBytesToRead = trailingBytesForUTF8[*source];
+        if (extraBytesToRead >= sourceEnd - source) {
+            result = sourceExhausted; break;
+        }
+        /* Do this check whether lenient or strict */
+        if (!isLegalUTF8(source, extraBytesToRead+1)) {
+            result = sourceIllegal;
+            break;
+        }
+        /*
+         * The cases all fall through. See "Note A" below.
+         */
+        switch (extraBytesToRead) {
+            case 5: ch += *source++; ch <<= 6; /* remember, illegal UTF-8 */
+            case 4: ch += *source++; ch <<= 6; /* remember, illegal UTF-8 */
+            case 3: ch += *source++; ch <<= 6;
+            case 2: ch += *source++; ch <<= 6;
+            case 1: ch += *source++; ch <<= 6;
+            case 0: ch += *source++;
+        }
+        ch -= offsetsFromUTF8[extraBytesToRead];
+
+        if (target >= targetEnd) {
+            source -= (extraBytesToRead+1); /* Back up source pointer! */
+            result = targetExhausted; break;
+        }
+        if (ch <= UNI_MAX_BMP) { /* Target is a character <= 0xFFFF */
+            /* UTF-16 surrogate values are illegal in UTF-32 */
+            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
+                if (flags == strictConversion) {
+                    source -= (extraBytesToRead+1); /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                } else {
+                    *target++ = UNI_REPLACEMENT_CHAR;
+                }
+            } else {
+                *target++ = (UTF16)ch; /* normal case */
+            }
+        } else if (ch > UNI_MAX_UTF16) {
+            if (flags == strictConversion) {
+                result = sourceIllegal;
+                source -= (extraBytesToRead+1); /* return to the start */
+                break; /* Bail out; shouldn't continue */
+            } else {
+                *target++ = UNI_REPLACEMENT_CHAR;
+            }
+        } else {
+            /* target is a character in range 0xFFFF - 0x10FFFF. */
+            if (target + 1 >= targetEnd) {
+                source -= (extraBytesToRead+1); /* Back up source pointer! */
+                result = targetExhausted; break;
+            }
+            ch -= halfBase;
+            *target++ = (UTF16)((ch >> halfShift) + UNI_SUR_HIGH_START);
+            *target++ = (UTF16)((ch & halfMask) + UNI_SUR_LOW_START);
+        }
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+/* --------------------------------------------------------------------- */
+
+static ConversionResult ConvertUTF8toUTF32Impl(
+        const UTF8** sourceStart, const UTF8* sourceEnd, 
+        UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags,
+        Boolean InputIsPartial) {
+    ConversionResult result = conversionOK;
+    const UTF8* source = *sourceStart;
+    UTF32* target = *targetStart;
+    while (source < sourceEnd) {
+        UTF32 ch = 0;
+        unsigned short extraBytesToRead = trailingBytesForUTF8[*source];
+        if (extraBytesToRead >= sourceEnd - source) {
+            if (flags == strictConversion || InputIsPartial) {
+                result = sourceExhausted;
+                break;
+            } else {
+                result = sourceIllegal;
+
+                /*
+                 * Replace the maximal subpart of ill-formed sequence with
+                 * replacement character.
+                 */
+                source += findMaximalSubpartOfIllFormedUTF8Sequence(source,
+                                                                    sourceEnd);
+                *target++ = UNI_REPLACEMENT_CHAR;
+                continue;
+            }
+        }
+        if (target >= targetEnd) {
+            result = targetExhausted; break;
+        }
+
+        /* Do this check whether lenient or strict */
+        if (!isLegalUTF8(source, extraBytesToRead+1)) {
+            result = sourceIllegal;
+            if (flags == strictConversion) {
+                /* Abort conversion. */
+                break;
+            } else {
+                /*
+                 * Replace the maximal subpart of ill-formed sequence with
+                 * replacement character.
+                 */
+                source += findMaximalSubpartOfIllFormedUTF8Sequence(source,
+                                                                    sourceEnd);
+                *target++ = UNI_REPLACEMENT_CHAR;
+                continue;
+            }
+        }
+        /*
+         * The cases all fall through. See "Note A" below.
+         */
+        switch (extraBytesToRead) {
+            case 5: ch += *source++; ch <<= 6;
+            case 4: ch += *source++; ch <<= 6;
+            case 3: ch += *source++; ch <<= 6;
+            case 2: ch += *source++; ch <<= 6;
+            case 1: ch += *source++; ch <<= 6;
+            case 0: ch += *source++;
+        }
+        ch -= offsetsFromUTF8[extraBytesToRead];
+
+        if (ch <= UNI_MAX_LEGAL_UTF32) {
+            /*
+             * UTF-16 surrogate values are illegal in UTF-32, and anything
+             * over Plane 17 (> 0x10FFFF) is illegal.
+             */
+            if (ch >= UNI_SUR_HIGH_START && ch <= UNI_SUR_LOW_END) {
+                if (flags == strictConversion) {
+                    source -= (extraBytesToRead+1); /* return to the illegal value itself */
+                    result = sourceIllegal;
+                    break;
+                } else {
+                    *target++ = UNI_REPLACEMENT_CHAR;
+                }
+            } else {
+                *target++ = ch;
+            }
+        } else { /* i.e., ch > UNI_MAX_LEGAL_UTF32 */
+            result = sourceIllegal;
+            *target++ = UNI_REPLACEMENT_CHAR;
+        }
+    }
+    *sourceStart = source;
+    *targetStart = target;
+    return result;
+}
+
+ConversionResult ConvertUTF8toUTF32Partial(const UTF8 **sourceStart,
+                                           const UTF8 *sourceEnd,
+                                           UTF32 **targetStart,
+                                           UTF32 *targetEnd,
+                                           ConversionFlags flags) {
+  return ConvertUTF8toUTF32Impl(sourceStart, sourceEnd, targetStart, targetEnd,
+                                flags, /*InputIsPartial=*/true);
+}
+
+ConversionResult ConvertUTF8toUTF32(const UTF8 **sourceStart,
+                                    const UTF8 *sourceEnd, UTF32 **targetStart,
+                                    UTF32 *targetEnd, ConversionFlags flags) {
+  return ConvertUTF8toUTF32Impl(sourceStart, sourceEnd, targetStart, targetEnd,
+                                flags, /*InputIsPartial=*/false);
+}
+
+/* ---------------------------------------------------------------------
+
+    Note A.
+    The fall-through switches in UTF-8 reading code save a
+    temp variable, some decrements & conditionals.  The switches
+    are equivalent to the following loop:
+        {
+            int tmpBytesToRead = extraBytesToRead+1;
+            do {
+                ch += *source++;
+                --tmpBytesToRead;
+                if (tmpBytesToRead) ch <<= 6;
+            } while (tmpBytesToRead > 0);
+        }
+    In UTF-8 writing code, the switches on "bytesToWrite" are
+    similarly unrolled loops.
+
+   --------------------------------------------------------------------- */
+
+} // namespace llvm
+
+ConvertUTF_RESTORE_WARNINGS
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ConvertUTFWrapper.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ConvertUTFWrapper.cpp
new file mode 100644
index 0000000..3402988
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ConvertUTFWrapper.cpp
@@ -0,0 +1,122 @@
+//===-- ConvertUTFWrapper.cpp - Wrap ConvertUTF.h with clang data types -----===
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/ConvertUTF.h"
+#include <string>
+#include <vector>
+
+namespace wpi {
+
+bool ConvertCodePointToUTF8(unsigned Source, char *&ResultPtr) {
+  const UTF32 *SourceStart = &Source;
+  const UTF32 *SourceEnd = SourceStart + 1;
+  UTF8 *TargetStart = reinterpret_cast<UTF8 *>(ResultPtr);
+  UTF8 *TargetEnd = TargetStart + 4;
+  ConversionResult CR = ConvertUTF32toUTF8(&SourceStart, SourceEnd,
+                                           &TargetStart, TargetEnd,
+                                           strictConversion);
+  if (CR != conversionOK)
+    return false;
+
+  ResultPtr = reinterpret_cast<char*>(TargetStart);
+  return true;
+}
+
+bool hasUTF16ByteOrderMark(ArrayRef<char> S) {
+  return (S.size() >= 2 &&
+          ((S[0] == '\xff' && S[1] == '\xfe') ||
+           (S[0] == '\xfe' && S[1] == '\xff')));
+}
+
+bool convertUTF16ToUTF8String(ArrayRef<UTF16> SrcUTF16,
+                              SmallVectorImpl<char> &DstUTF8) {
+  assert(DstUTF8.empty());
+
+  // Avoid OOB by returning early on empty input.
+  if (SrcUTF16.empty())
+    return true;
+
+  const UTF16 *Src = SrcUTF16.begin();
+  const UTF16 *SrcEnd = SrcUTF16.end();
+
+  // Byteswap if necessary.
+  std::vector<UTF16> ByteSwapped;
+  if (Src[0] == UNI_UTF16_BYTE_ORDER_MARK_SWAPPED) {
+    ByteSwapped.insert(ByteSwapped.end(), Src, SrcEnd);
+    for (unsigned I = 0, E = ByteSwapped.size(); I != E; ++I)
+      ByteSwapped[I] = (ByteSwapped[I] << 8) | (ByteSwapped[I] >> 8);
+    Src = &ByteSwapped[0];
+    SrcEnd = &ByteSwapped[ByteSwapped.size() - 1] + 1;
+  }
+
+  // Skip the BOM for conversion.
+  if (Src[0] == UNI_UTF16_BYTE_ORDER_MARK_NATIVE)
+    Src++;
+
+  // Just allocate enough space up front.  We'll shrink it later.  Allocate
+  // enough that we can fit a null terminator without reallocating.
+  DstUTF8.resize(SrcUTF16.size() * UNI_MAX_UTF8_BYTES_PER_CODE_POINT + 1);
+  UTF8 *Dst = reinterpret_cast<UTF8*>(&DstUTF8[0]);
+  UTF8 *DstEnd = Dst + DstUTF8.size();
+
+  ConversionResult CR =
+      ConvertUTF16toUTF8(&Src, SrcEnd, &Dst, DstEnd, strictConversion);
+  assert(CR != targetExhausted);
+
+  if (CR != conversionOK) {
+    DstUTF8.clear();
+    return false;
+  }
+
+  DstUTF8.resize(reinterpret_cast<char*>(Dst) - &DstUTF8[0]);
+  DstUTF8.push_back(0);
+  DstUTF8.pop_back();
+  return true;
+}
+
+bool convertUTF8ToUTF16String(StringRef SrcUTF8,
+                              SmallVectorImpl<UTF16> &DstUTF16) {
+  assert(DstUTF16.empty());
+
+  // Avoid OOB by returning early on empty input.
+  if (SrcUTF8.empty()) {
+    DstUTF16.push_back(0);
+    DstUTF16.pop_back();
+    return true;
+  }
+
+  const UTF8 *Src = reinterpret_cast<const UTF8 *>(SrcUTF8.begin());
+  const UTF8 *SrcEnd = reinterpret_cast<const UTF8 *>(SrcUTF8.end());
+
+  // Allocate the same number of UTF-16 code units as UTF-8 code units. Encoding
+  // as UTF-16 should always require the same amount or less code units than the
+  // UTF-8 encoding.  Allocate one extra byte for the null terminator though,
+  // so that someone calling DstUTF16.data() gets a null terminated string.
+  // We resize down later so we don't have to worry that this over allocates.
+  DstUTF16.resize(SrcUTF8.size()+1);
+  UTF16 *Dst = &DstUTF16[0];
+  UTF16 *DstEnd = Dst + DstUTF16.size();
+
+  ConversionResult CR =
+      ConvertUTF8toUTF16(&Src, SrcEnd, &Dst, DstEnd, strictConversion);
+  assert(CR != targetExhausted);
+
+  if (CR != conversionOK) {
+    DstUTF16.clear();
+    return false;
+  }
+
+  DstUTF16.resize(Dst - &DstUTF16[0]);
+  DstUTF16.push_back(0);
+  DstUTF16.pop_back();
+  return true;
+}
+
+} // end namespace wpi
+
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ErrorHandling.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ErrorHandling.cpp
new file mode 100644
index 0000000..088e805
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/ErrorHandling.cpp
@@ -0,0 +1,83 @@
+//===- lib/Support/ErrorHandling.cpp - Callbacks for errors ---------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines an API used to indicate fatal error conditions.  Non-fatal
+// errors (most of them) should be handled through LLVMContext.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/WindowsError.h"
+
+#ifdef _WIN32
+
+#include <system_error>
+#include <winerror.h>
+
+// I'd rather not double the line count of the following.
+#define MAP_ERR_TO_COND(x, y)                                                  \
+  case x:                                                                      \
+    return std::make_error_code(std::errc::y)
+
+std::error_code wpi::mapWindowsError(unsigned EV) {
+  switch (EV) {
+    MAP_ERR_TO_COND(ERROR_ACCESS_DENIED, permission_denied);
+    MAP_ERR_TO_COND(ERROR_ALREADY_EXISTS, file_exists);
+    MAP_ERR_TO_COND(ERROR_BAD_UNIT, no_such_device);
+    MAP_ERR_TO_COND(ERROR_BUFFER_OVERFLOW, filename_too_long);
+    MAP_ERR_TO_COND(ERROR_BUSY, device_or_resource_busy);
+    MAP_ERR_TO_COND(ERROR_BUSY_DRIVE, device_or_resource_busy);
+    MAP_ERR_TO_COND(ERROR_CANNOT_MAKE, permission_denied);
+    MAP_ERR_TO_COND(ERROR_CANTOPEN, io_error);
+    MAP_ERR_TO_COND(ERROR_CANTREAD, io_error);
+    MAP_ERR_TO_COND(ERROR_CANTWRITE, io_error);
+    MAP_ERR_TO_COND(ERROR_CURRENT_DIRECTORY, permission_denied);
+    MAP_ERR_TO_COND(ERROR_DEV_NOT_EXIST, no_such_device);
+    MAP_ERR_TO_COND(ERROR_DEVICE_IN_USE, device_or_resource_busy);
+    MAP_ERR_TO_COND(ERROR_DIR_NOT_EMPTY, directory_not_empty);
+    MAP_ERR_TO_COND(ERROR_DIRECTORY, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_DISK_FULL, no_space_on_device);
+    MAP_ERR_TO_COND(ERROR_FILE_EXISTS, file_exists);
+    MAP_ERR_TO_COND(ERROR_FILE_NOT_FOUND, no_such_file_or_directory);
+    MAP_ERR_TO_COND(ERROR_HANDLE_DISK_FULL, no_space_on_device);
+    MAP_ERR_TO_COND(ERROR_INVALID_ACCESS, permission_denied);
+    MAP_ERR_TO_COND(ERROR_INVALID_DRIVE, no_such_device);
+    MAP_ERR_TO_COND(ERROR_INVALID_FUNCTION, function_not_supported);
+    MAP_ERR_TO_COND(ERROR_INVALID_HANDLE, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_INVALID_NAME, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_LOCK_VIOLATION, no_lock_available);
+    MAP_ERR_TO_COND(ERROR_LOCKED, no_lock_available);
+    MAP_ERR_TO_COND(ERROR_NEGATIVE_SEEK, invalid_argument);
+    MAP_ERR_TO_COND(ERROR_NOACCESS, permission_denied);
+    MAP_ERR_TO_COND(ERROR_NOT_ENOUGH_MEMORY, not_enough_memory);
+    MAP_ERR_TO_COND(ERROR_NOT_READY, resource_unavailable_try_again);
+    MAP_ERR_TO_COND(ERROR_OPEN_FAILED, io_error);
+    MAP_ERR_TO_COND(ERROR_OPEN_FILES, device_or_resource_busy);
+    MAP_ERR_TO_COND(ERROR_OUTOFMEMORY, not_enough_memory);
+    MAP_ERR_TO_COND(ERROR_PATH_NOT_FOUND, no_such_file_or_directory);
+    MAP_ERR_TO_COND(ERROR_BAD_NETPATH, no_such_file_or_directory);
+    MAP_ERR_TO_COND(ERROR_READ_FAULT, io_error);
+    MAP_ERR_TO_COND(ERROR_RETRY, resource_unavailable_try_again);
+    MAP_ERR_TO_COND(ERROR_SEEK, io_error);
+    MAP_ERR_TO_COND(ERROR_SHARING_VIOLATION, permission_denied);
+    MAP_ERR_TO_COND(ERROR_TOO_MANY_OPEN_FILES, too_many_files_open);
+    MAP_ERR_TO_COND(ERROR_WRITE_FAULT, io_error);
+    MAP_ERR_TO_COND(ERROR_WRITE_PROTECT, permission_denied);
+    MAP_ERR_TO_COND(WSAEACCES, permission_denied);
+    MAP_ERR_TO_COND(WSAEBADF, bad_file_descriptor);
+    MAP_ERR_TO_COND(WSAEFAULT, bad_address);
+    MAP_ERR_TO_COND(WSAEINTR, interrupted);
+    MAP_ERR_TO_COND(WSAEINVAL, invalid_argument);
+    MAP_ERR_TO_COND(WSAEMFILE, too_many_files_open);
+    MAP_ERR_TO_COND(WSAENAMETOOLONG, filename_too_long);
+  default:
+    return std::error_code(EV, std::system_category());
+  }
+}
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Hashing.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Hashing.cpp
new file mode 100644
index 0000000..51c033e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Hashing.cpp
@@ -0,0 +1,29 @@
+//===-------------- lib/Support/Hashing.cpp -------------------------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file provides implementation bits for the LLVM common hashing
+// infrastructure. Documentation and most of the other information is in the
+// header file.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/Hashing.h"
+
+using namespace wpi;
+
+// Provide a definition and static initializer for the fixed seed. This
+// initializer should always be zero to ensure its value can never appear to be
+// non-zero, even during dynamic initialization.
+size_t wpi::hashing::detail::fixed_seed_override = 0;
+
+// Implement the function for forced setting of the fixed seed.
+// FIXME: Use atomic operations here so that there is no data race.
+void wpi::set_fixed_execution_hash_seed(size_t fixed_value) {
+  hashing::detail::fixed_seed_override = fixed_value;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/NativeFormatting.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/NativeFormatting.cpp
new file mode 100644
index 0000000..41c43e2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/NativeFormatting.cpp
@@ -0,0 +1,264 @@
+//===- NativeFormatting.cpp - Low level formatting helpers -------*- C++-*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/NativeFormatting.h"
+
+#include "wpi/ArrayRef.h"
+#include "wpi/SmallString.h"
+#include "wpi/StringExtras.h"
+#include "wpi/Format.h"
+
+#include <float.h>
+
+using namespace wpi;
+
+template<typename T, std::size_t N>
+static int format_to_buffer(T Value, char (&Buffer)[N]) {
+  char *EndPtr = std::end(Buffer);
+  char *CurPtr = EndPtr;
+
+  do {
+    *--CurPtr = '0' + char(Value % 10);
+    Value /= 10;
+  } while (Value);
+  return EndPtr - CurPtr;
+}
+
+static void writeWithCommas(raw_ostream &S, ArrayRef<char> Buffer) {
+  assert(!Buffer.empty());
+
+  ArrayRef<char> ThisGroup;
+  int InitialDigits = ((Buffer.size() - 1) % 3) + 1;
+  ThisGroup = Buffer.take_front(InitialDigits);
+  S.write(ThisGroup.data(), ThisGroup.size());
+
+  Buffer = Buffer.drop_front(InitialDigits);
+  assert(Buffer.size() % 3 == 0);
+  while (!Buffer.empty()) {
+    S << ',';
+    ThisGroup = Buffer.take_front(3);
+    S.write(ThisGroup.data(), 3);
+    Buffer = Buffer.drop_front(3);
+  }
+}
+
+template <typename T>
+static void write_unsigned_impl(raw_ostream &S, T N, size_t MinDigits,
+                                IntegerStyle Style, bool IsNegative) {
+  static_assert(std::is_unsigned<T>::value, "Value is not unsigned!");
+
+  char NumberBuffer[128];
+  std::memset(NumberBuffer, '0', sizeof(NumberBuffer));
+
+  size_t Len = 0;
+  Len = format_to_buffer(N, NumberBuffer);
+
+  if (IsNegative)
+    S << '-';
+
+  if (Len < MinDigits && Style != IntegerStyle::Number) {
+    for (size_t I = Len; I < MinDigits; ++I)
+      S << '0';
+  }
+
+  if (Style == IntegerStyle::Number) {
+    writeWithCommas(S, ArrayRef<char>(std::end(NumberBuffer) - Len, Len));
+  } else {
+    S.write(std::end(NumberBuffer) - Len, Len);
+  }
+}
+
+template <typename T>
+static void write_unsigned(raw_ostream &S, T N, size_t MinDigits,
+                           IntegerStyle Style, bool IsNegative = false) {
+  // Output using 32-bit div/mod if possible.
+  if (N == static_cast<uint32_t>(N))
+    write_unsigned_impl(S, static_cast<uint32_t>(N), MinDigits, Style,
+                        IsNegative);
+  else
+    write_unsigned_impl(S, N, MinDigits, Style, IsNegative);
+}
+
+template <typename T>
+static void write_signed(raw_ostream &S, T N, size_t MinDigits,
+                         IntegerStyle Style) {
+  static_assert(std::is_signed<T>::value, "Value is not signed!");
+
+  using UnsignedT = typename std::make_unsigned<T>::type;
+
+  if (N >= 0) {
+    write_unsigned(S, static_cast<UnsignedT>(N), MinDigits, Style);
+    return;
+  }
+
+  UnsignedT UN = -(UnsignedT)N;
+  write_unsigned(S, UN, MinDigits, Style, true);
+}
+
+void wpi::write_integer(raw_ostream &S, unsigned int N, size_t MinDigits,
+                         IntegerStyle Style) {
+  write_unsigned(S, N, MinDigits, Style);
+}
+
+void wpi::write_integer(raw_ostream &S, int N, size_t MinDigits,
+                         IntegerStyle Style) {
+  write_signed(S, N, MinDigits, Style);
+}
+
+void wpi::write_integer(raw_ostream &S, unsigned long N, size_t MinDigits,
+                         IntegerStyle Style) {
+  write_unsigned(S, N, MinDigits, Style);
+}
+
+void wpi::write_integer(raw_ostream &S, long N, size_t MinDigits,
+                         IntegerStyle Style) {
+  write_signed(S, N, MinDigits, Style);
+}
+
+void wpi::write_integer(raw_ostream &S, unsigned long long N, size_t MinDigits,
+                         IntegerStyle Style) {
+  write_unsigned(S, N, MinDigits, Style);
+}
+
+void wpi::write_integer(raw_ostream &S, long long N, size_t MinDigits,
+                         IntegerStyle Style) {
+  write_signed(S, N, MinDigits, Style);
+}
+
+void wpi::write_hex(raw_ostream &S, uint64_t N, HexPrintStyle Style,
+                     optional<size_t> Width) {
+  const size_t kMaxWidth = 128u;
+
+  size_t W = std::min(kMaxWidth, Width.value_or(0u));
+
+  unsigned Nibbles = (64 - countLeadingZeros(N) + 3) / 4;
+  bool Prefix = (Style == HexPrintStyle::PrefixLower ||
+                 Style == HexPrintStyle::PrefixUpper);
+  bool Upper =
+      (Style == HexPrintStyle::Upper || Style == HexPrintStyle::PrefixUpper);
+  unsigned PrefixChars = Prefix ? 2 : 0;
+  unsigned NumChars =
+      std::max(static_cast<unsigned>(W), std::max(1u, Nibbles) + PrefixChars);
+
+  char NumberBuffer[kMaxWidth];
+  ::memset(NumberBuffer, '0', wpi::array_lengthof(NumberBuffer));
+  if (Prefix)
+    NumberBuffer[1] = 'x';
+  char *EndPtr = NumberBuffer + NumChars;
+  char *CurPtr = EndPtr;
+  while (N) {
+    unsigned char x = static_cast<unsigned char>(N) % 16;
+    *--CurPtr = hexdigit(x, !Upper);
+    N /= 16;
+  }
+
+  S.write(NumberBuffer, NumChars);
+}
+
+void wpi::write_double(raw_ostream &S, double N, FloatStyle Style,
+                        optional<size_t> Precision) {
+  size_t Prec = Precision.value_or(getDefaultPrecision(Style));
+
+  if (std::isnan(N)) {
+    S << "nan";
+    return;
+  } else if (std::isinf(N)) {
+    S << "INF";
+    return;
+  }
+
+  char Letter;
+  if (Style == FloatStyle::Exponent)
+    Letter = 'e';
+  else if (Style == FloatStyle::ExponentUpper)
+    Letter = 'E';
+  else
+    Letter = 'f';
+
+  SmallString<8> Spec;
+  wpi::raw_svector_ostream Out(Spec);
+  Out << "%." << Prec << Letter;
+
+  if (Style == FloatStyle::Exponent || Style == FloatStyle::ExponentUpper) {
+#ifdef _WIN32
+// On MSVCRT and compatible, output of %e is incompatible to Posix
+// by default. Number of exponent digits should be at least 2. "%+03d"
+// FIXME: Implement our formatter to here or Support/Format.h!
+#if defined(__MINGW32__)
+    // FIXME: It should be generic to C++11.
+    if (N == 0.0 && std::signbit(N)) {
+      char NegativeZero[] = "-0.000000e+00";
+      if (Style == FloatStyle::ExponentUpper)
+        NegativeZero[strlen(NegativeZero) - 4] = 'E';
+      S << NegativeZero;
+      return;
+    }
+#else
+    int fpcl = _fpclass(N);
+
+    // negative zero
+    if (fpcl == _FPCLASS_NZ) {
+      char NegativeZero[] = "-0.000000e+00";
+      if (Style == FloatStyle::ExponentUpper)
+        NegativeZero[strlen(NegativeZero) - 4] = 'E';
+      S << NegativeZero;
+      return;
+    }
+#endif
+
+    char buf[32];
+    unsigned len;
+    len = format(Spec.c_str(), N).snprint(buf, sizeof(buf));
+    if (len <= sizeof(buf) - 2) {
+      if (len >= 5 && (buf[len - 5] == 'e' || buf[len - 5] == 'E') &&
+          buf[len - 3] == '0') {
+        int cs = buf[len - 4];
+        if (cs == '+' || cs == '-') {
+          int c1 = buf[len - 2];
+          int c0 = buf[len - 1];
+          if (isdigit(static_cast<unsigned char>(c1)) &&
+              isdigit(static_cast<unsigned char>(c0))) {
+            // Trim leading '0': "...e+012" -> "...e+12\0"
+            buf[len - 3] = c1;
+            buf[len - 2] = c0;
+            buf[--len] = 0;
+          }
+        }
+      }
+      S << buf;
+      return;
+    }
+#endif
+  }
+
+  if (Style == FloatStyle::Percent)
+    N *= 100.0;
+
+  char Buf[32];
+  format(Spec.c_str(), N).snprint(Buf, sizeof(Buf));
+  S << Buf;
+  if (Style == FloatStyle::Percent)
+    S << '%';
+}
+
+bool wpi::isPrefixedHexStyle(HexPrintStyle S) {
+  return (S == HexPrintStyle::PrefixLower || S == HexPrintStyle::PrefixUpper);
+}
+
+size_t wpi::getDefaultPrecision(FloatStyle Style) {
+  switch (Style) {
+  case FloatStyle::Exponent:
+  case FloatStyle::ExponentUpper:
+    return 6; // Number of decimal places.
+  case FloatStyle::Fixed:
+  case FloatStyle::Percent:
+    return 2; // Number of decimal places.
+  }
+  LLVM_BUILTIN_UNREACHABLE;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Path.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Path.cpp
new file mode 100644
index 0000000..12736b9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Path.cpp
@@ -0,0 +1,848 @@
+//===-- Path.cpp - Implement OS Path Concept ------------------------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+//  This file implements the operating system Path API.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/Path.h"
+
+#include <cctype>
+#include <cstring>
+
+#if !defined(_MSC_VER) && !defined(__MINGW32__)
+#include <unistd.h>
+#else
+#include <io.h>
+#endif
+
+#include "wpi/FileSystem.h"
+#include "wpi/SmallString.h"
+
+using namespace wpi;
+
+namespace {
+  using wpi::StringRef;
+  using wpi::sys::path::is_separator;
+  using wpi::sys::path::Style;
+
+  inline Style real_style(Style style) {
+#ifdef _WIN32
+    return (style == Style::posix) ? Style::posix : Style::windows;
+#else
+    return (style == Style::windows) ? Style::windows : Style::posix;
+#endif
+  }
+
+  inline const char *separators(Style style) {
+    if (real_style(style) == Style::windows)
+      return "\\/";
+    return "/";
+  }
+
+  inline char preferred_separator(Style style) {
+    if (real_style(style) == Style::windows)
+      return '\\';
+    return '/';
+  }
+
+  StringRef find_first_component(StringRef path, Style style) {
+    // Look for this first component in the following order.
+    // * empty (in this case we return an empty string)
+    // * either C: or {//,\\}net.
+    // * {/,\}
+    // * {file,directory}name
+
+    if (path.empty())
+      return path;
+
+    if (real_style(style) == Style::windows) {
+      // C:
+      if (path.size() >= 2 &&
+          std::isalpha(static_cast<unsigned char>(path[0])) && path[1] == ':')
+        return path.substr(0, 2);
+    }
+
+    // //net
+    if ((path.size() > 2) && is_separator(path[0], style) &&
+        path[0] == path[1] && !is_separator(path[2], style)) {
+      // Find the next directory separator.
+      size_t end = path.find_first_of(separators(style), 2);
+      return path.substr(0, end);
+    }
+
+    // {/,\}
+    if (is_separator(path[0], style))
+      return path.substr(0, 1);
+
+    // * {file,directory}name
+    size_t end = path.find_first_of(separators(style));
+    return path.substr(0, end);
+  }
+
+  // Returns the first character of the filename in str. For paths ending in
+  // '/', it returns the position of the '/'.
+  size_t filename_pos(StringRef str, Style style) {
+    if (str.size() > 0 && is_separator(str[str.size() - 1], style))
+      return str.size() - 1;
+
+    size_t pos = str.find_last_of(separators(style), str.size() - 1);
+
+    if (real_style(style) == Style::windows) {
+      if (pos == StringRef::npos)
+        pos = str.find_last_of(':', str.size() - 2);
+    }
+
+    if (pos == StringRef::npos || (pos == 1 && is_separator(str[0], style)))
+      return 0;
+
+    return pos + 1;
+  }
+
+  // Returns the position of the root directory in str. If there is no root
+  // directory in str, it returns StringRef::npos.
+  size_t root_dir_start(StringRef str, Style style) {
+    // case "c:/"
+    if (real_style(style) == Style::windows) {
+      if (str.size() > 2 && str[1] == ':' && is_separator(str[2], style))
+        return 2;
+    }
+
+    // case "//net"
+    if (str.size() > 3 && is_separator(str[0], style) && str[0] == str[1] &&
+        !is_separator(str[2], style)) {
+      return str.find_first_of(separators(style), 2);
+    }
+
+    // case "/"
+    if (str.size() > 0 && is_separator(str[0], style))
+      return 0;
+
+    return StringRef::npos;
+  }
+
+  // Returns the position past the end of the "parent path" of path. The parent
+  // path will not end in '/', unless the parent is the root directory. If the
+  // path has no parent, 0 is returned.
+  size_t parent_path_end(StringRef path, Style style) {
+    size_t end_pos = filename_pos(path, style);
+
+    bool filename_was_sep =
+        path.size() > 0 && is_separator(path[end_pos], style);
+
+    // Skip separators until we reach root dir (or the start of the string).
+    size_t root_dir_pos = root_dir_start(path, style);
+    while (end_pos > 0 &&
+           (root_dir_pos == StringRef::npos || end_pos > root_dir_pos) &&
+           is_separator(path[end_pos - 1], style))
+      --end_pos;
+
+    if (end_pos == root_dir_pos && !filename_was_sep) {
+      // We've reached the root dir and the input path was *not* ending in a
+      // sequence of slashes. Include the root dir in the parent path.
+      return root_dir_pos + 1;
+    }
+
+    // Otherwise, just include before the last slash.
+    return end_pos;
+  }
+} // end unnamed namespace
+
+namespace wpi {
+namespace sys  {
+namespace path {
+
+const_iterator begin(StringRef path, Style style) {
+  const_iterator i;
+  i.Path      = path;
+  i.Component = find_first_component(path, style);
+  i.Position  = 0;
+  i.S = style;
+  return i;
+}
+
+const_iterator end(StringRef path) {
+  const_iterator i;
+  i.Path      = path;
+  i.Position  = path.size();
+  return i;
+}
+
+const_iterator &const_iterator::operator++() {
+  assert(Position < Path.size() && "Tried to increment past end!");
+
+  // Increment Position to past the current component
+  Position += Component.size();
+
+  // Check for end.
+  if (Position == Path.size()) {
+    Component = StringRef();
+    return *this;
+  }
+
+  // Both POSIX and Windows treat paths that begin with exactly two separators
+  // specially.
+  bool was_net = Component.size() > 2 && is_separator(Component[0], S) &&
+                 Component[1] == Component[0] && !is_separator(Component[2], S);
+
+  // Handle separators.
+  if (is_separator(Path[Position], S)) {
+    // Root dir.
+    if (was_net ||
+        // c:/
+        (real_style(S) == Style::windows && Component.endswith(":"))) {
+      Component = Path.substr(Position, 1);
+      return *this;
+    }
+
+    // Skip extra separators.
+    while (Position != Path.size() && is_separator(Path[Position], S)) {
+      ++Position;
+    }
+
+    // Treat trailing '/' as a '.', unless it is the root dir.
+    if (Position == Path.size() && Component != "/") {
+      --Position;
+      Component = ".";
+      return *this;
+    }
+  }
+
+  // Find next component.
+  size_t end_pos = Path.find_first_of(separators(S), Position);
+  Component = Path.slice(Position, end_pos);
+
+  return *this;
+}
+
+bool const_iterator::operator==(const const_iterator &RHS) const {
+  return Path.begin() == RHS.Path.begin() && Position == RHS.Position;
+}
+
+ptrdiff_t const_iterator::operator-(const const_iterator &RHS) const {
+  return Position - RHS.Position;
+}
+
+reverse_iterator rbegin(StringRef Path, Style style) {
+  reverse_iterator I;
+  I.Path = Path;
+  I.Position = Path.size();
+  I.S = style;
+  return ++I;
+}
+
+reverse_iterator rend(StringRef Path) {
+  reverse_iterator I;
+  I.Path = Path;
+  I.Component = Path.substr(0, 0);
+  I.Position = 0;
+  return I;
+}
+
+reverse_iterator &reverse_iterator::operator++() {
+  size_t root_dir_pos = root_dir_start(Path, S);
+
+  // Skip separators unless it's the root directory.
+  size_t end_pos = Position;
+  while (end_pos > 0 && (end_pos - 1) != root_dir_pos &&
+         is_separator(Path[end_pos - 1], S))
+    --end_pos;
+
+  // Treat trailing '/' as a '.', unless it is the root dir.
+  if (Position == Path.size() && !Path.empty() &&
+      is_separator(Path.back(), S) &&
+      (root_dir_pos == StringRef::npos || end_pos - 1 > root_dir_pos)) {
+    --Position;
+    Component = ".";
+    return *this;
+  }
+
+  // Find next separator.
+  size_t start_pos = filename_pos(Path.substr(0, end_pos), S);
+  Component = Path.slice(start_pos, end_pos);
+  Position = start_pos;
+  return *this;
+}
+
+bool reverse_iterator::operator==(const reverse_iterator &RHS) const {
+  return Path.begin() == RHS.Path.begin() && Component == RHS.Component &&
+         Position == RHS.Position;
+}
+
+ptrdiff_t reverse_iterator::operator-(const reverse_iterator &RHS) const {
+  return Position - RHS.Position;
+}
+
+StringRef root_path(StringRef path, Style style) {
+  const_iterator b = begin(path, style), pos = b, e = end(path);
+  if (b != e) {
+    bool has_net =
+        b->size() > 2 && is_separator((*b)[0], style) && (*b)[1] == (*b)[0];
+    bool has_drive = (real_style(style) == Style::windows) && b->endswith(":");
+
+    if (has_net || has_drive) {
+      if ((++pos != e) && is_separator((*pos)[0], style)) {
+        // {C:/,//net/}, so get the first two components.
+        return path.substr(0, b->size() + pos->size());
+      } else {
+        // just {C:,//net}, return the first component.
+        return *b;
+      }
+    }
+
+    // POSIX style root directory.
+    if (is_separator((*b)[0], style)) {
+      return *b;
+    }
+  }
+
+  return StringRef();
+}
+
+StringRef root_name(StringRef path, Style style) {
+  const_iterator b = begin(path, style), e = end(path);
+  if (b != e) {
+    bool has_net =
+        b->size() > 2 && is_separator((*b)[0], style) && (*b)[1] == (*b)[0];
+    bool has_drive = (real_style(style) == Style::windows) && b->endswith(":");
+
+    if (has_net || has_drive) {
+      // just {C:,//net}, return the first component.
+      return *b;
+    }
+  }
+
+  // No path or no name.
+  return StringRef();
+}
+
+StringRef root_directory(StringRef path, Style style) {
+  const_iterator b = begin(path, style), pos = b, e = end(path);
+  if (b != e) {
+    bool has_net =
+        b->size() > 2 && is_separator((*b)[0], style) && (*b)[1] == (*b)[0];
+    bool has_drive = (real_style(style) == Style::windows) && b->endswith(":");
+
+    if ((has_net || has_drive) &&
+        // {C:,//net}, skip to the next component.
+        (++pos != e) && is_separator((*pos)[0], style)) {
+      return *pos;
+    }
+
+    // POSIX style root directory.
+    if (!has_net && is_separator((*b)[0], style)) {
+      return *b;
+    }
+  }
+
+  // No path or no root.
+  return StringRef();
+}
+
+StringRef relative_path(StringRef path, Style style) {
+  StringRef root = root_path(path, style);
+  return path.substr(root.size());
+}
+
+void append(SmallVectorImpl<char> &path, Style style, const Twine &a,
+            const Twine &b, const Twine &c, const Twine &d) {
+  SmallString<32> a_storage;
+  SmallString<32> b_storage;
+  SmallString<32> c_storage;
+  SmallString<32> d_storage;
+
+  SmallVector<StringRef, 4> components;
+  if (!a.isTriviallyEmpty()) components.push_back(a.toStringRef(a_storage));
+  if (!b.isTriviallyEmpty()) components.push_back(b.toStringRef(b_storage));
+  if (!c.isTriviallyEmpty()) components.push_back(c.toStringRef(c_storage));
+  if (!d.isTriviallyEmpty()) components.push_back(d.toStringRef(d_storage));
+
+  for (auto &component : components) {
+    bool path_has_sep =
+        !path.empty() && is_separator(path[path.size() - 1], style);
+    if (path_has_sep) {
+      // Strip separators from beginning of component.
+      size_t loc = component.find_first_not_of(separators(style));
+      StringRef c = component.substr(loc);
+
+      // Append it.
+      path.append(c.begin(), c.end());
+      continue;
+    }
+
+    bool component_has_sep =
+        !component.empty() && is_separator(component[0], style);
+    if (!component_has_sep &&
+        !(path.empty() || has_root_name(component, style))) {
+      // Add a separator.
+      path.push_back(preferred_separator(style));
+    }
+
+    path.append(component.begin(), component.end());
+  }
+}
+
+void append(SmallVectorImpl<char> &path, const Twine &a, const Twine &b,
+            const Twine &c, const Twine &d) {
+  append(path, Style::native, a, b, c, d);
+}
+
+void append(SmallVectorImpl<char> &path, const_iterator begin,
+            const_iterator end, Style style) {
+  for (; begin != end; ++begin)
+    path::append(path, style, *begin);
+}
+
+StringRef parent_path(StringRef path, Style style) {
+  size_t end_pos = parent_path_end(path, style);
+  if (end_pos == StringRef::npos)
+    return StringRef();
+  else
+    return path.substr(0, end_pos);
+}
+
+void remove_filename(SmallVectorImpl<char> &path, Style style) {
+  size_t end_pos = parent_path_end(StringRef(path.begin(), path.size()), style);
+  if (end_pos != StringRef::npos)
+    path.set_size(end_pos);
+}
+
+void replace_extension(SmallVectorImpl<char> &path, const Twine &extension,
+                       Style style) {
+  StringRef p(path.begin(), path.size());
+  SmallString<32> ext_storage;
+  StringRef ext = extension.toStringRef(ext_storage);
+
+  // Erase existing extension.
+  size_t pos = p.find_last_of('.');
+  if (pos != StringRef::npos && pos >= filename_pos(p, style))
+    path.set_size(pos);
+
+  // Append '.' if needed.
+  if (ext.size() > 0 && ext[0] != '.')
+    path.push_back('.');
+
+  // Append extension.
+  path.append(ext.begin(), ext.end());
+}
+
+void replace_path_prefix(SmallVectorImpl<char> &Path,
+                         const StringRef &OldPrefix, const StringRef &NewPrefix,
+                         Style style) {
+  if (OldPrefix.empty() && NewPrefix.empty())
+    return;
+
+  StringRef OrigPath(Path.begin(), Path.size());
+  if (!OrigPath.startswith(OldPrefix))
+    return;
+
+  // If prefixes have the same size we can simply copy the new one over.
+  if (OldPrefix.size() == NewPrefix.size()) {
+    std::copy(NewPrefix.begin(), NewPrefix.end(), Path.begin());
+    return;
+  }
+
+  StringRef RelPath = OrigPath.substr(OldPrefix.size());
+  SmallString<256> NewPath;
+  path::append(NewPath, style, NewPrefix);
+  path::append(NewPath, style, RelPath);
+  Path.swap(NewPath);
+}
+
+void native(const Twine &path, SmallVectorImpl<char> &result, Style style) {
+  assert((!path.isSingleStringRef() ||
+          path.getSingleStringRef().data() != result.data()) &&
+         "path and result are not allowed to overlap!");
+  // Clear result.
+  result.clear();
+  path.toVector(result);
+  native(result, style);
+}
+
+void native(SmallVectorImpl<char> &Path, Style style) {
+  if (Path.empty())
+    return;
+  if (real_style(style) == Style::windows) {
+    std::replace(Path.begin(), Path.end(), '/', '\\');
+    if (Path[0] == '~' && (Path.size() == 1 || is_separator(Path[1], style))) {
+      SmallString<128> PathHome;
+      home_directory(PathHome);
+      PathHome.append(Path.begin() + 1, Path.end());
+      Path = PathHome;
+    }
+  } else {
+    for (auto PI = Path.begin(), PE = Path.end(); PI < PE; ++PI) {
+      if (*PI == '\\') {
+        auto PN = PI + 1;
+        if (PN < PE && *PN == '\\')
+          ++PI; // increment once, the for loop will move over the escaped slash
+        else
+          *PI = '/';
+      }
+    }
+  }
+}
+
+std::string convert_to_slash(StringRef path, Style style) {
+  if (real_style(style) != Style::windows)
+    return path;
+
+  std::string s = path.str();
+  std::replace(s.begin(), s.end(), '\\', '/');
+  return s;
+}
+
+StringRef filename(StringRef path, Style style) { return *rbegin(path, style); }
+
+StringRef stem(StringRef path, Style style) {
+  StringRef fname = filename(path, style);
+  size_t pos = fname.find_last_of('.');
+  if (pos == StringRef::npos)
+    return fname;
+  else
+    if ((fname.size() == 1 && fname == ".") ||
+        (fname.size() == 2 && fname == ".."))
+      return fname;
+    else
+      return fname.substr(0, pos);
+}
+
+StringRef extension(StringRef path, Style style) {
+  StringRef fname = filename(path, style);
+  size_t pos = fname.find_last_of('.');
+  if (pos == StringRef::npos)
+    return StringRef();
+  else
+    if ((fname.size() == 1 && fname == ".") ||
+        (fname.size() == 2 && fname == ".."))
+      return StringRef();
+    else
+      return fname.substr(pos);
+}
+
+bool is_separator(char value, Style style) {
+  if (value == '/')
+    return true;
+  if (real_style(style) == Style::windows)
+    return value == '\\';
+  return false;
+}
+
+StringRef get_separator(Style style) {
+  if (real_style(style) == Style::windows)
+    return "\\";
+  return "/";
+}
+
+bool has_root_name(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  return !root_name(p, style).empty();
+}
+
+bool has_root_directory(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  return !root_directory(p, style).empty();
+}
+
+bool has_root_path(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  return !root_path(p, style).empty();
+}
+
+bool has_relative_path(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  return !relative_path(p, style).empty();
+}
+
+bool has_filename(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  return !filename(p, style).empty();
+}
+
+bool has_parent_path(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  return !parent_path(p, style).empty();
+}
+
+bool has_stem(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  return !stem(p, style).empty();
+}
+
+bool has_extension(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  return !extension(p, style).empty();
+}
+
+bool is_absolute(const Twine &path, Style style) {
+  SmallString<128> path_storage;
+  StringRef p = path.toStringRef(path_storage);
+
+  bool rootDir = has_root_directory(p, style);
+  bool rootName =
+      (real_style(style) != Style::windows) || has_root_name(p, style);
+
+  return rootDir && rootName;
+}
+
+bool is_relative(const Twine &path, Style style) {
+  return !is_absolute(path, style);
+}
+
+StringRef remove_leading_dotslash(StringRef Path, Style style) {
+  // Remove leading "./" (or ".//" or "././" etc.)
+  while (Path.size() > 2 && Path[0] == '.' && is_separator(Path[1], style)) {
+    Path = Path.substr(2);
+    while (Path.size() > 0 && is_separator(Path[0], style))
+      Path = Path.substr(1);
+  }
+  return Path;
+}
+
+static SmallString<256> remove_dots(StringRef path, bool remove_dot_dot,
+                                    Style style) {
+  SmallVector<StringRef, 16> components;
+
+  // Skip the root path, then look for traversal in the components.
+  StringRef rel = path::relative_path(path, style);
+  for (StringRef C :
+       wpi::make_range(path::begin(rel, style), path::end(rel))) {
+    if (C == ".")
+      continue;
+    // Leading ".." will remain in the path unless it's at the root.
+    if (remove_dot_dot && C == "..") {
+      if (!components.empty() && components.back() != "..") {
+        components.pop_back();
+        continue;
+      }
+      if (path::is_absolute(path, style))
+        continue;
+    }
+    components.push_back(C);
+  }
+
+  SmallString<256> buffer = path::root_path(path, style);
+  for (StringRef C : components)
+    path::append(buffer, style, C);
+  return buffer;
+}
+
+bool remove_dots(SmallVectorImpl<char> &path, bool remove_dot_dot,
+                 Style style) {
+  StringRef p(path.data(), path.size());
+
+  SmallString<256> result = remove_dots(p, remove_dot_dot, style);
+  if (result == path)
+    return false;
+
+  path.swap(result);
+  return true;
+}
+
+} // end namespace path
+
+namespace fs {
+
+std::error_code getUniqueID(const Twine Path, UniqueID &Result) {
+  file_status Status;
+  std::error_code EC = status(Path, Status);
+  if (EC)
+    return EC;
+  Result = Status.getUniqueID();
+  return std::error_code();
+}
+
+static std::error_code make_absolute(const Twine &current_directory,
+                                     SmallVectorImpl<char> &path,
+                                     bool use_current_directory) {
+  StringRef p(path.data(), path.size());
+
+  bool rootDirectory = path::has_root_directory(p);
+  bool rootName =
+      (real_style(Style::native) != Style::windows) || path::has_root_name(p);
+
+  // Already absolute.
+  if (rootName && rootDirectory)
+    return std::error_code();
+
+  // All of the following conditions will need the current directory.
+  SmallString<128> current_dir;
+  if (use_current_directory)
+    current_directory.toVector(current_dir);
+  else if (std::error_code ec = current_path(current_dir))
+    return ec;
+
+  // Relative path. Prepend the current directory.
+  if (!rootName && !rootDirectory) {
+    // Append path to the current directory.
+    path::append(current_dir, p);
+    // Set path to the result.
+    path.swap(current_dir);
+    return std::error_code();
+  }
+
+  if (!rootName && rootDirectory) {
+    StringRef cdrn = path::root_name(current_dir);
+    SmallString<128> curDirRootName(cdrn.begin(), cdrn.end());
+    path::append(curDirRootName, p);
+    // Set path to the result.
+    path.swap(curDirRootName);
+    return std::error_code();
+  }
+
+  if (rootName && !rootDirectory) {
+    StringRef pRootName      = path::root_name(p);
+    StringRef bRootDirectory = path::root_directory(current_dir);
+    StringRef bRelativePath  = path::relative_path(current_dir);
+    StringRef pRelativePath  = path::relative_path(p);
+
+    SmallString<128> res;
+    path::append(res, pRootName, bRootDirectory, bRelativePath, pRelativePath);
+    path.swap(res);
+    return std::error_code();
+  }
+
+  assert(false && "All rootName and rootDirectory combinations should have "
+                   "occurred above!");
+  return std::error_code();
+}
+
+std::error_code make_absolute(const Twine &current_directory,
+                              SmallVectorImpl<char> &path) {
+  return make_absolute(current_directory, path, true);
+}
+
+std::error_code make_absolute(SmallVectorImpl<char> &path) {
+  return make_absolute(Twine(), path, false);
+}
+
+bool exists(const basic_file_status &status) {
+  return status_known(status) && status.type() != file_type::file_not_found;
+}
+
+bool status_known(const basic_file_status &s) {
+  return s.type() != file_type::status_error;
+}
+
+file_type get_file_type(const Twine &Path, bool Follow) {
+  file_status st;
+  if (status(Path, st, Follow))
+    return file_type::status_error;
+  return st.type();
+}
+
+bool is_directory(const basic_file_status &status) {
+  return status.type() == file_type::directory_file;
+}
+
+std::error_code is_directory(const Twine &path, bool &result) {
+  file_status st;
+  if (std::error_code ec = status(path, st))
+    return ec;
+  result = is_directory(st);
+  return std::error_code();
+}
+
+bool is_regular_file(const basic_file_status &status) {
+  return status.type() == file_type::regular_file;
+}
+
+std::error_code is_regular_file(const Twine &path, bool &result) {
+  file_status st;
+  if (std::error_code ec = status(path, st))
+    return ec;
+  result = is_regular_file(st);
+  return std::error_code();
+}
+
+bool is_symlink_file(const basic_file_status &status) {
+  return status.type() == file_type::symlink_file;
+}
+
+std::error_code is_symlink_file(const Twine &path, bool &result) {
+  file_status st;
+  if (std::error_code ec = status(path, st, false))
+    return ec;
+  result = is_symlink_file(st);
+  return std::error_code();
+}
+
+bool is_other(const basic_file_status &status) {
+  return exists(status) &&
+         !is_regular_file(status) &&
+         !is_directory(status);
+}
+
+std::error_code is_other(const Twine &Path, bool &Result) {
+  file_status FileStatus;
+  if (std::error_code EC = status(Path, FileStatus))
+    return EC;
+  Result = is_other(FileStatus);
+  return std::error_code();
+}
+
+void directory_entry::replace_filename(const Twine &filename,
+                                       basic_file_status st) {
+  SmallString<128> path = path::parent_path(Path);
+  path::append(path, filename);
+  Path = path.str();
+  Status = st;
+}
+
+ErrorOr<perms> getPermissions(const Twine &Path) {
+  file_status Status;
+  if (std::error_code EC = status(Path, Status))
+    return EC;
+
+  return Status.permissions();
+}
+
+} // end namespace fs
+} // end namespace sys
+} // end namespace wpi
+
+// Include the truly platform-specific parts.
+#ifdef _WIN32
+#include "Windows/Path.inc"
+#else
+#include "Unix/Path.inc"
+#endif
+
+namespace wpi {
+namespace sys {
+namespace path {
+
+bool user_cache_directory(SmallVectorImpl<char> &Result, const Twine &Path1,
+                          const Twine &Path2, const Twine &Path3) {
+  if (getUserCacheDir(Result)) {
+    append(Result, Path1, Path2, Path3);
+    return true;
+  }
+  return false;
+}
+
+} // end namespace path
+} // end namsspace sys
+} // end namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/SmallPtrSet.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/SmallPtrSet.cpp
new file mode 100644
index 0000000..f91b6eb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/SmallPtrSet.cpp
@@ -0,0 +1,269 @@
+//===- llvm/ADT/SmallPtrSet.cpp - 'Normally small' pointer set ------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the SmallPtrSet class.  See SmallPtrSet.h for an
+// overview of the algorithm.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SmallPtrSet.h"
+#include "wpi/DenseMapInfo.h"
+#include "wpi/MathExtras.h"
+#include "wpi/memory.h"
+#include <algorithm>
+#include <cassert>
+#include <cstdlib>
+
+using namespace wpi;
+
+void SmallPtrSetImplBase::shrink_and_clear() {
+  assert(!isSmall() && "Can't shrink a small set!");
+  free(CurArray);
+
+  // Reduce the number of buckets.
+  unsigned Size = size();
+  CurArraySize = Size > 16 ? 1 << (Log2_32_Ceil(Size) + 1) : 32;
+  NumNonEmpty = NumTombstones = 0;
+
+  // Install the new array.  Clear all the buckets to empty.
+  CurArray = (const void**)CheckedMalloc(sizeof(void*) * CurArraySize);
+  memset(CurArray, -1, CurArraySize*sizeof(void*));
+}
+
+std::pair<const void *const *, bool>
+SmallPtrSetImplBase::insert_imp_big(const void *Ptr) {
+  if (LLVM_UNLIKELY(size() * 4 >= CurArraySize * 3)) {
+    // If more than 3/4 of the array is full, grow.
+    Grow(CurArraySize < 64 ? 128 : CurArraySize * 2);
+  } else if (LLVM_UNLIKELY(CurArraySize - NumNonEmpty < CurArraySize / 8)) {
+    // If fewer of 1/8 of the array is empty (meaning that many are filled with
+    // tombstones), rehash.
+    Grow(CurArraySize);
+  }
+
+  // Okay, we know we have space.  Find a hash bucket.
+  const void **Bucket = const_cast<const void**>(FindBucketFor(Ptr));
+  if (*Bucket == Ptr)
+    return std::make_pair(Bucket, false); // Already inserted, good.
+
+  // Otherwise, insert it!
+  if (*Bucket == getTombstoneMarker())
+    --NumTombstones;
+  else
+    ++NumNonEmpty; // Track density.
+  *Bucket = Ptr;
+  return std::make_pair(Bucket, true);
+}
+
+const void * const *SmallPtrSetImplBase::FindBucketFor(const void *Ptr) const {
+  unsigned Bucket = DenseMapInfo<void *>::getHashValue(Ptr) & (CurArraySize-1);
+  unsigned ArraySize = CurArraySize;
+  unsigned ProbeAmt = 1;
+  const void *const *Array = CurArray;
+  const void *const *Tombstone = nullptr;
+  while (true) {
+    // If we found an empty bucket, the pointer doesn't exist in the set.
+    // Return a tombstone if we've seen one so far, or the empty bucket if
+    // not.
+    if (LLVM_LIKELY(Array[Bucket] == getEmptyMarker()))
+      return Tombstone ? Tombstone : Array+Bucket;
+
+    // Found Ptr's bucket?
+    if (LLVM_LIKELY(Array[Bucket] == Ptr))
+      return Array+Bucket;
+
+    // If this is a tombstone, remember it.  If Ptr ends up not in the set, we
+    // prefer to return it than something that would require more probing.
+    if (Array[Bucket] == getTombstoneMarker() && !Tombstone)
+      Tombstone = Array+Bucket;  // Remember the first tombstone found.
+
+    // It's a hash collision or a tombstone. Reprobe.
+    Bucket = (Bucket + ProbeAmt++) & (ArraySize-1);
+  }
+}
+
+/// Grow - Allocate a larger backing store for the buckets and move it over.
+///
+void SmallPtrSetImplBase::Grow(unsigned NewSize) {
+  const void **OldBuckets = CurArray;
+  const void **OldEnd = EndPointer();
+  bool WasSmall = isSmall();
+
+  // Install the new array.  Clear all the buckets to empty.
+  CurArray = (const void**) CheckedMalloc(sizeof(void*) * NewSize);
+  CurArraySize = NewSize;
+  memset(CurArray, -1, NewSize*sizeof(void*));
+
+  // Copy over all valid entries.
+  for (const void **BucketPtr = OldBuckets; BucketPtr != OldEnd; ++BucketPtr) {
+    // Copy over the element if it is valid.
+    const void *Elt = *BucketPtr;
+    if (Elt != getTombstoneMarker() && Elt != getEmptyMarker())
+      *const_cast<void**>(FindBucketFor(Elt)) = const_cast<void*>(Elt);
+  }
+
+  if (!WasSmall)
+    free(OldBuckets);
+  NumNonEmpty -= NumTombstones;
+  NumTombstones = 0;
+}
+
+SmallPtrSetImplBase::SmallPtrSetImplBase(const void **SmallStorage,
+                                         const SmallPtrSetImplBase &that) {
+  SmallArray = SmallStorage;
+
+  // If we're becoming small, prepare to insert into our stack space
+  if (that.isSmall()) {
+    CurArray = SmallArray;
+  // Otherwise, allocate new heap space (unless we were the same size)
+  } else {
+    CurArray = (const void**)CheckedMalloc(sizeof(void*) * that.CurArraySize);
+  }
+
+  // Copy over the that array.
+  CopyHelper(that);
+}
+
+SmallPtrSetImplBase::SmallPtrSetImplBase(const void **SmallStorage,
+                                         unsigned SmallSize,
+                                         SmallPtrSetImplBase &&that) {
+  SmallArray = SmallStorage;
+  MoveHelper(SmallSize, std::move(that));
+}
+
+void SmallPtrSetImplBase::CopyFrom(const SmallPtrSetImplBase &RHS) {
+  assert(&RHS != this && "Self-copy should be handled by the caller.");
+
+  if (isSmall() && RHS.isSmall())
+    assert(CurArraySize == RHS.CurArraySize &&
+           "Cannot assign sets with different small sizes");
+
+  // If we're becoming small, prepare to insert into our stack space
+  if (RHS.isSmall()) {
+    if (!isSmall())
+      free(CurArray);
+    CurArray = SmallArray;
+  // Otherwise, allocate new heap space (unless we were the same size)
+  } else if (CurArraySize != RHS.CurArraySize) {
+    if (isSmall())
+      CurArray = (const void**)malloc(sizeof(void*) * RHS.CurArraySize);
+    else {
+      const void **T = (const void**)realloc(CurArray,
+                                             sizeof(void*) * RHS.CurArraySize);
+      if (!T)
+        free(CurArray);
+      CurArray = T;
+    }
+    assert(CurArray && "Failed to allocate memory?");
+  }
+
+  CopyHelper(RHS);
+}
+
+void SmallPtrSetImplBase::CopyHelper(const SmallPtrSetImplBase &RHS) {
+  // Copy over the new array size
+  CurArraySize = RHS.CurArraySize;
+
+  // Copy over the contents from the other set
+  std::copy(RHS.CurArray, RHS.EndPointer(), CurArray);
+
+  NumNonEmpty = RHS.NumNonEmpty;
+  NumTombstones = RHS.NumTombstones;
+}
+
+void SmallPtrSetImplBase::MoveFrom(unsigned SmallSize,
+                                   SmallPtrSetImplBase &&RHS) {
+  if (!isSmall())
+    free(CurArray);
+  MoveHelper(SmallSize, std::move(RHS));
+}
+
+void SmallPtrSetImplBase::MoveHelper(unsigned SmallSize,
+                                     SmallPtrSetImplBase &&RHS) {
+  assert(&RHS != this && "Self-move should be handled by the caller.");
+
+  if (RHS.isSmall()) {
+    // Copy a small RHS rather than moving.
+    CurArray = SmallArray;
+    std::copy(RHS.CurArray, RHS.CurArray + RHS.NumNonEmpty, CurArray);
+  } else {
+    CurArray = RHS.CurArray;
+    RHS.CurArray = RHS.SmallArray;
+  }
+
+  // Copy the rest of the trivial members.
+  CurArraySize = RHS.CurArraySize;
+  NumNonEmpty = RHS.NumNonEmpty;
+  NumTombstones = RHS.NumTombstones;
+
+  // Make the RHS small and empty.
+  RHS.CurArraySize = SmallSize;
+  assert(RHS.CurArray == RHS.SmallArray);
+  RHS.NumNonEmpty = 0;
+  RHS.NumTombstones = 0;
+}
+
+void SmallPtrSetImplBase::swap(SmallPtrSetImplBase &RHS) {
+  if (this == &RHS) return;
+
+  // We can only avoid copying elements if neither set is small.
+  if (!this->isSmall() && !RHS.isSmall()) {
+    std::swap(this->CurArray, RHS.CurArray);
+    std::swap(this->CurArraySize, RHS.CurArraySize);
+    std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
+    std::swap(this->NumTombstones, RHS.NumTombstones);
+    return;
+  }
+
+  // FIXME: From here on we assume that both sets have the same small size.
+
+  // If only RHS is small, copy the small elements into LHS and move the pointer
+  // from LHS to RHS.
+  if (!this->isSmall() && RHS.isSmall()) {
+    assert(RHS.CurArray == RHS.SmallArray);
+    std::copy(RHS.CurArray, RHS.CurArray + RHS.NumNonEmpty, this->SmallArray);
+    std::swap(RHS.CurArraySize, this->CurArraySize);
+    std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
+    std::swap(this->NumTombstones, RHS.NumTombstones);
+    RHS.CurArray = this->CurArray;
+    this->CurArray = this->SmallArray;
+    return;
+  }
+
+  // If only LHS is small, copy the small elements into RHS and move the pointer
+  // from RHS to LHS.
+  if (this->isSmall() && !RHS.isSmall()) {
+    assert(this->CurArray == this->SmallArray);
+    std::copy(this->CurArray, this->CurArray + this->NumNonEmpty,
+              RHS.SmallArray);
+    std::swap(RHS.CurArraySize, this->CurArraySize);
+    std::swap(RHS.NumNonEmpty, this->NumNonEmpty);
+    std::swap(RHS.NumTombstones, this->NumTombstones);
+    this->CurArray = RHS.CurArray;
+    RHS.CurArray = RHS.SmallArray;
+    return;
+  }
+
+  // Both a small, just swap the small elements.
+  assert(this->isSmall() && RHS.isSmall());
+  unsigned MinNonEmpty = std::min(this->NumNonEmpty, RHS.NumNonEmpty);
+  std::swap_ranges(this->SmallArray, this->SmallArray + MinNonEmpty,
+                   RHS.SmallArray);
+  if (this->NumNonEmpty > MinNonEmpty) {
+    std::copy(this->SmallArray + MinNonEmpty,
+              this->SmallArray + this->NumNonEmpty,
+              RHS.SmallArray + MinNonEmpty);
+  } else {
+    std::copy(RHS.SmallArray + MinNonEmpty, RHS.SmallArray + RHS.NumNonEmpty,
+              this->SmallArray + MinNonEmpty);
+  }
+  assert(this->CurArraySize == RHS.CurArraySize);
+  std::swap(this->NumNonEmpty, RHS.NumNonEmpty);
+  std::swap(this->NumTombstones, RHS.NumTombstones);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/SmallVector.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/SmallVector.cpp
new file mode 100644
index 0000000..faa5ba7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/SmallVector.cpp
@@ -0,0 +1,41 @@
+//===- llvm/ADT/SmallVector.cpp - 'Normally small' vectors ----------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the SmallVector class.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/SmallVector.h"
+#include "wpi/memory.h"
+using namespace wpi;
+
+/// grow_pod - This is an implementation of the grow() method which only works
+/// on POD-like datatypes and is out of line to reduce code duplication.
+void SmallVectorBase::grow_pod(void *FirstEl, size_t MinSizeInBytes,
+                               size_t TSize) {
+  size_t CurSizeBytes = size_in_bytes();
+  size_t NewCapacityInBytes = 2 * capacity_in_bytes() + TSize; // Always grow.
+  if (NewCapacityInBytes < MinSizeInBytes)
+    NewCapacityInBytes = MinSizeInBytes;
+
+  void *NewElts;
+  if (BeginX == FirstEl) {
+    NewElts = CheckedMalloc(NewCapacityInBytes);
+
+    // Copy the elements over.  No need to run dtors on PODs.
+    memcpy(NewElts, this->BeginX, CurSizeBytes);
+  } else {
+    // If this wasn't grown from the inline copy, grow the allocated space.
+    NewElts = CheckedRealloc(this->BeginX, NewCapacityInBytes);
+  }
+
+  this->EndX = (char*)NewElts+CurSizeBytes;
+  this->BeginX = NewElts;
+  this->CapacityX = (char*)this->BeginX + NewCapacityInBytes;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringExtras.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringExtras.cpp
new file mode 100644
index 0000000..41c3305
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringExtras.cpp
@@ -0,0 +1,74 @@
+//===-- StringExtras.cpp - Implement the StringExtras header --------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the StringExtras.h header
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/StringExtras.h"
+#include "wpi/SmallVector.h"
+#include "wpi/raw_ostream.h"
+using namespace wpi;
+
+/// StrInStrNoCase - Portable version of strcasestr.  Locates the first
+/// occurrence of string 's1' in string 's2', ignoring case.  Returns
+/// the offset of s2 in s1 or npos if s2 cannot be found.
+StringRef::size_type wpi::StrInStrNoCase(StringRef s1, StringRef s2) {
+  size_t N = s2.size(), M = s1.size();
+  if (N > M)
+    return StringRef::npos;
+  for (size_t i = 0, e = M - N + 1; i != e; ++i)
+    if (s1.substr(i, N).equals_lower(s2))
+      return i;
+  return StringRef::npos;
+}
+
+/// getToken - This function extracts one token from source, ignoring any
+/// leading characters that appear in the Delimiters string, and ending the
+/// token at any of the characters that appear in the Delimiters string.  If
+/// there are no tokens in the source string, an empty string is returned.
+/// The function returns a pair containing the extracted token and the
+/// remaining tail string.
+std::pair<StringRef, StringRef> wpi::getToken(StringRef Source,
+                                               StringRef Delimiters) {
+  // Figure out where the token starts.
+  StringRef::size_type Start = Source.find_first_not_of(Delimiters);
+
+  // Find the next occurrence of the delimiter.
+  StringRef::size_type End = Source.find_first_of(Delimiters, Start);
+
+  return std::make_pair(Source.slice(Start, End), Source.substr(End));
+}
+
+/// SplitString - Split up the specified string according to the specified
+/// delimiters, appending the result fragments to the output list.
+void wpi::SplitString(StringRef Source,
+                       SmallVectorImpl<StringRef> &OutFragments,
+                       StringRef Delimiters) {
+  std::pair<StringRef, StringRef> S = getToken(Source, Delimiters);
+  while (!S.first.empty()) {
+    OutFragments.push_back(S.first);
+    S = getToken(S.second, Delimiters);
+  }
+}
+
+void wpi::PrintEscapedString(StringRef Name, raw_ostream &Out) {
+  for (unsigned i = 0, e = Name.size(); i != e; ++i) {
+    unsigned char C = Name[i];
+    if (isprint(C) && C != '\\' && C != '"')
+      Out << C;
+    else
+      Out << '\\' << hexdigit(C >> 4) << hexdigit(C & 0x0F);
+  }
+}
+
+void wpi::printLowerCase(StringRef String, raw_ostream &Out) {
+  for (const char C : String)
+    Out << toLower(C);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringMap.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringMap.cpp
new file mode 100644
index 0000000..ea91dbb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringMap.cpp
@@ -0,0 +1,263 @@
+//===--- StringMap.cpp - String Hash table map implementation -------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the StringMap class.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/StringMap.h"
+#include "wpi/StringExtras.h"
+#include "wpi/Compiler.h"
+#include "wpi/MathExtras.h"
+#include "wpi/memory.h"
+#include <cassert>
+
+using namespace wpi;
+
+/// Returns the number of buckets to allocate to ensure that the DenseMap can
+/// accommodate \p NumEntries without need to grow().
+static unsigned getMinBucketToReserveForEntries(unsigned NumEntries) {
+  // Ensure that "NumEntries * 4 < NumBuckets * 3"
+  if (NumEntries == 0)
+    return 0;
+  // +1 is required because of the strict equality.
+  // For example if NumEntries is 48, we need to return 401.
+  return NextPowerOf2(NumEntries * 4 / 3 + 1);
+}
+
+StringMapImpl::StringMapImpl(unsigned InitSize, unsigned itemSize) {
+  ItemSize = itemSize;
+
+  // If a size is specified, initialize the table with that many buckets.
+  if (InitSize) {
+    // The table will grow when the number of entries reach 3/4 of the number of
+    // buckets. To guarantee that "InitSize" number of entries can be inserted
+    // in the table without growing, we allocate just what is needed here.
+    init(getMinBucketToReserveForEntries(InitSize));
+    return;
+  }
+
+  // Otherwise, initialize it with zero buckets to avoid the allocation.
+  TheTable = nullptr;
+  NumBuckets = 0;
+  NumItems = 0;
+  NumTombstones = 0;
+}
+
+void StringMapImpl::init(unsigned InitSize) {
+  assert((InitSize & (InitSize-1)) == 0 &&
+         "Init Size must be a power of 2 or zero!");
+
+  unsigned NewNumBuckets = InitSize ? InitSize : 16;
+  NumItems = 0;
+  NumTombstones = 0;
+
+  TheTable = static_cast<StringMapEntryBase **>(
+      CheckedCalloc(NewNumBuckets+1,
+                  sizeof(StringMapEntryBase **) + sizeof(unsigned)));
+
+  // Set the member only if TheTable was successfully allocated
+  NumBuckets = NewNumBuckets;
+
+  // Allocate one extra bucket, set it to look filled so the iterators stop at
+  // end.
+  TheTable[NumBuckets] = (StringMapEntryBase*)2;
+}
+
+/// LookupBucketFor - Look up the bucket that the specified string should end
+/// up in.  If it already exists as a key in the map, the Item pointer for the
+/// specified bucket will be non-null.  Otherwise, it will be null.  In either
+/// case, the FullHashValue field of the bucket will be set to the hash value
+/// of the string.
+unsigned StringMapImpl::LookupBucketFor(StringRef Name) {
+  unsigned HTSize = NumBuckets;
+  if (HTSize == 0) {  // Hash table unallocated so far?
+    init(16);
+    HTSize = NumBuckets;
+  }
+  unsigned FullHashValue = HashString(Name);
+  unsigned BucketNo = FullHashValue & (HTSize-1);
+  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
+
+  unsigned ProbeAmt = 1;
+  int FirstTombstone = -1;
+  while (true) {
+    StringMapEntryBase *BucketItem = TheTable[BucketNo];
+    // If we found an empty bucket, this key isn't in the table yet, return it.
+    if (LLVM_LIKELY(!BucketItem)) {
+      // If we found a tombstone, we want to reuse the tombstone instead of an
+      // empty bucket.  This reduces probing.
+      if (FirstTombstone != -1) {
+        HashTable[FirstTombstone] = FullHashValue;
+        return FirstTombstone;
+      }
+
+      HashTable[BucketNo] = FullHashValue;
+      return BucketNo;
+    }
+
+    if (BucketItem == getTombstoneVal()) {
+      // Skip over tombstones.  However, remember the first one we see.
+      if (FirstTombstone == -1) FirstTombstone = BucketNo;
+    } else if (LLVM_LIKELY(HashTable[BucketNo] == FullHashValue)) {
+      // If the full hash value matches, check deeply for a match.  The common
+      // case here is that we are only looking at the buckets (for item info
+      // being non-null and for the full hash value) not at the items.  This
+      // is important for cache locality.
+
+      // Do the comparison like this because Name isn't necessarily
+      // null-terminated!
+      char *ItemStr = (char*)BucketItem+ItemSize;
+      if (Name == StringRef(ItemStr, BucketItem->getKeyLength())) {
+        // We found a match!
+        return BucketNo;
+      }
+    }
+
+    // Okay, we didn't find the item.  Probe to the next bucket.
+    BucketNo = (BucketNo+ProbeAmt) & (HTSize-1);
+
+    // Use quadratic probing, it has fewer clumping artifacts than linear
+    // probing and has good cache behavior in the common case.
+    ++ProbeAmt;
+  }
+}
+
+
+/// FindKey - Look up the bucket that contains the specified key. If it exists
+/// in the map, return the bucket number of the key.  Otherwise return -1.
+/// This does not modify the map.
+int StringMapImpl::FindKey(StringRef Key) const {
+  unsigned HTSize = NumBuckets;
+  if (HTSize == 0) return -1;  // Really empty table?
+  unsigned FullHashValue = HashString(Key);
+  unsigned BucketNo = FullHashValue & (HTSize-1);
+  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
+
+  unsigned ProbeAmt = 1;
+  while (true) {
+    StringMapEntryBase *BucketItem = TheTable[BucketNo];
+    // If we found an empty bucket, this key isn't in the table yet, return.
+    if (LLVM_LIKELY(!BucketItem))
+      return -1;
+
+    if (BucketItem == getTombstoneVal()) {
+      // Ignore tombstones.
+    } else if (LLVM_LIKELY(HashTable[BucketNo] == FullHashValue)) {
+      // If the full hash value matches, check deeply for a match.  The common
+      // case here is that we are only looking at the buckets (for item info
+      // being non-null and for the full hash value) not at the items.  This
+      // is important for cache locality.
+
+      // Do the comparison like this because NameStart isn't necessarily
+      // null-terminated!
+      char *ItemStr = (char*)BucketItem+ItemSize;
+      if (Key == StringRef(ItemStr, BucketItem->getKeyLength())) {
+        // We found a match!
+        return BucketNo;
+      }
+    }
+
+    // Okay, we didn't find the item.  Probe to the next bucket.
+    BucketNo = (BucketNo+ProbeAmt) & (HTSize-1);
+
+    // Use quadratic probing, it has fewer clumping artifacts than linear
+    // probing and has good cache behavior in the common case.
+    ++ProbeAmt;
+  }
+}
+
+/// RemoveKey - Remove the specified StringMapEntry from the table, but do not
+/// delete it.  This aborts if the value isn't in the table.
+void StringMapImpl::RemoveKey(StringMapEntryBase *V) {
+  const char *VStr = (char*)V + ItemSize;
+  StringMapEntryBase *V2 = RemoveKey(StringRef(VStr, V->getKeyLength()));
+  (void)V2;
+  assert(V == V2 && "Didn't find key?");
+}
+
+/// RemoveKey - Remove the StringMapEntry for the specified key from the
+/// table, returning it.  If the key is not in the table, this returns null.
+StringMapEntryBase *StringMapImpl::RemoveKey(StringRef Key) {
+  int Bucket = FindKey(Key);
+  if (Bucket == -1) return nullptr;
+
+  StringMapEntryBase *Result = TheTable[Bucket];
+  TheTable[Bucket] = getTombstoneVal();
+  --NumItems;
+  ++NumTombstones;
+  assert(NumItems + NumTombstones <= NumBuckets);
+
+  return Result;
+}
+
+/// RehashTable - Grow the table, redistributing values into the buckets with
+/// the appropriate mod-of-hashtable-size.
+unsigned StringMapImpl::RehashTable(unsigned BucketNo) {
+  unsigned NewSize;
+  unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1);
+
+  // If the hash table is now more than 3/4 full, or if fewer than 1/8 of
+  // the buckets are empty (meaning that many are filled with tombstones),
+  // grow/rehash the table.
+  if (LLVM_UNLIKELY(NumItems * 4 > NumBuckets * 3)) {
+    NewSize = NumBuckets*2;
+  } else if (LLVM_UNLIKELY(NumBuckets - (NumItems + NumTombstones) <=
+                           NumBuckets / 8)) {
+    NewSize = NumBuckets;
+  } else {
+    return BucketNo;
+  }
+
+  unsigned NewBucketNo = BucketNo;
+  // Allocate one extra bucket which will always be non-empty.  This allows the
+  // iterators to stop at end.
+  auto NewTableArray = static_cast<StringMapEntryBase **>(
+      CheckedCalloc(NewSize+1, sizeof(StringMapEntryBase *) + sizeof(unsigned)));
+
+  unsigned *NewHashArray = (unsigned *)(NewTableArray + NewSize + 1);
+  NewTableArray[NewSize] = (StringMapEntryBase*)2;
+
+  // Rehash all the items into their new buckets.  Luckily :) we already have
+  // the hash values available, so we don't have to rehash any strings.
+  for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
+    StringMapEntryBase *Bucket = TheTable[I];
+    if (Bucket && Bucket != getTombstoneVal()) {
+      // Fast case, bucket available.
+      unsigned FullHash = HashTable[I];
+      unsigned NewBucket = FullHash & (NewSize-1);
+      if (!NewTableArray[NewBucket]) {
+        NewTableArray[FullHash & (NewSize-1)] = Bucket;
+        NewHashArray[FullHash & (NewSize-1)] = FullHash;
+        if (I == BucketNo)
+          NewBucketNo = NewBucket;
+        continue;
+      }
+
+      // Otherwise probe for a spot.
+      unsigned ProbeSize = 1;
+      do {
+        NewBucket = (NewBucket + ProbeSize++) & (NewSize-1);
+      } while (NewTableArray[NewBucket]);
+
+      // Finally found a slot.  Fill it in.
+      NewTableArray[NewBucket] = Bucket;
+      NewHashArray[NewBucket] = FullHash;
+      if (I == BucketNo)
+        NewBucketNo = NewBucket;
+    }
+  }
+
+  free(TheTable);
+
+  TheTable = NewTableArray;
+  NumBuckets = NewSize;
+  NumTombstones = 0;
+  return NewBucketNo;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringRef.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringRef.cpp
new file mode 100644
index 0000000..ea44bea
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/StringRef.cpp
@@ -0,0 +1,507 @@
+//===-- StringRef.cpp - Lightweight String References ---------------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/StringRef.h"
+#include "wpi/Hashing.h"
+#include "wpi/StringExtras.h"
+#include "wpi/SmallVector.h"
+#include <bitset>
+#include <climits>
+#include <ostream>
+
+using namespace wpi;
+
+// MSVC emits references to this into the translation units which reference it.
+#ifndef _MSC_VER
+const size_t StringRef::npos;
+#endif
+
+// strncasecmp() is not available on non-POSIX systems, so define an
+// alternative function here.
+static int ascii_strncasecmp(const char *LHS, const char *RHS, size_t Length) noexcept {
+  for (size_t I = 0; I < Length; ++I) {
+    unsigned char LHC = toLower(LHS[I]);
+    unsigned char RHC = toLower(RHS[I]);
+    if (LHC != RHC)
+      return LHC < RHC ? -1 : 1;
+  }
+  return 0;
+}
+
+/// compare_lower - Compare strings, ignoring case.
+int StringRef::compare_lower(StringRef RHS) const noexcept {
+  if (int Res = ascii_strncasecmp(Data, RHS.Data, std::min(Length, RHS.Length)))
+    return Res;
+  if (Length == RHS.Length)
+    return 0;
+  return Length < RHS.Length ? -1 : 1;
+}
+
+/// Check if this string starts with the given \p Prefix, ignoring case.
+bool StringRef::startswith_lower(StringRef Prefix) const noexcept {
+  return Length >= Prefix.Length &&
+      ascii_strncasecmp(Data, Prefix.Data, Prefix.Length) == 0;
+}
+
+/// Check if this string ends with the given \p Suffix, ignoring case.
+bool StringRef::endswith_lower(StringRef Suffix) const noexcept {
+  return Length >= Suffix.Length &&
+      ascii_strncasecmp(end() - Suffix.Length, Suffix.Data, Suffix.Length) == 0;
+}
+
+size_t StringRef::find_lower(char C, size_t From) const noexcept {
+  char L = toLower(C);
+  return find_if([L](char D) { return toLower(D) == L; }, From);
+}
+
+/// compare_numeric - Compare strings, handle embedded numbers.
+int StringRef::compare_numeric(StringRef RHS) const noexcept {
+  for (size_t I = 0, E = std::min(Length, RHS.Length); I != E; ++I) {
+    // Check for sequences of digits.
+    if (isDigit(Data[I]) && isDigit(RHS.Data[I])) {
+      // The longer sequence of numbers is considered larger.
+      // This doesn't really handle prefixed zeros well.
+      size_t J;
+      for (J = I + 1; J != E + 1; ++J) {
+        bool ld = J < Length && isDigit(Data[J]);
+        bool rd = J < RHS.Length && isDigit(RHS.Data[J]);
+        if (ld != rd)
+          return rd ? -1 : 1;
+        if (!rd)
+          break;
+      }
+      // The two number sequences have the same length (J-I), just memcmp them.
+      if (int Res = compareMemory(Data + I, RHS.Data + I, J - I))
+        return Res < 0 ? -1 : 1;
+      // Identical number sequences, continue search after the numbers.
+      I = J - 1;
+      continue;
+    }
+    if (Data[I] != RHS.Data[I])
+      return (unsigned char)Data[I] < (unsigned char)RHS.Data[I] ? -1 : 1;
+  }
+  if (Length == RHS.Length)
+    return 0;
+  return Length < RHS.Length ? -1 : 1;
+}
+
+//===----------------------------------------------------------------------===//
+// String Operations
+//===----------------------------------------------------------------------===//
+
+std::string StringRef::lower() const {
+  std::string Result(size(), char());
+  for (size_type i = 0, e = size(); i != e; ++i) {
+    Result[i] = toLower(Data[i]);
+  }
+  return Result;
+}
+
+std::string StringRef::upper() const {
+  std::string Result(size(), char());
+  for (size_type i = 0, e = size(); i != e; ++i) {
+    Result[i] = toUpper(Data[i]);
+  }
+  return Result;
+}
+
+//===----------------------------------------------------------------------===//
+// String Searching
+//===----------------------------------------------------------------------===//
+
+
+/// find - Search for the first string \arg Str in the string.
+///
+/// \return - The index of the first occurrence of \arg Str, or npos if not
+/// found.
+size_t StringRef::find(StringRef Str, size_t From) const noexcept {
+  if (From > Length)
+    return npos;
+
+  const char *Start = Data + From;
+  size_t Size = Length - From;
+
+  const char *Needle = Str.data();
+  size_t N = Str.size();
+  if (N == 0)
+    return From;
+  if (Size < N)
+    return npos;
+  if (N == 1) {
+    const char *Ptr = (const char *)::memchr(Start, Needle[0], Size);
+    return Ptr == nullptr ? npos : Ptr - Data;
+  }
+
+  const char *Stop = Start + (Size - N + 1);
+
+  // For short haystacks or unsupported needles fall back to the naive algorithm
+  if (Size < 16 || N > 255) {
+    do {
+      if (std::memcmp(Start, Needle, N) == 0)
+        return Start - Data;
+      ++Start;
+    } while (Start < Stop);
+    return npos;
+  }
+
+  // Build the bad char heuristic table, with uint8_t to reduce cache thrashing.
+  uint8_t BadCharSkip[256];
+  std::memset(BadCharSkip, N, 256);
+  for (unsigned i = 0; i != N-1; ++i)
+    BadCharSkip[(uint8_t)Str[i]] = N-1-i;
+
+  do {
+    uint8_t Last = Start[N - 1];
+    if (LLVM_UNLIKELY(Last == (uint8_t)Needle[N - 1]))
+      if (std::memcmp(Start, Needle, N - 1) == 0)
+        return Start - Data;
+
+    // Otherwise skip the appropriate number of bytes.
+    Start += BadCharSkip[Last];
+  } while (Start < Stop);
+
+  return npos;
+}
+
+size_t StringRef::find_lower(StringRef Str, size_t From) const noexcept {
+  StringRef This = substr(From);
+  while (This.size() >= Str.size()) {
+    if (This.startswith_lower(Str))
+      return From;
+    This = This.drop_front();
+    ++From;
+  }
+  return npos;
+}
+
+size_t StringRef::rfind_lower(char C, size_t From) const noexcept {
+  From = std::min(From, Length);
+  size_t i = From;
+  while (i != 0) {
+    --i;
+    if (toLower(Data[i]) == toLower(C))
+      return i;
+  }
+  return npos;
+}
+
+/// rfind - Search for the last string \arg Str in the string.
+///
+/// \return - The index of the last occurrence of \arg Str, or npos if not
+/// found.
+size_t StringRef::rfind(StringRef Str) const noexcept {
+  size_t N = Str.size();
+  if (N > Length)
+    return npos;
+  for (size_t i = Length - N + 1, e = 0; i != e;) {
+    --i;
+    if (substr(i, N).equals(Str))
+      return i;
+  }
+  return npos;
+}
+
+size_t StringRef::rfind_lower(StringRef Str) const noexcept {
+  size_t N = Str.size();
+  if (N > Length)
+    return npos;
+  for (size_t i = Length - N + 1, e = 0; i != e;) {
+    --i;
+    if (substr(i, N).equals_lower(Str))
+      return i;
+  }
+  return npos;
+}
+
+/// find_first_of - Find the first character in the string that is in \arg
+/// Chars, or npos if not found.
+///
+/// Note: O(size() + Chars.size())
+StringRef::size_type StringRef::find_first_of(StringRef Chars,
+                                              size_t From) const noexcept {
+  std::bitset<1 << CHAR_BIT> CharBits;
+  for (size_type i = 0; i != Chars.size(); ++i)
+    CharBits.set((unsigned char)Chars[i]);
+
+  for (size_type i = std::min(From, Length), e = Length; i != e; ++i)
+    if (CharBits.test((unsigned char)Data[i]))
+      return i;
+  return npos;
+}
+
+/// find_first_not_of - Find the first character in the string that is not
+/// \arg C or npos if not found.
+StringRef::size_type StringRef::find_first_not_of(char C, size_t From) const noexcept {
+  for (size_type i = std::min(From, Length), e = Length; i != e; ++i)
+    if (Data[i] != C)
+      return i;
+  return npos;
+}
+
+/// find_first_not_of - Find the first character in the string that is not
+/// in the string \arg Chars, or npos if not found.
+///
+/// Note: O(size() + Chars.size())
+StringRef::size_type StringRef::find_first_not_of(StringRef Chars,
+                                                  size_t From) const noexcept {
+  std::bitset<1 << CHAR_BIT> CharBits;
+  for (size_type i = 0; i != Chars.size(); ++i)
+    CharBits.set((unsigned char)Chars[i]);
+
+  for (size_type i = std::min(From, Length), e = Length; i != e; ++i)
+    if (!CharBits.test((unsigned char)Data[i]))
+      return i;
+  return npos;
+}
+
+/// find_last_of - Find the last character in the string that is in \arg C,
+/// or npos if not found.
+///
+/// Note: O(size() + Chars.size())
+StringRef::size_type StringRef::find_last_of(StringRef Chars,
+                                             size_t From) const noexcept {
+  std::bitset<1 << CHAR_BIT> CharBits;
+  for (size_type i = 0; i != Chars.size(); ++i)
+    CharBits.set((unsigned char)Chars[i]);
+
+  for (size_type i = std::min(From, Length) - 1, e = -1; i != e; --i)
+    if (CharBits.test((unsigned char)Data[i]))
+      return i;
+  return npos;
+}
+
+/// find_last_not_of - Find the last character in the string that is not
+/// \arg C, or npos if not found.
+StringRef::size_type StringRef::find_last_not_of(char C, size_t From) const noexcept {
+  for (size_type i = std::min(From, Length) - 1, e = -1; i != e; --i)
+    if (Data[i] != C)
+      return i;
+  return npos;
+}
+
+/// find_last_not_of - Find the last character in the string that is not in
+/// \arg Chars, or npos if not found.
+///
+/// Note: O(size() + Chars.size())
+StringRef::size_type StringRef::find_last_not_of(StringRef Chars,
+                                                 size_t From) const noexcept {
+  std::bitset<1 << CHAR_BIT> CharBits;
+  for (size_type i = 0, e = Chars.size(); i != e; ++i)
+    CharBits.set((unsigned char)Chars[i]);
+
+  for (size_type i = std::min(From, Length) - 1, e = -1; i != e; --i)
+    if (!CharBits.test((unsigned char)Data[i]))
+      return i;
+  return npos;
+}
+
+void StringRef::split(SmallVectorImpl<StringRef> &A,
+                      StringRef Separator, int MaxSplit,
+                      bool KeepEmpty) const {
+  StringRef S = *this;
+
+  // Count down from MaxSplit. When MaxSplit is -1, this will just split
+  // "forever". This doesn't support splitting more than 2^31 times
+  // intentionally; if we ever want that we can make MaxSplit a 64-bit integer
+  // but that seems unlikely to be useful.
+  while (MaxSplit-- != 0) {
+    size_t Idx = S.find(Separator);
+    if (Idx == npos)
+      break;
+
+    // Push this split.
+    if (KeepEmpty || Idx > 0)
+      A.push_back(S.slice(0, Idx));
+
+    // Jump forward.
+    S = S.slice(Idx + Separator.size(), npos);
+  }
+
+  // Push the tail.
+  if (KeepEmpty || !S.empty())
+    A.push_back(S);
+}
+
+void StringRef::split(SmallVectorImpl<StringRef> &A, char Separator,
+                      int MaxSplit, bool KeepEmpty) const {
+  StringRef S = *this;
+
+  // Count down from MaxSplit. When MaxSplit is -1, this will just split
+  // "forever". This doesn't support splitting more than 2^31 times
+  // intentionally; if we ever want that we can make MaxSplit a 64-bit integer
+  // but that seems unlikely to be useful.
+  while (MaxSplit-- != 0) {
+    size_t Idx = S.find(Separator);
+    if (Idx == npos)
+      break;
+
+    // Push this split.
+    if (KeepEmpty || Idx > 0)
+      A.push_back(S.slice(0, Idx));
+
+    // Jump forward.
+    S = S.slice(Idx + 1, npos);
+  }
+
+  // Push the tail.
+  if (KeepEmpty || !S.empty())
+    A.push_back(S);
+}
+
+//===----------------------------------------------------------------------===//
+// Helpful Algorithms
+//===----------------------------------------------------------------------===//
+
+/// count - Return the number of non-overlapped occurrences of \arg Str in
+/// the string.
+size_t StringRef::count(StringRef Str) const noexcept {
+  size_t Count = 0;
+  size_t N = Str.size();
+  if (N > Length)
+    return 0;
+  for (size_t i = 0, e = Length - N + 1; i != e; ++i)
+    if (substr(i, N).equals(Str))
+      ++Count;
+  return Count;
+}
+
+static unsigned GetAutoSenseRadix(StringRef &Str) noexcept {
+  if (Str.empty())
+    return 10;
+
+  if (Str.startswith("0x") || Str.startswith("0X")) {
+    Str = Str.substr(2);
+    return 16;
+  }
+
+  if (Str.startswith("0b") || Str.startswith("0B")) {
+    Str = Str.substr(2);
+    return 2;
+  }
+
+  if (Str.startswith("0o")) {
+    Str = Str.substr(2);
+    return 8;
+  }
+
+  if (Str[0] == '0' && Str.size() > 1 && isDigit(Str[1])) {
+    Str = Str.substr(1);
+    return 8;
+  }
+
+  return 10;
+}
+
+bool wpi::consumeUnsignedInteger(StringRef &Str, unsigned Radix,
+                                  unsigned long long &Result) noexcept {
+  // Autosense radix if not specified.
+  if (Radix == 0)
+    Radix = GetAutoSenseRadix(Str);
+
+  // Empty strings (after the radix autosense) are invalid.
+  if (Str.empty()) return true;
+
+  // Parse all the bytes of the string given this radix.  Watch for overflow.
+  StringRef Str2 = Str;
+  Result = 0;
+  while (!Str2.empty()) {
+    unsigned CharVal;
+    if (Str2[0] >= '0' && Str2[0] <= '9')
+      CharVal = Str2[0] - '0';
+    else if (Str2[0] >= 'a' && Str2[0] <= 'z')
+      CharVal = Str2[0] - 'a' + 10;
+    else if (Str2[0] >= 'A' && Str2[0] <= 'Z')
+      CharVal = Str2[0] - 'A' + 10;
+    else
+      break;
+
+    // If the parsed value is larger than the integer radix, we cannot
+    // consume any more characters.
+    if (CharVal >= Radix)
+      break;
+
+    // Add in this character.
+    unsigned long long PrevResult = Result;
+    Result = Result * Radix + CharVal;
+
+    // Check for overflow by shifting back and seeing if bits were lost.
+    if (Result / Radix < PrevResult)
+      return true;
+
+    Str2 = Str2.substr(1);
+  }
+
+  // We consider the operation a failure if no characters were consumed
+  // successfully.
+  if (Str.size() == Str2.size())
+    return true;
+
+  Str = Str2;
+  return false;
+}
+
+bool wpi::consumeSignedInteger(StringRef &Str, unsigned Radix,
+                                long long &Result) noexcept {
+  unsigned long long ULLVal;
+
+  // Handle positive strings first.
+  if (Str.empty() || Str.front() != '-') {
+    if (consumeUnsignedInteger(Str, Radix, ULLVal) ||
+        // Check for value so large it overflows a signed value.
+        (long long)ULLVal < 0)
+      return true;
+    Result = ULLVal;
+    return false;
+  }
+
+  // Get the positive part of the value.
+  StringRef Str2 = Str.drop_front(1);
+  if (consumeUnsignedInteger(Str2, Radix, ULLVal) ||
+      // Reject values so large they'd overflow as negative signed, but allow
+      // "-0".  This negates the unsigned so that the negative isn't undefined
+      // on signed overflow.
+      (long long)-ULLVal > 0)
+    return true;
+
+  Str = Str2;
+  Result = -ULLVal;
+  return false;
+}
+
+/// GetAsUnsignedInteger - Workhorse method that converts a integer character
+/// sequence of radix up to 36 to an unsigned long long value.
+bool wpi::getAsUnsignedInteger(StringRef Str, unsigned Radix,
+                                unsigned long long &Result) noexcept {
+  if (consumeUnsignedInteger(Str, Radix, Result))
+    return true;
+
+  // For getAsUnsignedInteger, we require the whole string to be consumed or
+  // else we consider it a failure.
+  return !Str.empty();
+}
+
+bool wpi::getAsSignedInteger(StringRef Str, unsigned Radix,
+                              long long &Result) noexcept {
+  if (consumeSignedInteger(Str, Radix, Result))
+    return true;
+
+  // For getAsSignedInteger, we require the whole string to be consumed or else
+  // we consider it a failure.
+  return !Str.empty();
+}
+
+std::ostream &wpi::operator<<(std::ostream &os, StringRef string) {
+  os.write(string.data(), string.size());
+  return os;
+}
+
+// Implementation of StringRef hashing.
+hash_code wpi::hash_value(StringRef S) {
+  return hash_combine_range(S.begin(), S.end());
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Twine.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Twine.cpp
new file mode 100644
index 0000000..ac705ff
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Twine.cpp
@@ -0,0 +1,169 @@
+//===-- Twine.cpp - Fast Temporary String Concatenation -------------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/Twine.h"
+#include "wpi/SmallString.h"
+#include "wpi/raw_ostream.h"
+using namespace wpi;
+
+std::string Twine::str() const {
+  // If we're storing only a std::string, just return it.
+  if (LHSKind == StdStringKind && RHSKind == EmptyKind)
+    return *LHS.stdString;
+
+  // Otherwise, flatten and copy the contents first.
+  SmallString<256> Vec;
+  return toStringRef(Vec).str();
+}
+
+void Twine::toVector(SmallVectorImpl<char> &Out) const {
+  raw_svector_ostream OS(Out);
+  print(OS);
+}
+
+StringRef Twine::toNullTerminatedStringRef(SmallVectorImpl<char> &Out) const {
+  if (isUnary()) {
+    switch (getLHSKind()) {
+    case CStringKind:
+      // Already null terminated, yay!
+      return StringRef(LHS.cString);
+    case StdStringKind: {
+      const std::string *str = LHS.stdString;
+      return StringRef(str->c_str(), str->size());
+    }
+    default:
+      break;
+    }
+  }
+  toVector(Out);
+  Out.push_back(0);
+  Out.pop_back();
+  return StringRef(Out.data(), Out.size());
+}
+
+void Twine::printOneChild(raw_ostream &OS, Child Ptr,
+                          NodeKind Kind) const {
+  switch (Kind) {
+  case Twine::NullKind: break;
+  case Twine::EmptyKind: break;
+  case Twine::TwineKind:
+    Ptr.twine->print(OS);
+    break;
+  case Twine::CStringKind:
+    OS << Ptr.cString;
+    break;
+  case Twine::StdStringKind:
+    OS << *Ptr.stdString;
+    break;
+  case Twine::StringRefKind:
+    OS << *Ptr.stringRef;
+    break;
+  case Twine::SmallStringKind:
+    OS << *Ptr.smallString;
+    break;
+  case Twine::CharKind:
+    OS << Ptr.character;
+    break;
+  case Twine::DecUIKind:
+    OS << Ptr.decUI;
+    break;
+  case Twine::DecIKind:
+    OS << Ptr.decI;
+    break;
+  case Twine::DecULKind:
+    OS << *Ptr.decUL;
+    break;
+  case Twine::DecLKind:
+    OS << *Ptr.decL;
+    break;
+  case Twine::DecULLKind:
+    OS << *Ptr.decULL;
+    break;
+  case Twine::DecLLKind:
+    OS << *Ptr.decLL;
+    break;
+  case Twine::UHexKind:
+    OS.write_hex(*Ptr.uHex);
+    break;
+  }
+}
+
+void Twine::printOneChildRepr(raw_ostream &OS, Child Ptr,
+                              NodeKind Kind) const {
+  switch (Kind) {
+  case Twine::NullKind:
+    OS << "null"; break;
+  case Twine::EmptyKind:
+    OS << "empty"; break;
+  case Twine::TwineKind:
+    OS << "rope:";
+    Ptr.twine->printRepr(OS);
+    break;
+  case Twine::CStringKind:
+    OS << "cstring:\""
+       << Ptr.cString << "\"";
+    break;
+  case Twine::StdStringKind:
+    OS << "std::string:\""
+       << Ptr.stdString << "\"";
+    break;
+  case Twine::StringRefKind:
+    OS << "stringref:\""
+       << Ptr.stringRef << "\"";
+    break;
+  case Twine::SmallStringKind:
+    OS << "smallstring:\"" << *Ptr.smallString << "\"";
+    break;
+  case Twine::CharKind:
+    OS << "char:\"" << Ptr.character << "\"";
+    break;
+  case Twine::DecUIKind:
+    OS << "decUI:\"" << Ptr.decUI << "\"";
+    break;
+  case Twine::DecIKind:
+    OS << "decI:\"" << Ptr.decI << "\"";
+    break;
+  case Twine::DecULKind:
+    OS << "decUL:\"" << *Ptr.decUL << "\"";
+    break;
+  case Twine::DecLKind:
+    OS << "decL:\"" << *Ptr.decL << "\"";
+    break;
+  case Twine::DecULLKind:
+    OS << "decULL:\"" << *Ptr.decULL << "\"";
+    break;
+  case Twine::DecLLKind:
+    OS << "decLL:\"" << *Ptr.decLL << "\"";
+    break;
+  case Twine::UHexKind:
+    OS << "uhex:\"" << Ptr.uHex << "\"";
+    break;
+  }
+}
+
+void Twine::print(raw_ostream &OS) const {
+  printOneChild(OS, LHS, getLHSKind());
+  printOneChild(OS, RHS, getRHSKind());
+}
+
+void Twine::printRepr(raw_ostream &OS) const {
+  OS << "(Twine ";
+  printOneChildRepr(OS, LHS, getLHSKind());
+  OS << " ";
+  printOneChildRepr(OS, RHS, getRHSKind());
+  OS << ")";
+}
+
+LLVM_DUMP_METHOD void Twine::dump() const {
+  print(errs());
+}
+
+LLVM_DUMP_METHOD void Twine::dumpRepr() const {
+  printRepr(errs());
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Unix/Path.inc b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Unix/Path.inc
new file mode 100644
index 0000000..a1ea5a1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Unix/Path.inc
@@ -0,0 +1,401 @@
+//===- llvm/Support/Unix/Path.inc - Unix Path Implementation ----*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the Unix specific implementation of the Path API.
+//
+//===----------------------------------------------------------------------===//
+
+//===----------------------------------------------------------------------===//
+//=== WARNING: Implementation here must contain only generic UNIX code that
+//===          is guaranteed to work on *all* UNIX variants.
+//===----------------------------------------------------------------------===//
+
+#include <fcntl.h>
+#include <limits.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+#include <dirent.h>
+#define NAMLEN(dirent) strlen((dirent)->d_name)
+#include <sys/param.h>
+#include <sys/types.h>
+#include <unistd.h>
+
+namespace wpi {
+namespace sys  {
+namespace fs {
+UniqueID file_status::getUniqueID() const {
+  return UniqueID(fs_st_dev, fs_st_ino);
+}
+
+std::error_code current_path(SmallVectorImpl<char> &result) {
+  result.clear();
+
+  const char *pwd = ::getenv("PWD");
+  wpi::sys::fs::file_status PWDStatus, DotStatus;
+  if (pwd && wpi::sys::path::is_absolute(pwd) &&
+      !wpi::sys::fs::status(pwd, PWDStatus) &&
+      !wpi::sys::fs::status(".", DotStatus) &&
+      PWDStatus.getUniqueID() == DotStatus.getUniqueID()) {
+    result.append(pwd, pwd + strlen(pwd));
+    return std::error_code();
+  }
+
+#ifdef MAXPATHLEN
+  result.reserve(MAXPATHLEN);
+#else
+  result.reserve(1024);
+#endif
+
+  while (true) {
+    if (::getcwd(result.data(), result.capacity()) == nullptr) {
+      // See if there was a real error.
+      if (errno != ENOMEM)
+        return std::error_code(errno, std::generic_category());
+      // Otherwise there just wasn't enough space.
+      result.reserve(result.capacity() * 2);
+    } else
+      break;
+  }
+
+  result.set_size(strlen(result.data()));
+  return std::error_code();
+}
+
+static int convertAccessMode(AccessMode Mode) {
+  switch (Mode) {
+  case AccessMode::Exist:
+    return F_OK;
+  case AccessMode::Write:
+    return W_OK;
+  case AccessMode::Execute:
+    return R_OK | X_OK; // scripts also need R_OK.
+  default:
+    return F_OK;
+  }
+}
+
+std::error_code access(const Twine &Path, AccessMode Mode) {
+  SmallString<128> PathStorage;
+  StringRef P = Path.toNullTerminatedStringRef(PathStorage);
+
+  if (::access(P.begin(), convertAccessMode(Mode)) == -1)
+    return std::error_code(errno, std::generic_category());
+
+  if (Mode == AccessMode::Execute) {
+    // Don't say that directories are executable.
+    struct stat buf;
+    if (0 != stat(P.begin(), &buf))
+      return std::make_error_code(std::errc::permission_denied);
+    if (!S_ISREG(buf.st_mode))
+      return std::make_error_code(std::errc::permission_denied);
+  }
+
+  return std::error_code();
+}
+
+bool equivalent(file_status A, file_status B) {
+  assert(status_known(A) && status_known(B));
+  return A.fs_st_dev == B.fs_st_dev &&
+         A.fs_st_ino == B.fs_st_ino;
+}
+
+std::error_code equivalent(const Twine &A, const Twine &B, bool &result) {
+  file_status fsA, fsB;
+  if (std::error_code ec = status(A, fsA))
+    return ec;
+  if (std::error_code ec = status(B, fsB))
+    return ec;
+  result = equivalent(fsA, fsB);
+  return std::error_code();
+}
+
+static std::error_code fillStatus(int StatRet, const struct stat &Status,
+                             file_status &Result) {
+  if (StatRet != 0) {
+    std::error_code ec(errno, std::generic_category());
+    if (ec == std::errc::no_such_file_or_directory)
+      Result = file_status(file_type::file_not_found);
+    else
+      Result = file_status(file_type::status_error);
+    return ec;
+  }
+
+  file_type Type = file_type::type_unknown;
+
+  if (S_ISDIR(Status.st_mode))
+    Type = file_type::directory_file;
+  else if (S_ISREG(Status.st_mode))
+    Type = file_type::regular_file;
+  else if (S_ISBLK(Status.st_mode))
+    Type = file_type::block_file;
+  else if (S_ISCHR(Status.st_mode))
+    Type = file_type::character_file;
+  else if (S_ISFIFO(Status.st_mode))
+    Type = file_type::fifo_file;
+  else if (S_ISSOCK(Status.st_mode))
+    Type = file_type::socket_file;
+  else if (S_ISLNK(Status.st_mode))
+    Type = file_type::symlink_file;
+
+  perms Perms = static_cast<perms>(Status.st_mode) & all_perms;
+  Result = file_status(Type, Perms, Status.st_dev, Status.st_nlink,
+                       Status.st_ino, Status.st_atime, Status.st_mtime,
+                       Status.st_uid, Status.st_gid, Status.st_size);
+
+  return std::error_code();
+}
+
+std::error_code status(const Twine &Path, file_status &Result, bool Follow) {
+  SmallString<128> PathStorage;
+  StringRef P = Path.toNullTerminatedStringRef(PathStorage);
+
+  struct stat Status;
+  int StatRet = (Follow ? ::stat : ::lstat)(P.begin(), &Status);
+  return fillStatus(StatRet, Status, Result);
+}
+
+std::error_code status(int FD, file_status &Result) {
+  struct stat Status;
+  int StatRet = ::fstat(FD, &Status);
+  return fillStatus(StatRet, Status, Result);
+}
+
+std::error_code detail::directory_iterator_construct(detail::DirIterState &it,
+                                                     StringRef path,
+                                                     bool follow_symlinks) {
+  SmallString<128> path_null(path);
+  DIR *directory = ::opendir(path_null.c_str());
+  if (!directory)
+    return std::error_code(errno, std::generic_category());
+
+  it.IterationHandle = reinterpret_cast<intptr_t>(directory);
+  // Add something for replace_filename to replace.
+  path::append(path_null, ".");
+  it.CurrentEntry = directory_entry(path_null.str(), follow_symlinks);
+  return directory_iterator_increment(it);
+}
+
+std::error_code detail::directory_iterator_destruct(detail::DirIterState &it) {
+  if (it.IterationHandle)
+    ::closedir(reinterpret_cast<DIR *>(it.IterationHandle));
+  it.IterationHandle = 0;
+  it.CurrentEntry = directory_entry();
+  return std::error_code();
+}
+
+std::error_code detail::directory_iterator_increment(detail::DirIterState &it) {
+  errno = 0;
+  dirent *cur_dir = ::readdir(reinterpret_cast<DIR *>(it.IterationHandle));
+  if (cur_dir == nullptr && errno != 0) {
+    return std::error_code(errno, std::generic_category());
+  } else if (cur_dir != nullptr) {
+    StringRef name(cur_dir->d_name, NAMLEN(cur_dir));
+    if ((name.size() == 1 && name[0] == '.') ||
+        (name.size() == 2 && name[0] == '.' && name[1] == '.'))
+      return directory_iterator_increment(it);
+    it.CurrentEntry.replace_filename(name);
+  } else
+    return directory_iterator_destruct(it);
+
+  return std::error_code();
+}
+
+ErrorOr<basic_file_status> directory_entry::status() const {
+  file_status s;
+  if (auto EC = fs::status(Path, s, FollowSymlinks))
+    return EC;
+  return s;
+}
+
+#if !defined(F_GETPATH)
+static bool hasProcSelfFD() {
+  // If we have a /proc filesystem mounted, we can quickly establish the
+  // real name of the file with readlink
+  static const bool Result = (::access("/proc/self/fd", R_OK) == 0);
+  return Result;
+}
+#endif
+
+std::error_code openFileForRead(const Twine &Name, int &ResultFD,
+                                SmallVectorImpl<char> *RealPath) {
+  SmallString<128> Storage;
+  StringRef P = Name.toNullTerminatedStringRef(Storage);
+  while ((ResultFD = open(P.begin(), O_RDONLY)) < 0) {
+    if (errno != EINTR)
+      return std::error_code(errno, std::generic_category());
+  }
+  // Attempt to get the real name of the file, if the user asked
+  if(!RealPath)
+    return std::error_code();
+  RealPath->clear();
+#if defined(F_GETPATH)
+  // When F_GETPATH is availble, it is the quickest way to get
+  // the real path name.
+  char Buffer[MAXPATHLEN];
+  if (::fcntl(ResultFD, F_GETPATH, Buffer) != -1)
+    RealPath->append(Buffer, Buffer + strlen(Buffer));
+#else
+  char Buffer[PATH_MAX];
+  if (hasProcSelfFD()) {
+    char ProcPath[64];
+    snprintf(ProcPath, sizeof(ProcPath), "/proc/self/fd/%d", ResultFD);
+    ssize_t CharCount = ::readlink(ProcPath, Buffer, sizeof(Buffer));
+    if (CharCount > 0)
+      RealPath->append(Buffer, Buffer + CharCount);
+  } else {
+    // Use ::realpath to get the real path name
+    if (::realpath(P.begin(), Buffer) != nullptr)
+      RealPath->append(Buffer, Buffer + strlen(Buffer));
+  }
+#endif
+  return std::error_code();
+}
+
+std::error_code openFileForWrite(const Twine &Name, int &ResultFD,
+                                 OpenFlags Flags, unsigned Mode) {
+  // Verify that we don't have both "append" and "excl".
+  assert((!(Flags & F_Excl) || !(Flags & F_Append)) &&
+         "Cannot specify both 'excl' and 'append' file creation flags!");
+
+  int OpenFlags = O_CREAT;
+
+#ifdef O_CLOEXEC
+  OpenFlags |= O_CLOEXEC;
+#endif
+
+  if (Flags & F_RW)
+    OpenFlags |= O_RDWR;
+  else
+    OpenFlags |= O_WRONLY;
+
+  if (Flags & F_Append)
+    OpenFlags |= O_APPEND;
+  else if (!(Flags & F_NoTrunc))
+    OpenFlags |= O_TRUNC;
+
+  if (Flags & F_Excl)
+    OpenFlags |= O_EXCL;
+
+  SmallString<128> Storage;
+  StringRef P = Name.toNullTerminatedStringRef(Storage);
+  while ((ResultFD = open(P.begin(), OpenFlags, Mode)) < 0) {
+    if (errno != EINTR)
+      return std::error_code(errno, std::generic_category());
+  }
+  return std::error_code();
+}
+
+} // end namespace fs
+
+namespace path {
+
+bool home_directory(SmallVectorImpl<char> &result) {
+  if (char *RequestedDir = std::getenv("HOME")) {
+    result.clear();
+    result.append(RequestedDir, RequestedDir + strlen(RequestedDir));
+    return true;
+  }
+
+  return false;
+}
+
+static bool getDarwinConfDir(bool TempDir, SmallVectorImpl<char> &Result) {
+  #if defined(_CS_DARWIN_USER_TEMP_DIR) && defined(_CS_DARWIN_USER_CACHE_DIR)
+  // On Darwin, use DARWIN_USER_TEMP_DIR or DARWIN_USER_CACHE_DIR.
+  // macros defined in <unistd.h> on darwin >= 9
+  int ConfName = TempDir ? _CS_DARWIN_USER_TEMP_DIR
+                         : _CS_DARWIN_USER_CACHE_DIR;
+  size_t ConfLen = confstr(ConfName, nullptr, 0);
+  if (ConfLen > 0) {
+    do {
+      Result.resize(ConfLen);
+      ConfLen = confstr(ConfName, Result.data(), Result.size());
+    } while (ConfLen > 0 && ConfLen != Result.size());
+
+    if (ConfLen > 0) {
+      assert(Result.back() == 0);
+      Result.pop_back();
+      return true;
+    }
+
+    Result.clear();
+  }
+  #endif
+  return false;
+}
+
+static bool getUserCacheDir(SmallVectorImpl<char> &Result) {
+  // First try using XDG_CACHE_HOME env variable,
+  // as specified in XDG Base Directory Specification at
+  // http://standards.freedesktop.org/basedir-spec/basedir-spec-latest.html
+  if (const char *XdgCacheDir = std::getenv("XDG_CACHE_HOME")) {
+    Result.clear();
+    Result.append(XdgCacheDir, XdgCacheDir + strlen(XdgCacheDir));
+    return true;
+  }
+
+  // Try Darwin configuration query
+  if (getDarwinConfDir(false, Result))
+    return true;
+
+  // Use "$HOME/.cache" if $HOME is available
+  if (home_directory(Result)) {
+    append(Result, ".cache");
+    return true;
+  }
+
+  return false;
+}
+
+static const char *getEnvTempDir() {
+  // Check whether the temporary directory is specified by an environment
+  // variable.
+  const char *EnvironmentVariables[] = {"TMPDIR", "TMP", "TEMP", "TEMPDIR"};
+  for (const char *Env : EnvironmentVariables) {
+    if (const char *Dir = std::getenv(Env))
+      return Dir;
+  }
+
+  return nullptr;
+}
+
+static const char *getDefaultTempDir(bool ErasedOnReboot) {
+#ifdef P_tmpdir
+  if ((bool)P_tmpdir)
+    return P_tmpdir;
+#endif
+
+  if (ErasedOnReboot)
+    return "/tmp";
+  return "/var/tmp";
+}
+
+void system_temp_directory(bool ErasedOnReboot, SmallVectorImpl<char> &Result) {
+  Result.clear();
+
+  if (ErasedOnReboot) {
+    // There is no env variable for the cache directory.
+    if (const char *RequestedDir = getEnvTempDir()) {
+      Result.append(RequestedDir, RequestedDir + strlen(RequestedDir));
+      return;
+    }
+  }
+
+  if (getDarwinConfDir(ErasedOnReboot, Result))
+    return;
+
+  const char *RequestedDir = getDefaultTempDir(ErasedOnReboot);
+  Result.append(RequestedDir, RequestedDir + strlen(RequestedDir));
+}
+
+} // end namespace path
+} // end namespace sys
+} // end namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Windows/Path.inc b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Windows/Path.inc
new file mode 100644
index 0000000..3a170eb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Windows/Path.inc
@@ -0,0 +1,688 @@
+//===- llvm/Support/Windows/Path.inc - Windows Path Impl --------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the Windows specific implementation of the Path API.
+//
+//===----------------------------------------------------------------------===//
+
+//===----------------------------------------------------------------------===//
+//=== WARNING: Implementation here must contain only generic Windows code that
+//===          is guaranteed to work on *all* Windows variants.
+//===----------------------------------------------------------------------===//
+
+#include "wpi/STLExtras.h"
+#include "wpi/WindowsError.h"
+#include <fcntl.h>
+#include <io.h>
+#include <sys/stat.h>
+#include <sys/types.h>
+
+// These two headers must be included last, and make sure shlobj is required
+// after Windows.h to make sure it picks up our definition of _WIN32_WINNT
+#include "WindowsSupport.h"
+#include <shellapi.h>
+#include <shlobj.h>
+
+#undef max
+
+#ifdef _MSC_VER
+# pragma comment(lib, "shell32.lib")
+# pragma comment(lib, "ole32.lib")
+#endif
+
+using namespace wpi;
+
+using wpi::sys::windows::UTF8ToUTF16;
+using wpi::sys::windows::CurCPToUTF16;
+using wpi::sys::windows::UTF16ToUTF8;
+using wpi::sys::path::widenPath;
+
+static bool is_separator(const wchar_t value) {
+  switch (value) {
+  case L'\\':
+  case L'/':
+    return true;
+  default:
+    return false;
+  }
+}
+
+namespace wpi {
+namespace sys  {
+namespace path {
+
+// Convert a UTF-8 path to UTF-16.  Also, if the absolute equivalent of the
+// path is longer than CreateDirectory can tolerate, make it absolute and
+// prefixed by '\\?\'.
+std::error_code widenPath(const Twine &Path8,
+                          SmallVectorImpl<wchar_t> &Path16) {
+  const size_t MaxDirLen = MAX_PATH - 12; // Must leave room for 8.3 filename.
+
+  // Several operations would convert Path8 to SmallString; more efficient to
+  // do it once up front.
+  SmallString<128> Path8Str;
+  Path8.toVector(Path8Str);
+
+  // If we made this path absolute, how much longer would it get?
+  size_t CurPathLen;
+  if (wpi::sys::path::is_absolute(Twine(Path8Str)))
+    CurPathLen = 0; // No contribution from current_path needed.
+  else {
+    CurPathLen = ::GetCurrentDirectoryW(0, NULL);
+    if (CurPathLen == 0)
+      return mapWindowsError(::GetLastError());
+  }
+
+  // Would the absolute path be longer than our limit?
+  if ((Path8Str.size() + CurPathLen) >= MaxDirLen &&
+      !Path8Str.startswith("\\\\?\\")) {
+    SmallString<2*MAX_PATH> FullPath("\\\\?\\");
+    if (CurPathLen) {
+      SmallString<80> CurPath;
+      if (std::error_code EC = wpi::sys::fs::current_path(CurPath))
+        return EC;
+      FullPath.append(CurPath);
+    }
+    // Traverse the requested path, canonicalizing . and .. (because the \\?\
+    // prefix is documented to treat them as real components).  Ignore
+    // separators, which can be returned from the iterator if the path has a
+    // drive name.  We don't need to call native() on the result since append()
+    // always attaches preferred_separator.
+    for (wpi::sys::path::const_iterator I = wpi::sys::path::begin(Path8Str),
+                                         E = wpi::sys::path::end(Path8Str);
+                                         I != E; ++I) {
+      if (I->size() == 1 && is_separator((*I)[0]))
+        continue;
+      if (I->size() == 1 && *I == ".")
+        continue;
+      if (I->size() == 2 && *I == "..")
+        wpi::sys::path::remove_filename(FullPath);
+      else
+        wpi::sys::path::append(FullPath, *I);
+    }
+    return UTF8ToUTF16(FullPath, Path16);
+  }
+
+  // Just use the caller's original path.
+  return UTF8ToUTF16(Path8Str, Path16);
+}
+} // end namespace path
+
+namespace fs {
+
+UniqueID file_status::getUniqueID() const {
+  // The file is uniquely identified by the volume serial number along
+  // with the 64-bit file identifier.
+  uint64_t FileID = (static_cast<uint64_t>(FileIndexHigh) << 32ULL) |
+                    static_cast<uint64_t>(FileIndexLow);
+
+  return UniqueID(VolumeSerialNumber, FileID);
+}
+
+std::error_code current_path(SmallVectorImpl<char> &result) {
+  SmallVector<wchar_t, MAX_PATH> cur_path;
+  DWORD len = MAX_PATH;
+
+  do {
+    cur_path.reserve(len);
+    len = ::GetCurrentDirectoryW(cur_path.capacity(), cur_path.data());
+
+    // A zero return value indicates a failure other than insufficient space.
+    if (len == 0)
+      return mapWindowsError(::GetLastError());
+
+    // If there's insufficient space, the len returned is larger than the len
+    // given.
+  } while (len > cur_path.capacity());
+
+  // On success, GetCurrentDirectoryW returns the number of characters not
+  // including the null-terminator.
+  cur_path.set_size(len);
+  return UTF16ToUTF8(cur_path.begin(), cur_path.size(), result);
+}
+
+
+std::error_code access(const Twine &Path, AccessMode Mode) {
+  SmallVector<wchar_t, 128> PathUtf16;
+
+  if (std::error_code EC = widenPath(Path, PathUtf16))
+    return EC;
+
+  DWORD Attributes = ::GetFileAttributesW(PathUtf16.begin());
+
+  if (Attributes == INVALID_FILE_ATTRIBUTES) {
+    // See if the file didn't actually exist.
+    DWORD LastError = ::GetLastError();
+    if (LastError != ERROR_FILE_NOT_FOUND &&
+        LastError != ERROR_PATH_NOT_FOUND)
+      return mapWindowsError(LastError);
+    return std::make_error_code(std::errc::no_such_file_or_directory);
+  }
+
+  if (Mode == AccessMode::Write && (Attributes & FILE_ATTRIBUTE_READONLY))
+    return std::make_error_code(std::errc::permission_denied);
+
+  return std::error_code();
+}
+
+bool equivalent(file_status A, file_status B) {
+  assert(status_known(A) && status_known(B));
+  return A.FileIndexHigh         == B.FileIndexHigh &&
+         A.FileIndexLow          == B.FileIndexLow &&
+         A.FileSizeHigh          == B.FileSizeHigh &&
+         A.FileSizeLow           == B.FileSizeLow &&
+         A.LastAccessedTimeHigh  == B.LastAccessedTimeHigh &&
+         A.LastAccessedTimeLow   == B.LastAccessedTimeLow &&
+         A.LastWriteTimeHigh     == B.LastWriteTimeHigh &&
+         A.LastWriteTimeLow      == B.LastWriteTimeLow &&
+         A.VolumeSerialNumber    == B.VolumeSerialNumber;
+}
+
+std::error_code equivalent(const Twine &A, const Twine &B, bool &result) {
+  file_status fsA, fsB;
+  if (std::error_code ec = status(A, fsA))
+    return ec;
+  if (std::error_code ec = status(B, fsB))
+    return ec;
+  result = equivalent(fsA, fsB);
+  return std::error_code();
+}
+
+static bool isReservedName(StringRef path) {
+  // This list of reserved names comes from MSDN, at:
+  // http://msdn.microsoft.com/en-us/library/aa365247%28v=vs.85%29.aspx
+  static const char *const sReservedNames[] = { "nul", "con", "prn", "aux",
+                                                "com1", "com2", "com3", "com4",
+                                                "com5", "com6", "com7", "com8",
+                                                "com9", "lpt1", "lpt2", "lpt3",
+                                                "lpt4", "lpt5", "lpt6", "lpt7",
+                                                "lpt8", "lpt9" };
+
+  // First, check to see if this is a device namespace, which always
+  // starts with \\.\, since device namespaces are not legal file paths.
+  if (path.startswith("\\\\.\\"))
+    return true;
+
+  // Then compare against the list of ancient reserved names.
+  for (size_t i = 0; i < array_lengthof(sReservedNames); ++i) {
+    if (path.equals_lower(sReservedNames[i]))
+      return true;
+  }
+
+  // The path isn't what we consider reserved.
+  return false;
+}
+
+static file_type file_type_from_attrs(DWORD Attrs) {
+  return (Attrs & FILE_ATTRIBUTE_DIRECTORY) ? file_type::directory_file
+                                            : file_type::regular_file;
+}
+
+static perms perms_from_attrs(DWORD Attrs) {
+  return (Attrs & FILE_ATTRIBUTE_READONLY) ? (all_read | all_exe) : all_all;
+}
+
+static std::error_code getStatus(HANDLE FileHandle, file_status &Result) {
+  if (FileHandle == INVALID_HANDLE_VALUE)
+    goto handle_status_error;
+
+  switch (::GetFileType(FileHandle)) {
+  default:
+    Result = file_status(file_type::type_unknown);
+    return std::error_code();
+  case FILE_TYPE_UNKNOWN: {
+    DWORD Err = ::GetLastError();
+    if (Err != NO_ERROR)
+      return mapWindowsError(Err);
+    Result = file_status(file_type::type_unknown);
+    return std::error_code();
+  }
+  case FILE_TYPE_DISK:
+    break;
+  case FILE_TYPE_CHAR:
+    Result = file_status(file_type::character_file);
+    return std::error_code();
+  case FILE_TYPE_PIPE:
+    Result = file_status(file_type::fifo_file);
+    return std::error_code();
+  }
+
+  BY_HANDLE_FILE_INFORMATION Info;
+  if (!::GetFileInformationByHandle(FileHandle, &Info))
+    goto handle_status_error;
+
+  Result = file_status(
+      file_type_from_attrs(Info.dwFileAttributes),
+      perms_from_attrs(Info.dwFileAttributes), Info.nNumberOfLinks,
+      Info.ftLastAccessTime.dwHighDateTime, Info.ftLastAccessTime.dwLowDateTime,
+      Info.ftLastWriteTime.dwHighDateTime, Info.ftLastWriteTime.dwLowDateTime,
+      Info.dwVolumeSerialNumber, Info.nFileSizeHigh, Info.nFileSizeLow,
+      Info.nFileIndexHigh, Info.nFileIndexLow);
+  return std::error_code();
+
+handle_status_error:
+  DWORD LastError = ::GetLastError();
+  if (LastError == ERROR_FILE_NOT_FOUND ||
+      LastError == ERROR_PATH_NOT_FOUND)
+    Result = file_status(file_type::file_not_found);
+  else if (LastError == ERROR_SHARING_VIOLATION)
+    Result = file_status(file_type::type_unknown);
+  else
+    Result = file_status(file_type::status_error);
+  return mapWindowsError(LastError);
+}
+
+std::error_code status(const Twine &path, file_status &result, bool Follow) {
+  SmallString<128> path_storage;
+  SmallVector<wchar_t, 128> path_utf16;
+
+  StringRef path8 = path.toStringRef(path_storage);
+  if (isReservedName(path8)) {
+    result = file_status(file_type::character_file);
+    return std::error_code();
+  }
+
+  if (std::error_code ec = widenPath(path8, path_utf16))
+    return ec;
+
+  DWORD attr = ::GetFileAttributesW(path_utf16.begin());
+  if (attr == INVALID_FILE_ATTRIBUTES)
+    return getStatus(INVALID_HANDLE_VALUE, result);
+
+  DWORD Flags = FILE_FLAG_BACKUP_SEMANTICS;
+  // Handle reparse points.
+  if (!Follow && (attr & FILE_ATTRIBUTE_REPARSE_POINT))
+    Flags |= FILE_FLAG_OPEN_REPARSE_POINT;
+
+  ScopedFileHandle h(
+      ::CreateFileW(path_utf16.begin(), 0, // Attributes only.
+                    FILE_SHARE_DELETE | FILE_SHARE_READ | FILE_SHARE_WRITE,
+                    NULL, OPEN_EXISTING, Flags, 0));
+  if (!h)
+    return getStatus(INVALID_HANDLE_VALUE, result);
+
+  return getStatus(h, result);
+}
+
+std::error_code status(int FD, file_status &Result) {
+  HANDLE FileHandle = reinterpret_cast<HANDLE>(_get_osfhandle(FD));
+  return getStatus(FileHandle, Result);
+}
+
+static basic_file_status status_from_find_data(WIN32_FIND_DATAW *FindData) {
+  return basic_file_status(file_type_from_attrs(FindData->dwFileAttributes),
+                           perms_from_attrs(FindData->dwFileAttributes),
+                           FindData->ftLastAccessTime.dwHighDateTime,
+                           FindData->ftLastAccessTime.dwLowDateTime,
+                           FindData->ftLastWriteTime.dwHighDateTime,
+                           FindData->ftLastWriteTime.dwLowDateTime,
+                           FindData->nFileSizeHigh, FindData->nFileSizeLow);
+}
+
+std::error_code detail::directory_iterator_construct(detail::DirIterState &it,
+                                                     StringRef path,
+                                                     bool follow_symlinks) {
+  SmallVector<wchar_t, 128> path_utf16;
+
+  if (std::error_code ec = widenPath(path, path_utf16))
+    return ec;
+
+  // Convert path to the format that Windows is happy with.
+  if (path_utf16.size() > 0 &&
+      !is_separator(path_utf16[path.size() - 1]) &&
+      path_utf16[path.size() - 1] != L':') {
+    path_utf16.push_back(L'\\');
+    path_utf16.push_back(L'*');
+  } else {
+    path_utf16.push_back(L'*');
+  }
+
+  //  Get the first directory entry.
+  WIN32_FIND_DATAW FirstFind;
+  ScopedFindHandle FindHandle(::FindFirstFileExW(
+      c_str(path_utf16), FindExInfoBasic, &FirstFind, FindExSearchNameMatch,
+      NULL, FIND_FIRST_EX_LARGE_FETCH));
+  if (!FindHandle)
+    return mapWindowsError(::GetLastError());
+
+  size_t FilenameLen = ::wcslen(FirstFind.cFileName);
+  while ((FilenameLen == 1 && FirstFind.cFileName[0] == L'.') ||
+         (FilenameLen == 2 && FirstFind.cFileName[0] == L'.' &&
+                              FirstFind.cFileName[1] == L'.'))
+    if (!::FindNextFileW(FindHandle, &FirstFind)) {
+      DWORD LastError = ::GetLastError();
+      // Check for end.
+      if (LastError == ERROR_NO_MORE_FILES)
+        return detail::directory_iterator_destruct(it);
+      return mapWindowsError(LastError);
+    } else
+      FilenameLen = ::wcslen(FirstFind.cFileName);
+
+  // Construct the current directory entry.
+  SmallString<128> directory_entry_name_utf8;
+  if (std::error_code ec =
+          UTF16ToUTF8(FirstFind.cFileName, ::wcslen(FirstFind.cFileName),
+                      directory_entry_name_utf8))
+    return ec;
+
+  it.IterationHandle = intptr_t(FindHandle.take());
+  SmallString<128> directory_entry_path(path);
+  path::append(directory_entry_path, directory_entry_name_utf8);
+  it.CurrentEntry = directory_entry(directory_entry_path, follow_symlinks,
+                                    status_from_find_data(&FirstFind));
+
+  return std::error_code();
+}
+
+std::error_code detail::directory_iterator_destruct(detail::DirIterState &it) {
+  if (it.IterationHandle != 0)
+    // Closes the handle if it's valid.
+    ScopedFindHandle close(HANDLE(it.IterationHandle));
+  it.IterationHandle = 0;
+  it.CurrentEntry = directory_entry();
+  return std::error_code();
+}
+
+std::error_code detail::directory_iterator_increment(detail::DirIterState &it) {
+  WIN32_FIND_DATAW FindData;
+  if (!::FindNextFileW(HANDLE(it.IterationHandle), &FindData)) {
+    DWORD LastError = ::GetLastError();
+    // Check for end.
+    if (LastError == ERROR_NO_MORE_FILES)
+      return detail::directory_iterator_destruct(it);
+    return mapWindowsError(LastError);
+  }
+
+  size_t FilenameLen = ::wcslen(FindData.cFileName);
+  if ((FilenameLen == 1 && FindData.cFileName[0] == L'.') ||
+      (FilenameLen == 2 && FindData.cFileName[0] == L'.' &&
+                           FindData.cFileName[1] == L'.'))
+    return directory_iterator_increment(it);
+
+  SmallString<128> directory_entry_path_utf8;
+  if (std::error_code ec =
+          UTF16ToUTF8(FindData.cFileName, ::wcslen(FindData.cFileName),
+                      directory_entry_path_utf8))
+    return ec;
+
+  it.CurrentEntry.replace_filename(Twine(directory_entry_path_utf8),
+                                   status_from_find_data(&FindData));
+  return std::error_code();
+}
+
+ErrorOr<basic_file_status> directory_entry::status() const {
+  return Status;
+}
+
+std::error_code openFileForRead(const Twine &Name, int &ResultFD,
+                                SmallVectorImpl<char> *RealPath) {
+  ResultFD = -1;
+  SmallVector<wchar_t, 128> PathUTF16;
+
+  if (std::error_code EC = widenPath(Name, PathUTF16))
+    return EC;
+
+  HANDLE H =
+      ::CreateFileW(PathUTF16.begin(), GENERIC_READ,
+                    FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                    NULL, OPEN_EXISTING, FILE_ATTRIBUTE_NORMAL, NULL);
+  if (H == INVALID_HANDLE_VALUE) {
+    DWORD LastError = ::GetLastError();
+    std::error_code EC = mapWindowsError(LastError);
+    // Provide a better error message when trying to open directories.
+    // This only runs if we failed to open the file, so there is probably
+    // no performances issues.
+    if (LastError != ERROR_ACCESS_DENIED)
+      return EC;
+    if (is_directory(Name))
+      return std::make_error_code(std::errc::is_a_directory);
+    return EC;
+  }
+
+  ResultFD = ::_open_osfhandle(intptr_t(H), 0);
+  if (ResultFD == -1) {
+    ::CloseHandle(H);
+    return mapWindowsError(ERROR_INVALID_HANDLE);
+  }
+
+  // Fetch the real name of the file, if the user asked
+  if (RealPath) {
+    RealPath->clear();
+    wchar_t RealPathUTF16[MAX_PATH];
+    DWORD CountChars =
+      ::GetFinalPathNameByHandleW(H, RealPathUTF16, MAX_PATH,
+                                  FILE_NAME_NORMALIZED);
+    if (CountChars > 0 && CountChars < MAX_PATH) {
+      // Convert the result from UTF-16 to UTF-8.
+      SmallString<MAX_PATH> RealPathUTF8;
+      if (!UTF16ToUTF8(RealPathUTF16, CountChars, RealPathUTF8))
+        RealPath->append(RealPathUTF8.data(),
+                         RealPathUTF8.data() + strlen(RealPathUTF8.data()));
+    }
+  }
+
+  return std::error_code();
+}
+
+std::error_code openFileForWrite(const Twine &Name, int &ResultFD,
+                                 OpenFlags Flags, unsigned Mode) {
+  // Verify that we don't have both "append" and "excl".
+  assert((!(Flags & F_Excl) || !(Flags & F_Append)) &&
+         "Cannot specify both 'excl' and 'append' file creation flags!");
+
+  ResultFD = -1;
+  SmallVector<wchar_t, 128> PathUTF16;
+
+  if (std::error_code EC = widenPath(Name, PathUTF16))
+    return EC;
+
+  DWORD CreationDisposition;
+  if (Flags & F_Excl)
+    CreationDisposition = CREATE_NEW;
+  else if ((Flags & F_Append) || (Flags & F_NoTrunc))
+    CreationDisposition = OPEN_ALWAYS;
+  else
+    CreationDisposition = CREATE_ALWAYS;
+
+  DWORD Access = GENERIC_WRITE;
+  DWORD Attributes = FILE_ATTRIBUTE_NORMAL;
+  if (Flags & F_RW)
+    Access |= GENERIC_READ;
+  if (Flags & F_Delete) {
+    Access |= DELETE;
+    Attributes |= FILE_FLAG_DELETE_ON_CLOSE;
+  }
+
+  HANDLE H =
+      ::CreateFileW(PathUTF16.data(), Access,
+                    FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                    NULL, CreationDisposition, Attributes, NULL);
+
+  if (H == INVALID_HANDLE_VALUE) {
+    DWORD LastError = ::GetLastError();
+    std::error_code EC = mapWindowsError(LastError);
+    // Provide a better error message when trying to open directories.
+    // This only runs if we failed to open the file, so there is probably
+    // no performances issues.
+    if (LastError != ERROR_ACCESS_DENIED)
+      return EC;
+    if (is_directory(Name))
+      return std::make_error_code(std::errc::is_a_directory);
+    return EC;
+  }
+
+  int OpenFlags = 0;
+  if (Flags & F_Append)
+    OpenFlags |= _O_APPEND;
+
+  if (Flags & F_Text)
+    OpenFlags |= _O_TEXT;
+
+  ResultFD = ::_open_osfhandle(intptr_t(H), OpenFlags);
+  if (ResultFD == -1) {
+    ::CloseHandle(H);
+    return mapWindowsError(ERROR_INVALID_HANDLE);
+  }
+
+  return std::error_code();
+}
+
+} // end namespace fs
+
+namespace path {
+static bool getKnownFolderPath(KNOWNFOLDERID folderId,
+                               SmallVectorImpl<char> &result) {
+  wchar_t *path = nullptr;
+  if (::SHGetKnownFolderPath(folderId, KF_FLAG_CREATE, nullptr, &path) != S_OK)
+    return false;
+
+  bool ok = !UTF16ToUTF8(path, ::wcslen(path), result);
+  ::CoTaskMemFree(path);
+  return ok;
+}
+
+bool getUserCacheDir(SmallVectorImpl<char> &Result) {
+  return getKnownFolderPath(FOLDERID_LocalAppData, Result);
+}
+
+bool home_directory(SmallVectorImpl<char> &result) {
+  return getKnownFolderPath(FOLDERID_Profile, result);
+}
+
+static bool getTempDirEnvVar(const wchar_t *Var, SmallVectorImpl<char> &Res) {
+  SmallVector<wchar_t, 1024> Buf;
+  size_t Size = 1024;
+  do {
+    Buf.reserve(Size);
+    Size = GetEnvironmentVariableW(Var, Buf.data(), Buf.capacity());
+    if (Size == 0)
+      return false;
+
+    // Try again with larger buffer.
+  } while (Size > Buf.capacity());
+  Buf.set_size(Size);
+
+  return !windows::UTF16ToUTF8(Buf.data(), Size, Res);
+}
+
+static bool getTempDirEnvVar(SmallVectorImpl<char> &Res) {
+  const wchar_t *EnvironmentVariables[] = {L"TMP", L"TEMP", L"USERPROFILE"};
+  for (auto *Env : EnvironmentVariables) {
+    if (getTempDirEnvVar(Env, Res))
+      return true;
+  }
+  return false;
+}
+
+void system_temp_directory(bool ErasedOnReboot, SmallVectorImpl<char> &Result) {
+  (void)ErasedOnReboot;
+  Result.clear();
+
+  // Check whether the temporary directory is specified by an environment var.
+  // This matches GetTempPath logic to some degree. GetTempPath is not used
+  // directly as it cannot handle evn var longer than 130 chars on Windows 7
+  // (fixed on Windows 8).
+  if (getTempDirEnvVar(Result)) {
+    assert(!Result.empty() && "Unexpected empty path");
+    native(Result); // Some Unix-like shells use Unix path separator in $TMP.
+    fs::make_absolute(Result); // Make it absolute if not already.
+    return;
+  }
+
+  // Fall back to a system default.
+  const char *DefaultResult = "C:\\Temp";
+  Result.append(DefaultResult, DefaultResult + strlen(DefaultResult));
+}
+} // end namespace path
+
+namespace windows {
+std::error_code CodePageToUTF16(unsigned codepage,
+                                wpi::StringRef original,
+                                wpi::SmallVectorImpl<wchar_t> &utf16) {
+  if (!original.empty()) {
+    int len = ::MultiByteToWideChar(codepage, MB_ERR_INVALID_CHARS, original.begin(),
+                                    original.size(), utf16.begin(), 0);
+
+    if (len == 0) {
+      return mapWindowsError(::GetLastError());
+    }
+
+    utf16.reserve(len + 1);
+    utf16.set_size(len);
+
+    len = ::MultiByteToWideChar(codepage, MB_ERR_INVALID_CHARS, original.begin(),
+                                original.size(), utf16.begin(), utf16.size());
+
+    if (len == 0) {
+      return mapWindowsError(::GetLastError());
+    }
+  }
+
+  // Make utf16 null terminated.
+  utf16.push_back(0);
+  utf16.pop_back();
+
+  return std::error_code();
+}
+
+std::error_code UTF8ToUTF16(wpi::StringRef utf8,
+                            wpi::SmallVectorImpl<wchar_t> &utf16) {
+  return CodePageToUTF16(CP_UTF8, utf8, utf16);
+}
+
+std::error_code CurCPToUTF16(wpi::StringRef curcp,
+                            wpi::SmallVectorImpl<wchar_t> &utf16) {
+  return CodePageToUTF16(CP_ACP, curcp, utf16);
+}
+
+static
+std::error_code UTF16ToCodePage(unsigned codepage, const wchar_t *utf16,
+                                size_t utf16_len,
+                                wpi::SmallVectorImpl<char> &converted) {
+  if (utf16_len) {
+    // Get length.
+    int len = ::WideCharToMultiByte(codepage, 0, utf16, utf16_len, converted.begin(),
+                                    0, NULL, NULL);
+
+    if (len == 0) {
+      return mapWindowsError(::GetLastError());
+    }
+
+    converted.reserve(len);
+    converted.set_size(len);
+
+    // Now do the actual conversion.
+    len = ::WideCharToMultiByte(codepage, 0, utf16, utf16_len, converted.data(),
+                                converted.size(), NULL, NULL);
+
+    if (len == 0) {
+      return mapWindowsError(::GetLastError());
+    }
+  }
+
+  // Make the new string null terminated.
+  converted.push_back(0);
+  converted.pop_back();
+
+  return std::error_code();
+}
+
+std::error_code UTF16ToUTF8(const wchar_t *utf16, size_t utf16_len,
+                            wpi::SmallVectorImpl<char> &utf8) {
+  return UTF16ToCodePage(CP_UTF8, utf16, utf16_len, utf8);
+}
+
+std::error_code UTF16ToCurCP(const wchar_t *utf16, size_t utf16_len,
+                             wpi::SmallVectorImpl<char> &curcp) {
+  return UTF16ToCodePage(CP_ACP, utf16, utf16_len, curcp);
+}
+
+} // end namespace windows
+} // end namespace sys
+} // end namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Windows/WindowsSupport.h b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Windows/WindowsSupport.h
new file mode 100644
index 0000000..2f78a4e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/Windows/WindowsSupport.h
@@ -0,0 +1,213 @@
+//===- WindowsSupport.h - Common Windows Include File -----------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines things specific to Windows implementations.  In addition to
+// providing some helpers for working with win32 APIs, this header wraps
+// <windows.h> with some portability macros.  Always include WindowsSupport.h
+// instead of including <windows.h> directly.
+//
+//===----------------------------------------------------------------------===//
+
+//===----------------------------------------------------------------------===//
+//=== WARNING: Implementation here must contain only generic Win32 code that
+//===          is guaranteed to work on *all* Win32 variants.
+//===----------------------------------------------------------------------===//
+
+#ifndef LLVM_SUPPORT_WINDOWSSUPPORT_H
+#define LLVM_SUPPORT_WINDOWSSUPPORT_H
+
+// mingw-w64 tends to define it as 0x0502 in its headers.
+#undef _WIN32_WINNT
+#undef _WIN32_IE
+
+// Require at least Windows 7 API.
+#define _WIN32_WINNT 0x0601
+#define _WIN32_IE    0x0800 // MinGW at it again. FIXME: verify if still needed.
+#define WIN32_LEAN_AND_MEAN
+#ifndef NOMINMAX
+#define NOMINMAX
+#endif
+
+#include "wpi/SmallVector.h"
+#include "wpi/StringExtras.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+#include "wpi/Compiler.h"
+#include <cassert>
+#include <string>
+#include <system_error>
+#include <windows.h>
+
+/// Determines if the program is running on Windows 8 or newer. This
+/// reimplements one of the helpers in the Windows 8.1 SDK, which are intended
+/// to supercede raw calls to GetVersionEx. Old SDKs, Cygwin, and MinGW don't
+/// yet have VersionHelpers.h, so we have our own helper.
+inline bool RunningWindows8OrGreater() {
+  // Windows 8 is version 6.2, service pack 0.
+  OSVERSIONINFOEXW osvi = {};
+  osvi.dwOSVersionInfoSize = sizeof(OSVERSIONINFO);
+  osvi.dwMajorVersion = 6;
+  osvi.dwMinorVersion = 2;
+  osvi.wServicePackMajor = 0;
+
+  DWORDLONG Mask = 0;
+  Mask = VerSetConditionMask(Mask, VER_MAJORVERSION, VER_GREATER_EQUAL);
+  Mask = VerSetConditionMask(Mask, VER_MINORVERSION, VER_GREATER_EQUAL);
+  Mask = VerSetConditionMask(Mask, VER_SERVICEPACKMAJOR, VER_GREATER_EQUAL);
+
+  return VerifyVersionInfoW(&osvi, VER_MAJORVERSION | VER_MINORVERSION |
+                                       VER_SERVICEPACKMAJOR,
+                            Mask) != FALSE;
+}
+
+inline bool MakeErrMsg(std::string *ErrMsg, const std::string &prefix) {
+  if (!ErrMsg)
+    return true;
+  char *buffer = NULL;
+  DWORD LastError = GetLastError();
+  DWORD R = FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER |
+                               FORMAT_MESSAGE_FROM_SYSTEM |
+                               FORMAT_MESSAGE_MAX_WIDTH_MASK,
+                           NULL, LastError, 0, (LPSTR)&buffer, 1, NULL);
+  if (R)
+    *ErrMsg = prefix + ": " + buffer;
+  else
+    *ErrMsg = prefix + ": Unknown error";
+  *ErrMsg += " (0x" + wpi::utohexstr(LastError) + ")";
+
+  LocalFree(buffer);
+  return R != 0;
+}
+
+template <typename HandleTraits>
+class ScopedHandle {
+  typedef typename HandleTraits::handle_type handle_type;
+  handle_type Handle;
+
+  ScopedHandle(const ScopedHandle &other); // = delete;
+  void operator=(const ScopedHandle &other); // = delete;
+public:
+  ScopedHandle()
+    : Handle(HandleTraits::GetInvalid()) {}
+
+  explicit ScopedHandle(handle_type h)
+    : Handle(h) {}
+
+  ~ScopedHandle() {
+    if (HandleTraits::IsValid(Handle))
+      HandleTraits::Close(Handle);
+  }
+
+  handle_type take() {
+    handle_type t = Handle;
+    Handle = HandleTraits::GetInvalid();
+    return t;
+  }
+
+  ScopedHandle &operator=(handle_type h) {
+    if (HandleTraits::IsValid(Handle))
+      HandleTraits::Close(Handle);
+    Handle = h;
+    return *this;
+  }
+
+  // True if Handle is valid.
+  explicit operator bool() const {
+    return HandleTraits::IsValid(Handle) ? true : false;
+  }
+
+  operator handle_type() const {
+    return Handle;
+  }
+};
+
+struct CommonHandleTraits {
+  typedef HANDLE handle_type;
+
+  static handle_type GetInvalid() {
+    return INVALID_HANDLE_VALUE;
+  }
+
+  static void Close(handle_type h) {
+    ::CloseHandle(h);
+  }
+
+  static bool IsValid(handle_type h) {
+    return h != GetInvalid();
+  }
+};
+
+struct JobHandleTraits : CommonHandleTraits {
+  static handle_type GetInvalid() {
+    return NULL;
+  }
+};
+
+struct RegTraits : CommonHandleTraits {
+  typedef HKEY handle_type;
+
+  static handle_type GetInvalid() {
+    return NULL;
+  }
+
+  static void Close(handle_type h) {
+    ::RegCloseKey(h);
+  }
+
+  static bool IsValid(handle_type h) {
+    return h != GetInvalid();
+  }
+};
+
+struct FindHandleTraits : CommonHandleTraits {
+  static void Close(handle_type h) {
+    ::FindClose(h);
+  }
+};
+
+struct FileHandleTraits : CommonHandleTraits {};
+
+typedef ScopedHandle<CommonHandleTraits> ScopedCommonHandle;
+typedef ScopedHandle<FileHandleTraits>   ScopedFileHandle;
+typedef ScopedHandle<RegTraits>          ScopedRegHandle;
+typedef ScopedHandle<FindHandleTraits>   ScopedFindHandle;
+typedef ScopedHandle<JobHandleTraits>    ScopedJobHandle;
+
+namespace wpi {
+template <class T>
+class SmallVectorImpl;
+
+template <class T>
+typename SmallVectorImpl<T>::const_pointer
+c_str(SmallVectorImpl<T> &str) {
+  str.push_back(0);
+  str.pop_back();
+  return str.data();
+}
+
+namespace sys {
+namespace path {
+std::error_code widenPath(const Twine &Path8,
+                          SmallVectorImpl<wchar_t> &Path16);
+} // end namespace path
+
+namespace windows {
+std::error_code UTF8ToUTF16(StringRef utf8, SmallVectorImpl<wchar_t> &utf16);
+/// Convert to UTF16 from the current code page used in the system
+std::error_code CurCPToUTF16(StringRef utf8, SmallVectorImpl<wchar_t> &utf16);
+std::error_code UTF16ToUTF8(const wchar_t *utf16, size_t utf16_len,
+                            SmallVectorImpl<char> &utf8);
+/// Convert from UTF16 to the current code page used in the system
+std::error_code UTF16ToCurCP(const wchar_t *utf16, size_t utf16_len,
+                             SmallVectorImpl<char> &utf8);
+} // end namespace windows
+} // end namespace sys
+} // end namespace wpi.
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/raw_os_ostream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/raw_os_ostream.cpp
new file mode 100644
index 0000000..1fb6c51
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/raw_os_ostream.cpp
@@ -0,0 +1,30 @@
+//===--- raw_os_ostream.cpp - Implement the raw_os_ostream class ----------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This implements support adapting raw_ostream to std::ostream.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/raw_os_ostream.h"
+#include <ostream>
+using namespace wpi;
+
+//===----------------------------------------------------------------------===//
+//  raw_os_ostream
+//===----------------------------------------------------------------------===//
+
+raw_os_ostream::~raw_os_ostream() {
+  flush();
+}
+
+void raw_os_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.write(Ptr, Size);
+}
+
+uint64_t raw_os_ostream::current_pos() const { return OS.tellp(); }
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/raw_ostream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/raw_ostream.cpp
new file mode 100644
index 0000000..04bae65
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/llvm/raw_ostream.cpp
@@ -0,0 +1,793 @@
+//===--- raw_ostream.cpp - Implement the raw_ostream classes --------------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This implements support for bulk buffered stream output.
+//
+//===----------------------------------------------------------------------===//
+
+#include "wpi/raw_ostream.h"
+#include "wpi/STLExtras.h"
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringExtras.h"
+#include "wpi/Compiler.h"
+#include "wpi/FileSystem.h"
+#include "wpi/Format.h"
+#include "wpi/MathExtras.h"
+#include "wpi/NativeFormatting.h"
+#include "wpi/WindowsError.h"
+#include <algorithm>
+#include <cctype>
+#include <cerrno>
+#include <cstdio>
+#include <iterator>
+#include <sys/stat.h>
+#include <system_error>
+
+// <fcntl.h> may provide O_BINARY.
+#include <fcntl.h>
+
+#ifndef _WIN32
+#include <unistd.h>
+#include <sys/uio.h>
+#endif
+
+#if defined(__CYGWIN__)
+#include <io.h>
+#endif
+
+#if defined(_MSC_VER)
+#include <io.h>
+#ifndef STDIN_FILENO
+# define STDIN_FILENO 0
+#endif
+#ifndef STDOUT_FILENO
+# define STDOUT_FILENO 1
+#endif
+#ifndef STDERR_FILENO
+# define STDERR_FILENO 2
+#endif
+#endif
+
+#ifdef _WIN32
+#include "Windows/WindowsSupport.h"
+#endif
+
+using namespace wpi;
+
+raw_ostream::~raw_ostream() {
+  // raw_ostream's subclasses should take care to flush the buffer
+  // in their destructors.
+  assert(OutBufCur == OutBufStart &&
+         "raw_ostream destructor called with non-empty buffer!");
+
+  if (BufferMode == InternalBuffer)
+    delete [] OutBufStart;
+}
+
+// An out of line virtual method to provide a home for the class vtable.
+void raw_ostream::handle() {}
+
+size_t raw_ostream::preferred_buffer_size() const {
+  // BUFSIZ is intended to be a reasonable default.
+  return BUFSIZ;
+}
+
+void raw_ostream::SetBuffered() {
+  // Ask the subclass to determine an appropriate buffer size.
+  if (size_t Size = preferred_buffer_size())
+    SetBufferSize(Size);
+  else
+    // It may return 0, meaning this stream should be unbuffered.
+    SetUnbuffered();
+}
+
+void raw_ostream::SetBufferAndMode(char *BufferStart, size_t Size,
+                                   BufferKind Mode) {
+  assert(((Mode == Unbuffered && !BufferStart && Size == 0) ||
+          (Mode != Unbuffered && BufferStart && Size != 0)) &&
+         "stream must be unbuffered or have at least one byte");
+  // Make sure the current buffer is free of content (we can't flush here; the
+  // child buffer management logic will be in write_impl).
+  assert(GetNumBytesInBuffer() == 0 && "Current buffer is non-empty!");
+
+  if (BufferMode == InternalBuffer)
+    delete [] OutBufStart;
+  OutBufStart = BufferStart;
+  OutBufEnd = OutBufStart+Size;
+  OutBufCur = OutBufStart;
+  BufferMode = Mode;
+
+  assert(OutBufStart <= OutBufEnd && "Invalid size!");
+}
+
+raw_ostream &raw_ostream::operator<<(unsigned long N) {
+  write_integer(*this, static_cast<uint64_t>(N), 0, IntegerStyle::Integer);
+  return *this;
+}
+
+raw_ostream &raw_ostream::operator<<(long N) {
+  write_integer(*this, static_cast<int64_t>(N), 0, IntegerStyle::Integer);
+  return *this;
+}
+
+raw_ostream &raw_ostream::operator<<(unsigned long long N) {
+  write_integer(*this, static_cast<uint64_t>(N), 0, IntegerStyle::Integer);
+  return *this;
+}
+
+raw_ostream &raw_ostream::operator<<(long long N) {
+  write_integer(*this, static_cast<int64_t>(N), 0, IntegerStyle::Integer);
+  return *this;
+}
+
+raw_ostream &raw_ostream::write_hex(unsigned long long N) {
+  wpi::write_hex(*this, N, HexPrintStyle::Lower);
+  return *this;
+}
+
+raw_ostream &raw_ostream::write_escaped(StringRef Str,
+                                        bool UseHexEscapes) {
+  for (unsigned char c : Str) {
+    switch (c) {
+    case '\\':
+      *this << '\\' << '\\';
+      break;
+    case '\t':
+      *this << '\\' << 't';
+      break;
+    case '\n':
+      *this << '\\' << 'n';
+      break;
+    case '"':
+      *this << '\\' << '"';
+      break;
+    default:
+      if (std::isprint(c)) {
+        *this << c;
+        break;
+      }
+
+      // Write out the escaped representation.
+      if (UseHexEscapes) {
+        *this << '\\' << 'x';
+        *this << hexdigit((c >> 4 & 0xF));
+        *this << hexdigit((c >> 0) & 0xF);
+      } else {
+        // Always use a full 3-character octal escape.
+        *this << '\\';
+        *this << char('0' + ((c >> 6) & 7));
+        *this << char('0' + ((c >> 3) & 7));
+        *this << char('0' + ((c >> 0) & 7));
+      }
+    }
+  }
+
+  return *this;
+}
+
+raw_ostream &raw_ostream::operator<<(const void *P) {
+  wpi::write_hex(*this, (uintptr_t)P, HexPrintStyle::PrefixLower);
+  return *this;
+}
+
+raw_ostream &raw_ostream::operator<<(double N) {
+  wpi::write_double(*this, N, FloatStyle::Exponent);
+  return *this;
+}
+
+void raw_ostream::flush_nonempty() {
+  assert(OutBufCur > OutBufStart && "Invalid call to flush_nonempty.");
+  size_t Length = OutBufCur - OutBufStart;
+  OutBufCur = OutBufStart;
+  write_impl(OutBufStart, Length);
+}
+
+raw_ostream &raw_ostream::write(unsigned char C) {
+  // Group exceptional cases into a single branch.
+  if (LLVM_UNLIKELY(OutBufCur >= OutBufEnd)) {
+    if (LLVM_UNLIKELY(!OutBufStart)) {
+      if (BufferMode == Unbuffered) {
+        write_impl(reinterpret_cast<char*>(&C), 1);
+        return *this;
+      }
+      // Set up a buffer and start over.
+      SetBuffered();
+      return write(C);
+    }
+
+    flush_nonempty();
+  }
+
+  *OutBufCur++ = C;
+  return *this;
+}
+
+raw_ostream &raw_ostream::write(const char *Ptr, size_t Size) {
+  // Group exceptional cases into a single branch.
+  if (LLVM_UNLIKELY(size_t(OutBufEnd - OutBufCur) < Size)) {
+    if (LLVM_UNLIKELY(!OutBufStart)) {
+      if (BufferMode == Unbuffered) {
+        write_impl(Ptr, Size);
+        return *this;
+      }
+      // Set up a buffer and start over.
+      SetBuffered();
+      return write(Ptr, Size);
+    }
+
+    size_t NumBytes = OutBufEnd - OutBufCur;
+
+    // If the buffer is empty at this point we have a string that is larger
+    // than the buffer. Directly write the chunk that is a multiple of the
+    // preferred buffer size and put the remainder in the buffer.
+    if (LLVM_UNLIKELY(OutBufCur == OutBufStart)) {
+      assert(NumBytes != 0 && "undefined behavior");
+      size_t BytesToWrite = Size - (Size % NumBytes);
+      write_impl(Ptr, BytesToWrite);
+      size_t BytesRemaining = Size - BytesToWrite;
+      if (BytesRemaining > size_t(OutBufEnd - OutBufCur)) {
+        // Too much left over to copy into our buffer.
+        return write(Ptr + BytesToWrite, BytesRemaining);
+      }
+      copy_to_buffer(Ptr + BytesToWrite, BytesRemaining);
+      return *this;
+    }
+
+    // We don't have enough space in the buffer to fit the string in. Insert as
+    // much as possible, flush and start over with the remainder.
+    copy_to_buffer(Ptr, NumBytes);
+    flush_nonempty();
+    return write(Ptr + NumBytes, Size - NumBytes);
+  }
+
+  copy_to_buffer(Ptr, Size);
+
+  return *this;
+}
+
+void raw_ostream::copy_to_buffer(const char *Ptr, size_t Size) {
+  assert(Size <= size_t(OutBufEnd - OutBufCur) && "Buffer overrun!");
+
+  // Handle short strings specially, memcpy isn't very good at very short
+  // strings.
+  switch (Size) {
+  case 4: OutBufCur[3] = Ptr[3]; LLVM_FALLTHROUGH;
+  case 3: OutBufCur[2] = Ptr[2]; LLVM_FALLTHROUGH;
+  case 2: OutBufCur[1] = Ptr[1]; LLVM_FALLTHROUGH;
+  case 1: OutBufCur[0] = Ptr[0]; LLVM_FALLTHROUGH;
+  case 0: break;
+  default:
+    memcpy(OutBufCur, Ptr, Size);
+    break;
+  }
+
+  OutBufCur += Size;
+}
+
+// Formatted output.
+raw_ostream &raw_ostream::operator<<(const format_object_base &Fmt) {
+  // If we have more than a few bytes left in our output buffer, try
+  // formatting directly onto its end.
+  size_t NextBufferSize = 127;
+  size_t BufferBytesLeft = OutBufEnd - OutBufCur;
+  if (BufferBytesLeft > 3) {
+    size_t BytesUsed = Fmt.print(OutBufCur, BufferBytesLeft);
+
+    // Common case is that we have plenty of space.
+    if (BytesUsed <= BufferBytesLeft) {
+      OutBufCur += BytesUsed;
+      return *this;
+    }
+
+    // Otherwise, we overflowed and the return value tells us the size to try
+    // again with.
+    NextBufferSize = BytesUsed;
+  }
+
+  // If we got here, we didn't have enough space in the output buffer for the
+  // string.  Try printing into a SmallVector that is resized to have enough
+  // space.  Iterate until we win.
+  SmallVector<char, 128> V;
+
+  while (true) {
+    V.resize(NextBufferSize);
+
+    // Try formatting into the SmallVector.
+    size_t BytesUsed = Fmt.print(V.data(), NextBufferSize);
+
+    // If BytesUsed fit into the vector, we win.
+    if (BytesUsed <= NextBufferSize)
+      return write(V.data(), BytesUsed);
+
+    // Otherwise, try again with a new size.
+    assert(BytesUsed > NextBufferSize && "Didn't grow buffer!?");
+    NextBufferSize = BytesUsed;
+  }
+}
+
+raw_ostream &raw_ostream::operator<<(const FormattedString &FS) {
+  if (FS.Str.size() >= FS.Width || FS.Justify == FormattedString::JustifyNone) {
+    this->operator<<(FS.Str);
+    return *this;
+  }
+  const size_t Difference = FS.Width - FS.Str.size();
+  switch (FS.Justify) {
+  case FormattedString::JustifyLeft:
+    this->operator<<(FS.Str);
+    this->indent(Difference);
+    break;
+  case FormattedString::JustifyRight:
+    this->indent(Difference);
+    this->operator<<(FS.Str);
+    break;
+  case FormattedString::JustifyCenter: {
+    int PadAmount = Difference / 2;
+    this->indent(PadAmount);
+    this->operator<<(FS.Str);
+    this->indent(Difference - PadAmount);
+    break;
+  }
+  default:
+    assert(false && "Bad Justification");
+  }
+  return *this;
+}
+
+raw_ostream &raw_ostream::operator<<(const FormattedNumber &FN) {
+  if (FN.Hex) {
+    HexPrintStyle Style;
+    if (FN.Upper && FN.HexPrefix)
+      Style = HexPrintStyle::PrefixUpper;
+    else if (FN.Upper && !FN.HexPrefix)
+      Style = HexPrintStyle::Upper;
+    else if (!FN.Upper && FN.HexPrefix)
+      Style = HexPrintStyle::PrefixLower;
+    else
+      Style = HexPrintStyle::Lower;
+    wpi::write_hex(*this, FN.HexValue, Style, FN.Width);
+  } else {
+    wpi::SmallString<16> Buffer;
+    wpi::raw_svector_ostream Stream(Buffer);
+    wpi::write_integer(Stream, FN.DecValue, 0, IntegerStyle::Integer);
+    if (Buffer.size() < FN.Width)
+      indent(FN.Width - Buffer.size());
+    (*this) << Buffer;
+  }
+  return *this;
+}
+
+raw_ostream &raw_ostream::operator<<(const FormattedBytes &FB) {
+  if (FB.Bytes.empty())
+    return *this;
+
+  size_t LineIndex = 0;
+  auto Bytes = FB.Bytes;
+  const size_t Size = Bytes.size();
+  HexPrintStyle HPS = FB.Upper ? HexPrintStyle::Upper : HexPrintStyle::Lower;
+  uint64_t OffsetWidth = 0;
+  if (FB.FirstByteOffset.has_value()) {
+    // Figure out how many nibbles are needed to print the largest offset
+    // represented by this data set, so that we can align the offset field
+    // to the right width.
+    size_t Lines = Size / FB.NumPerLine;
+    uint64_t MaxOffset = *FB.FirstByteOffset + Lines * FB.NumPerLine;
+    unsigned Power = 0;
+    if (MaxOffset > 0)
+      Power = wpi::Log2_64_Ceil(MaxOffset);
+    OffsetWidth = std::max<uint64_t>(4, wpi::alignTo(Power, 4) / 4);
+  }
+
+  // The width of a block of data including all spaces for group separators.
+  unsigned NumByteGroups =
+      alignTo(FB.NumPerLine, FB.ByteGroupSize) / FB.ByteGroupSize;
+  unsigned BlockCharWidth = FB.NumPerLine * 2 + NumByteGroups - 1;
+
+  while (!Bytes.empty()) {
+    indent(FB.IndentLevel);
+
+    if (FB.FirstByteOffset.has_value()) {
+      uint64_t Offset = FB.FirstByteOffset.value();
+      wpi::write_hex(*this, Offset + LineIndex, HPS, OffsetWidth);
+      *this << ": ";
+    }
+
+    auto Line = Bytes.take_front(FB.NumPerLine);
+
+    size_t CharsPrinted = 0;
+    // Print the hex bytes for this line in groups
+    for (size_t I = 0; I < Line.size(); ++I, CharsPrinted += 2) {
+      if (I && (I % FB.ByteGroupSize) == 0) {
+        ++CharsPrinted;
+        *this << " ";
+      }
+      wpi::write_hex(*this, Line[I], HPS, 2);
+    }
+
+    if (FB.ASCII) {
+      // Print any spaces needed for any bytes that we didn't print on this
+      // line so that the ASCII bytes are correctly aligned.
+      assert(BlockCharWidth >= CharsPrinted);
+      indent(BlockCharWidth - CharsPrinted + 2);
+      *this << "|";
+
+      // Print the ASCII char values for each byte on this line
+      for (uint8_t Byte : Line) {
+        if (isprint(Byte))
+          *this << static_cast<char>(Byte);
+        else
+          *this << '.';
+      }
+      *this << '|';
+    }
+
+    Bytes = Bytes.drop_front(Line.size());
+    LineIndex += Line.size();
+    if (LineIndex < Size)
+      *this << '\n';
+  }
+  return *this;
+}
+
+template <char C>
+static raw_ostream &write_padding(raw_ostream &OS, unsigned NumChars) {
+  static const char Chars[] = {C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
+                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
+                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
+                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C,
+                               C, C, C, C, C, C, C, C, C, C, C, C, C, C, C, C};
+
+  // Usually the indentation is small, handle it with a fastpath.
+  if (NumChars < array_lengthof(Chars))
+    return OS.write(Chars, NumChars);
+
+  while (NumChars) {
+    unsigned NumToWrite = std::min(NumChars,
+                                   (unsigned)array_lengthof(Chars)-1);
+    OS.write(Chars, NumToWrite);
+    NumChars -= NumToWrite;
+  }
+  return OS;
+}
+
+/// indent - Insert 'NumSpaces' spaces.
+raw_ostream &raw_ostream::indent(unsigned NumSpaces) {
+  return write_padding<' '>(*this, NumSpaces);
+}
+
+/// write_zeros - Insert 'NumZeros' nulls.
+raw_ostream &raw_ostream::write_zeros(unsigned NumZeros) {
+  return write_padding<'\0'>(*this, NumZeros);
+}
+
+void raw_ostream::anchor() {}
+
+//===----------------------------------------------------------------------===//
+//  Formatted Output
+//===----------------------------------------------------------------------===//
+
+// Out of line virtual method.
+void format_object_base::home() {
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_fd_ostream
+//===----------------------------------------------------------------------===//
+
+static int getFD(StringRef Filename, std::error_code &EC,
+                 sys::fs::OpenFlags Flags) {
+  // Handle "-" as stdout. Note that when we do this, we consider ourself
+  // the owner of stdout and may set the "binary" flag globally based on Flags.
+  if (Filename == "-") {
+    EC = std::error_code();
+    // If user requested binary then put stdout into binary mode if
+    // possible.
+    if (!(Flags & sys::fs::F_Text)) {
+#if defined(_WIN32)
+      _setmode(_fileno(stdout), _O_BINARY);
+#endif
+    }
+    return STDOUT_FILENO;
+  }
+
+  int FD;
+  EC = sys::fs::openFileForWrite(Filename, FD, Flags);
+  if (EC)
+    return -1;
+
+  return FD;
+}
+
+raw_fd_ostream::raw_fd_ostream(StringRef Filename, std::error_code &EC,
+                               sys::fs::OpenFlags Flags)
+    : raw_fd_ostream(getFD(Filename, EC, Flags), true) {}
+
+/// FD is the file descriptor that this writes to.  If ShouldClose is true, this
+/// closes the file when the stream is destroyed.
+raw_fd_ostream::raw_fd_ostream(int fd, bool shouldClose, bool unbuffered)
+    : raw_pwrite_stream(unbuffered), FD(fd), ShouldClose(shouldClose) {
+  if (FD < 0 ) {
+    ShouldClose = false;
+    return;
+  }
+
+  // Do not attempt to close stdout or stderr. We used to try to maintain the
+  // property that tools that support writing file to stdout should not also
+  // write informational output to stdout, but in practice we were never able to
+  // maintain this invariant. Many features have been added to LLVM and clang
+  // (-fdump-record-layouts, optimization remarks, etc) that print to stdout, so
+  // users must simply be aware that mixed output and remarks is a possibility.
+  if (FD <= STDERR_FILENO)
+    ShouldClose = false;
+
+  // Get the starting position.
+  off_t loc = ::lseek(FD, 0, SEEK_CUR);
+#ifdef _WIN32
+  // MSVCRT's _lseek(SEEK_CUR) doesn't return -1 for pipes.
+  SupportsSeeking = loc != (off_t)-1 && ::GetFileType(reinterpret_cast<HANDLE>(::_get_osfhandle(FD))) != FILE_TYPE_PIPE;
+#else
+  SupportsSeeking = loc != (off_t)-1;
+#endif
+  if (!SupportsSeeking)
+    pos = 0;
+  else
+    pos = static_cast<uint64_t>(loc);
+}
+
+raw_fd_ostream::~raw_fd_ostream() {
+  if (FD >= 0) {
+    flush();
+    if (ShouldClose && ::close(FD) < 0)
+      error_detected(std::error_code(errno, std::generic_category()));
+  }
+
+#ifdef __MINGW32__
+  // On mingw, global dtors should not call exit().
+  // report_fatal_error() invokes exit(). We know report_fatal_error()
+  // might not write messages to stderr when any errors were detected
+  // on FD == 2.
+  if (FD == 2) return;
+#endif
+}
+
+void raw_fd_ostream::write_impl(const char *Ptr, size_t Size) {
+  assert(FD >= 0 && "File already closed.");
+  pos += Size;
+
+  // The maximum write size is limited to SSIZE_MAX because a write
+  // greater than SSIZE_MAX is implementation-defined in POSIX.
+  // Since SSIZE_MAX is not portable, we use SIZE_MAX >> 1 instead.
+  size_t MaxWriteSize = SIZE_MAX >> 1;
+
+#if defined(__linux__)
+  // It is observed that Linux returns EINVAL for a very large write (>2G).
+  // Make it a reasonably small value.
+  MaxWriteSize = 1024 * 1024 * 1024;
+#elif defined(_WIN32)
+  // Writing a large size of output to Windows console returns ENOMEM. It seems
+  // that, prior to Windows 8, WriteFile() is redirecting to WriteConsole(), and
+  // the latter has a size limit (66000 bytes or less, depending on heap usage).
+  if (::_isatty(FD) && !RunningWindows8OrGreater())
+    MaxWriteSize = 32767;
+#endif
+
+  do {
+    size_t ChunkSize = std::min(Size, MaxWriteSize);
+#ifdef _WIN32
+    int ret = ::_write(FD, Ptr, ChunkSize);
+#else
+    ssize_t ret = ::write(FD, Ptr, ChunkSize);
+#endif
+
+    if (ret < 0) {
+      // If it's a recoverable error, swallow it and retry the write.
+      //
+      // Ideally we wouldn't ever see EAGAIN or EWOULDBLOCK here, since
+      // raw_ostream isn't designed to do non-blocking I/O. However, some
+      // programs, such as old versions of bjam, have mistakenly used
+      // O_NONBLOCK. For compatibility, emulate blocking semantics by
+      // spinning until the write succeeds. If you don't want spinning,
+      // don't use O_NONBLOCK file descriptors with raw_ostream.
+      if (errno == EINTR || errno == EAGAIN
+#ifdef EWOULDBLOCK
+          || errno == EWOULDBLOCK
+#endif
+          )
+        continue;
+
+      // Otherwise it's a non-recoverable error. Note it and quit.
+      error_detected(std::error_code(errno, std::generic_category()));
+      break;
+    }
+
+    // The write may have written some or all of the data. Update the
+    // size and buffer pointer to reflect the remainder that needs
+    // to be written. If there are no bytes left, we're done.
+    Ptr += ret;
+    Size -= ret;
+  } while (Size > 0);
+}
+
+void raw_fd_ostream::close() {
+  assert(ShouldClose);
+  ShouldClose = false;
+  flush();
+  if (::close(FD) < 0)
+    error_detected(std::error_code(errno, std::generic_category()));
+  FD = -1;
+}
+
+uint64_t raw_fd_ostream::seek(uint64_t off) {
+  assert(SupportsSeeking && "Stream does not support seeking!");
+  flush();
+#ifdef _WIN32
+  pos = ::_lseeki64(FD, off, SEEK_SET);
+#else
+  pos = ::lseek(FD, off, SEEK_SET);
+#endif
+  if (pos == (uint64_t)-1)
+    error_detected(std::error_code(errno, std::generic_category()));
+  return pos;
+}
+
+void raw_fd_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                 uint64_t Offset) {
+  uint64_t Pos = tell();
+  seek(Offset);
+  write(Ptr, Size);
+  seek(Pos);
+}
+
+size_t raw_fd_ostream::preferred_buffer_size() const {
+#if !defined(_MSC_VER) && !defined(__MINGW32__) && !defined(__minix)
+  // Windows and Minix have no st_blksize.
+  assert(FD >= 0 && "File not yet open!");
+  struct stat statbuf;
+  if (fstat(FD, &statbuf) != 0)
+    return 0;
+
+  // If this is a terminal, don't use buffering. Line buffering
+  // would be a more traditional thing to do, but it's not worth
+  // the complexity.
+  if (S_ISCHR(statbuf.st_mode) && isatty(FD))
+    return 0;
+  // Return the preferred block size.
+  return statbuf.st_blksize;
+#else
+  return raw_ostream::preferred_buffer_size();
+#endif
+}
+
+void raw_fd_ostream::anchor() {}
+
+//===----------------------------------------------------------------------===//
+//  outs(), errs(), nulls()
+//===----------------------------------------------------------------------===//
+
+/// outs() - This returns a reference to a raw_ostream for standard output.
+/// Use it like: outs() << "foo" << "bar";
+raw_ostream &wpi::outs() {
+  // Set buffer settings to model stdout behavior.
+  std::error_code EC;
+  static raw_fd_ostream* S = new raw_fd_ostream("-", EC, sys::fs::F_None);
+  assert(!EC);
+  return *S;
+}
+
+/// errs() - This returns a reference to a raw_ostream for standard error.
+/// Use it like: errs() << "foo" << "bar";
+raw_ostream &wpi::errs() {
+  // Set standard error to be unbuffered by default.
+  static raw_fd_ostream* S = new raw_fd_ostream(STDERR_FILENO, false, true);
+  return *S;
+}
+
+/// nulls() - This returns a reference to a raw_ostream which discards output.
+raw_ostream &wpi::nulls() {
+  static raw_null_ostream* S = new raw_null_ostream;
+  return *S;
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_string_ostream
+//===----------------------------------------------------------------------===//
+
+raw_string_ostream::~raw_string_ostream() {
+  flush();
+}
+
+void raw_string_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.append(Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_svector_ostream
+//===----------------------------------------------------------------------===//
+
+uint64_t raw_svector_ostream::current_pos() const { return OS.size(); }
+
+void raw_svector_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.append(Ptr, Ptr + Size);
+}
+
+void raw_svector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                      uint64_t Offset) {
+  memcpy(OS.data() + Offset, Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_vector_ostream
+//===----------------------------------------------------------------------===//
+
+uint64_t raw_vector_ostream::current_pos() const { return OS.size(); }
+
+void raw_vector_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.insert(OS.end(), Ptr, Ptr + Size);
+}
+
+void raw_vector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                     uint64_t Offset) {
+  memcpy(OS.data() + Offset, Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_usvector_ostream
+//===----------------------------------------------------------------------===//
+
+uint64_t raw_usvector_ostream::current_pos() const { return OS.size(); }
+
+void raw_usvector_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.append(reinterpret_cast<const uint8_t *>(Ptr),
+            reinterpret_cast<const uint8_t *>(Ptr) + Size);
+}
+
+void raw_usvector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                       uint64_t Offset) {
+  memcpy(OS.data() + Offset, Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_uvector_ostream
+//===----------------------------------------------------------------------===//
+
+uint64_t raw_uvector_ostream::current_pos() const { return OS.size(); }
+
+void raw_uvector_ostream::write_impl(const char *Ptr, size_t Size) {
+  OS.insert(OS.end(), reinterpret_cast<const uint8_t *>(Ptr),
+            reinterpret_cast<const uint8_t *>(Ptr) + Size);
+}
+
+void raw_uvector_ostream::pwrite_impl(const char *Ptr, size_t Size,
+                                      uint64_t Offset) {
+  memcpy(OS.data() + Offset, Ptr, Size);
+}
+
+//===----------------------------------------------------------------------===//
+//  raw_null_ostream
+//===----------------------------------------------------------------------===//
+
+raw_null_ostream::~raw_null_ostream() {
+#ifndef NDEBUG
+  // ~raw_ostream asserts that the buffer is empty. This isn't necessary
+  // with raw_null_ostream, but it's better to have raw_null_ostream follow
+  // the rules than to change the rules just for raw_null_ostream.
+  flush();
+#endif
+}
+
+void raw_null_ostream::write_impl(const char * /*Ptr*/, size_t /*Size*/) {}
+
+uint64_t raw_null_ostream::current_pos() const {
+  return 0;
+}
+
+void raw_null_ostream::pwrite_impl(const char * /*Ptr*/, size_t /*Size*/,
+                                   uint64_t /*Offset*/) {}
+
+void raw_pwrite_stream::anchor() {}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/memory.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/memory.cpp
new file mode 100644
index 0000000..54e55c9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/memory.cpp
@@ -0,0 +1,43 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/memory.h"
+
+#include <exception>
+
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+void* CheckedCalloc(size_t num, size_t size) {
+  void* p = std::calloc(num, size);
+  if (!p) {
+    errs() << "FATAL: failed to allocate " << (num * size) << " bytes\n";
+    std::terminate();
+  }
+  return p;
+}
+
+void* CheckedMalloc(size_t size) {
+  void* p = std::malloc(size == 0 ? 1 : size);
+  if (!p) {
+    errs() << "FATAL: failed to allocate " << size << " bytes\n";
+    std::terminate();
+  }
+  return p;
+}
+
+void* CheckedRealloc(void* ptr, size_t size) {
+  void* p = std::realloc(ptr, size == 0 ? 1 : size);
+  if (!p) {
+    errs() << "FATAL: failed to allocate " << size << " bytes\n";
+    std::terminate();
+  }
+  return p;
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_istream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_istream.cpp
new file mode 100644
index 0000000..bdfb2bb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_istream.cpp
@@ -0,0 +1,138 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "wpi/raw_istream.h"
+
+#ifdef _WIN32
+#include <io.h>
+#else
+#include <unistd.h>
+#endif
+
+#include <cstdlib>
+#include <cstring>
+
+#include "wpi/FileSystem.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+
+#if defined(_MSC_VER)
+#ifndef STDIN_FILENO
+#define STDIN_FILENO 0
+#endif
+#ifndef STDOUT_FILENO
+#define STDOUT_FILENO 1
+#endif
+#ifndef STDERR_FILENO
+#define STDERR_FILENO 2
+#endif
+#endif
+
+using namespace wpi;
+
+StringRef raw_istream::getline(SmallVectorImpl<char>& buf, int maxLen) {
+  buf.clear();
+  for (int i = 0; i < maxLen; ++i) {
+    char c;
+    read(c);
+    if (has_error()) return StringRef{buf.data(), buf.size()};
+    if (c == '\r') continue;
+    buf.push_back(c);
+    if (c == '\n') break;
+  }
+  return StringRef{buf.data(), buf.size()};
+}
+
+void raw_mem_istream::close() {}
+
+size_t raw_mem_istream::in_avail() const { return m_left; }
+
+void raw_mem_istream::read_impl(void* data, size_t len) {
+  if (len > m_left) {
+    error_detected();
+    len = m_left;
+  }
+  std::memcpy(data, m_cur, len);
+  m_cur += len;
+  m_left -= len;
+  set_read_count(len);
+}
+
+static int getFD(const Twine& Filename, std::error_code& EC) {
+  // Handle "-" as stdin. Note that when we do this, we consider ourself
+  // the owner of stdin. This means that we can do things like close the
+  // file descriptor when we're done and set the "binary" flag globally.
+  if (Filename.isSingleStringRef() && Filename.getSingleStringRef() == "-") {
+    EC = std::error_code();
+    return STDIN_FILENO;
+  }
+
+  int FD;
+
+  EC = sys::fs::openFileForRead(Filename, FD);
+  if (EC) return -1;
+
+  EC = std::error_code();
+  return FD;
+}
+
+raw_fd_istream::raw_fd_istream(const Twine& filename, std::error_code& ec,
+                               size_t bufSize)
+    : raw_fd_istream(getFD(filename, ec), true, bufSize) {}
+
+raw_fd_istream::raw_fd_istream(int fd, bool shouldClose, size_t bufSize)
+    : m_bufSize(bufSize), m_fd(fd), m_shouldClose(shouldClose) {
+  m_cur = m_end = m_buf = static_cast<char*>(std::malloc(bufSize));
+}
+
+raw_fd_istream::~raw_fd_istream() {
+  if (m_shouldClose) close();
+  std::free(m_buf);
+}
+
+void raw_fd_istream::close() {
+  if (m_fd >= 0) {
+    ::close(m_fd);
+    m_fd = -1;
+  }
+}
+
+size_t raw_fd_istream::in_avail() const { return m_end - m_cur; }
+
+void raw_fd_istream::read_impl(void* data, size_t len) {
+  char* cdata = static_cast<char*>(data);
+  size_t pos = 0;
+  while (static_cast<size_t>(m_end - m_cur) < len) {
+    // not enough data
+    if (m_cur == m_end) {
+#ifdef _WIN32
+      int count = ::_read(m_fd, m_buf, m_bufSize);
+#else
+      ssize_t count = ::read(m_fd, m_buf, m_bufSize);
+#endif
+      if (count <= 0) {
+        error_detected();
+        set_read_count(pos);
+        return;
+      }
+      m_cur = m_buf;
+      m_end = m_buf + count;
+      continue;
+    }
+
+    size_t left = m_end - m_cur;
+    std::memcpy(&cdata[pos], m_cur, left);
+    m_cur += left;
+    pos += left;
+    len -= left;
+  }
+
+  std::memcpy(&cdata[pos], m_cur, len);
+  m_cur += len;
+  pos += len;
+  set_read_count(pos);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_socket_istream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_socket_istream.cpp
new file mode 100644
index 0000000..68c4dd6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_socket_istream.cpp
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "wpi/raw_socket_istream.h"
+
+#include "wpi/NetworkStream.h"
+
+using namespace wpi;
+
+void raw_socket_istream::read_impl(void* data, size_t len) {
+  char* cdata = static_cast<char*>(data);
+  size_t pos = 0;
+
+  while (pos < len) {
+    NetworkStream::Error err;
+    size_t count = m_stream.receive(&cdata[pos], len - pos, &err, m_timeout);
+    if (count == 0) {
+      error_detected();
+      break;
+    }
+    pos += count;
+  }
+  set_read_count(pos);
+}
+
+void raw_socket_istream::close() { m_stream.close(); }
+
+size_t raw_socket_istream::in_avail() const { return 0; }
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_socket_ostream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_socket_ostream.cpp
new file mode 100644
index 0000000..fb8d94d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_socket_ostream.cpp
@@ -0,0 +1,39 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "wpi/raw_socket_ostream.h"
+
+#include "wpi/NetworkStream.h"
+
+using namespace wpi;
+
+raw_socket_ostream::~raw_socket_ostream() {
+  flush();
+  if (m_shouldClose) close();
+}
+
+void raw_socket_ostream::write_impl(const char* data, size_t len) {
+  size_t pos = 0;
+
+  while (pos < len) {
+    NetworkStream::Error err;
+    size_t count = m_stream.send(&data[pos], len - pos, &err);
+    if (count == 0) {
+      error_detected();
+      return;
+    }
+    pos += count;
+  }
+}
+
+uint64_t raw_socket_ostream::current_pos() const { return 0; }
+
+void raw_socket_ostream::close() {
+  if (!m_shouldClose) return;
+  flush();
+  m_stream.close();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_uv_ostream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_uv_ostream.cpp
new file mode 100644
index 0000000..317de41
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/raw_uv_ostream.cpp
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/raw_uv_ostream.h"
+
+#include <cstring>
+
+using namespace wpi;
+
+void raw_uv_ostream::write_impl(const char* data, size_t len) {
+  while (len > 0) {
+    // allocate additional buffers as required
+    if (m_left == 0) {
+      m_bufs.emplace_back(m_alloc());
+      // we want bufs() to always be valid, so set len=0 and keep track of the
+      // amount of space remaining separately
+      m_left = m_bufs.back().len;
+      m_bufs.back().len = 0;
+      assert(m_left != 0);
+    }
+
+    size_t amt = std::min(m_left, len);
+    auto& buf = m_bufs.back();
+    std::memcpy(buf.base + buf.len, data, amt);
+    data += amt;
+    len -= amt;
+    buf.len += amt;
+    m_left -= amt;
+  }
+}
+
+uint64_t raw_uv_ostream::current_pos() const {
+  uint64_t size = 0;
+  for (auto&& buf : m_bufs) size += buf.len;
+  return size;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/sha1.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/sha1.cpp
new file mode 100644
index 0000000..e1346f4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/sha1.cpp
@@ -0,0 +1,316 @@
+/*
+    sha1.cpp - source code of
+
+    ============
+    SHA-1 in C++
+    ============
+
+    100% Public Domain.
+
+    Original C Code
+        -- Steve Reid <steve@edmweb.com>
+    Small changes to fit into bglibs
+        -- Bruce Guenter <bruce@untroubled.org>
+    Translation to simpler C++ Code
+        -- Volker Grabsch <vog@notjusthosting.com>
+    Safety fixes
+        -- Eugene Hopkinson <slowriot at voxelstorm dot com>
+*/
+
+#include "wpi/sha1.h"
+
+#include "wpi/SmallVector.h"
+#include "wpi/StringExtras.h"
+#include "wpi/raw_istream.h"
+#include "wpi/raw_ostream.h"
+
+using namespace wpi;
+
+static const size_t BLOCK_INTS =
+    16; /* number of 32bit integers per SHA1 block */
+static const size_t BLOCK_BYTES = BLOCK_INTS * 4;
+
+static void reset(uint32_t digest[], size_t& buf_size, uint64_t& transforms) {
+  /* SHA1 initialization constants */
+  digest[0] = 0x67452301;
+  digest[1] = 0xefcdab89;
+  digest[2] = 0x98badcfe;
+  digest[3] = 0x10325476;
+  digest[4] = 0xc3d2e1f0;
+
+  /* Reset counters */
+  buf_size = 0;
+  transforms = 0;
+}
+
+static uint32_t rol(const uint32_t value, const size_t bits) {
+  return (value << bits) | (value >> (32 - bits));
+}
+
+static uint32_t blk(const uint32_t block[BLOCK_INTS], const size_t i) {
+  return rol(block[(i + 13) & 15] ^ block[(i + 8) & 15] ^ block[(i + 2) & 15] ^
+                 block[i],
+             1);
+}
+
+/*
+ * (R0+R1), R2, R3, R4 are the different operations used in SHA1
+ */
+
+static void R0(const uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t& w,
+               const uint32_t x, const uint32_t y, uint32_t& z,
+               const size_t i) {
+  z += ((w & (x ^ y)) ^ y) + block[i] + 0x5a827999 + rol(v, 5);
+  w = rol(w, 30);
+}
+
+static void R1(uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t& w,
+               const uint32_t x, const uint32_t y, uint32_t& z,
+               const size_t i) {
+  block[i] = blk(block, i);
+  z += ((w & (x ^ y)) ^ y) + block[i] + 0x5a827999 + rol(v, 5);
+  w = rol(w, 30);
+}
+
+static void R2(uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t& w,
+               const uint32_t x, const uint32_t y, uint32_t& z,
+               const size_t i) {
+  block[i] = blk(block, i);
+  z += (w ^ x ^ y) + block[i] + 0x6ed9eba1 + rol(v, 5);
+  w = rol(w, 30);
+}
+
+static void R3(uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t& w,
+               const uint32_t x, const uint32_t y, uint32_t& z,
+               const size_t i) {
+  block[i] = blk(block, i);
+  z += (((w | x) & y) | (w & x)) + block[i] + 0x8f1bbcdc + rol(v, 5);
+  w = rol(w, 30);
+}
+
+static void R4(uint32_t block[BLOCK_INTS], const uint32_t v, uint32_t& w,
+               const uint32_t x, const uint32_t y, uint32_t& z,
+               const size_t i) {
+  block[i] = blk(block, i);
+  z += (w ^ x ^ y) + block[i] + 0xca62c1d6 + rol(v, 5);
+  w = rol(w, 30);
+}
+
+/*
+ * Hash a single 512-bit block. This is the core of the algorithm.
+ */
+
+static void do_transform(uint32_t digest[], uint32_t block[BLOCK_INTS],
+                         uint64_t& transforms) {
+  /* Copy digest[] to working vars */
+  uint32_t a = digest[0];
+  uint32_t b = digest[1];
+  uint32_t c = digest[2];
+  uint32_t d = digest[3];
+  uint32_t e = digest[4];
+
+  /* 4 rounds of 20 operations each. Loop unrolled. */
+  R0(block, a, b, c, d, e, 0);
+  R0(block, e, a, b, c, d, 1);
+  R0(block, d, e, a, b, c, 2);
+  R0(block, c, d, e, a, b, 3);
+  R0(block, b, c, d, e, a, 4);
+  R0(block, a, b, c, d, e, 5);
+  R0(block, e, a, b, c, d, 6);
+  R0(block, d, e, a, b, c, 7);
+  R0(block, c, d, e, a, b, 8);
+  R0(block, b, c, d, e, a, 9);
+  R0(block, a, b, c, d, e, 10);
+  R0(block, e, a, b, c, d, 11);
+  R0(block, d, e, a, b, c, 12);
+  R0(block, c, d, e, a, b, 13);
+  R0(block, b, c, d, e, a, 14);
+  R0(block, a, b, c, d, e, 15);
+  R1(block, e, a, b, c, d, 0);
+  R1(block, d, e, a, b, c, 1);
+  R1(block, c, d, e, a, b, 2);
+  R1(block, b, c, d, e, a, 3);
+  R2(block, a, b, c, d, e, 4);
+  R2(block, e, a, b, c, d, 5);
+  R2(block, d, e, a, b, c, 6);
+  R2(block, c, d, e, a, b, 7);
+  R2(block, b, c, d, e, a, 8);
+  R2(block, a, b, c, d, e, 9);
+  R2(block, e, a, b, c, d, 10);
+  R2(block, d, e, a, b, c, 11);
+  R2(block, c, d, e, a, b, 12);
+  R2(block, b, c, d, e, a, 13);
+  R2(block, a, b, c, d, e, 14);
+  R2(block, e, a, b, c, d, 15);
+  R2(block, d, e, a, b, c, 0);
+  R2(block, c, d, e, a, b, 1);
+  R2(block, b, c, d, e, a, 2);
+  R2(block, a, b, c, d, e, 3);
+  R2(block, e, a, b, c, d, 4);
+  R2(block, d, e, a, b, c, 5);
+  R2(block, c, d, e, a, b, 6);
+  R2(block, b, c, d, e, a, 7);
+  R3(block, a, b, c, d, e, 8);
+  R3(block, e, a, b, c, d, 9);
+  R3(block, d, e, a, b, c, 10);
+  R3(block, c, d, e, a, b, 11);
+  R3(block, b, c, d, e, a, 12);
+  R3(block, a, b, c, d, e, 13);
+  R3(block, e, a, b, c, d, 14);
+  R3(block, d, e, a, b, c, 15);
+  R3(block, c, d, e, a, b, 0);
+  R3(block, b, c, d, e, a, 1);
+  R3(block, a, b, c, d, e, 2);
+  R3(block, e, a, b, c, d, 3);
+  R3(block, d, e, a, b, c, 4);
+  R3(block, c, d, e, a, b, 5);
+  R3(block, b, c, d, e, a, 6);
+  R3(block, a, b, c, d, e, 7);
+  R3(block, e, a, b, c, d, 8);
+  R3(block, d, e, a, b, c, 9);
+  R3(block, c, d, e, a, b, 10);
+  R3(block, b, c, d, e, a, 11);
+  R4(block, a, b, c, d, e, 12);
+  R4(block, e, a, b, c, d, 13);
+  R4(block, d, e, a, b, c, 14);
+  R4(block, c, d, e, a, b, 15);
+  R4(block, b, c, d, e, a, 0);
+  R4(block, a, b, c, d, e, 1);
+  R4(block, e, a, b, c, d, 2);
+  R4(block, d, e, a, b, c, 3);
+  R4(block, c, d, e, a, b, 4);
+  R4(block, b, c, d, e, a, 5);
+  R4(block, a, b, c, d, e, 6);
+  R4(block, e, a, b, c, d, 7);
+  R4(block, d, e, a, b, c, 8);
+  R4(block, c, d, e, a, b, 9);
+  R4(block, b, c, d, e, a, 10);
+  R4(block, a, b, c, d, e, 11);
+  R4(block, e, a, b, c, d, 12);
+  R4(block, d, e, a, b, c, 13);
+  R4(block, c, d, e, a, b, 14);
+  R4(block, b, c, d, e, a, 15);
+
+  /* Add the working vars back into digest[] */
+  digest[0] += a;
+  digest[1] += b;
+  digest[2] += c;
+  digest[3] += d;
+  digest[4] += e;
+
+  /* Count the number of transformations */
+  transforms++;
+}
+
+static void buffer_to_block(const unsigned char* buffer,
+                            uint32_t block[BLOCK_INTS]) {
+  /* Convert the std::string (byte buffer) to a uint32_t array (MSB) */
+  for (size_t i = 0; i < BLOCK_INTS; i++) {
+    block[i] = (buffer[4 * i + 3] & 0xff) | (buffer[4 * i + 2] & 0xff) << 8 |
+               (buffer[4 * i + 1] & 0xff) << 16 |
+               (buffer[4 * i + 0] & 0xff) << 24;
+  }
+}
+
+SHA1::SHA1() { reset(digest, buf_size, transforms); }
+
+void SHA1::Update(StringRef s) {
+  raw_mem_istream is(makeArrayRef(s.data(), s.size()));
+  Update(is);
+}
+
+void SHA1::Update(raw_istream& is) {
+  while (true) {
+    buf_size += is.readsome(&buffer[buf_size], BLOCK_BYTES - buf_size);
+    if (buf_size != BLOCK_BYTES) {
+      return;
+    }
+    uint32_t block[BLOCK_INTS];
+    buffer_to_block(buffer, block);
+    do_transform(digest, block, transforms);
+    buf_size = 0;
+  }
+}
+
+/*
+ * Add padding and return the message digest.
+ */
+
+static void finalize(uint32_t digest[], unsigned char* buffer, size_t& buf_size,
+                     uint64_t& transforms, raw_ostream& os, bool hex) {
+  /* Total number of hashed bits */
+  uint64_t total_bits = (transforms * BLOCK_BYTES + buf_size) * 8;
+
+  /* Padding */
+  buffer[buf_size++] = 0x80;
+  for (size_t i = buf_size; i < BLOCK_BYTES; ++i) {
+    buffer[i] = 0x00;
+  }
+
+  uint32_t block[BLOCK_INTS];
+  buffer_to_block(buffer, block);
+
+  if (buf_size > BLOCK_BYTES - 8) {
+    do_transform(digest, block, transforms);
+    for (size_t i = 0; i < BLOCK_INTS - 2; i++) {
+      block[i] = 0;
+    }
+  }
+
+  /* Append total_bits, split this uint64_t into two uint32_t */
+  block[BLOCK_INTS - 1] = total_bits;
+  block[BLOCK_INTS - 2] = (total_bits >> 32);
+  do_transform(digest, block, transforms);
+
+  /* Hex string */
+  static const char* const LUT = "0123456789abcdef";
+  for (size_t i = 0; i < 5; i++) {
+    uint32_t v = digest[i];
+    if (hex) {
+      os << LUT[(v >> 28) & 0xf] << LUT[(v >> 24) & 0xf] << LUT[(v >> 20) & 0xf]
+         << LUT[(v >> 16) & 0xf] << LUT[(v >> 12) & 0xf] << LUT[(v >> 8) & 0xf]
+         << LUT[(v >> 4) & 0xf] << LUT[(v >> 0) & 0xf];
+    } else {
+      os.write(static_cast<unsigned char>((v >> 24) & 0xff));
+      os.write(static_cast<unsigned char>((v >> 16) & 0xff));
+      os.write(static_cast<unsigned char>((v >> 8) & 0xff));
+      os.write(static_cast<unsigned char>((v >> 0) & 0xff));
+    }
+  }
+
+  /* Reset for next run */
+  reset(digest, buf_size, transforms);
+}
+
+std::string SHA1::Final() {
+  std::string out;
+  raw_string_ostream os(out);
+
+  finalize(digest, buffer, buf_size, transforms, os, true);
+
+  return os.str();
+}
+
+StringRef SHA1::Final(SmallVectorImpl<char>& buf) {
+  raw_svector_ostream os(buf);
+
+  finalize(digest, buffer, buf_size, transforms, os, true);
+
+  return os.str();
+}
+
+StringRef SHA1::RawFinal(SmallVectorImpl<char>& buf) {
+  raw_svector_ostream os(buf);
+
+  finalize(digest, buffer, buf_size, transforms, os, false);
+
+  return os.str();
+}
+
+std::string SHA1::FromFile(StringRef filename) {
+  std::error_code ec;
+  raw_fd_istream stream(filename, ec);
+  SHA1 checksum;
+  checksum.Update(stream);
+  return checksum.Final();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/timestamp.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/timestamp.cpp
new file mode 100644
index 0000000..7f3b0cf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/timestamp.cpp
@@ -0,0 +1,108 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "wpi/timestamp.h"
+
+#include <atomic>
+
+#ifdef _WIN32
+#include <windows.h>
+
+#include <cassert>
+#include <exception>
+#else
+#include <chrono>
+#endif
+
+// offset in microseconds
+static uint64_t zerotime() {
+#ifdef _WIN32
+  FILETIME ft;
+  uint64_t tmpres = 0;
+  // 100-nanosecond intervals since January 1, 1601 (UTC)
+  // which means 0.1 us
+  GetSystemTimeAsFileTime(&ft);
+  tmpres |= ft.dwHighDateTime;
+  tmpres <<= 32;
+  tmpres |= ft.dwLowDateTime;
+  tmpres /= 10u;  // convert to us
+  // January 1st, 1970 - January 1st, 1601 UTC ~ 369 years
+  // or 11644473600000000 us
+  static const uint64_t deltaepoch = 11644473600000000ull;
+  tmpres -= deltaepoch;
+  return tmpres;
+#else
+  // 1-us intervals
+  return std::chrono::duration_cast<std::chrono::microseconds>(
+             std::chrono::high_resolution_clock::now().time_since_epoch())
+      .count();
+#endif
+}
+
+static uint64_t timestamp() {
+#ifdef _WIN32
+  LARGE_INTEGER li;
+  QueryPerformanceCounter(&li);
+  // there is an imprecision with the initial value,
+  // but what matters is that timestamps are monotonic and consistent
+  return static_cast<uint64_t>(li.QuadPart);
+#else
+  // 1-us intervals
+  return std::chrono::duration_cast<std::chrono::microseconds>(
+             std::chrono::steady_clock::now().time_since_epoch())
+      .count();
+#endif
+}
+
+#ifdef _WIN32
+static uint64_t update_frequency() {
+  LARGE_INTEGER li;
+  if (!QueryPerformanceFrequency(&li) || !li.QuadPart) {
+    // log something
+    std::terminate();
+  }
+  return static_cast<uint64_t>(li.QuadPart);
+}
+#endif
+
+static const uint64_t zerotime_val = zerotime();
+static const uint64_t offset_val = timestamp();
+#ifdef _WIN32
+static const uint64_t frequency_val = update_frequency();
+#endif
+
+uint64_t wpi::NowDefault() {
+#ifdef _WIN32
+  assert(offset_val > 0u);
+  assert(frequency_val > 0u);
+  uint64_t delta = timestamp() - offset_val;
+  // because the frequency is in update per seconds, we have to multiply the
+  // delta by 1,000,000
+  uint64_t delta_in_us = delta * 1000000ull / frequency_val;
+  return delta_in_us + zerotime_val;
+#else
+  return zerotime_val + timestamp() - offset_val;
+#endif
+}
+
+static std::atomic<uint64_t (*)()> now_impl{wpi::NowDefault};
+
+void wpi::SetNowImpl(uint64_t (*func)(void)) {
+  now_impl = func ? func : NowDefault;
+}
+
+uint64_t wpi::Now() { return (now_impl.load())(); }
+
+extern "C" {
+
+uint64_t WPI_NowDefault(void) { return wpi::NowDefault(); }
+
+void WPI_SetNowImpl(uint64_t (*func)(void)) { wpi::SetNowImpl(func); }
+
+uint64_t WPI_Now(void) { return wpi::Now(); }
+
+}  // extern "C"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Async.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Async.cpp
new file mode 100644
index 0000000..5479f49
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Async.cpp
@@ -0,0 +1,37 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Async.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+Async<>::~Async() noexcept {
+  if (auto loop = m_loop.lock())
+    Close();
+  else
+    ForceClosed();
+}
+
+std::shared_ptr<Async<>> Async<>::Create(const std::shared_ptr<Loop>& loop) {
+  auto h = std::make_shared<Async>(loop, private_init{});
+  int err = uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
+    Async& h = *static_cast<Async*>(handle->data);
+    h.wakeup();
+  });
+  if (err < 0) {
+    loop->ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Check.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Check.cpp
new file mode 100644
index 0000000..0f4cccf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Check.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Check.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Check> Check::Create(Loop& loop) {
+  auto h = std::make_shared<Check>(private_init{});
+  int err = uv_check_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Check::Start() {
+  Invoke(&uv_check_start, GetRaw(), [](uv_check_t* handle) {
+    Check& h = *static_cast<Check*>(handle->data);
+    h.check();
+  });
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/FsEvent.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/FsEvent.cpp
new file mode 100644
index 0000000..54ba31f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/FsEvent.cpp
@@ -0,0 +1,67 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/FsEvent.h"
+
+#include <cstdlib>
+
+#include "wpi/SmallString.h"
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<FsEvent> FsEvent::Create(Loop& loop) {
+  auto h = std::make_shared<FsEvent>(private_init{});
+  int err = uv_fs_event_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void FsEvent::Start(const Twine& path, unsigned int flags) {
+  SmallString<128> pathBuf;
+  Invoke(
+      &uv_fs_event_start, GetRaw(),
+      [](uv_fs_event_t* handle, const char* filename, int events, int status) {
+        FsEvent& h = *static_cast<FsEvent*>(handle->data);
+        if (status < 0)
+          h.ReportError(status);
+        else
+          h.fsEvent(filename, events);
+      },
+      path.toNullTerminatedStringRef(pathBuf).data(), flags);
+}
+
+std::string FsEvent::GetPath() {
+  // Per the libuv docs, GetPath() always gives us a null-terminated string.
+  // common case should be small
+  char buf[128];
+  size_t size = 128;
+  int r = uv_fs_event_getpath(GetRaw(), buf, &size);
+  if (r == 0) {
+    return buf;
+  } else if (r == UV_ENOBUFS) {
+    // need to allocate a big enough buffer
+    char* buf2 = static_cast<char*>(std::malloc(size));
+    r = uv_fs_event_getpath(GetRaw(), buf2, &size);
+    if (r == 0) {
+      std::string out{buf2};
+      std::free(buf2);
+      return out;
+    }
+    std::free(buf2);
+  }
+  ReportError(r);
+  return std::string{};
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/GetAddrInfo.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/GetAddrInfo.cpp
new file mode 100644
index 0000000..21f6404
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/GetAddrInfo.cpp
@@ -0,0 +1,55 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/GetAddrInfo.h"
+
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/util.h"
+
+namespace wpi {
+namespace uv {
+
+GetAddrInfoReq::GetAddrInfoReq() {
+  error = [this](Error err) { GetLoop().error(err); };
+}
+
+void GetAddrInfo(Loop& loop, const std::shared_ptr<GetAddrInfoReq>& req,
+                 const Twine& node, const Twine& service,
+                 const addrinfo* hints) {
+  SmallVector<char, 128> nodeStr;
+  SmallVector<char, 128> serviceStr;
+  int err = uv_getaddrinfo(
+      loop.GetRaw(), req->GetRaw(),
+      [](uv_getaddrinfo_t* req, int status, addrinfo* res) {
+        auto& h = *static_cast<GetAddrInfoReq*>(req->data);
+        if (status < 0)
+          h.ReportError(status);
+        else
+          h.resolved(*res);
+        uv_freeaddrinfo(res);
+        h.Release();  // this is always a one-shot
+      },
+      node.isNull() ? nullptr : node.toNullTerminatedStringRef(nodeStr).data(),
+      service.isNull() ? nullptr
+                       : service.toNullTerminatedStringRef(serviceStr).data(),
+      hints);
+  if (err < 0)
+    loop.ReportError(err);
+  else
+    req->Keep();
+}
+
+void GetAddrInfo(Loop& loop, std::function<void(const addrinfo&)> callback,
+                 const Twine& node, const Twine& service,
+                 const addrinfo* hints) {
+  auto req = std::make_shared<GetAddrInfoReq>();
+  req->resolved.connect(callback);
+  GetAddrInfo(loop, req, node, service, hints);
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/GetNameInfo.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/GetNameInfo.cpp
new file mode 100644
index 0000000..994aadc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/GetNameInfo.cpp
@@ -0,0 +1,90 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/GetNameInfo.h"
+
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/util.h"
+
+namespace wpi {
+namespace uv {
+
+GetNameInfoReq::GetNameInfoReq() {
+  error = [this](Error err) { GetLoop().error(err); };
+}
+
+void GetNameInfo(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                 const sockaddr& addr, int flags) {
+  int err = uv_getnameinfo(loop.GetRaw(), req->GetRaw(),
+                           [](uv_getnameinfo_t* req, int status,
+                              const char* hostname, const char* service) {
+                             auto& h = *static_cast<GetNameInfoReq*>(req->data);
+                             if (status < 0)
+                               h.ReportError(status);
+                             else
+                               h.resolved(hostname, service);
+                             h.Release();  // this is always a one-shot
+                           },
+                           &addr, flags);
+  if (err < 0)
+    loop.ReportError(err);
+  else
+    req->Keep();
+}
+
+void GetNameInfo(Loop& loop,
+                 std::function<void(const char*, const char*)> callback,
+                 const sockaddr& addr, int flags) {
+  auto req = std::make_shared<GetNameInfoReq>();
+  req->resolved.connect(callback);
+  GetNameInfo(loop, req, addr, flags);
+}
+
+void GetNameInfo4(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                  const Twine& ip, unsigned int port, int flags) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    loop.ReportError(err);
+  else
+    GetNameInfo(loop, req, reinterpret_cast<const sockaddr&>(addr), flags);
+}
+
+void GetNameInfo4(Loop& loop,
+                  std::function<void(const char*, const char*)> callback,
+                  const Twine& ip, unsigned int port, int flags) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    loop.ReportError(err);
+  else
+    GetNameInfo(loop, callback, reinterpret_cast<const sockaddr&>(addr), flags);
+}
+
+void GetNameInfo6(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                  const Twine& ip, unsigned int port, int flags) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    loop.ReportError(err);
+  else
+    GetNameInfo(loop, req, reinterpret_cast<const sockaddr&>(addr), flags);
+}
+
+void GetNameInfo6(Loop& loop,
+                  std::function<void(const char*, const char*)> callback,
+                  const Twine& ip, unsigned int port, int flags) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    loop.ReportError(err);
+  else
+    GetNameInfo(loop, callback, reinterpret_cast<const sockaddr&>(addr), flags);
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Handle.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Handle.cpp
new file mode 100644
index 0000000..93ef423
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Handle.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Handle.h"
+
+using namespace wpi::uv;
+
+Handle::~Handle() noexcept {
+  if (!m_closed && m_uv_handle->type != UV_UNKNOWN_HANDLE) {
+    uv_close(m_uv_handle, [](uv_handle_t* uv_handle) { delete uv_handle; });
+  } else {
+    delete m_uv_handle;
+  }
+}
+
+void Handle::Close() noexcept {
+  if (!IsClosing()) {
+    uv_close(m_uv_handle, [](uv_handle_t* handle) {
+      Handle& h = *static_cast<Handle*>(handle->data);
+      h.closed();
+      h.Release();  // free ourselves
+    });
+    m_closed = true;
+  }
+}
+
+void Handle::AllocBuf(uv_handle_t* handle, size_t size, uv_buf_t* buf) {
+  auto& h = *static_cast<Handle*>(handle->data);
+  *buf = h.m_allocBuf(size);
+}
+
+void Handle::DefaultFreeBuf(Buffer& buf) { buf.Deallocate(); }
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Idle.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Idle.cpp
new file mode 100644
index 0000000..9eae218
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Idle.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Idle.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Idle> Idle::Create(Loop& loop) {
+  auto h = std::make_shared<Idle>(private_init{});
+  int err = uv_idle_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Idle::Start() {
+  Invoke(&uv_idle_start, GetRaw(), [](uv_idle_t* handle) {
+    Idle& h = *static_cast<Idle*>(handle->data);
+    h.idle();
+  });
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Loop.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Loop.cpp
new file mode 100644
index 0000000..2602150
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Loop.cpp
@@ -0,0 +1,64 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Loop.h"
+
+using namespace wpi::uv;
+
+Loop::Loop(const private_init&) noexcept {
+#ifndef _WIN32
+  // Ignore SIGPIPE (see https://github.com/joyent/libuv/issues/1254)
+  static bool once = []() {
+    signal(SIGPIPE, SIG_IGN);
+    return true;
+  }();
+  (void)once;
+#endif
+}
+
+Loop::~Loop() noexcept {
+  if (m_loop) {
+    m_loop->data = nullptr;
+    Close();
+  }
+}
+
+std::shared_ptr<Loop> Loop::Create() {
+  auto loop = std::make_shared<Loop>(private_init{});
+  if (uv_loop_init(&loop->m_loopStruct) < 0) return nullptr;
+  loop->m_loop = &loop->m_loopStruct;
+  loop->m_loop->data = loop.get();
+  return loop;
+}
+
+std::shared_ptr<Loop> Loop::GetDefault() {
+  static std::shared_ptr<Loop> loop = std::make_shared<Loop>(private_init{});
+  loop->m_loop = uv_default_loop();
+  if (!loop->m_loop) return nullptr;
+  loop->m_loop->data = loop.get();
+  return loop;
+}
+
+void Loop::Close() {
+  int err = uv_loop_close(m_loop);
+  if (err < 0) ReportError(err);
+}
+
+void Loop::Walk(std::function<void(Handle&)> callback) {
+  uv_walk(m_loop,
+          [](uv_handle_t* handle, void* func) {
+            auto& h = *static_cast<Handle*>(handle->data);
+            auto& f = *static_cast<std::function<void(Handle&)>*>(func);
+            f(h);
+          },
+          &callback);
+}
+
+void Loop::Fork() {
+  int err = uv_loop_fork(m_loop);
+  if (err < 0) ReportError(err);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/NameToAddr.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/NameToAddr.cpp
new file mode 100644
index 0000000..b407c2b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/NameToAddr.cpp
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/util.h"  // NOLINT(build/include_order)
+
+#include <cstring>
+
+#include "wpi/SmallString.h"
+
+namespace wpi {
+namespace uv {
+
+int NameToAddr(const Twine& ip, unsigned int port, sockaddr_in* addr) {
+  SmallString<128> tmp;
+  StringRef ipStr = ip.toNullTerminatedStringRef(tmp);
+  if (ipStr.empty()) {
+    std::memset(addr, 0, sizeof(sockaddr_in));
+    addr->sin_family = PF_INET;
+    addr->sin_addr.s_addr = INADDR_ANY;
+    addr->sin_port = htons(port);
+    return 0;
+  } else {
+    return uv_ip4_addr(ipStr.data(), port, addr);
+  }
+}
+
+int NameToAddr(const Twine& ip, unsigned int port, sockaddr_in6* addr) {
+  SmallString<128> tmp;
+  StringRef ipStr = ip.toNullTerminatedStringRef(tmp);
+  if (ipStr.empty()) {
+    std::memset(addr, 0, sizeof(sockaddr_in6));
+    addr->sin6_family = PF_INET6;
+    addr->sin6_addr = in6addr_any;
+    addr->sin6_port = htons(port);
+    return 0;
+  } else {
+    return uv_ip6_addr(ipStr.data(), port, addr);
+  }
+}
+
+int NameToAddr(const Twine& ip, in_addr* addr) {
+  SmallString<128> tmp;
+  StringRef ipStr = ip.toNullTerminatedStringRef(tmp);
+  if (ipStr.empty()) {
+    addr->s_addr = INADDR_ANY;
+    return 0;
+  } else {
+    return uv_inet_pton(AF_INET, ipStr.data(), addr);
+  }
+}
+
+int NameToAddr(const Twine& ip, in6_addr* addr) {
+  SmallString<128> tmp;
+  StringRef ipStr = ip.toNullTerminatedStringRef(tmp);
+  if (ipStr.empty()) {
+    *addr = in6addr_any;
+    return 0;
+  } else {
+    return uv_inet_pton(AF_INET6, ipStr.data(), addr);
+  }
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/NetworkStream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/NetworkStream.cpp
new file mode 100644
index 0000000..6e327a7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/NetworkStream.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/NetworkStream.h"
+
+namespace wpi {
+namespace uv {
+
+ConnectReq::ConnectReq() {
+  error = [this](Error err) { GetStream().error(err); };
+}
+
+void NetworkStream::Listen(int backlog) {
+  Invoke(&uv_listen, GetRawStream(), backlog,
+         [](uv_stream_t* handle, int status) {
+           auto& h = *static_cast<NetworkStream*>(handle->data);
+           if (status < 0)
+             h.ReportError(status);
+           else
+             h.connection();
+         });
+}
+
+void NetworkStream::Listen(std::function<void()> callback, int backlog) {
+  connection.connect(callback);
+  Listen(backlog);
+}
+
+}  // namespace uv
+}  // namespace wpi
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
new file mode 100644
index 0000000..8da7244
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Pipe.cpp
@@ -0,0 +1,115 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Pipe.h"
+
+#include <cstdlib>
+
+#include "wpi/SmallString.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Pipe> Pipe::Create(Loop& loop, bool ipc) {
+  auto h = std::make_shared<Pipe>(private_init{});
+  int err = uv_pipe_init(loop.GetRaw(), h->GetRaw(), ipc ? 1 : 0);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+std::shared_ptr<Pipe> Pipe::Accept() {
+  auto client = Create(GetLoopRef());
+  if (!client) return nullptr;
+  if (!Accept(client)) {
+    client->Release();
+    return nullptr;
+  }
+  return client;
+}
+
+Pipe* Pipe::DoAccept() { return Accept().get(); }
+
+void Pipe::Bind(const Twine& name) {
+  SmallString<128> nameBuf;
+  Invoke(&uv_pipe_bind, GetRaw(),
+         name.toNullTerminatedStringRef(nameBuf).data());
+}
+
+void Pipe::Connect(const Twine& name,
+                   const std::shared_ptr<PipeConnectReq>& req) {
+  SmallString<128> nameBuf;
+  uv_pipe_connect(req->GetRaw(), GetRaw(),
+                  name.toNullTerminatedStringRef(nameBuf).data(),
+                  [](uv_connect_t* req, int status) {
+                    auto& h = *static_cast<PipeConnectReq*>(req->data);
+                    if (status < 0)
+                      h.ReportError(status);
+                    else
+                      h.connected();
+                    h.Release();  // this is always a one-shot
+                  });
+  req->Keep();
+}
+
+void Pipe::Connect(const Twine& name, std::function<void()> callback) {
+  auto req = std::make_shared<PipeConnectReq>();
+  req->connected.connect(callback);
+  Connect(name, req);
+}
+
+std::string Pipe::GetSock() {
+  // Per libuv docs, the returned buffer is NOT null terminated.
+  // common case should be small
+  char buf[128];
+  size_t size = 128;
+  int r = uv_pipe_getsockname(GetRaw(), buf, &size);
+  if (r == 0) {
+    return std::string{buf, size};
+  } else if (r == UV_ENOBUFS) {
+    // need to allocate a big enough buffer
+    char* buf2 = static_cast<char*>(std::malloc(size));
+    r = uv_pipe_getsockname(GetRaw(), buf2, &size);
+    if (r == 0) {
+      std::string out{buf2, size};
+      std::free(buf2);
+      return out;
+    }
+    std::free(buf2);
+  }
+  ReportError(r);
+  return std::string{};
+}
+
+std::string Pipe::GetPeer() {
+  // Per libuv docs, the returned buffer is NOT null terminated.
+  // common case should be small
+  char buf[128];
+  size_t size = 128;
+  int r = uv_pipe_getpeername(GetRaw(), buf, &size);
+  if (r == 0) {
+    return std::string{buf, size};
+  } else if (r == UV_ENOBUFS) {
+    // need to allocate a big enough buffer
+    char* buf2 = static_cast<char*>(std::malloc(size));
+    r = uv_pipe_getpeername(GetRaw(), buf2, &size);
+    if (r == 0) {
+      std::string out{buf2, size};
+      std::free(buf2);
+      return out;
+    }
+    std::free(buf2);
+  }
+  ReportError(r);
+  return std::string{};
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Poll.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Poll.cpp
new file mode 100644
index 0000000..8b608cb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Poll.cpp
@@ -0,0 +1,87 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Poll.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Poll> Poll::Create(Loop& loop, int fd) {
+  auto h = std::make_shared<Poll>(private_init{});
+  int err = uv_poll_init(loop.GetRaw(), h->GetRaw(), fd);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+std::shared_ptr<Poll> Poll::CreateSocket(Loop& loop, uv_os_sock_t sock) {
+  auto h = std::make_shared<Poll>(private_init{});
+  int err = uv_poll_init_socket(loop.GetRaw(), h->GetRaw(), sock);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Poll::Reuse(int fd, std::function<void()> callback) {
+  if (IsClosing()) return;
+  if (!m_reuseData) m_reuseData = std::make_unique<ReuseData>();
+  m_reuseData->callback = callback;
+  m_reuseData->isSocket = false;
+  m_reuseData->fd = fd;
+  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
+    Poll& h = *static_cast<Poll*>(handle->data);
+    if (!h.m_reuseData || h.m_reuseData->isSocket) return;  // just in case
+    auto data = std::move(h.m_reuseData);
+    int err = uv_poll_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->fd);
+    if (err < 0) {
+      h.ReportError(err);
+      return;
+    }
+    data->callback();
+  });
+}
+
+void Poll::ReuseSocket(uv_os_sock_t sock, std::function<void()> callback) {
+  if (IsClosing()) return;
+  if (!m_reuseData) m_reuseData = std::make_unique<ReuseData>();
+  m_reuseData->callback = callback;
+  m_reuseData->isSocket = true;
+  m_reuseData->sock = sock;
+  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
+    Poll& h = *static_cast<Poll*>(handle->data);
+    if (!h.m_reuseData || !h.m_reuseData->isSocket) return;  // just in case
+    auto data = std::move(h.m_reuseData);
+    int err = uv_poll_init(h.GetLoopRef().GetRaw(), h.GetRaw(), data->sock);
+    if (err < 0) {
+      h.ReportError(err);
+      return;
+    }
+    data->callback();
+  });
+}
+
+void Poll::Start(int events) {
+  Invoke(&uv_poll_start, GetRaw(), events,
+         [](uv_poll_t* handle, int status, int events) {
+           Poll& h = *static_cast<Poll*>(handle->data);
+           if (status < 0)
+             h.ReportError(status);
+           else
+             h.pollEvent(events);
+         });
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Prepare.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Prepare.cpp
new file mode 100644
index 0000000..f27f477
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Prepare.cpp
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Prepare.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Prepare> Prepare::Create(Loop& loop) {
+  auto h = std::make_shared<Prepare>(private_init{});
+  int err = uv_prepare_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Prepare::Start() {
+  Invoke(&uv_prepare_start, GetRaw(), [](uv_prepare_t* handle) {
+    Prepare& h = *static_cast<Prepare*>(handle->data);
+    h.prepare();
+  });
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Process.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Process.cpp
new file mode 100644
index 0000000..5778965
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Process.cpp
@@ -0,0 +1,128 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Process.h"
+
+#include "wpi/SmallString.h"
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/Pipe.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Process> Process::SpawnArray(Loop& loop, const Twine& file,
+                                             ArrayRef<Option> options) {
+  // convert Option array to libuv structure
+  uv_process_options_t coptions;
+
+  coptions.exit_cb = [](uv_process_t* handle, int64_t status, int signal) {
+    auto& h = *static_cast<Process*>(handle->data);
+    h.exited(status, signal);
+  };
+
+  SmallString<128> fileBuf;
+  coptions.file = file.toNullTerminatedStringRef(fileBuf).data();
+  coptions.cwd = nullptr;
+  coptions.flags = 0;
+  coptions.uid = 0;
+  coptions.gid = 0;
+
+  SmallVector<char*, 4> argsBuf;
+  SmallVector<char*, 4> envBuf;
+  struct StdioContainer : public uv_stdio_container_t {
+    StdioContainer() {
+      flags = UV_IGNORE;
+      data.fd = 0;
+    }
+  };
+  SmallVector<StdioContainer, 4> stdioBuf;
+
+  for (auto&& o : options) {
+    switch (o.m_type) {
+      case Option::kArg:
+        argsBuf.push_back(const_cast<char*>(o.m_data.str));
+        break;
+      case Option::kEnv:
+        envBuf.push_back(const_cast<char*>(o.m_data.str));
+        break;
+      case Option::kCwd:
+        coptions.cwd = o.m_data.str[0] == '\0' ? nullptr : o.m_data.str;
+        break;
+      case Option::kUid:
+        coptions.uid = o.m_data.uid;
+        coptions.flags |= UV_PROCESS_SETUID;
+        break;
+      case Option::kGid:
+        coptions.gid = o.m_data.gid;
+        coptions.flags |= UV_PROCESS_SETGID;
+        break;
+      case Option::kSetFlags:
+        coptions.flags |= o.m_data.flags;
+        break;
+      case Option::kClearFlags:
+        coptions.flags &= ~o.m_data.flags;
+        break;
+      case Option::kStdioIgnore: {
+        size_t index = o.m_data.stdio.index;
+        if (index >= stdioBuf.size()) stdioBuf.resize(index + 1);
+        stdioBuf[index].flags = UV_IGNORE;
+        stdioBuf[index].data.fd = 0;
+        break;
+      }
+      case Option::kStdioInheritFd: {
+        size_t index = o.m_data.stdio.index;
+        if (index >= stdioBuf.size()) stdioBuf.resize(index + 1);
+        stdioBuf[index].flags = UV_INHERIT_FD;
+        stdioBuf[index].data.fd = o.m_data.stdio.fd;
+        break;
+      }
+      case Option::kStdioInheritPipe: {
+        size_t index = o.m_data.stdio.index;
+        if (index >= stdioBuf.size()) stdioBuf.resize(index + 1);
+        stdioBuf[index].flags = UV_INHERIT_STREAM;
+        stdioBuf[index].data.stream = o.m_data.stdio.pipe->GetRawStream();
+        break;
+      }
+      case Option::kStdioCreatePipe: {
+        size_t index = o.m_data.stdio.index;
+        if (index >= stdioBuf.size()) stdioBuf.resize(index + 1);
+        stdioBuf[index].flags =
+            static_cast<uv_stdio_flags>(UV_CREATE_PIPE | o.m_data.stdio.flags);
+        stdioBuf[index].data.stream = o.m_data.stdio.pipe->GetRawStream();
+        break;
+      }
+      default:
+        break;
+    }
+  }
+
+  if (argsBuf.empty()) argsBuf.push_back(const_cast<char*>(coptions.file));
+  argsBuf.push_back(nullptr);
+  coptions.args = argsBuf.data();
+
+  if (envBuf.empty()) {
+    coptions.env = nullptr;
+  } else {
+    envBuf.push_back(nullptr);
+    coptions.env = envBuf.data();
+  }
+
+  coptions.stdio_count = stdioBuf.size();
+  coptions.stdio = static_cast<uv_stdio_container_t*>(stdioBuf.data());
+
+  auto h = std::make_shared<Process>(private_init{});
+  int err = uv_spawn(loop.GetRaw(), h->GetRaw(), &coptions);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Signal.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Signal.cpp
new file mode 100644
index 0000000..083b852
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Signal.cpp
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Signal.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Signal> Signal::Create(Loop& loop) {
+  auto h = std::make_shared<Signal>(private_init{});
+  int err = uv_signal_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Signal::Start(int signum) {
+  Invoke(&uv_signal_start, GetRaw(),
+         [](uv_signal_t* handle, int signum) {
+           Signal& h = *static_cast<Signal*>(handle->data);
+           h.signal(signum);
+         },
+         signum);
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Stream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Stream.cpp
new file mode 100644
index 0000000..b1fd294
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Stream.cpp
@@ -0,0 +1,106 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Stream.h"
+
+#include "wpi/SmallVector.h"
+
+using namespace wpi;
+using namespace wpi::uv;
+
+namespace {
+class CallbackWriteReq : public WriteReq {
+ public:
+  CallbackWriteReq(ArrayRef<Buffer> bufs,
+                   std::function<void(MutableArrayRef<Buffer>, Error)> callback)
+      : m_bufs{bufs.begin(), bufs.end()} {
+    finish.connect([=](Error err) { callback(m_bufs, err); });
+  }
+
+ private:
+  SmallVector<Buffer, 4> m_bufs;
+};
+}  // namespace
+
+namespace wpi {
+namespace uv {
+
+ShutdownReq::ShutdownReq() {
+  error = [this](Error err) { GetStream().error(err); };
+}
+
+WriteReq::WriteReq() {
+  error = [this](Error err) { GetStream().error(err); };
+}
+
+void Stream::Shutdown(const std::shared_ptr<ShutdownReq>& req) {
+  if (Invoke(&uv_shutdown, req->GetRaw(), GetRawStream(),
+             [](uv_shutdown_t* req, int status) {
+               auto& h = *static_cast<ShutdownReq*>(req->data);
+               if (status < 0)
+                 h.ReportError(status);
+               else
+                 h.complete();
+               h.Release();  // this is always a one-shot
+             }))
+    req->Keep();
+}
+
+void Stream::Shutdown(std::function<void()> callback) {
+  auto req = std::make_shared<ShutdownReq>();
+  if (callback) req->complete.connect(callback);
+  Shutdown(req);
+}
+
+void Stream::StartRead() {
+  Invoke(&uv_read_start, GetRawStream(), &Handle::AllocBuf,
+         [](uv_stream_t* stream, ssize_t nread, const uv_buf_t* buf) {
+           auto& h = *static_cast<Stream*>(stream->data);
+           Buffer data = *buf;
+
+           // nread=0 is simply ignored
+           if (nread == UV_EOF)
+             h.end();
+           else if (nread > 0)
+             h.data(data, static_cast<size_t>(nread));
+           else if (nread < 0)
+             h.ReportError(nread);
+
+           // free the buffer
+           h.FreeBuf(data);
+         });
+}
+
+void Stream::Write(ArrayRef<Buffer> bufs,
+                   const std::shared_ptr<WriteReq>& req) {
+  if (Invoke(&uv_write, req->GetRaw(), GetRawStream(), bufs.data(), bufs.size(),
+             [](uv_write_t* r, int status) {
+               auto& h = *static_cast<WriteReq*>(r->data);
+               if (status < 0) h.ReportError(status);
+               h.finish(Error(status));
+               h.Release();  // this is always a one-shot
+             }))
+    req->Keep();
+}
+
+void Stream::Write(
+    ArrayRef<Buffer> bufs,
+    std::function<void(MutableArrayRef<Buffer>, Error)> callback) {
+  Write(bufs, std::make_shared<CallbackWriteReq>(bufs, callback));
+}
+
+int Stream::TryWrite(ArrayRef<Buffer> bufs) {
+  int val = uv_try_write(GetRawStream(), bufs.data(), bufs.size());
+  if (val < 0) {
+    this->ReportError(val);
+    return 0;
+  }
+  return val;
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Tcp.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Tcp.cpp
new file mode 100644
index 0000000..f71e055
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Tcp.cpp
@@ -0,0 +1,155 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Tcp.h"
+
+#include <cstring>
+
+#include "wpi/uv/util.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Tcp> Tcp::Create(Loop& loop, unsigned int flags) {
+  auto h = std::make_shared<Tcp>(private_init{});
+  int err = uv_tcp_init_ex(loop.GetRaw(), h->GetRaw(), flags);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Tcp::Reuse(std::function<void()> callback, unsigned int flags) {
+  if (IsClosing()) return;
+  if (!m_reuseData) m_reuseData = std::make_unique<ReuseData>();
+  m_reuseData->callback = callback;
+  m_reuseData->flags = flags;
+  uv_close(GetRawHandle(), [](uv_handle_t* handle) {
+    Tcp& h = *static_cast<Tcp*>(handle->data);
+    if (!h.m_reuseData) return;  // just in case
+    auto data = std::move(h.m_reuseData);
+    int err = uv_tcp_init_ex(h.GetLoopRef().GetRaw(), h.GetRaw(), data->flags);
+    if (err < 0) {
+      h.ReportError(err);
+      return;
+    }
+    data->callback();
+  });
+}
+
+std::shared_ptr<Tcp> Tcp::Accept() {
+  auto client = Create(GetLoopRef());
+  if (!client) return nullptr;
+  if (!Accept(client)) {
+    client->Release();
+    return nullptr;
+  }
+  return client;
+}
+
+Tcp* Tcp::DoAccept() { return Accept().get(); }
+
+void Tcp::Bind(const Twine& ip, unsigned int port, unsigned int flags) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    ReportError(err);
+  else
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+}
+
+void Tcp::Bind6(const Twine& ip, unsigned int port, unsigned int flags) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    ReportError(err);
+  else
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+}
+
+sockaddr_storage Tcp::GetSock() {
+  sockaddr_storage name;
+  int len = sizeof(name);
+  if (!Invoke(&uv_tcp_getsockname, GetRaw(), reinterpret_cast<sockaddr*>(&name),
+              &len))
+    std::memset(&name, 0, sizeof(name));
+  return name;
+}
+
+sockaddr_storage Tcp::GetPeer() {
+  sockaddr_storage name;
+  int len = sizeof(name);
+  if (!Invoke(&uv_tcp_getpeername, GetRaw(), reinterpret_cast<sockaddr*>(&name),
+              &len))
+    std::memset(&name, 0, sizeof(name));
+  return name;
+}
+
+void Tcp::Connect(const sockaddr& addr,
+                  const std::shared_ptr<TcpConnectReq>& req) {
+  if (Invoke(&uv_tcp_connect, req->GetRaw(), GetRaw(), &addr,
+             [](uv_connect_t* req, int status) {
+               auto& h = *static_cast<TcpConnectReq*>(req->data);
+               if (status < 0)
+                 h.ReportError(status);
+               else
+                 h.connected();
+               h.Release();  // this is always a one-shot
+             }))
+    req->Keep();
+}
+
+void Tcp::Connect(const sockaddr& addr, std::function<void()> callback) {
+  auto req = std::make_shared<TcpConnectReq>();
+  req->connected.connect(callback);
+  Connect(addr, req);
+}
+
+void Tcp::Connect(const Twine& ip, unsigned int port,
+                  const std::shared_ptr<TcpConnectReq>& req) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    ReportError(err);
+  else
+    Connect(reinterpret_cast<const sockaddr&>(addr), req);
+}
+
+void Tcp::Connect(const Twine& ip, unsigned int port,
+                  std::function<void()> callback) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    ReportError(err);
+  else
+    Connect(reinterpret_cast<const sockaddr&>(addr), callback);
+}
+
+void Tcp::Connect6(const Twine& ip, unsigned int port,
+                   const std::shared_ptr<TcpConnectReq>& req) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    ReportError(err);
+  else
+    Connect(reinterpret_cast<const sockaddr&>(addr), req);
+}
+
+void Tcp::Connect6(const Twine& ip, unsigned int port,
+                   std::function<void()> callback) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    ReportError(err);
+  else
+    Connect(reinterpret_cast<const sockaddr&>(addr), callback);
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Timer.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Timer.cpp
new file mode 100644
index 0000000..4825ea3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Timer.cpp
@@ -0,0 +1,46 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Timer.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Timer> Timer::Create(Loop& loop) {
+  auto h = std::make_shared<Timer>(private_init{});
+  int err = uv_timer_init(loop.GetRaw(), h->GetRaw());
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Timer::SingleShot(Loop& loop, Time timeout, std::function<void()> func) {
+  auto h = Create(loop);
+  if (!h) return;
+  h->timeout.connect([ theTimer = h.get(), func ]() {
+    func();
+    theTimer->Close();
+  });
+  h->Start(timeout);
+}
+
+void Timer::Start(Time timeout, Time repeat) {
+  Invoke(&uv_timer_start, GetRaw(),
+         [](uv_timer_t* handle) {
+           Timer& h = *static_cast<Timer*>(handle->data);
+           h.timeout();
+         },
+         timeout.count(), repeat.count());
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Tty.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Tty.cpp
new file mode 100644
index 0000000..cdd6fd5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Tty.cpp
@@ -0,0 +1,27 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Tty.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+std::shared_ptr<Tty> Tty::Create(Loop& loop, uv_file fd, bool readable) {
+  auto h = std::make_shared<Tty>(private_init{});
+  int err = uv_tty_init(loop.GetRaw(), h->GetRaw(), fd, readable ? 1 : 0);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Udp.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Udp.cpp
new file mode 100644
index 0000000..cc7208d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Udp.cpp
@@ -0,0 +1,133 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Udp.h"
+
+#include <cstring>
+
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "wpi/uv/util.h"
+
+namespace {
+
+using namespace wpi;
+using namespace wpi::uv;
+
+class CallbackUdpSendReq : public UdpSendReq {
+ public:
+  CallbackUdpSendReq(
+      ArrayRef<Buffer> bufs,
+      std::function<void(MutableArrayRef<Buffer>, Error)> callback)
+      : m_bufs{bufs.begin(), bufs.end()} {
+    complete.connect([=](Error err) { callback(m_bufs, err); });
+  }
+
+ private:
+  SmallVector<Buffer, 4> m_bufs;
+};
+
+}  // namespace
+
+namespace wpi {
+namespace uv {
+
+UdpSendReq::UdpSendReq() {
+  error = [this](Error err) { GetUdp().error(err); };
+}
+
+std::shared_ptr<Udp> Udp::Create(Loop& loop, unsigned int flags) {
+  auto h = std::make_shared<Udp>(private_init{});
+  int err = uv_udp_init_ex(loop.GetRaw(), h->GetRaw(), flags);
+  if (err < 0) {
+    loop.ReportError(err);
+    return nullptr;
+  }
+  h->Keep();
+  return h;
+}
+
+void Udp::Bind(const Twine& ip, unsigned int port, unsigned int flags) {
+  sockaddr_in addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    ReportError(err);
+  else
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+}
+
+void Udp::Bind6(const Twine& ip, unsigned int port, unsigned int flags) {
+  sockaddr_in6 addr;
+  int err = NameToAddr(ip, port, &addr);
+  if (err < 0)
+    ReportError(err);
+  else
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+}
+
+sockaddr_storage Udp::GetSock() {
+  sockaddr_storage name;
+  int len = sizeof(name);
+  if (!Invoke(&uv_udp_getsockname, GetRaw(), reinterpret_cast<sockaddr*>(&name),
+              &len))
+    std::memset(&name, 0, sizeof(name));
+  return name;
+}
+
+void Udp::SetMembership(const Twine& multicastAddr, const Twine& interfaceAddr,
+                        uv_membership membership) {
+  SmallString<128> multicastAddrBuf;
+  SmallString<128> interfaceAddrBuf;
+  Invoke(&uv_udp_set_membership, GetRaw(),
+         multicastAddr.toNullTerminatedStringRef(multicastAddrBuf).data(),
+         interfaceAddr.toNullTerminatedStringRef(interfaceAddrBuf).data(),
+         membership);
+}
+
+void Udp::SetMulticastInterface(const Twine& interfaceAddr) {
+  SmallString<128> interfaceAddrBuf;
+  Invoke(&uv_udp_set_multicast_interface, GetRaw(),
+         interfaceAddr.toNullTerminatedStringRef(interfaceAddrBuf).data());
+}
+
+void Udp::Send(const sockaddr& addr, ArrayRef<Buffer> bufs,
+               const std::shared_ptr<UdpSendReq>& req) {
+  if (Invoke(&uv_udp_send, req->GetRaw(), GetRaw(), bufs.data(), bufs.size(),
+             &addr, [](uv_udp_send_t* r, int status) {
+               auto& h = *static_cast<UdpSendReq*>(r->data);
+               if (status < 0) h.ReportError(status);
+               h.complete(Error(status));
+               h.Release();  // this is always a one-shot
+             }))
+    req->Keep();
+}
+
+void Udp::Send(const sockaddr& addr, ArrayRef<Buffer> bufs,
+               std::function<void(MutableArrayRef<Buffer>, Error)> callback) {
+  Send(addr, bufs, std::make_shared<CallbackUdpSendReq>(bufs, callback));
+}
+
+void Udp::StartRecv() {
+  Invoke(&uv_udp_recv_start, GetRaw(), &AllocBuf,
+         [](uv_udp_t* handle, ssize_t nread, const uv_buf_t* buf,
+            const sockaddr* addr, unsigned flags) {
+           auto& h = *static_cast<Udp*>(handle->data);
+           Buffer data = *buf;
+
+           // nread=0 is simply ignored
+           if (nread > 0)
+             h.received(data, static_cast<size_t>(nread), *addr, flags);
+           else if (nread < 0)
+             h.ReportError(nread);
+
+           // free the buffer
+           h.FreeBuf(data);
+         });
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Work.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Work.cpp
new file mode 100644
index 0000000..d71ef81
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/cpp/uv/Work.cpp
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Work.h"
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+WorkReq::WorkReq() {
+  error = [this](Error err) { GetLoop().error(err); };
+}
+
+void QueueWork(Loop& loop, const std::shared_ptr<WorkReq>& req) {
+  int err = uv_queue_work(loop.GetRaw(), req->GetRaw(),
+                          [](uv_work_t* req) {
+                            auto& h = *static_cast<WorkReq*>(req->data);
+                            h.work();
+                          },
+                          [](uv_work_t* req, int status) {
+                            auto& h = *static_cast<WorkReq*>(req->data);
+                            if (status < 0)
+                              h.ReportError(status);
+                            else
+                              h.afterWork();
+                            h.Release();  // this is always a one-shot
+                          });
+  if (err < 0)
+    loop.ReportError(err);
+  else
+    req->Keep();
+}
+
+void QueueWork(Loop& loop, std::function<void()> work,
+               std::function<void()> afterWork) {
+  auto req = std::make_shared<WorkReq>();
+  if (work) req->work.connect(work);
+  if (afterWork) req->afterWork.connect(afterWork);
+  QueueWork(loop, req);
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/AlignOf.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/AlignOf.h
new file mode 100644
index 0000000..6ecb22c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/AlignOf.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/AlignOf.h is deprecated; include wpi/AlignOf.h instead"
+#else
+#warning "llvm/AlignOf.h is deprecated; include wpi/AlignOf.h instead"
+#endif
+// clang-format on
+
+#include "wpi/AlignOf.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/ArrayRef.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/ArrayRef.h
new file mode 100644
index 0000000..9cf71a6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/ArrayRef.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/ArrayRef.h is deprecated; include wpi/ArrayRef.h instead"
+#else
+#warning "llvm/ArrayRef.h is deprecated; include wpi/ArrayRef.h instead"
+#endif
+// clang-format on
+
+#include "wpi/ArrayRef.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Compiler.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Compiler.h
new file mode 100644
index 0000000..658e7e0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Compiler.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/Compiler.h is deprecated; include wpi/Compiler.h instead"
+#else
+#warning "llvm/Compiler.h is deprecated; include wpi/Compiler.h instead"
+#endif
+// clang-format on
+
+#include "wpi/Compiler.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/ConvertUTF.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/ConvertUTF.h
new file mode 100644
index 0000000..18645f7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/ConvertUTF.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/ConvertUTF.h is deprecated; include wpi/ConvertUTF.h instead"
+#else
+#warning "llvm/ConvertUTF.h is deprecated; include wpi/ConvertUTF.h instead"
+#endif
+// clang-format on
+
+#include "wpi/ConvertUTF.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/DenseMap.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/DenseMap.h
new file mode 100644
index 0000000..cf609a9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/DenseMap.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/DenseMap.h is deprecated; include wpi/DenseMap.h instead"
+#else
+#warning "llvm/DenseMap.h is deprecated; include wpi/DenseMap.h instead"
+#endif
+// clang-format on
+
+#include "wpi/DenseMap.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/DenseMapInfo.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/DenseMapInfo.h
new file mode 100644
index 0000000..ab582fb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/DenseMapInfo.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/DenseMapInfo.h is deprecated; include wpi/DenseMapInfo.h instead"
+#else
+#warning "llvm/DenseMapInfo.h is deprecated; include wpi/DenseMapInfo.h instead"
+#endif
+// clang-format on
+
+#include "wpi/DenseMapInfo.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/EpochTracker.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/EpochTracker.h
new file mode 100644
index 0000000..b9351c4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/EpochTracker.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/EpochTracker.h is deprecated; include wpi/EpochTracker.h instead"
+#else
+#warning "llvm/EpochTracker.h is deprecated; include wpi/EpochTracker.h instead"
+#endif
+// clang-format on
+
+#include "wpi/EpochTracker.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/FileSystem.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/FileSystem.h
new file mode 100644
index 0000000..41a8a0f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/FileSystem.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/FileSystem.h is deprecated; include wpi/FileSystem.h instead"
+#else
+#warning "llvm/FileSystem.h is deprecated; include wpi/FileSystem.h instead"
+#endif
+// clang-format on
+
+#include "wpi/FileSystem.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Format.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Format.h
new file mode 100644
index 0000000..7494722
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Format.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/Format.h is deprecated; include wpi/Format.h instead"
+#else
+#warning "llvm/Format.h is deprecated; include wpi/Format.h instead"
+#endif
+// clang-format on
+
+#include "wpi/Format.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Hashing.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Hashing.h
new file mode 100644
index 0000000..3e9d464
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Hashing.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/Hashing.h is deprecated; include wpi/Hashing.h instead"
+#else
+#warning "llvm/Hashing.h is deprecated; include wpi/Hashing.h instead"
+#endif
+// clang-format on
+
+#include "wpi/Hashing.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/IntrusiveRefCntPtr.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/IntrusiveRefCntPtr.h
new file mode 100644
index 0000000..6a98483
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/IntrusiveRefCntPtr.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/IntrusiveRefCntPtr.h is deprecated; include wpi/IntrusiveRefCntPtr.h instead"
+#else
+#warning "llvm/IntrusiveRefCntPtr.h is deprecated; include wpi/IntrusiveRefCntPtr.h instead"
+#endif
+// clang-format on
+
+#include "wpi/IntrusiveRefCntPtr.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/MathExtras.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/MathExtras.h
new file mode 100644
index 0000000..49b7419
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/MathExtras.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/MathExtras.h is deprecated; include wpi/MathExtras.h instead"
+#else
+#warning "llvm/MathExtras.h is deprecated; include wpi/MathExtras.h instead"
+#endif
+// clang-format on
+
+#include "wpi/MathExtras.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Path.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Path.h
new file mode 100644
index 0000000..85aaf59
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Path.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/Path.h is deprecated; include wpi/Path.h instead"
+#else
+#warning "llvm/Path.h is deprecated; include wpi/Path.h instead"
+#endif
+// clang-format on
+
+#include "wpi/Path.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/PointerLikeTypeTraits.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/PointerLikeTypeTraits.h
new file mode 100644
index 0000000..b0f460a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/PointerLikeTypeTraits.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/PointerLikeTypeTraits.h is deprecated; include wpi/PointerLikeTypeTraits.h instead"
+#else
+#warning "llvm/PointerLikeTypeTraits.h is deprecated; include wpi/PointerLikeTypeTraits.h instead"
+#endif
+// clang-format on
+
+#include "wpi/PointerLikeTypeTraits.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/STLExtras.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/STLExtras.h
new file mode 100644
index 0000000..87ea631
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/STLExtras.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/STLExtras.h is deprecated; include wpi/STLExtras.h instead"
+#else
+#warning "llvm/STLExtras.h is deprecated; include wpi/STLExtras.h instead"
+#endif
+// clang-format on
+
+#include "wpi/STLExtras.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallPtrSet.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallPtrSet.h
new file mode 100644
index 0000000..546b04e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallPtrSet.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/SmallPtrSet.h is deprecated; include wpi/SmallPtrSet.h instead"
+#else
+#warning "llvm/SmallPtrSet.h is deprecated; include wpi/SmallPtrSet.h instead"
+#endif
+// clang-format on
+
+#include "wpi/SmallPtrSet.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallSet.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallSet.h
new file mode 100644
index 0000000..c431bd5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallSet.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/SmallSet.h is deprecated; include wpi/SmallSet.h instead"
+#else
+#warning "llvm/SmallSet.h is deprecated; include wpi/SmallSet.h instead"
+#endif
+// clang-format on
+
+#include "wpi/SmallSet.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallString.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallString.h
new file mode 100644
index 0000000..7679f6b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallString.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/SmallString.h is deprecated; include wpi/SmallString.h instead"
+#else
+#warning "llvm/SmallString.h is deprecated; include wpi/SmallString.h instead"
+#endif
+// clang-format on
+
+#include "wpi/SmallString.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallVector.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallVector.h
new file mode 100644
index 0000000..9291933
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/SmallVector.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/SmallVector.h is deprecated; include wpi/SmallVector.h instead"
+#else
+#warning "llvm/SmallVector.h is deprecated; include wpi/SmallVector.h instead"
+#endif
+// clang-format on
+
+#include "wpi/SmallVector.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringExtras.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringExtras.h
new file mode 100644
index 0000000..4fcfdd6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringExtras.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/StringExtras.h is deprecated; include wpi/StringExtras.h instead"
+#else
+#warning "llvm/StringExtras.h is deprecated; include wpi/StringExtras.h instead"
+#endif
+// clang-format on
+
+#include "wpi/StringExtras.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringMap.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringMap.h
new file mode 100644
index 0000000..4fd06aa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringMap.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/StringMap.h is deprecated; include wpi/StringMap.h instead"
+#else
+#warning "llvm/StringMap.h is deprecated; include wpi/StringMap.h instead"
+#endif
+// clang-format on
+
+#include "wpi/StringMap.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringRef.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringRef.h
new file mode 100644
index 0000000..74f44b5
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/StringRef.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/StringRef.h is deprecated; include wpi/StringRef.h instead"
+#else
+#warning "llvm/StringRef.h is deprecated; include wpi/StringRef.h instead"
+#endif
+// clang-format on
+
+#include "wpi/StringRef.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Twine.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Twine.h
new file mode 100644
index 0000000..ddd40a4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/Twine.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/Twine.h is deprecated; include wpi/Twine.h instead"
+#else
+#warning "llvm/Twine.h is deprecated; include wpi/Twine.h instead"
+#endif
+// clang-format on
+
+#include "wpi/Twine.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/WindowsError.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/WindowsError.h
new file mode 100644
index 0000000..1f7c618
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/WindowsError.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/WindowsError.h is deprecated; include wpi/WindowsError.h instead"
+#else
+#warning "llvm/WindowsError.h is deprecated; include wpi/WindowsError.h instead"
+#endif
+// clang-format on
+
+#include "wpi/WindowsError.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/iterator_range.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/iterator_range.h
new file mode 100644
index 0000000..acd9d7d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/iterator_range.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/iterator_range.h is deprecated; include wpi/iterator_range.h instead"
+#else
+#warning "llvm/iterator_range.h is deprecated; include wpi/iterator_range.h instead"
+#endif
+// clang-format on
+
+#include "wpi/iterator_range.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/raw_os_ostream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/raw_os_ostream.h
new file mode 100644
index 0000000..b9e7fd6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/raw_os_ostream.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/raw_os_ostream.h is deprecated; include wpi/raw_os_ostream.h instead"
+#else
+#warning "llvm/raw_os_ostream.h is deprecated; include wpi/raw_os_ostream.h instead"
+#endif
+// clang-format on
+
+#include "wpi/raw_os_ostream.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/raw_ostream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/raw_ostream.h
new file mode 100644
index 0000000..3781bd7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/raw_ostream.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/raw_ostream.h is deprecated; include wpi/raw_ostream.h instead"
+#else
+#warning "llvm/raw_ostream.h is deprecated; include wpi/raw_ostream.h instead"
+#endif
+// clang-format on
+
+#include "wpi/raw_ostream.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/type_traits.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/type_traits.h
new file mode 100644
index 0000000..e662e0e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/llvm/type_traits.h
@@ -0,0 +1,20 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: llvm/type_traits.h is deprecated; include wpi/type_traits.h instead"
+#else
+#warning "llvm/type_traits.h is deprecated; include wpi/type_traits.h instead"
+#endif
+// clang-format on
+
+#include "wpi/type_traits.h"
+
+namespace llvm = wpi;
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/Base64.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/Base64.h
new file mode 100644
index 0000000..54f6702
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/Base64.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/Base64.h is deprecated; include wpi/Base64.h instead"
+#else
+#warning "support/Base64.h is deprecated; include wpi/Base64.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/Base64.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/ConcurrentQueue.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/ConcurrentQueue.h
new file mode 100644
index 0000000..77f5eba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/ConcurrentQueue.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/ConcurrentQueue.h is deprecated; include wpi/ConcurrentQueue.h instead"
+#else
+#warning "support/ConcurrentQueue.h is deprecated; include wpi/ConcurrentQueue.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/ConcurrentQueue.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/HttpUtil.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/HttpUtil.h
new file mode 100644
index 0000000..d8e2be0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/HttpUtil.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/HttpUtil.h is deprecated; include wpi/HttpUtil.h instead"
+#else
+#warning "support/HttpUtil.h is deprecated; include wpi/HttpUtil.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/HttpUtil.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/HttpUtil.inl b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/HttpUtil.inl
new file mode 100644
index 0000000..8210c25
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/HttpUtil.inl
@@ -0,0 +1,18 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/HttpUtil.inl is deprecated; include wpi/HttpUtil.inl instead"
+#else
+#warning "support/HttpUtil.inl is deprecated; include wpi/HttpUtil.inl instead"
+#endif
+// clang-format on
+
+#include "wpi/HttpUtil.inl"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/Logger.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/Logger.h
new file mode 100644
index 0000000..5bf2cdf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/Logger.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/Logger.h is deprecated; include wpi/Logger.h instead"
+#else
+#warning "support/Logger.h is deprecated; include wpi/Logger.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/Logger.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/SafeThread.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/SafeThread.h
new file mode 100644
index 0000000..cceaf57
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/SafeThread.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/SafeThread.h is deprecated; include wpi/SafeThread.h instead"
+#else
+#warning "support/SafeThread.h is deprecated; include wpi/SafeThread.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/SafeThread.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/UidVector.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/UidVector.h
new file mode 100644
index 0000000..d5d4806
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/UidVector.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/UidVector.h is deprecated; include wpi/UidVector.h instead"
+#else
+#warning "support/UidVector.h is deprecated; include wpi/UidVector.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/UidVector.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/atomic_static.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/atomic_static.h
new file mode 100644
index 0000000..27ec4b1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/atomic_static.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/atomic_static.h is deprecated; include wpi/atomic_static.h instead"
+#else
+#warning "support/atomic_static.h is deprecated; include wpi/atomic_static.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/atomic_static.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/condition_variable.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/condition_variable.h
new file mode 100644
index 0000000..434f797
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/condition_variable.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/condition_variable.h is deprecated; include wpi/condition_variable.h instead"
+#else
+#warning "support/condition_variable.h is deprecated; include wpi/condition_variable.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/condition_variable.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/deprecated.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/deprecated.h
new file mode 100644
index 0000000..c130df4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/deprecated.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/deprecated.h is deprecated; include wpi/deprecated.h instead"
+#else
+#warning "support/deprecated.h is deprecated; include wpi/deprecated.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/deprecated.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/hostname.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/hostname.h
new file mode 100644
index 0000000..33160a1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/hostname.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/hostname.h is deprecated; include wpi/hostname.h instead"
+#else
+#warning "support/hostname.h is deprecated; include wpi/hostname.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/hostname.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/jni_util.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/jni_util.h
new file mode 100644
index 0000000..e5f8633
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/jni_util.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/jni_util.h is deprecated; include wpi/jni_util.h instead"
+#else
+#warning "support/jni_util.h is deprecated; include wpi/jni_util.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/jni_util.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/json.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/json.h
new file mode 100644
index 0000000..e98f04f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/json.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/json.h is deprecated; include wpi/json.h instead"
+#else
+#warning "support/json.h is deprecated; include wpi/json.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/json.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/leb128.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/leb128.h
new file mode 100644
index 0000000..ccf0422
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/leb128.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/leb128.h is deprecated; include wpi/leb128.h instead"
+#else
+#warning "support/leb128.h is deprecated; include wpi/leb128.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/leb128.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/mutex.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/mutex.h
new file mode 100644
index 0000000..cd6118b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/mutex.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/mutex.h is deprecated; include wpi/mutex.h instead"
+#else
+#warning "support/mutex.h is deprecated; include wpi/mutex.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/mutex.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/priority_mutex.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/priority_mutex.h
new file mode 100644
index 0000000..6b86e02
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/priority_mutex.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/priority_mutex.h is deprecated; include wpi/priority_mutex.h instead"
+#else
+#warning "support/priority_mutex.h is deprecated; include wpi/priority_mutex.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/priority_mutex.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_istream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_istream.h
new file mode 100644
index 0000000..9451baf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_istream.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/raw_istream.h is deprecated; include wpi/raw_istream.h instead"
+#else
+#warning "support/raw_istream.h is deprecated; include wpi/raw_istream.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/raw_istream.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_socket_istream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_socket_istream.h
new file mode 100644
index 0000000..bf8ca02
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_socket_istream.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/raw_socket_istream.h is deprecated; include wpi/raw_socket_istream.h instead"
+#else
+#warning "support/raw_socket_istream.h is deprecated; include wpi/raw_socket_istream.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/raw_socket_istream.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_socket_ostream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_socket_ostream.h
new file mode 100644
index 0000000..4070d55
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/raw_socket_ostream.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/raw_socket_ostream.h is deprecated; include wpi/raw_socket_ostream.h instead"
+#else
+#warning "support/raw_socket_ostream.h is deprecated; include wpi/raw_socket_ostream.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/raw_socket_ostream.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/sha1.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/sha1.h
new file mode 100644
index 0000000..b755a4e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/sha1.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/sha1.h is deprecated; include wpi/sha1.h instead"
+#else
+#warning "support/sha1.h is deprecated; include wpi/sha1.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/sha1.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/timestamp.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/timestamp.h
new file mode 100644
index 0000000..0ae505a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/support/timestamp.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: support/timestamp.h is deprecated; include wpi/timestamp.h instead"
+#else
+#warning "support/timestamp.h is deprecated; include wpi/timestamp.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/timestamp.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/NetworkAcceptor.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/NetworkAcceptor.h
new file mode 100644
index 0000000..8a87f7b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/NetworkAcceptor.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: tcpsockets/NetworkAcceptor.h is deprecated; include wpi/NetworkAcceptor.h instead"
+#else
+#warning "tcpsockets/NetworkAcceptor.h is deprecated; include wpi/NetworkAcceptor.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/NetworkAcceptor.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/NetworkStream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/NetworkStream.h
new file mode 100644
index 0000000..3e9d306
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/NetworkStream.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: tcpsockets/NetworkStream.h is deprecated; include wpi/NetworkStream.h instead"
+#else
+#warning "tcpsockets/NetworkStream.h is deprecated; include wpi/NetworkStream.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/NetworkStream.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/SocketError.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/SocketError.h
new file mode 100644
index 0000000..0ffe322
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/SocketError.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: tcpsockets/SocketError.h is deprecated; include wpi/SocketError.h instead"
+#else
+#warning "tcpsockets/SocketError.h is deprecated; include wpi/SocketError.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/SocketError.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPAcceptor.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPAcceptor.h
new file mode 100644
index 0000000..4544e04
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPAcceptor.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: tcpsockets/TCPAcceptor.h is deprecated; include wpi/TCPAcceptor.h instead"
+#else
+#warning "tcpsockets/TCPAcceptor.h is deprecated; include wpi/TCPAcceptor.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/TCPAcceptor.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPConnector.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPConnector.h
new file mode 100644
index 0000000..a988872
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPConnector.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: tcpsockets/TCPConnector.h is deprecated; include wpi/TCPConnector.h instead"
+#else
+#warning "tcpsockets/TCPConnector.h is deprecated; include wpi/TCPConnector.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/TCPConnector.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPStream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPStream.h
new file mode 100644
index 0000000..74af7fa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/tcpsockets/TCPStream.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: tcpsockets/TCPStream.h is deprecated; include wpi/TCPStream.h instead"
+#else
+#warning "tcpsockets/TCPStream.h is deprecated; include wpi/TCPStream.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/TCPStream.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/udpsockets/UDPClient.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/udpsockets/UDPClient.h
new file mode 100644
index 0000000..c70a13b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/udpsockets/UDPClient.h
@@ -0,0 +1,19 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// clang-format off
+#ifdef _MSC_VER
+#pragma message "warning: udpsockets/UDPClient.h is deprecated; include wpi/UDPClient.h instead"
+#else
+#warning "udpsockets/UDPClient.h is deprecated; include wpi/UDPClient.h instead"
+#endif
+
+// clang-format on
+
+#include "wpi/UDPClient.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv.h
new file mode 100644
index 0000000..0d62c18
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv.h
@@ -0,0 +1,1581 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* See https://github.com/libuv/libuv#documentation for documentation. */
+
+#ifndef UV_H
+#define UV_H
+
+#ifdef _WIN32
+  /* Windows - set up dll import/export decorators. */
+# if defined(BUILDING_UV_SHARED)
+    /* Building shared library. */
+#   define UV_EXTERN __declspec(dllexport)
+# elif defined(USING_UV_SHARED)
+    /* Using shared library. */
+#   define UV_EXTERN __declspec(dllimport)
+# else
+    /* Building static library. */
+#   define UV_EXTERN /* nothing */
+# endif
+#elif __GNUC__ >= 4
+# define UV_EXTERN __attribute__((visibility("default")))
+#else
+# define UV_EXTERN /* nothing */
+#endif
+
+#include "uv/errno.h"
+#include "uv/version.h"
+#include <stddef.h>
+#include <stdio.h>
+
+#include <stdint.h>
+
+#if defined(_WIN32)
+# include "uv/win.h"
+#else
+# include "uv/unix.h"
+#endif
+
+/* Expand this list if necessary. */
+#define UV_ERRNO_MAP(XX)                                                      \
+  XX(E2BIG, "argument list too long")                                         \
+  XX(EACCES, "permission denied")                                             \
+  XX(EADDRINUSE, "address already in use")                                    \
+  XX(EADDRNOTAVAIL, "address not available")                                  \
+  XX(EAFNOSUPPORT, "address family not supported")                            \
+  XX(EAGAIN, "resource temporarily unavailable")                              \
+  XX(EAI_ADDRFAMILY, "address family not supported")                          \
+  XX(EAI_AGAIN, "temporary failure")                                          \
+  XX(EAI_BADFLAGS, "bad ai_flags value")                                      \
+  XX(EAI_BADHINTS, "invalid value for hints")                                 \
+  XX(EAI_CANCELED, "request canceled")                                        \
+  XX(EAI_FAIL, "permanent failure")                                           \
+  XX(EAI_FAMILY, "ai_family not supported")                                   \
+  XX(EAI_MEMORY, "out of memory")                                             \
+  XX(EAI_NODATA, "no address")                                                \
+  XX(EAI_NONAME, "unknown node or service")                                   \
+  XX(EAI_OVERFLOW, "argument buffer overflow")                                \
+  XX(EAI_PROTOCOL, "resolved protocol is unknown")                            \
+  XX(EAI_SERVICE, "service not available for socket type")                    \
+  XX(EAI_SOCKTYPE, "socket type not supported")                               \
+  XX(EALREADY, "connection already in progress")                              \
+  XX(EBADF, "bad file descriptor")                                            \
+  XX(EBUSY, "resource busy or locked")                                        \
+  XX(ECANCELED, "operation canceled")                                         \
+  XX(ECHARSET, "invalid Unicode character")                                   \
+  XX(ECONNABORTED, "software caused connection abort")                        \
+  XX(ECONNREFUSED, "connection refused")                                      \
+  XX(ECONNRESET, "connection reset by peer")                                  \
+  XX(EDESTADDRREQ, "destination address required")                            \
+  XX(EEXIST, "file already exists")                                           \
+  XX(EFAULT, "bad address in system call argument")                           \
+  XX(EFBIG, "file too large")                                                 \
+  XX(EHOSTUNREACH, "host is unreachable")                                     \
+  XX(EINTR, "interrupted system call")                                        \
+  XX(EINVAL, "invalid argument")                                              \
+  XX(EIO, "i/o error")                                                        \
+  XX(EISCONN, "socket is already connected")                                  \
+  XX(EISDIR, "illegal operation on a directory")                              \
+  XX(ELOOP, "too many symbolic links encountered")                            \
+  XX(EMFILE, "too many open files")                                           \
+  XX(EMSGSIZE, "message too long")                                            \
+  XX(ENAMETOOLONG, "name too long")                                           \
+  XX(ENETDOWN, "network is down")                                             \
+  XX(ENETUNREACH, "network is unreachable")                                   \
+  XX(ENFILE, "file table overflow")                                           \
+  XX(ENOBUFS, "no buffer space available")                                    \
+  XX(ENODEV, "no such device")                                                \
+  XX(ENOENT, "no such file or directory")                                     \
+  XX(ENOMEM, "not enough memory")                                             \
+  XX(ENONET, "machine is not on the network")                                 \
+  XX(ENOPROTOOPT, "protocol not available")                                   \
+  XX(ENOSPC, "no space left on device")                                       \
+  XX(ENOSYS, "function not implemented")                                      \
+  XX(ENOTCONN, "socket is not connected")                                     \
+  XX(ENOTDIR, "not a directory")                                              \
+  XX(ENOTEMPTY, "directory not empty")                                        \
+  XX(ENOTSOCK, "socket operation on non-socket")                              \
+  XX(ENOTSUP, "operation not supported on socket")                            \
+  XX(EPERM, "operation not permitted")                                        \
+  XX(EPIPE, "broken pipe")                                                    \
+  XX(EPROTO, "protocol error")                                                \
+  XX(EPROTONOSUPPORT, "protocol not supported")                               \
+  XX(EPROTOTYPE, "protocol wrong type for socket")                            \
+  XX(ERANGE, "result too large")                                              \
+  XX(EROFS, "read-only file system")                                          \
+  XX(ESHUTDOWN, "cannot send after transport endpoint shutdown")              \
+  XX(ESPIPE, "invalid seek")                                                  \
+  XX(ESRCH, "no such process")                                                \
+  XX(ETIMEDOUT, "connection timed out")                                       \
+  XX(ETXTBSY, "text file is busy")                                            \
+  XX(EXDEV, "cross-device link not permitted")                                \
+  XX(UNKNOWN, "unknown error")                                                \
+  XX(EOF, "end of file")                                                      \
+  XX(ENXIO, "no such device or address")                                      \
+  XX(EMLINK, "too many links")                                                \
+  XX(EHOSTDOWN, "host is down")                                               \
+  XX(EREMOTEIO, "remote I/O error")                                           \
+  XX(ENOTTY, "inappropriate ioctl for device")                                \
+  XX(EFTYPE, "inappropriate file type or format")                             \
+
+#define UV_HANDLE_TYPE_MAP(XX)                                                \
+  XX(ASYNC, async)                                                            \
+  XX(CHECK, check)                                                            \
+  XX(FS_EVENT, fs_event)                                                      \
+  XX(FS_POLL, fs_poll)                                                        \
+  XX(HANDLE, handle)                                                          \
+  XX(IDLE, idle)                                                              \
+  XX(NAMED_PIPE, pipe)                                                        \
+  XX(POLL, poll)                                                              \
+  XX(PREPARE, prepare)                                                        \
+  XX(PROCESS, process)                                                        \
+  XX(STREAM, stream)                                                          \
+  XX(TCP, tcp)                                                                \
+  XX(TIMER, timer)                                                            \
+  XX(TTY, tty)                                                                \
+  XX(UDP, udp)                                                                \
+  XX(SIGNAL, signal)                                                          \
+
+#define UV_REQ_TYPE_MAP(XX)                                                   \
+  XX(REQ, req)                                                                \
+  XX(CONNECT, connect)                                                        \
+  XX(WRITE, write)                                                            \
+  XX(SHUTDOWN, shutdown)                                                      \
+  XX(UDP_SEND, udp_send)                                                      \
+  XX(FS, fs)                                                                  \
+  XX(WORK, work)                                                              \
+  XX(GETADDRINFO, getaddrinfo)                                                \
+  XX(GETNAMEINFO, getnameinfo)                                                \
+
+typedef enum {
+#define XX(code, _) UV_ ## code = UV__ ## code,
+  UV_ERRNO_MAP(XX)
+#undef XX
+  UV_ERRNO_MAX = UV__EOF - 1
+} uv_errno_t;
+
+typedef enum {
+  UV_UNKNOWN_HANDLE = 0,
+#define XX(uc, lc) UV_##uc,
+  UV_HANDLE_TYPE_MAP(XX)
+#undef XX
+  UV_FILE,
+  UV_HANDLE_TYPE_MAX
+} uv_handle_type;
+
+typedef enum {
+  UV_UNKNOWN_REQ = 0,
+#define XX(uc, lc) UV_##uc,
+  UV_REQ_TYPE_MAP(XX)
+#undef XX
+  UV_REQ_TYPE_PRIVATE
+  UV_REQ_TYPE_MAX
+} uv_req_type;
+
+
+/* Handle types. */
+typedef struct uv_loop_s uv_loop_t;
+typedef struct uv_handle_s uv_handle_t;
+typedef struct uv_stream_s uv_stream_t;
+typedef struct uv_tcp_s uv_tcp_t;
+typedef struct uv_udp_s uv_udp_t;
+typedef struct uv_pipe_s uv_pipe_t;
+typedef struct uv_tty_s uv_tty_t;
+typedef struct uv_poll_s uv_poll_t;
+typedef struct uv_timer_s uv_timer_t;
+typedef struct uv_prepare_s uv_prepare_t;
+typedef struct uv_check_s uv_check_t;
+typedef struct uv_idle_s uv_idle_t;
+typedef struct uv_async_s uv_async_t;
+typedef struct uv_process_s uv_process_t;
+typedef struct uv_fs_event_s uv_fs_event_t;
+typedef struct uv_fs_poll_s uv_fs_poll_t;
+typedef struct uv_signal_s uv_signal_t;
+
+/* Request types. */
+typedef struct uv_req_s uv_req_t;
+typedef struct uv_getaddrinfo_s uv_getaddrinfo_t;
+typedef struct uv_getnameinfo_s uv_getnameinfo_t;
+typedef struct uv_shutdown_s uv_shutdown_t;
+typedef struct uv_write_s uv_write_t;
+typedef struct uv_connect_s uv_connect_t;
+typedef struct uv_udp_send_s uv_udp_send_t;
+typedef struct uv_fs_s uv_fs_t;
+typedef struct uv_work_s uv_work_t;
+
+/* None of the above. */
+typedef struct uv_cpu_info_s uv_cpu_info_t;
+typedef struct uv_interface_address_s uv_interface_address_t;
+typedef struct uv_dirent_s uv_dirent_t;
+typedef struct uv_passwd_s uv_passwd_t;
+
+typedef enum {
+  UV_LOOP_BLOCK_SIGNAL
+} uv_loop_option;
+
+typedef enum {
+  UV_RUN_DEFAULT = 0,
+  UV_RUN_ONCE,
+  UV_RUN_NOWAIT
+} uv_run_mode;
+
+
+UV_EXTERN unsigned int uv_version(void);
+UV_EXTERN const char* uv_version_string(void);
+
+typedef void* (*uv_malloc_func)(size_t size);
+typedef void* (*uv_realloc_func)(void* ptr, size_t size);
+typedef void* (*uv_calloc_func)(size_t count, size_t size);
+typedef void (*uv_free_func)(void* ptr);
+
+UV_EXTERN int uv_replace_allocator(uv_malloc_func malloc_func,
+                                   uv_realloc_func realloc_func,
+                                   uv_calloc_func calloc_func,
+                                   uv_free_func free_func);
+
+UV_EXTERN uv_loop_t* uv_default_loop(void);
+UV_EXTERN int uv_loop_init(uv_loop_t* loop);
+UV_EXTERN int uv_loop_close(uv_loop_t* loop);
+/*
+ * NOTE:
+ *  This function is DEPRECATED (to be removed after 0.12), users should
+ *  allocate the loop manually and use uv_loop_init instead.
+ */
+UV_EXTERN uv_loop_t* uv_loop_new(void);
+/*
+ * NOTE:
+ *  This function is DEPRECATED (to be removed after 0.12). Users should use
+ *  uv_loop_close and free the memory manually instead.
+ */
+UV_EXTERN void uv_loop_delete(uv_loop_t*);
+UV_EXTERN size_t uv_loop_size(void);
+UV_EXTERN int uv_loop_alive(const uv_loop_t* loop);
+UV_EXTERN int uv_loop_configure(uv_loop_t* loop, uv_loop_option option, ...);
+UV_EXTERN int uv_loop_fork(uv_loop_t* loop);
+
+UV_EXTERN int uv_run(uv_loop_t*, uv_run_mode mode);
+UV_EXTERN void uv_stop(uv_loop_t*);
+
+UV_EXTERN void uv_ref(uv_handle_t*);
+UV_EXTERN void uv_unref(uv_handle_t*);
+UV_EXTERN int uv_has_ref(const uv_handle_t*);
+
+UV_EXTERN void uv_update_time(uv_loop_t*);
+UV_EXTERN uint64_t uv_now(const uv_loop_t*);
+
+UV_EXTERN int uv_backend_fd(const uv_loop_t*);
+UV_EXTERN int uv_backend_timeout(const uv_loop_t*);
+
+typedef void (*uv_alloc_cb)(uv_handle_t* handle,
+                            size_t suggested_size,
+                            uv_buf_t* buf);
+typedef void (*uv_read_cb)(uv_stream_t* stream,
+                           ssize_t nread,
+                           const uv_buf_t* buf);
+typedef void (*uv_write_cb)(uv_write_t* req, int status);
+typedef void (*uv_connect_cb)(uv_connect_t* req, int status);
+typedef void (*uv_shutdown_cb)(uv_shutdown_t* req, int status);
+typedef void (*uv_connection_cb)(uv_stream_t* server, int status);
+typedef void (*uv_close_cb)(uv_handle_t* handle);
+typedef void (*uv_poll_cb)(uv_poll_t* handle, int status, int events);
+typedef void (*uv_timer_cb)(uv_timer_t* handle);
+typedef void (*uv_async_cb)(uv_async_t* handle);
+typedef void (*uv_prepare_cb)(uv_prepare_t* handle);
+typedef void (*uv_check_cb)(uv_check_t* handle);
+typedef void (*uv_idle_cb)(uv_idle_t* handle);
+typedef void (*uv_exit_cb)(uv_process_t*, int64_t exit_status, int term_signal);
+typedef void (*uv_walk_cb)(uv_handle_t* handle, void* arg);
+typedef void (*uv_fs_cb)(uv_fs_t* req);
+typedef void (*uv_work_cb)(uv_work_t* req);
+typedef void (*uv_after_work_cb)(uv_work_t* req, int status);
+typedef void (*uv_getaddrinfo_cb)(uv_getaddrinfo_t* req,
+                                  int status,
+                                  struct addrinfo* res);
+typedef void (*uv_getnameinfo_cb)(uv_getnameinfo_t* req,
+                                  int status,
+                                  const char* hostname,
+                                  const char* service);
+
+typedef struct {
+  long tv_sec;
+  long tv_nsec;
+} uv_timespec_t;
+
+
+typedef struct {
+  uint64_t st_dev;
+  uint64_t st_mode;
+  uint64_t st_nlink;
+  uint64_t st_uid;
+  uint64_t st_gid;
+  uint64_t st_rdev;
+  uint64_t st_ino;
+  uint64_t st_size;
+  uint64_t st_blksize;
+  uint64_t st_blocks;
+  uint64_t st_flags;
+  uint64_t st_gen;
+  uv_timespec_t st_atim;
+  uv_timespec_t st_mtim;
+  uv_timespec_t st_ctim;
+  uv_timespec_t st_birthtim;
+} uv_stat_t;
+
+
+typedef void (*uv_fs_event_cb)(uv_fs_event_t* handle,
+                               const char* filename,
+                               int events,
+                               int status);
+
+typedef void (*uv_fs_poll_cb)(uv_fs_poll_t* handle,
+                              int status,
+                              const uv_stat_t* prev,
+                              const uv_stat_t* curr);
+
+typedef void (*uv_signal_cb)(uv_signal_t* handle, int signum);
+
+
+typedef enum {
+  UV_LEAVE_GROUP = 0,
+  UV_JOIN_GROUP
+} uv_membership;
+
+
+UV_EXTERN int uv_translate_sys_error(int sys_errno);
+
+UV_EXTERN const char* uv_strerror(int err);
+UV_EXTERN const char* uv_err_name(int err);
+
+
+#define UV_REQ_FIELDS                                                         \
+  /* public */                                                                \
+  void* data;                                                                 \
+  /* read-only */                                                             \
+  uv_req_type type;                                                           \
+  /* private */                                                               \
+  void* reserved[6];                                                          \
+  UV_REQ_PRIVATE_FIELDS                                                       \
+
+/* Abstract base class of all requests. */
+struct uv_req_s {
+  UV_REQ_FIELDS
+};
+
+
+/* Platform-specific request types. */
+UV_PRIVATE_REQ_TYPES
+
+
+UV_EXTERN int uv_shutdown(uv_shutdown_t* req,
+                          uv_stream_t* handle,
+                          uv_shutdown_cb cb);
+
+struct uv_shutdown_s {
+  UV_REQ_FIELDS
+  uv_stream_t* handle;
+  uv_shutdown_cb cb;
+  UV_SHUTDOWN_PRIVATE_FIELDS
+};
+
+
+#define UV_HANDLE_FIELDS                                                      \
+  /* public */                                                                \
+  void* data;                                                                 \
+  /* read-only */                                                             \
+  uv_loop_t* loop;                                                            \
+  uv_handle_type type;                                                        \
+  /* private */                                                               \
+  uv_close_cb close_cb;                                                       \
+  void* handle_queue[2];                                                      \
+  union {                                                                     \
+    int fd;                                                                   \
+    void* reserved[4];                                                        \
+  } u;                                                                        \
+  UV_HANDLE_PRIVATE_FIELDS                                                    \
+
+/* The abstract base class of all handles. */
+struct uv_handle_s {
+  UV_HANDLE_FIELDS
+};
+
+UV_EXTERN size_t uv_handle_size(uv_handle_type type);
+UV_EXTERN uv_handle_type uv_handle_get_type(const uv_handle_t* handle);
+UV_EXTERN const char* uv_handle_type_name(uv_handle_type type);
+UV_EXTERN void* uv_handle_get_data(const uv_handle_t* handle);
+UV_EXTERN uv_loop_t* uv_handle_get_loop(const uv_handle_t* handle);
+UV_EXTERN void uv_handle_set_data(uv_handle_t* handle, void* data);
+
+UV_EXTERN size_t uv_req_size(uv_req_type type);
+UV_EXTERN void* uv_req_get_data(const uv_req_t* req);
+UV_EXTERN void uv_req_set_data(uv_req_t* req, void* data);
+UV_EXTERN uv_req_type uv_req_get_type(const uv_req_t* req);
+UV_EXTERN const char* uv_req_type_name(uv_req_type type);
+
+UV_EXTERN int uv_is_active(const uv_handle_t* handle);
+
+UV_EXTERN void uv_walk(uv_loop_t* loop, uv_walk_cb walk_cb, void* arg);
+
+/* Helpers for ad hoc debugging, no API/ABI stability guaranteed. */
+UV_EXTERN void uv_print_all_handles(uv_loop_t* loop, FILE* stream);
+UV_EXTERN void uv_print_active_handles(uv_loop_t* loop, FILE* stream);
+
+UV_EXTERN void uv_close(uv_handle_t* handle, uv_close_cb close_cb);
+
+UV_EXTERN int uv_send_buffer_size(uv_handle_t* handle, int* value);
+UV_EXTERN int uv_recv_buffer_size(uv_handle_t* handle, int* value);
+
+UV_EXTERN int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd);
+
+UV_EXTERN uv_buf_t uv_buf_init(char* base, unsigned int len);
+
+
+#define UV_STREAM_FIELDS                                                      \
+  /* number of bytes queued for writing */                                    \
+  size_t write_queue_size;                                                    \
+  uv_alloc_cb alloc_cb;                                                       \
+  uv_read_cb read_cb;                                                         \
+  /* private */                                                               \
+  UV_STREAM_PRIVATE_FIELDS
+
+/*
+ * uv_stream_t is a subclass of uv_handle_t.
+ *
+ * uv_stream is an abstract class.
+ *
+ * uv_stream_t is the parent class of uv_tcp_t, uv_pipe_t and uv_tty_t.
+ */
+struct uv_stream_s {
+  UV_HANDLE_FIELDS
+  UV_STREAM_FIELDS
+};
+
+UV_EXTERN size_t uv_stream_get_write_queue_size(const uv_stream_t* stream);
+
+UV_EXTERN int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb);
+UV_EXTERN int uv_accept(uv_stream_t* server, uv_stream_t* client);
+
+UV_EXTERN int uv_read_start(uv_stream_t*,
+                            uv_alloc_cb alloc_cb,
+                            uv_read_cb read_cb);
+UV_EXTERN int uv_read_stop(uv_stream_t*);
+
+UV_EXTERN int uv_write(uv_write_t* req,
+                       uv_stream_t* handle,
+                       const uv_buf_t bufs[],
+                       unsigned int nbufs,
+                       uv_write_cb cb);
+UV_EXTERN int uv_write2(uv_write_t* req,
+                        uv_stream_t* handle,
+                        const uv_buf_t bufs[],
+                        unsigned int nbufs,
+                        uv_stream_t* send_handle,
+                        uv_write_cb cb);
+UV_EXTERN int uv_try_write(uv_stream_t* handle,
+                           const uv_buf_t bufs[],
+                           unsigned int nbufs);
+
+/* uv_write_t is a subclass of uv_req_t. */
+struct uv_write_s {
+  UV_REQ_FIELDS
+  uv_write_cb cb;
+  uv_stream_t* send_handle; /* TODO: make private and unix-only in v2.x. */
+  uv_stream_t* handle;
+  UV_WRITE_PRIVATE_FIELDS
+};
+
+
+UV_EXTERN int uv_is_readable(const uv_stream_t* handle);
+UV_EXTERN int uv_is_writable(const uv_stream_t* handle);
+
+UV_EXTERN int uv_stream_set_blocking(uv_stream_t* handle, int blocking);
+
+UV_EXTERN int uv_is_closing(const uv_handle_t* handle);
+
+
+/*
+ * uv_tcp_t is a subclass of uv_stream_t.
+ *
+ * Represents a TCP stream or TCP server.
+ */
+struct uv_tcp_s {
+  UV_HANDLE_FIELDS
+  UV_STREAM_FIELDS
+  UV_TCP_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_tcp_init(uv_loop_t*, uv_tcp_t* handle);
+UV_EXTERN int uv_tcp_init_ex(uv_loop_t*, uv_tcp_t* handle, unsigned int flags);
+UV_EXTERN int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock);
+UV_EXTERN int uv_tcp_nodelay(uv_tcp_t* handle, int enable);
+UV_EXTERN int uv_tcp_keepalive(uv_tcp_t* handle,
+                               int enable,
+                               unsigned int delay);
+UV_EXTERN int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable);
+
+enum uv_tcp_flags {
+  /* Used with uv_tcp_bind, when an IPv6 address is used. */
+  UV_TCP_IPV6ONLY = 1
+};
+
+UV_EXTERN int uv_tcp_bind(uv_tcp_t* handle,
+                          const struct sockaddr* addr,
+                          unsigned int flags);
+UV_EXTERN int uv_tcp_getsockname(const uv_tcp_t* handle,
+                                 struct sockaddr* name,
+                                 int* namelen);
+UV_EXTERN int uv_tcp_getpeername(const uv_tcp_t* handle,
+                                 struct sockaddr* name,
+                                 int* namelen);
+UV_EXTERN int uv_tcp_connect(uv_connect_t* req,
+                             uv_tcp_t* handle,
+                             const struct sockaddr* addr,
+                             uv_connect_cb cb);
+
+/* uv_connect_t is a subclass of uv_req_t. */
+struct uv_connect_s {
+  UV_REQ_FIELDS
+  uv_connect_cb cb;
+  uv_stream_t* handle;
+  UV_CONNECT_PRIVATE_FIELDS
+};
+
+
+/*
+ * UDP support.
+ */
+
+enum uv_udp_flags {
+  /* Disables dual stack mode. */
+  UV_UDP_IPV6ONLY = 1,
+  /*
+   * Indicates message was truncated because read buffer was too small. The
+   * remainder was discarded by the OS. Used in uv_udp_recv_cb.
+   */
+  UV_UDP_PARTIAL = 2,
+  /*
+   * Indicates if SO_REUSEADDR will be set when binding the handle.
+   * This sets the SO_REUSEPORT socket flag on the BSDs and OS X. On other
+   * Unix platforms, it sets the SO_REUSEADDR flag.  What that means is that
+   * multiple threads or processes can bind to the same address without error
+   * (provided they all set the flag) but only the last one to bind will receive
+   * any traffic, in effect "stealing" the port from the previous listener.
+   */
+  UV_UDP_REUSEADDR = 4
+};
+
+typedef void (*uv_udp_send_cb)(uv_udp_send_t* req, int status);
+typedef void (*uv_udp_recv_cb)(uv_udp_t* handle,
+                               ssize_t nread,
+                               const uv_buf_t* buf,
+                               const struct sockaddr* addr,
+                               unsigned flags);
+
+/* uv_udp_t is a subclass of uv_handle_t. */
+struct uv_udp_s {
+  UV_HANDLE_FIELDS
+  /* read-only */
+  /*
+   * Number of bytes queued for sending. This field strictly shows how much
+   * information is currently queued.
+   */
+  size_t send_queue_size;
+  /*
+   * Number of send requests currently in the queue awaiting to be processed.
+   */
+  size_t send_queue_count;
+  UV_UDP_PRIVATE_FIELDS
+};
+
+/* uv_udp_send_t is a subclass of uv_req_t. */
+struct uv_udp_send_s {
+  UV_REQ_FIELDS
+  uv_udp_t* handle;
+  uv_udp_send_cb cb;
+  UV_UDP_SEND_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_udp_init(uv_loop_t*, uv_udp_t* handle);
+UV_EXTERN int uv_udp_init_ex(uv_loop_t*, uv_udp_t* handle, unsigned int flags);
+UV_EXTERN int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock);
+UV_EXTERN int uv_udp_bind(uv_udp_t* handle,
+                          const struct sockaddr* addr,
+                          unsigned int flags);
+
+UV_EXTERN int uv_udp_getsockname(const uv_udp_t* handle,
+                                 struct sockaddr* name,
+                                 int* namelen);
+UV_EXTERN int uv_udp_set_membership(uv_udp_t* handle,
+                                    const char* multicast_addr,
+                                    const char* interface_addr,
+                                    uv_membership membership);
+UV_EXTERN int uv_udp_set_multicast_loop(uv_udp_t* handle, int on);
+UV_EXTERN int uv_udp_set_multicast_ttl(uv_udp_t* handle, int ttl);
+UV_EXTERN int uv_udp_set_multicast_interface(uv_udp_t* handle,
+                                             const char* interface_addr);
+UV_EXTERN int uv_udp_set_broadcast(uv_udp_t* handle, int on);
+UV_EXTERN int uv_udp_set_ttl(uv_udp_t* handle, int ttl);
+UV_EXTERN int uv_udp_send(uv_udp_send_t* req,
+                          uv_udp_t* handle,
+                          const uv_buf_t bufs[],
+                          unsigned int nbufs,
+                          const struct sockaddr* addr,
+                          uv_udp_send_cb send_cb);
+UV_EXTERN int uv_udp_try_send(uv_udp_t* handle,
+                              const uv_buf_t bufs[],
+                              unsigned int nbufs,
+                              const struct sockaddr* addr);
+UV_EXTERN int uv_udp_recv_start(uv_udp_t* handle,
+                                uv_alloc_cb alloc_cb,
+                                uv_udp_recv_cb recv_cb);
+UV_EXTERN int uv_udp_recv_stop(uv_udp_t* handle);
+UV_EXTERN size_t uv_udp_get_send_queue_size(const uv_udp_t* handle);
+UV_EXTERN size_t uv_udp_get_send_queue_count(const uv_udp_t* handle);
+
+
+/*
+ * uv_tty_t is a subclass of uv_stream_t.
+ *
+ * Representing a stream for the console.
+ */
+struct uv_tty_s {
+  UV_HANDLE_FIELDS
+  UV_STREAM_FIELDS
+  UV_TTY_PRIVATE_FIELDS
+};
+
+typedef enum {
+  /* Initial/normal terminal mode */
+  UV_TTY_MODE_NORMAL,
+  /* Raw input mode (On Windows, ENABLE_WINDOW_INPUT is also enabled) */
+  UV_TTY_MODE_RAW,
+  /* Binary-safe I/O mode for IPC (Unix-only) */
+  UV_TTY_MODE_IO
+} uv_tty_mode_t;
+
+UV_EXTERN int uv_tty_init(uv_loop_t*, uv_tty_t*, uv_file fd, int readable);
+UV_EXTERN int uv_tty_set_mode(uv_tty_t*, uv_tty_mode_t mode);
+UV_EXTERN int uv_tty_reset_mode(void);
+UV_EXTERN int uv_tty_get_winsize(uv_tty_t*, int* width, int* height);
+
+inline int uv_tty_set_mode(uv_tty_t* handle, int mode) {
+  return uv_tty_set_mode(handle, static_cast<uv_tty_mode_t>(mode));
+}
+
+UV_EXTERN uv_handle_type uv_guess_handle(uv_file file);
+
+/*
+ * uv_pipe_t is a subclass of uv_stream_t.
+ *
+ * Representing a pipe stream or pipe server. On Windows this is a Named
+ * Pipe. On Unix this is a Unix domain socket.
+ */
+struct uv_pipe_s {
+  UV_HANDLE_FIELDS
+  UV_STREAM_FIELDS
+  int ipc; /* non-zero if this pipe is used for passing handles */
+  UV_PIPE_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_pipe_init(uv_loop_t*, uv_pipe_t* handle, int ipc);
+UV_EXTERN int uv_pipe_open(uv_pipe_t*, uv_file file);
+UV_EXTERN int uv_pipe_bind(uv_pipe_t* handle, const char* name);
+UV_EXTERN void uv_pipe_connect(uv_connect_t* req,
+                               uv_pipe_t* handle,
+                               const char* name,
+                               uv_connect_cb cb);
+UV_EXTERN int uv_pipe_getsockname(const uv_pipe_t* handle,
+                                  char* buffer,
+                                  size_t* size);
+UV_EXTERN int uv_pipe_getpeername(const uv_pipe_t* handle,
+                                  char* buffer,
+                                  size_t* size);
+UV_EXTERN void uv_pipe_pending_instances(uv_pipe_t* handle, int count);
+UV_EXTERN int uv_pipe_pending_count(uv_pipe_t* handle);
+UV_EXTERN uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle);
+UV_EXTERN int uv_pipe_chmod(uv_pipe_t* handle, int flags);
+
+
+struct uv_poll_s {
+  UV_HANDLE_FIELDS
+  uv_poll_cb poll_cb;
+  UV_POLL_PRIVATE_FIELDS
+};
+
+enum uv_poll_event {
+  UV_READABLE = 1,
+  UV_WRITABLE = 2,
+  UV_DISCONNECT = 4,
+  UV_PRIORITIZED = 8
+};
+
+UV_EXTERN int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd);
+UV_EXTERN int uv_poll_init_socket(uv_loop_t* loop,
+                                  uv_poll_t* handle,
+                                  uv_os_sock_t socket);
+UV_EXTERN int uv_poll_start(uv_poll_t* handle, int events, uv_poll_cb cb);
+UV_EXTERN int uv_poll_stop(uv_poll_t* handle);
+
+
+struct uv_prepare_s {
+  UV_HANDLE_FIELDS
+  UV_PREPARE_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_prepare_init(uv_loop_t*, uv_prepare_t* prepare);
+UV_EXTERN int uv_prepare_start(uv_prepare_t* prepare, uv_prepare_cb cb);
+UV_EXTERN int uv_prepare_stop(uv_prepare_t* prepare);
+
+
+struct uv_check_s {
+  UV_HANDLE_FIELDS
+  UV_CHECK_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_check_init(uv_loop_t*, uv_check_t* check);
+UV_EXTERN int uv_check_start(uv_check_t* check, uv_check_cb cb);
+UV_EXTERN int uv_check_stop(uv_check_t* check);
+
+
+struct uv_idle_s {
+  UV_HANDLE_FIELDS
+  UV_IDLE_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_idle_init(uv_loop_t*, uv_idle_t* idle);
+UV_EXTERN int uv_idle_start(uv_idle_t* idle, uv_idle_cb cb);
+UV_EXTERN int uv_idle_stop(uv_idle_t* idle);
+
+
+struct uv_async_s {
+  UV_HANDLE_FIELDS
+  UV_ASYNC_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_async_init(uv_loop_t*,
+                            uv_async_t* async,
+                            uv_async_cb async_cb);
+UV_EXTERN int uv_async_send(uv_async_t* async);
+
+
+/*
+ * uv_timer_t is a subclass of uv_handle_t.
+ *
+ * Used to get woken up at a specified time in the future.
+ */
+struct uv_timer_s {
+  UV_HANDLE_FIELDS
+  UV_TIMER_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_timer_init(uv_loop_t*, uv_timer_t* handle);
+UV_EXTERN int uv_timer_start(uv_timer_t* handle,
+                             uv_timer_cb cb,
+                             uint64_t timeout,
+                             uint64_t repeat);
+UV_EXTERN int uv_timer_stop(uv_timer_t* handle);
+UV_EXTERN int uv_timer_again(uv_timer_t* handle);
+UV_EXTERN void uv_timer_set_repeat(uv_timer_t* handle, uint64_t repeat);
+UV_EXTERN uint64_t uv_timer_get_repeat(const uv_timer_t* handle);
+
+
+/*
+ * uv_getaddrinfo_t is a subclass of uv_req_t.
+ *
+ * Request object for uv_getaddrinfo.
+ */
+struct uv_getaddrinfo_s {
+  UV_REQ_FIELDS
+  /* read-only */
+  uv_loop_t* loop;
+  /* struct addrinfo* addrinfo is marked as private, but it really isn't. */
+  UV_GETADDRINFO_PRIVATE_FIELDS
+};
+
+
+UV_EXTERN int uv_getaddrinfo(uv_loop_t* loop,
+                             uv_getaddrinfo_t* req,
+                             uv_getaddrinfo_cb getaddrinfo_cb,
+                             const char* node,
+                             const char* service,
+                             const struct addrinfo* hints);
+UV_EXTERN void uv_freeaddrinfo(struct addrinfo* ai);
+
+
+/*
+* uv_getnameinfo_t is a subclass of uv_req_t.
+*
+* Request object for uv_getnameinfo.
+*/
+struct uv_getnameinfo_s {
+  UV_REQ_FIELDS
+  /* read-only */
+  uv_loop_t* loop;
+  /* host and service are marked as private, but they really aren't. */
+  UV_GETNAMEINFO_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_getnameinfo(uv_loop_t* loop,
+                             uv_getnameinfo_t* req,
+                             uv_getnameinfo_cb getnameinfo_cb,
+                             const struct sockaddr* addr,
+                             int flags);
+
+
+/* uv_spawn() options. */
+typedef enum {
+  UV_IGNORE         = 0x00,
+  UV_CREATE_PIPE    = 0x01,
+  UV_INHERIT_FD     = 0x02,
+  UV_INHERIT_STREAM = 0x04,
+
+  /*
+   * When UV_CREATE_PIPE is specified, UV_READABLE_PIPE and UV_WRITABLE_PIPE
+   * determine the direction of flow, from the child process' perspective. Both
+   * flags may be specified to create a duplex data stream.
+   */
+  UV_READABLE_PIPE  = 0x10,
+  UV_WRITABLE_PIPE  = 0x20,
+
+  /*
+   * Open the child pipe handle in overlapped mode on Windows.
+   * On Unix it is silently ignored.
+   */
+  UV_OVERLAPPED_PIPE = 0x40
+} uv_stdio_flags;
+
+typedef struct uv_stdio_container_s {
+  uv_stdio_flags flags;
+
+  union {
+    uv_stream_t* stream;
+    int fd;
+  } data;
+} uv_stdio_container_t;
+
+typedef struct uv_process_options_s {
+  uv_exit_cb exit_cb; /* Called after the process exits. */
+  const char* file;   /* Path to program to execute. */
+  /*
+   * Command line arguments. args[0] should be the path to the program. On
+   * Windows this uses CreateProcess which concatenates the arguments into a
+   * string this can cause some strange errors. See the note at
+   * windows_verbatim_arguments.
+   */
+  char** args;
+  /*
+   * This will be set as the environ variable in the subprocess. If this is
+   * NULL then the parents environ will be used.
+   */
+  char** env;
+  /*
+   * If non-null this represents a directory the subprocess should execute
+   * in. Stands for current working directory.
+   */
+  const char* cwd;
+  /*
+   * Various flags that control how uv_spawn() behaves. See the definition of
+   * `enum uv_process_flags` below.
+   */
+  unsigned int flags;
+  /*
+   * The `stdio` field points to an array of uv_stdio_container_t structs that
+   * describe the file descriptors that will be made available to the child
+   * process. The convention is that stdio[0] points to stdin, fd 1 is used for
+   * stdout, and fd 2 is stderr.
+   *
+   * Note that on windows file descriptors greater than 2 are available to the
+   * child process only if the child processes uses the MSVCRT runtime.
+   */
+  int stdio_count;
+  uv_stdio_container_t* stdio;
+  /*
+   * Libuv can change the child process' user/group id. This happens only when
+   * the appropriate bits are set in the flags fields. This is not supported on
+   * windows; uv_spawn() will fail and set the error to UV_ENOTSUP.
+   */
+  uv_uid_t uid;
+  uv_gid_t gid;
+} uv_process_options_t;
+
+/*
+ * These are the flags that can be used for the uv_process_options.flags field.
+ */
+enum uv_process_flags {
+  /*
+   * Set the child process' user id. The user id is supplied in the `uid` field
+   * of the options struct. This does not work on windows; setting this flag
+   * will cause uv_spawn() to fail.
+   */
+  UV_PROCESS_SETUID = (1 << 0),
+  /*
+   * Set the child process' group id. The user id is supplied in the `gid`
+   * field of the options struct. This does not work on windows; setting this
+   * flag will cause uv_spawn() to fail.
+   */
+  UV_PROCESS_SETGID = (1 << 1),
+  /*
+   * Do not wrap any arguments in quotes, or perform any other escaping, when
+   * converting the argument list into a command line string. This option is
+   * only meaningful on Windows systems. On Unix it is silently ignored.
+   */
+  UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS = (1 << 2),
+  /*
+   * Spawn the child process in a detached state - this will make it a process
+   * group leader, and will effectively enable the child to keep running after
+   * the parent exits.  Note that the child process will still keep the
+   * parent's event loop alive unless the parent process calls uv_unref() on
+   * the child's process handle.
+   */
+  UV_PROCESS_DETACHED = (1 << 3),
+  /*
+   * Hide the subprocess console window that would normally be created. This
+   * option is only meaningful on Windows systems. On Unix it is silently
+   * ignored.
+   */
+  UV_PROCESS_WINDOWS_HIDE = (1 << 4)
+};
+
+/*
+ * uv_process_t is a subclass of uv_handle_t.
+ */
+struct uv_process_s {
+  UV_HANDLE_FIELDS
+  uv_exit_cb exit_cb;
+  int pid;
+  UV_PROCESS_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_spawn(uv_loop_t* loop,
+                       uv_process_t* handle,
+                       const uv_process_options_t* options);
+UV_EXTERN int uv_process_kill(uv_process_t*, int signum);
+UV_EXTERN int uv_kill(int pid, int signum);
+UV_EXTERN uv_pid_t uv_process_get_pid(const uv_process_t*);
+
+
+/*
+ * uv_work_t is a subclass of uv_req_t.
+ */
+struct uv_work_s {
+  UV_REQ_FIELDS
+  uv_loop_t* loop;
+  uv_work_cb work_cb;
+  uv_after_work_cb after_work_cb;
+  UV_WORK_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_queue_work(uv_loop_t* loop,
+                            uv_work_t* req,
+                            uv_work_cb work_cb,
+                            uv_after_work_cb after_work_cb);
+
+UV_EXTERN int uv_cancel(uv_req_t* req);
+
+
+struct uv_cpu_times_s {
+  uint64_t user;
+  uint64_t nice;
+  uint64_t sys;
+  uint64_t idle;
+  uint64_t irq;
+};
+
+struct uv_cpu_info_s {
+  char* model;
+  int speed;
+  struct uv_cpu_times_s cpu_times;
+};
+
+struct uv_interface_address_s {
+  char* name;
+  char phys_addr[6];
+  int is_internal;
+  union {
+    struct sockaddr_in address4;
+    struct sockaddr_in6 address6;
+  } address;
+  union {
+    struct sockaddr_in netmask4;
+    struct sockaddr_in6 netmask6;
+  } netmask;
+};
+
+struct uv_passwd_s {
+  char* username;
+  long uid;
+  long gid;
+  char* shell;
+  char* homedir;
+};
+
+typedef enum {
+  UV_DIRENT_UNKNOWN,
+  UV_DIRENT_FILE,
+  UV_DIRENT_DIR,
+  UV_DIRENT_LINK,
+  UV_DIRENT_FIFO,
+  UV_DIRENT_SOCKET,
+  UV_DIRENT_CHAR,
+  UV_DIRENT_BLOCK
+} uv_dirent_type_t;
+
+struct uv_dirent_s {
+  const char* name;
+  uv_dirent_type_t type;
+};
+
+UV_EXTERN char** uv_setup_args(int argc, char** argv);
+UV_EXTERN int uv_get_process_title(char* buffer, size_t size);
+UV_EXTERN int uv_set_process_title(const char* title);
+UV_EXTERN int uv_resident_set_memory(size_t* rss);
+UV_EXTERN int uv_uptime(double* uptime);
+UV_EXTERN uv_os_fd_t uv_get_osfhandle(int fd);
+
+typedef struct {
+  long tv_sec;
+  long tv_usec;
+} uv_timeval_t;
+
+typedef struct {
+   uv_timeval_t ru_utime; /* user CPU time used */
+   uv_timeval_t ru_stime; /* system CPU time used */
+   uint64_t ru_maxrss;    /* maximum resident set size */
+   uint64_t ru_ixrss;     /* integral shared memory size */
+   uint64_t ru_idrss;     /* integral unshared data size */
+   uint64_t ru_isrss;     /* integral unshared stack size */
+   uint64_t ru_minflt;    /* page reclaims (soft page faults) */
+   uint64_t ru_majflt;    /* page faults (hard page faults) */
+   uint64_t ru_nswap;     /* swaps */
+   uint64_t ru_inblock;   /* block input operations */
+   uint64_t ru_oublock;   /* block output operations */
+   uint64_t ru_msgsnd;    /* IPC messages sent */
+   uint64_t ru_msgrcv;    /* IPC messages received */
+   uint64_t ru_nsignals;  /* signals received */
+   uint64_t ru_nvcsw;     /* voluntary context switches */
+   uint64_t ru_nivcsw;    /* involuntary context switches */
+} uv_rusage_t;
+
+UV_EXTERN int uv_getrusage(uv_rusage_t* rusage);
+
+UV_EXTERN int uv_os_homedir(char* buffer, size_t* size);
+UV_EXTERN int uv_os_tmpdir(char* buffer, size_t* size);
+UV_EXTERN int uv_os_get_passwd(uv_passwd_t* pwd);
+UV_EXTERN void uv_os_free_passwd(uv_passwd_t* pwd);
+UV_EXTERN uv_pid_t uv_os_getpid(void);
+UV_EXTERN uv_pid_t uv_os_getppid(void);
+
+UV_EXTERN int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count);
+UV_EXTERN void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count);
+
+UV_EXTERN int uv_interface_addresses(uv_interface_address_t** addresses,
+                                     int* count);
+UV_EXTERN void uv_free_interface_addresses(uv_interface_address_t* addresses,
+                                           int count);
+
+UV_EXTERN int uv_os_getenv(const char* name, char* buffer, size_t* size);
+UV_EXTERN int uv_os_setenv(const char* name, const char* value);
+UV_EXTERN int uv_os_unsetenv(const char* name);
+
+UV_EXTERN int uv_os_gethostname(char* buffer, size_t* size);
+
+
+typedef enum {
+  UV_FS_UNKNOWN = -1,
+  UV_FS_CUSTOM,
+  UV_FS_OPEN,
+  UV_FS_CLOSE,
+  UV_FS_READ,
+  UV_FS_WRITE,
+  UV_FS_SENDFILE,
+  UV_FS_STAT,
+  UV_FS_LSTAT,
+  UV_FS_FSTAT,
+  UV_FS_FTRUNCATE,
+  UV_FS_UTIME,
+  UV_FS_FUTIME,
+  UV_FS_ACCESS,
+  UV_FS_CHMOD,
+  UV_FS_FCHMOD,
+  UV_FS_FSYNC,
+  UV_FS_FDATASYNC,
+  UV_FS_UNLINK,
+  UV_FS_RMDIR,
+  UV_FS_MKDIR,
+  UV_FS_MKDTEMP,
+  UV_FS_RENAME,
+  UV_FS_SCANDIR,
+  UV_FS_LINK,
+  UV_FS_SYMLINK,
+  UV_FS_READLINK,
+  UV_FS_CHOWN,
+  UV_FS_FCHOWN,
+  UV_FS_LCHOWN,
+  UV_FS_REALPATH,
+  UV_FS_COPYFILE
+} uv_fs_type;
+
+/* uv_fs_t is a subclass of uv_req_t. */
+struct uv_fs_s {
+  UV_REQ_FIELDS
+  uv_fs_type fs_type;
+  uv_loop_t* loop;
+  uv_fs_cb cb;
+  ssize_t result;
+  void* ptr;
+  const char* path;
+  uv_stat_t statbuf;  /* Stores the result of uv_fs_stat() and uv_fs_fstat(). */
+  UV_FS_PRIVATE_FIELDS
+};
+
+UV_EXTERN uv_fs_type uv_fs_get_type(const uv_fs_t*);
+UV_EXTERN ssize_t uv_fs_get_result(const uv_fs_t*);
+UV_EXTERN void* uv_fs_get_ptr(const uv_fs_t*);
+UV_EXTERN const char* uv_fs_get_path(const uv_fs_t*);
+UV_EXTERN uv_stat_t* uv_fs_get_statbuf(uv_fs_t*);
+
+UV_EXTERN void uv_fs_req_cleanup(uv_fs_t* req);
+UV_EXTERN int uv_fs_close(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          uv_file file,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_open(uv_loop_t* loop,
+                         uv_fs_t* req,
+                         const char* path,
+                         int flags,
+                         int mode,
+                         uv_fs_cb cb);
+UV_EXTERN int uv_fs_read(uv_loop_t* loop,
+                         uv_fs_t* req,
+                         uv_file file,
+                         const uv_buf_t bufs[],
+                         unsigned int nbufs,
+                         int64_t offset,
+                         uv_fs_cb cb);
+UV_EXTERN int uv_fs_unlink(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_write(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          uv_file file,
+                          const uv_buf_t bufs[],
+                          unsigned int nbufs,
+                          int64_t offset,
+                          uv_fs_cb cb);
+/*
+ * This flag can be used with uv_fs_copyfile() to return an error if the
+ * destination already exists.
+ */
+#define UV_FS_COPYFILE_EXCL   0x0001
+
+/*
+ * This flag can be used with uv_fs_copyfile() to attempt to create a reflink.
+ * If copy-on-write is not supported, a fallback copy mechanism is used.
+ */
+#define UV_FS_COPYFILE_FICLONE 0x0002
+
+/*
+ * This flag can be used with uv_fs_copyfile() to attempt to create a reflink.
+ * If copy-on-write is not supported, an error is returned.
+ */
+#define UV_FS_COPYFILE_FICLONE_FORCE 0x0004
+
+UV_EXTERN int uv_fs_copyfile(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             const char* path,
+                             const char* new_path,
+                             int flags,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_mkdir(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          int mode,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_mkdtemp(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            const char* tpl,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_rmdir(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_scandir(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            const char* path,
+                            int flags,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_scandir_next(uv_fs_t* req,
+                                 uv_dirent_t* ent);
+UV_EXTERN int uv_fs_stat(uv_loop_t* loop,
+                         uv_fs_t* req,
+                         const char* path,
+                         uv_fs_cb cb);
+UV_EXTERN int uv_fs_fstat(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          uv_file file,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_rename(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           const char* new_path,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_fsync(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          uv_file file,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_fdatasync(uv_loop_t* loop,
+                              uv_fs_t* req,
+                              uv_file file,
+                              uv_fs_cb cb);
+UV_EXTERN int uv_fs_ftruncate(uv_loop_t* loop,
+                              uv_fs_t* req,
+                              uv_file file,
+                              int64_t offset,
+                              uv_fs_cb cb);
+UV_EXTERN int uv_fs_sendfile(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             uv_file out_fd,
+                             uv_file in_fd,
+                             int64_t in_offset,
+                             size_t length,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_access(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           int mode,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_chmod(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          int mode,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_utime(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          double atime,
+                          double mtime,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_futime(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           uv_file file,
+                           double atime,
+                           double mtime,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_lstat(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_link(uv_loop_t* loop,
+                         uv_fs_t* req,
+                         const char* path,
+                         const char* new_path,
+                         uv_fs_cb cb);
+
+/*
+ * This flag can be used with uv_fs_symlink() on Windows to specify whether
+ * path argument points to a directory.
+ */
+#define UV_FS_SYMLINK_DIR          0x0001
+
+/*
+ * This flag can be used with uv_fs_symlink() on Windows to specify whether
+ * the symlink is to be created using junction points.
+ */
+#define UV_FS_SYMLINK_JUNCTION     0x0002
+
+UV_EXTERN int uv_fs_symlink(uv_loop_t* loop,
+                            uv_fs_t* req,
+                            const char* path,
+                            const char* new_path,
+                            int flags,
+                            uv_fs_cb cb);
+UV_EXTERN int uv_fs_readlink(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             const char* path,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_realpath(uv_loop_t* loop,
+                             uv_fs_t* req,
+                             const char* path,
+                             uv_fs_cb cb);
+UV_EXTERN int uv_fs_fchmod(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           uv_file file,
+                           int mode,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_chown(uv_loop_t* loop,
+                          uv_fs_t* req,
+                          const char* path,
+                          uv_uid_t uid,
+                          uv_gid_t gid,
+                          uv_fs_cb cb);
+UV_EXTERN int uv_fs_fchown(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           uv_file file,
+                           uv_uid_t uid,
+                           uv_gid_t gid,
+                           uv_fs_cb cb);
+UV_EXTERN int uv_fs_lchown(uv_loop_t* loop,
+                           uv_fs_t* req,
+                           const char* path,
+                           uv_uid_t uid,
+                           uv_gid_t gid,
+                           uv_fs_cb cb);
+
+
+enum uv_fs_event {
+  UV_RENAME = 1,
+  UV_CHANGE = 2
+};
+
+
+struct uv_fs_event_s {
+  UV_HANDLE_FIELDS
+  /* private */
+  char* path;
+  UV_FS_EVENT_PRIVATE_FIELDS
+};
+
+
+/*
+ * uv_fs_stat() based polling file watcher.
+ */
+struct uv_fs_poll_s {
+  UV_HANDLE_FIELDS
+  /* Private, don't touch. */
+  void* poll_ctx;
+};
+
+UV_EXTERN int uv_fs_poll_init(uv_loop_t* loop, uv_fs_poll_t* handle);
+UV_EXTERN int uv_fs_poll_start(uv_fs_poll_t* handle,
+                               uv_fs_poll_cb poll_cb,
+                               const char* path,
+                               unsigned int interval);
+UV_EXTERN int uv_fs_poll_stop(uv_fs_poll_t* handle);
+UV_EXTERN int uv_fs_poll_getpath(uv_fs_poll_t* handle,
+                                 char* buffer,
+                                 size_t* size);
+
+
+struct uv_signal_s {
+  UV_HANDLE_FIELDS
+  uv_signal_cb signal_cb;
+  int signum;
+  UV_SIGNAL_PRIVATE_FIELDS
+};
+
+UV_EXTERN int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle);
+UV_EXTERN int uv_signal_start(uv_signal_t* handle,
+                              uv_signal_cb signal_cb,
+                              int signum);
+UV_EXTERN int uv_signal_start_oneshot(uv_signal_t* handle,
+                                      uv_signal_cb signal_cb,
+                                      int signum);
+UV_EXTERN int uv_signal_stop(uv_signal_t* handle);
+
+UV_EXTERN void uv_loadavg(double avg[3]);
+
+
+/*
+ * Flags to be passed to uv_fs_event_start().
+ */
+enum uv_fs_event_flags {
+  /*
+   * By default, if the fs event watcher is given a directory name, we will
+   * watch for all events in that directory. This flags overrides this behavior
+   * and makes fs_event report only changes to the directory entry itself. This
+   * flag does not affect individual files watched.
+   * This flag is currently not implemented yet on any backend.
+   */
+  UV_FS_EVENT_WATCH_ENTRY = 1,
+
+  /*
+   * By default uv_fs_event will try to use a kernel interface such as inotify
+   * or kqueue to detect events. This may not work on remote filesystems such
+   * as NFS mounts. This flag makes fs_event fall back to calling stat() on a
+   * regular interval.
+   * This flag is currently not implemented yet on any backend.
+   */
+  UV_FS_EVENT_STAT = 2,
+
+  /*
+   * By default, event watcher, when watching directory, is not registering
+   * (is ignoring) changes in it's subdirectories.
+   * This flag will override this behaviour on platforms that support it.
+   */
+  UV_FS_EVENT_RECURSIVE = 4
+};
+
+
+UV_EXTERN int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle);
+UV_EXTERN int uv_fs_event_start(uv_fs_event_t* handle,
+                                uv_fs_event_cb cb,
+                                const char* path,
+                                unsigned int flags);
+UV_EXTERN int uv_fs_event_stop(uv_fs_event_t* handle);
+UV_EXTERN int uv_fs_event_getpath(uv_fs_event_t* handle,
+                                  char* buffer,
+                                  size_t* size);
+
+UV_EXTERN int uv_ip4_addr(const char* ip, int port, struct sockaddr_in* addr);
+UV_EXTERN int uv_ip6_addr(const char* ip, int port, struct sockaddr_in6* addr);
+
+UV_EXTERN int uv_ip4_name(const struct sockaddr_in* src, char* dst, size_t size);
+UV_EXTERN int uv_ip6_name(const struct sockaddr_in6* src, char* dst, size_t size);
+
+UV_EXTERN int uv_inet_ntop(int af, const void* src, char* dst, size_t size);
+UV_EXTERN int uv_inet_pton(int af, const char* src, void* dst);
+
+#if defined(IF_NAMESIZE)
+# define UV_IF_NAMESIZE (IF_NAMESIZE + 1)
+#elif defined(IFNAMSIZ)
+# define UV_IF_NAMESIZE (IFNAMSIZ + 1)
+#else
+# define UV_IF_NAMESIZE (16 + 1)
+#endif
+
+UV_EXTERN int uv_if_indextoname(unsigned int ifindex,
+                                char* buffer,
+                                size_t* size);
+UV_EXTERN int uv_if_indextoiid(unsigned int ifindex,
+                               char* buffer,
+                               size_t* size);
+
+UV_EXTERN int uv_exepath(char* buffer, size_t* size);
+
+UV_EXTERN int uv_cwd(char* buffer, size_t* size);
+
+UV_EXTERN int uv_chdir(const char* dir);
+
+UV_EXTERN uint64_t uv_get_free_memory(void);
+UV_EXTERN uint64_t uv_get_total_memory(void);
+
+UV_EXTERN uint64_t uv_hrtime(void);
+
+UV_EXTERN void uv_disable_stdio_inheritance(void);
+
+UV_EXTERN int uv_dlopen(const char* filename, uv_lib_t* lib);
+UV_EXTERN void uv_dlclose(uv_lib_t* lib);
+UV_EXTERN int uv_dlsym(uv_lib_t* lib, const char* name, void** ptr);
+UV_EXTERN const char* uv_dlerror(const uv_lib_t* lib);
+
+UV_EXTERN int uv_mutex_init(uv_mutex_t* handle);
+UV_EXTERN int uv_mutex_init_recursive(uv_mutex_t* handle);
+UV_EXTERN void uv_mutex_destroy(uv_mutex_t* handle);
+UV_EXTERN void uv_mutex_lock(uv_mutex_t* handle);
+UV_EXTERN int uv_mutex_trylock(uv_mutex_t* handle);
+UV_EXTERN void uv_mutex_unlock(uv_mutex_t* handle);
+
+UV_EXTERN int uv_rwlock_init(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_destroy(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_rdlock(uv_rwlock_t* rwlock);
+UV_EXTERN int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_rdunlock(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_wrlock(uv_rwlock_t* rwlock);
+UV_EXTERN int uv_rwlock_trywrlock(uv_rwlock_t* rwlock);
+UV_EXTERN void uv_rwlock_wrunlock(uv_rwlock_t* rwlock);
+
+UV_EXTERN int uv_sem_init(uv_sem_t* sem, unsigned int value);
+UV_EXTERN void uv_sem_destroy(uv_sem_t* sem);
+UV_EXTERN void uv_sem_post(uv_sem_t* sem);
+UV_EXTERN void uv_sem_wait(uv_sem_t* sem);
+UV_EXTERN int uv_sem_trywait(uv_sem_t* sem);
+
+UV_EXTERN int uv_cond_init(uv_cond_t* cond);
+UV_EXTERN void uv_cond_destroy(uv_cond_t* cond);
+UV_EXTERN void uv_cond_signal(uv_cond_t* cond);
+UV_EXTERN void uv_cond_broadcast(uv_cond_t* cond);
+
+UV_EXTERN int uv_barrier_init(uv_barrier_t* barrier, unsigned int count);
+UV_EXTERN void uv_barrier_destroy(uv_barrier_t* barrier);
+UV_EXTERN int uv_barrier_wait(uv_barrier_t* barrier);
+
+UV_EXTERN void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex);
+UV_EXTERN int uv_cond_timedwait(uv_cond_t* cond,
+                                uv_mutex_t* mutex,
+                                uint64_t timeout);
+
+UV_EXTERN void uv_once(uv_once_t* guard, void (*callback)(void));
+
+UV_EXTERN int uv_key_create(uv_key_t* key);
+UV_EXTERN void uv_key_delete(uv_key_t* key);
+UV_EXTERN void* uv_key_get(uv_key_t* key);
+UV_EXTERN void uv_key_set(uv_key_t* key, void* value);
+
+typedef void (*uv_thread_cb)(void* arg);
+
+UV_EXTERN int uv_thread_create(uv_thread_t* tid, uv_thread_cb entry, void* arg);
+UV_EXTERN uv_thread_t uv_thread_self(void);
+UV_EXTERN int uv_thread_join(uv_thread_t *tid);
+UV_EXTERN int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2);
+
+/* The presence of these unions force similar struct layout. */
+#define XX(_, name) uv_ ## name ## _t name;
+union uv_any_handle {
+  UV_HANDLE_TYPE_MAP(XX)
+};
+
+union uv_any_req {
+  UV_REQ_TYPE_MAP(XX)
+};
+#undef XX
+
+
+struct uv_loop_s {
+  /* User data - use this for whatever. */
+  void* data;
+  /* Loop reference counting. */
+  unsigned int active_handles;
+  void* handle_queue[2];
+  union {
+    void* unused[2];
+    unsigned int count;
+  } active_reqs;
+  /* Internal flag to signal loop stop. */
+  unsigned int stop_flag;
+  UV_LOOP_PRIVATE_FIELDS
+};
+
+UV_EXTERN void* uv_loop_get_data(const uv_loop_t*);
+UV_EXTERN void uv_loop_set_data(uv_loop_t*, void* data);
+
+/* Don't export the private CPP symbols. */
+#undef UV_HANDLE_TYPE_PRIVATE
+#undef UV_REQ_TYPE_PRIVATE
+#undef UV_REQ_PRIVATE_FIELDS
+#undef UV_STREAM_PRIVATE_FIELDS
+#undef UV_TCP_PRIVATE_FIELDS
+#undef UV_PREPARE_PRIVATE_FIELDS
+#undef UV_CHECK_PRIVATE_FIELDS
+#undef UV_IDLE_PRIVATE_FIELDS
+#undef UV_ASYNC_PRIVATE_FIELDS
+#undef UV_TIMER_PRIVATE_FIELDS
+#undef UV_GETADDRINFO_PRIVATE_FIELDS
+#undef UV_GETNAMEINFO_PRIVATE_FIELDS
+#undef UV_FS_REQ_PRIVATE_FIELDS
+#undef UV_WORK_PRIVATE_FIELDS
+#undef UV_FS_EVENT_PRIVATE_FIELDS
+#undef UV_SIGNAL_PRIVATE_FIELDS
+#undef UV_LOOP_PRIVATE_FIELDS
+#undef UV_LOOP_PRIVATE_PLATFORM_FIELDS
+#undef UV__ERR
+
+#endif /* UV_H */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/android-ifaddrs.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/android-ifaddrs.h
new file mode 100644
index 0000000..9cd19fe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/android-ifaddrs.h
@@ -0,0 +1,54 @@
+/*
+ * Copyright (c) 1995, 1999
+ *	Berkeley Software Design, Inc.  All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ *
+ * THIS SOFTWARE IS PROVIDED BY Berkeley Software Design, Inc. ``AS IS'' AND
+ * ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
+ * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
+ * ARE DISCLAIMED.  IN NO EVENT SHALL Berkeley Software Design, Inc. BE LIABLE
+ * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
+ * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS
+ * OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
+ * HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
+ * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY
+ * OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF
+ * SUCH DAMAGE.
+ *
+ *	BSDI ifaddrs.h,v 2.5 2000/02/23 14:51:59 dab Exp
+ */
+
+#ifndef	_IFADDRS_H_
+#define	_IFADDRS_H_
+
+struct ifaddrs {
+	struct ifaddrs  *ifa_next;
+	char		*ifa_name;
+	unsigned int	 ifa_flags;
+	struct sockaddr	*ifa_addr;
+	struct sockaddr	*ifa_netmask;
+	struct sockaddr	*ifa_dstaddr;
+	void		*ifa_data;
+};
+
+/*
+ * This may have been defined in <net/if.h>.  Note that if <net/if.h> is
+ * to be included it must be included before this header file.
+ */
+#ifndef	ifa_broadaddr
+#define	ifa_broadaddr	ifa_dstaddr	/* broadcast address interface */
+#endif
+
+#include <sys/cdefs.h>
+
+__BEGIN_DECLS
+extern int getifaddrs(struct ifaddrs **ifap);
+extern void freeifaddrs(struct ifaddrs *ifa);
+__END_DECLS
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/bsd.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/bsd.h
new file mode 100644
index 0000000..2d72b3d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/bsd.h
@@ -0,0 +1,34 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_BSD_H
+#define UV_BSD_H
+
+#define UV_PLATFORM_FS_EVENT_FIELDS                                           \
+  uv__io_t event_watcher;                                                     \
+
+#define UV_IO_PRIVATE_PLATFORM_FIELDS                                         \
+  int rcount;                                                                 \
+  int wcount;                                                                 \
+
+#define UV_HAVE_KQUEUE 1
+
+#endif /* UV_BSD_H */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/darwin.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/darwin.h
new file mode 100644
index 0000000..d226415
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/darwin.h
@@ -0,0 +1,61 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_DARWIN_H
+#define UV_DARWIN_H
+
+#if defined(__APPLE__) && defined(__MACH__)
+# include <mach/mach.h>
+# include <mach/task.h>
+# include <mach/semaphore.h>
+# include <TargetConditionals.h>
+# define UV_PLATFORM_SEM_T semaphore_t
+#endif
+
+#define UV_IO_PRIVATE_PLATFORM_FIELDS                                         \
+  int rcount;                                                                 \
+  int wcount;                                                                 \
+
+#define UV_PLATFORM_LOOP_FIELDS                                               \
+  uv_thread_t cf_thread;                                                      \
+  void* _cf_reserved;                                                         \
+  void* cf_state;                                                             \
+  uv_mutex_t cf_mutex;                                                        \
+  uv_sem_t cf_sem;                                                            \
+  void* cf_signals[2];                                                        \
+
+#define UV_PLATFORM_FS_EVENT_FIELDS                                           \
+  uv__io_t event_watcher;                                                     \
+  char* realpath;                                                             \
+  int realpath_len;                                                           \
+  int cf_flags;                                                               \
+  uv_async_t* cf_cb;                                                          \
+  void* cf_events[2];                                                         \
+  void* cf_member[2];                                                         \
+  int cf_error;                                                               \
+  uv_mutex_t cf_mutex;                                                        \
+
+#define UV_STREAM_PRIVATE_PLATFORM_FIELDS                                     \
+  void* select;                                                               \
+
+#define UV_HAVE_KQUEUE 1
+
+#endif /* UV_DARWIN_H */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/errno.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/errno.h
new file mode 100644
index 0000000..8eeb95d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/errno.h
@@ -0,0 +1,443 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_ERRNO_H_
+#define UV_ERRNO_H_
+
+#include <errno.h>
+#if EDOM > 0
+# define UV__ERR(x) (-(x))
+#else
+# define UV__ERR(x) (x)
+#endif
+
+#define UV__EOF     (-4095)
+#define UV__UNKNOWN (-4094)
+
+#define UV__EAI_ADDRFAMILY  (-3000)
+#define UV__EAI_AGAIN       (-3001)
+#define UV__EAI_BADFLAGS    (-3002)
+#define UV__EAI_CANCELED    (-3003)
+#define UV__EAI_FAIL        (-3004)
+#define UV__EAI_FAMILY      (-3005)
+#define UV__EAI_MEMORY      (-3006)
+#define UV__EAI_NODATA      (-3007)
+#define UV__EAI_NONAME      (-3008)
+#define UV__EAI_OVERFLOW    (-3009)
+#define UV__EAI_SERVICE     (-3010)
+#define UV__EAI_SOCKTYPE    (-3011)
+#define UV__EAI_BADHINTS    (-3013)
+#define UV__EAI_PROTOCOL    (-3014)
+
+/* Only map to the system errno on non-Windows platforms. It's apparently
+ * a fairly common practice for Windows programmers to redefine errno codes.
+ */
+#if defined(E2BIG) && !defined(_WIN32)
+# define UV__E2BIG UV__ERR(E2BIG)
+#else
+# define UV__E2BIG (-4093)
+#endif
+
+#if defined(EACCES) && !defined(_WIN32)
+# define UV__EACCES UV__ERR(EACCES)
+#else
+# define UV__EACCES (-4092)
+#endif
+
+#if defined(EADDRINUSE) && !defined(_WIN32)
+# define UV__EADDRINUSE UV__ERR(EADDRINUSE)
+#else
+# define UV__EADDRINUSE (-4091)
+#endif
+
+#if defined(EADDRNOTAVAIL) && !defined(_WIN32)
+# define UV__EADDRNOTAVAIL UV__ERR(EADDRNOTAVAIL)
+#else
+# define UV__EADDRNOTAVAIL (-4090)
+#endif
+
+#if defined(EAFNOSUPPORT) && !defined(_WIN32)
+# define UV__EAFNOSUPPORT UV__ERR(EAFNOSUPPORT)
+#else
+# define UV__EAFNOSUPPORT (-4089)
+#endif
+
+#if defined(EAGAIN) && !defined(_WIN32)
+# define UV__EAGAIN UV__ERR(EAGAIN)
+#else
+# define UV__EAGAIN (-4088)
+#endif
+
+#if defined(EALREADY) && !defined(_WIN32)
+# define UV__EALREADY UV__ERR(EALREADY)
+#else
+# define UV__EALREADY (-4084)
+#endif
+
+#if defined(EBADF) && !defined(_WIN32)
+# define UV__EBADF UV__ERR(EBADF)
+#else
+# define UV__EBADF (-4083)
+#endif
+
+#if defined(EBUSY) && !defined(_WIN32)
+# define UV__EBUSY UV__ERR(EBUSY)
+#else
+# define UV__EBUSY (-4082)
+#endif
+
+#if defined(ECANCELED) && !defined(_WIN32)
+# define UV__ECANCELED UV__ERR(ECANCELED)
+#else
+# define UV__ECANCELED (-4081)
+#endif
+
+#if defined(ECHARSET) && !defined(_WIN32)
+# define UV__ECHARSET UV__ERR(ECHARSET)
+#else
+# define UV__ECHARSET (-4080)
+#endif
+
+#if defined(ECONNABORTED) && !defined(_WIN32)
+# define UV__ECONNABORTED UV__ERR(ECONNABORTED)
+#else
+# define UV__ECONNABORTED (-4079)
+#endif
+
+#if defined(ECONNREFUSED) && !defined(_WIN32)
+# define UV__ECONNREFUSED UV__ERR(ECONNREFUSED)
+#else
+# define UV__ECONNREFUSED (-4078)
+#endif
+
+#if defined(ECONNRESET) && !defined(_WIN32)
+# define UV__ECONNRESET UV__ERR(ECONNRESET)
+#else
+# define UV__ECONNRESET (-4077)
+#endif
+
+#if defined(EDESTADDRREQ) && !defined(_WIN32)
+# define UV__EDESTADDRREQ UV__ERR(EDESTADDRREQ)
+#else
+# define UV__EDESTADDRREQ (-4076)
+#endif
+
+#if defined(EEXIST) && !defined(_WIN32)
+# define UV__EEXIST UV__ERR(EEXIST)
+#else
+# define UV__EEXIST (-4075)
+#endif
+
+#if defined(EFAULT) && !defined(_WIN32)
+# define UV__EFAULT UV__ERR(EFAULT)
+#else
+# define UV__EFAULT (-4074)
+#endif
+
+#if defined(EHOSTUNREACH) && !defined(_WIN32)
+# define UV__EHOSTUNREACH UV__ERR(EHOSTUNREACH)
+#else
+# define UV__EHOSTUNREACH (-4073)
+#endif
+
+#if defined(EINTR) && !defined(_WIN32)
+# define UV__EINTR UV__ERR(EINTR)
+#else
+# define UV__EINTR (-4072)
+#endif
+
+#if defined(EINVAL) && !defined(_WIN32)
+# define UV__EINVAL UV__ERR(EINVAL)
+#else
+# define UV__EINVAL (-4071)
+#endif
+
+#if defined(EIO) && !defined(_WIN32)
+# define UV__EIO UV__ERR(EIO)
+#else
+# define UV__EIO (-4070)
+#endif
+
+#if defined(EISCONN) && !defined(_WIN32)
+# define UV__EISCONN UV__ERR(EISCONN)
+#else
+# define UV__EISCONN (-4069)
+#endif
+
+#if defined(EISDIR) && !defined(_WIN32)
+# define UV__EISDIR UV__ERR(EISDIR)
+#else
+# define UV__EISDIR (-4068)
+#endif
+
+#if defined(ELOOP) && !defined(_WIN32)
+# define UV__ELOOP UV__ERR(ELOOP)
+#else
+# define UV__ELOOP (-4067)
+#endif
+
+#if defined(EMFILE) && !defined(_WIN32)
+# define UV__EMFILE UV__ERR(EMFILE)
+#else
+# define UV__EMFILE (-4066)
+#endif
+
+#if defined(EMSGSIZE) && !defined(_WIN32)
+# define UV__EMSGSIZE UV__ERR(EMSGSIZE)
+#else
+# define UV__EMSGSIZE (-4065)
+#endif
+
+#if defined(ENAMETOOLONG) && !defined(_WIN32)
+# define UV__ENAMETOOLONG UV__ERR(ENAMETOOLONG)
+#else
+# define UV__ENAMETOOLONG (-4064)
+#endif
+
+#if defined(ENETDOWN) && !defined(_WIN32)
+# define UV__ENETDOWN UV__ERR(ENETDOWN)
+#else
+# define UV__ENETDOWN (-4063)
+#endif
+
+#if defined(ENETUNREACH) && !defined(_WIN32)
+# define UV__ENETUNREACH UV__ERR(ENETUNREACH)
+#else
+# define UV__ENETUNREACH (-4062)
+#endif
+
+#if defined(ENFILE) && !defined(_WIN32)
+# define UV__ENFILE UV__ERR(ENFILE)
+#else
+# define UV__ENFILE (-4061)
+#endif
+
+#if defined(ENOBUFS) && !defined(_WIN32)
+# define UV__ENOBUFS UV__ERR(ENOBUFS)
+#else
+# define UV__ENOBUFS (-4060)
+#endif
+
+#if defined(ENODEV) && !defined(_WIN32)
+# define UV__ENODEV UV__ERR(ENODEV)
+#else
+# define UV__ENODEV (-4059)
+#endif
+
+#if defined(ENOENT) && !defined(_WIN32)
+# define UV__ENOENT UV__ERR(ENOENT)
+#else
+# define UV__ENOENT (-4058)
+#endif
+
+#if defined(ENOMEM) && !defined(_WIN32)
+# define UV__ENOMEM UV__ERR(ENOMEM)
+#else
+# define UV__ENOMEM (-4057)
+#endif
+
+#if defined(ENONET) && !defined(_WIN32)
+# define UV__ENONET UV__ERR(ENONET)
+#else
+# define UV__ENONET (-4056)
+#endif
+
+#if defined(ENOSPC) && !defined(_WIN32)
+# define UV__ENOSPC UV__ERR(ENOSPC)
+#else
+# define UV__ENOSPC (-4055)
+#endif
+
+#if defined(ENOSYS) && !defined(_WIN32)
+# define UV__ENOSYS UV__ERR(ENOSYS)
+#else
+# define UV__ENOSYS (-4054)
+#endif
+
+#if defined(ENOTCONN) && !defined(_WIN32)
+# define UV__ENOTCONN UV__ERR(ENOTCONN)
+#else
+# define UV__ENOTCONN (-4053)
+#endif
+
+#if defined(ENOTDIR) && !defined(_WIN32)
+# define UV__ENOTDIR UV__ERR(ENOTDIR)
+#else
+# define UV__ENOTDIR (-4052)
+#endif
+
+#if defined(ENOTEMPTY) && !defined(_WIN32)
+# define UV__ENOTEMPTY UV__ERR(ENOTEMPTY)
+#else
+# define UV__ENOTEMPTY (-4051)
+#endif
+
+#if defined(ENOTSOCK) && !defined(_WIN32)
+# define UV__ENOTSOCK UV__ERR(ENOTSOCK)
+#else
+# define UV__ENOTSOCK (-4050)
+#endif
+
+#if defined(ENOTSUP) && !defined(_WIN32)
+# define UV__ENOTSUP UV__ERR(ENOTSUP)
+#else
+# define UV__ENOTSUP (-4049)
+#endif
+
+#if defined(EPERM) && !defined(_WIN32)
+# define UV__EPERM UV__ERR(EPERM)
+#else
+# define UV__EPERM (-4048)
+#endif
+
+#if defined(EPIPE) && !defined(_WIN32)
+# define UV__EPIPE UV__ERR(EPIPE)
+#else
+# define UV__EPIPE (-4047)
+#endif
+
+#if defined(EPROTO) && !defined(_WIN32)
+# define UV__EPROTO UV__ERR(EPROTO)
+#else
+# define UV__EPROTO UV__ERR(4046)
+#endif
+
+#if defined(EPROTONOSUPPORT) && !defined(_WIN32)
+# define UV__EPROTONOSUPPORT UV__ERR(EPROTONOSUPPORT)
+#else
+# define UV__EPROTONOSUPPORT (-4045)
+#endif
+
+#if defined(EPROTOTYPE) && !defined(_WIN32)
+# define UV__EPROTOTYPE UV__ERR(EPROTOTYPE)
+#else
+# define UV__EPROTOTYPE (-4044)
+#endif
+
+#if defined(EROFS) && !defined(_WIN32)
+# define UV__EROFS UV__ERR(EROFS)
+#else
+# define UV__EROFS (-4043)
+#endif
+
+#if defined(ESHUTDOWN) && !defined(_WIN32)
+# define UV__ESHUTDOWN UV__ERR(ESHUTDOWN)
+#else
+# define UV__ESHUTDOWN (-4042)
+#endif
+
+#if defined(ESPIPE) && !defined(_WIN32)
+# define UV__ESPIPE UV__ERR(ESPIPE)
+#else
+# define UV__ESPIPE (-4041)
+#endif
+
+#if defined(ESRCH) && !defined(_WIN32)
+# define UV__ESRCH UV__ERR(ESRCH)
+#else
+# define UV__ESRCH (-4040)
+#endif
+
+#if defined(ETIMEDOUT) && !defined(_WIN32)
+# define UV__ETIMEDOUT UV__ERR(ETIMEDOUT)
+#else
+# define UV__ETIMEDOUT (-4039)
+#endif
+
+#if defined(ETXTBSY) && !defined(_WIN32)
+# define UV__ETXTBSY UV__ERR(ETXTBSY)
+#else
+# define UV__ETXTBSY (-4038)
+#endif
+
+#if defined(EXDEV) && !defined(_WIN32)
+# define UV__EXDEV UV__ERR(EXDEV)
+#else
+# define UV__EXDEV (-4037)
+#endif
+
+#if defined(EFBIG) && !defined(_WIN32)
+# define UV__EFBIG UV__ERR(EFBIG)
+#else
+# define UV__EFBIG (-4036)
+#endif
+
+#if defined(ENOPROTOOPT) && !defined(_WIN32)
+# define UV__ENOPROTOOPT UV__ERR(ENOPROTOOPT)
+#else
+# define UV__ENOPROTOOPT (-4035)
+#endif
+
+#if defined(ERANGE) && !defined(_WIN32)
+# define UV__ERANGE UV__ERR(ERANGE)
+#else
+# define UV__ERANGE (-4034)
+#endif
+
+#if defined(ENXIO) && !defined(_WIN32)
+# define UV__ENXIO UV__ERR(ENXIO)
+#else
+# define UV__ENXIO (-4033)
+#endif
+
+#if defined(EMLINK) && !defined(_WIN32)
+# define UV__EMLINK UV__ERR(EMLINK)
+#else
+# define UV__EMLINK (-4032)
+#endif
+
+/* EHOSTDOWN is not visible on BSD-like systems when _POSIX_C_SOURCE is
+ * defined. Fortunately, its value is always 64 so it's possible albeit
+ * icky to hard-code it.
+ */
+#if defined(EHOSTDOWN) && !defined(_WIN32)
+# define UV__EHOSTDOWN UV__ERR(EHOSTDOWN)
+#elif defined(__APPLE__) || \
+      defined(__DragonFly__) || \
+      defined(__FreeBSD__) || \
+      defined(__FreeBSD_kernel__) || \
+      defined(__NetBSD__) || \
+      defined(__OpenBSD__)
+# define UV__EHOSTDOWN (-64)
+#else
+# define UV__EHOSTDOWN (-4031)
+#endif
+
+#if defined(EREMOTEIO) && !defined(_WIN32)
+# define UV__EREMOTEIO UV__ERR(EREMOTEIO)
+#else
+# define UV__EREMOTEIO (-4030)
+#endif
+
+#if defined(ENOTTY) && !defined(_WIN32)
+# define UV__ENOTTY UV__ERR(ENOTTY)
+#else
+# define UV__ENOTTY (-4029)
+#endif
+
+#if defined(EFTYPE) && !defined(_WIN32)
+# define UV__EFTYPE UV__ERR(EFTYPE)
+#else
+# define UV__EFTYPE (-4028)
+#endif
+
+
+#endif /* UV_ERRNO_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/linux.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/linux.h
new file mode 100644
index 0000000..9b38405
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/linux.h
@@ -0,0 +1,34 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_LINUX_H
+#define UV_LINUX_H
+
+#define UV_PLATFORM_LOOP_FIELDS                                               \
+  uv__io_t inotify_read_watcher;                                              \
+  void* inotify_watchers;                                                     \
+  int inotify_fd;                                                             \
+
+#define UV_PLATFORM_FS_EVENT_FIELDS                                           \
+  void* watchers[2];                                                          \
+  int wd;                                                                     \
+
+#endif /* UV_LINUX_H */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/posix.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/posix.h
new file mode 100644
index 0000000..9a96634
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/posix.h
@@ -0,0 +1,31 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_POSIX_H
+#define UV_POSIX_H
+
+#define UV_PLATFORM_LOOP_FIELDS                                               \
+  struct pollfd* poll_fds;                                                    \
+  size_t poll_fds_used;                                                       \
+  size_t poll_fds_size;                                                       \
+  unsigned char poll_fds_iterating;                                           \
+
+#endif /* UV_POSIX_H */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/pthread-barrier.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/pthread-barrier.h
new file mode 100644
index 0000000..07db9b8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/pthread-barrier.h
@@ -0,0 +1,69 @@
+/*
+Copyright (c) 2016, Kari Tristan Helgason <kthelgason@gmail.com>
+
+Permission to use, copy, modify, and/or distribute this software for any
+purpose with or without fee is hereby granted, provided that the above
+copyright notice and this permission notice appear in all copies.
+
+THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+*/
+
+#ifndef _UV_PTHREAD_BARRIER_
+#define _UV_PTHREAD_BARRIER_
+#include <errno.h>
+#include <pthread.h>
+#if !defined(__MVS__)
+#include <semaphore.h> /* sem_t */
+#endif
+
+#define PTHREAD_BARRIER_SERIAL_THREAD  0x12345
+#define UV__PTHREAD_BARRIER_FALLBACK   1
+
+/*
+ * To maintain ABI compatibility with
+ * libuv v1.x struct is padded according
+ * to target platform
+ */
+#if defined(__ANDROID__)
+# define UV_BARRIER_STRUCT_PADDING \
+  sizeof(pthread_mutex_t) + \
+  sizeof(pthread_cond_t) + \
+  sizeof(unsigned int) - \
+  sizeof(void *)
+#elif defined(__APPLE__)
+# define UV_BARRIER_STRUCT_PADDING \
+  sizeof(pthread_mutex_t) + \
+  2 * sizeof(sem_t) + \
+  2 * sizeof(unsigned int) - \
+  sizeof(void *)
+#else
+# define UV_BARRIER_STRUCT_PADDING 0
+#endif
+
+typedef struct {
+  pthread_mutex_t  mutex;
+  pthread_cond_t   cond;
+  unsigned         threshold;
+  unsigned         in;
+  unsigned         out;
+} _uv_barrier;
+
+typedef struct {
+  _uv_barrier* b;
+  char _pad[UV_BARRIER_STRUCT_PADDING];
+} pthread_barrier_t;
+
+int pthread_barrier_init(pthread_barrier_t* barrier,
+                         const void* barrier_attr,
+                         unsigned count);
+
+int pthread_barrier_wait(pthread_barrier_t* barrier);
+int pthread_barrier_destroy(pthread_barrier_t *barrier);
+
+#endif /* _UV_PTHREAD_BARRIER_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/threadpool.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/threadpool.h
new file mode 100644
index 0000000..9708ebd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/threadpool.h
@@ -0,0 +1,37 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/*
+ * This file is private to libuv. It provides common functionality to both
+ * Windows and Unix backends.
+ */
+
+#ifndef UV_THREADPOOL_H_
+#define UV_THREADPOOL_H_
+
+struct uv__work {
+  void (*work)(struct uv__work *w);
+  void (*done)(struct uv__work *w, int status);
+  struct uv_loop_s* loop;
+  void* wq[2];
+};
+
+#endif /* UV_THREADPOOL_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/tree.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/tree.h
new file mode 100644
index 0000000..f936416
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/tree.h
@@ -0,0 +1,768 @@
+/*-
+ * Copyright 2002 Niels Provos <provos@citi.umich.edu>
+ * All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * are met:
+ * 1. Redistributions of source code must retain the above copyright
+ *    notice, this list of conditions and the following disclaimer.
+ * 2. Redistributions in binary form must reproduce the above copyright
+ *    notice, this list of conditions and the following disclaimer in the
+ *    documentation and/or other materials provided with the distribution.
+ *
+ * THIS SOFTWARE IS PROVIDED BY THE AUTHOR ``AS IS'' AND ANY EXPRESS OR
+ * IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES
+ * OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED.
+ * IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR ANY DIRECT, INDIRECT,
+ * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT
+ * NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+ * DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+ * THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+ * (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
+ * THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+ */
+
+#ifndef  UV_TREE_H_
+#define  UV_TREE_H_
+
+#ifndef UV__UNUSED
+# if __GNUC__
+#  define UV__UNUSED __attribute__((unused))
+# else
+#  define UV__UNUSED
+# endif
+#endif
+
+/*
+ * This file defines data structures for different types of trees:
+ * splay trees and red-black trees.
+ *
+ * A splay tree is a self-organizing data structure.  Every operation
+ * on the tree causes a splay to happen.  The splay moves the requested
+ * node to the root of the tree and partly rebalances it.
+ *
+ * This has the benefit that request locality causes faster lookups as
+ * the requested nodes move to the top of the tree.  On the other hand,
+ * every lookup causes memory writes.
+ *
+ * The Balance Theorem bounds the total access time for m operations
+ * and n inserts on an initially empty tree as O((m + n)lg n).  The
+ * amortized cost for a sequence of m accesses to a splay tree is O(lg n);
+ *
+ * A red-black tree is a binary search tree with the node color as an
+ * extra attribute.  It fulfills a set of conditions:
+ *  - every search path from the root to a leaf consists of the
+ *    same number of black nodes,
+ *  - each red node (except for the root) has a black parent,
+ *  - each leaf node is black.
+ *
+ * Every operation on a red-black tree is bounded as O(lg n).
+ * The maximum height of a red-black tree is 2lg (n+1).
+ */
+
+#define SPLAY_HEAD(name, type)                                                \
+struct name {                                                                 \
+  struct type *sph_root; /* root of the tree */                               \
+}
+
+#define SPLAY_INITIALIZER(root)                                               \
+  { NULL }
+
+#define SPLAY_INIT(root) do {                                                 \
+  (root)->sph_root = NULL;                                                    \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_ENTRY(type)                                                     \
+struct {                                                                      \
+  struct type *spe_left;          /* left element */                          \
+  struct type *spe_right;         /* right element */                         \
+}
+
+#define SPLAY_LEFT(elm, field)    (elm)->field.spe_left
+#define SPLAY_RIGHT(elm, field)   (elm)->field.spe_right
+#define SPLAY_ROOT(head)          (head)->sph_root
+#define SPLAY_EMPTY(head)         (SPLAY_ROOT(head) == NULL)
+
+/* SPLAY_ROTATE_{LEFT,RIGHT} expect that tmp hold SPLAY_{RIGHT,LEFT} */
+#define SPLAY_ROTATE_RIGHT(head, tmp, field) do {                             \
+  SPLAY_LEFT((head)->sph_root, field) = SPLAY_RIGHT(tmp, field);              \
+  SPLAY_RIGHT(tmp, field) = (head)->sph_root;                                 \
+  (head)->sph_root = tmp;                                                     \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_ROTATE_LEFT(head, tmp, field) do {                              \
+  SPLAY_RIGHT((head)->sph_root, field) = SPLAY_LEFT(tmp, field);              \
+  SPLAY_LEFT(tmp, field) = (head)->sph_root;                                  \
+  (head)->sph_root = tmp;                                                     \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_LINKLEFT(head, tmp, field) do {                                 \
+  SPLAY_LEFT(tmp, field) = (head)->sph_root;                                  \
+  tmp = (head)->sph_root;                                                     \
+  (head)->sph_root = SPLAY_LEFT((head)->sph_root, field);                     \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_LINKRIGHT(head, tmp, field) do {                                \
+  SPLAY_RIGHT(tmp, field) = (head)->sph_root;                                 \
+  tmp = (head)->sph_root;                                                     \
+  (head)->sph_root = SPLAY_RIGHT((head)->sph_root, field);                    \
+} while (/*CONSTCOND*/ 0)
+
+#define SPLAY_ASSEMBLE(head, node, left, right, field) do {                   \
+  SPLAY_RIGHT(left, field) = SPLAY_LEFT((head)->sph_root, field);             \
+  SPLAY_LEFT(right, field) = SPLAY_RIGHT((head)->sph_root, field);            \
+  SPLAY_LEFT((head)->sph_root, field) = SPLAY_RIGHT(node, field);             \
+  SPLAY_RIGHT((head)->sph_root, field) = SPLAY_LEFT(node, field);             \
+} while (/*CONSTCOND*/ 0)
+
+/* Generates prototypes and inline functions */
+
+#define SPLAY_PROTOTYPE(name, type, field, cmp)                               \
+void name##_SPLAY(struct name *, struct type *);                              \
+void name##_SPLAY_MINMAX(struct name *, int);                                 \
+struct type *name##_SPLAY_INSERT(struct name *, struct type *);               \
+struct type *name##_SPLAY_REMOVE(struct name *, struct type *);               \
+                                                                              \
+/* Finds the node with the same key as elm */                                 \
+static __inline struct type *                                                 \
+name##_SPLAY_FIND(struct name *head, struct type *elm)                        \
+{                                                                             \
+  if (SPLAY_EMPTY(head))                                                      \
+    return(NULL);                                                             \
+  name##_SPLAY(head, elm);                                                    \
+  if ((cmp)(elm, (head)->sph_root) == 0)                                      \
+    return (head->sph_root);                                                  \
+  return (NULL);                                                              \
+}                                                                             \
+                                                                              \
+static __inline struct type *                                                 \
+name##_SPLAY_NEXT(struct name *head, struct type *elm)                        \
+{                                                                             \
+  name##_SPLAY(head, elm);                                                    \
+  if (SPLAY_RIGHT(elm, field) != NULL) {                                      \
+    elm = SPLAY_RIGHT(elm, field);                                            \
+    while (SPLAY_LEFT(elm, field) != NULL) {                                  \
+      elm = SPLAY_LEFT(elm, field);                                           \
+    }                                                                         \
+  } else                                                                      \
+    elm = NULL;                                                               \
+  return (elm);                                                               \
+}                                                                             \
+                                                                              \
+static __inline struct type *                                                 \
+name##_SPLAY_MIN_MAX(struct name *head, int val)                              \
+{                                                                             \
+  name##_SPLAY_MINMAX(head, val);                                             \
+  return (SPLAY_ROOT(head));                                                  \
+}
+
+/* Main splay operation.
+ * Moves node close to the key of elm to top
+ */
+#define SPLAY_GENERATE(name, type, field, cmp)                                \
+struct type *                                                                 \
+name##_SPLAY_INSERT(struct name *head, struct type *elm)                      \
+{                                                                             \
+    if (SPLAY_EMPTY(head)) {                                                  \
+      SPLAY_LEFT(elm, field) = SPLAY_RIGHT(elm, field) = NULL;                \
+    } else {                                                                  \
+      int __comp;                                                             \
+      name##_SPLAY(head, elm);                                                \
+      __comp = (cmp)(elm, (head)->sph_root);                                  \
+      if(__comp < 0) {                                                        \
+        SPLAY_LEFT(elm, field) = SPLAY_LEFT((head)->sph_root, field);         \
+        SPLAY_RIGHT(elm, field) = (head)->sph_root;                           \
+        SPLAY_LEFT((head)->sph_root, field) = NULL;                           \
+      } else if (__comp > 0) {                                                \
+        SPLAY_RIGHT(elm, field) = SPLAY_RIGHT((head)->sph_root, field);       \
+        SPLAY_LEFT(elm, field) = (head)->sph_root;                            \
+        SPLAY_RIGHT((head)->sph_root, field) = NULL;                          \
+      } else                                                                  \
+        return ((head)->sph_root);                                            \
+    }                                                                         \
+    (head)->sph_root = (elm);                                                 \
+    return (NULL);                                                            \
+}                                                                             \
+                                                                              \
+struct type *                                                                 \
+name##_SPLAY_REMOVE(struct name *head, struct type *elm)                      \
+{                                                                             \
+  struct type *__tmp;                                                         \
+  if (SPLAY_EMPTY(head))                                                      \
+    return (NULL);                                                            \
+  name##_SPLAY(head, elm);                                                    \
+  if ((cmp)(elm, (head)->sph_root) == 0) {                                    \
+    if (SPLAY_LEFT((head)->sph_root, field) == NULL) {                        \
+      (head)->sph_root = SPLAY_RIGHT((head)->sph_root, field);                \
+    } else {                                                                  \
+      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
+      (head)->sph_root = SPLAY_LEFT((head)->sph_root, field);                 \
+      name##_SPLAY(head, elm);                                                \
+      SPLAY_RIGHT((head)->sph_root, field) = __tmp;                           \
+    }                                                                         \
+    return (elm);                                                             \
+  }                                                                           \
+  return (NULL);                                                              \
+}                                                                             \
+                                                                              \
+void                                                                          \
+name##_SPLAY(struct name *head, struct type *elm)                             \
+{                                                                             \
+  struct type __node, *__left, *__right, *__tmp;                              \
+  int __comp;                                                                 \
+                                                                              \
+  SPLAY_LEFT(&__node, field) = SPLAY_RIGHT(&__node, field) = NULL;            \
+  __left = __right = &__node;                                                 \
+                                                                              \
+  while ((__comp = (cmp)(elm, (head)->sph_root)) != 0) {                      \
+    if (__comp < 0) {                                                         \
+      __tmp = SPLAY_LEFT((head)->sph_root, field);                            \
+      if (__tmp == NULL)                                                      \
+        break;                                                                \
+      if ((cmp)(elm, __tmp) < 0){                                             \
+        SPLAY_ROTATE_RIGHT(head, __tmp, field);                               \
+        if (SPLAY_LEFT((head)->sph_root, field) == NULL)                      \
+          break;                                                              \
+      }                                                                       \
+      SPLAY_LINKLEFT(head, __right, field);                                   \
+    } else if (__comp > 0) {                                                  \
+      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
+      if (__tmp == NULL)                                                      \
+        break;                                                                \
+      if ((cmp)(elm, __tmp) > 0){                                             \
+        SPLAY_ROTATE_LEFT(head, __tmp, field);                                \
+        if (SPLAY_RIGHT((head)->sph_root, field) == NULL)                     \
+          break;                                                              \
+      }                                                                       \
+      SPLAY_LINKRIGHT(head, __left, field);                                   \
+    }                                                                         \
+  }                                                                           \
+  SPLAY_ASSEMBLE(head, &__node, __left, __right, field);                      \
+}                                                                             \
+                                                                              \
+/* Splay with either the minimum or the maximum element                       \
+ * Used to find minimum or maximum element in tree.                           \
+ */                                                                           \
+void name##_SPLAY_MINMAX(struct name *head, int __comp)                       \
+{                                                                             \
+  struct type __node, *__left, *__right, *__tmp;                              \
+                                                                              \
+  SPLAY_LEFT(&__node, field) = SPLAY_RIGHT(&__node, field) = NULL;            \
+  __left = __right = &__node;                                                 \
+                                                                              \
+  while (1) {                                                                 \
+    if (__comp < 0) {                                                         \
+      __tmp = SPLAY_LEFT((head)->sph_root, field);                            \
+      if (__tmp == NULL)                                                      \
+        break;                                                                \
+      if (__comp < 0){                                                        \
+        SPLAY_ROTATE_RIGHT(head, __tmp, field);                               \
+        if (SPLAY_LEFT((head)->sph_root, field) == NULL)                      \
+          break;                                                              \
+      }                                                                       \
+      SPLAY_LINKLEFT(head, __right, field);                                   \
+    } else if (__comp > 0) {                                                  \
+      __tmp = SPLAY_RIGHT((head)->sph_root, field);                           \
+      if (__tmp == NULL)                                                      \
+        break;                                                                \
+      if (__comp > 0) {                                                       \
+        SPLAY_ROTATE_LEFT(head, __tmp, field);                                \
+        if (SPLAY_RIGHT((head)->sph_root, field) == NULL)                     \
+          break;                                                              \
+      }                                                                       \
+      SPLAY_LINKRIGHT(head, __left, field);                                   \
+    }                                                                         \
+  }                                                                           \
+  SPLAY_ASSEMBLE(head, &__node, __left, __right, field);                      \
+}
+
+#define SPLAY_NEGINF  -1
+#define SPLAY_INF     1
+
+#define SPLAY_INSERT(name, x, y)  name##_SPLAY_INSERT(x, y)
+#define SPLAY_REMOVE(name, x, y)  name##_SPLAY_REMOVE(x, y)
+#define SPLAY_FIND(name, x, y)    name##_SPLAY_FIND(x, y)
+#define SPLAY_NEXT(name, x, y)    name##_SPLAY_NEXT(x, y)
+#define SPLAY_MIN(name, x)        (SPLAY_EMPTY(x) ? NULL                      \
+                                  : name##_SPLAY_MIN_MAX(x, SPLAY_NEGINF))
+#define SPLAY_MAX(name, x)        (SPLAY_EMPTY(x) ? NULL                      \
+                                  : name##_SPLAY_MIN_MAX(x, SPLAY_INF))
+
+#define SPLAY_FOREACH(x, name, head)                                          \
+  for ((x) = SPLAY_MIN(name, head);                                           \
+       (x) != NULL;                                                           \
+       (x) = SPLAY_NEXT(name, head, x))
+
+/* Macros that define a red-black tree */
+#define RB_HEAD(name, type)                                                   \
+struct name {                                                                 \
+  struct type *rbh_root; /* root of the tree */                               \
+}
+
+#define RB_INITIALIZER(root)                                                  \
+  { NULL }
+
+#define RB_INIT(root) do {                                                    \
+  (root)->rbh_root = NULL;                                                    \
+} while (/*CONSTCOND*/ 0)
+
+#define RB_BLACK  0
+#define RB_RED    1
+#define RB_ENTRY(type)                                                        \
+struct {                                                                      \
+  struct type *rbe_left;        /* left element */                            \
+  struct type *rbe_right;       /* right element */                           \
+  struct type *rbe_parent;      /* parent element */                          \
+  int rbe_color;                /* node color */                              \
+}
+
+#define RB_LEFT(elm, field)     (elm)->field.rbe_left
+#define RB_RIGHT(elm, field)    (elm)->field.rbe_right
+#define RB_PARENT(elm, field)   (elm)->field.rbe_parent
+#define RB_COLOR(elm, field)    (elm)->field.rbe_color
+#define RB_ROOT(head)           (head)->rbh_root
+#define RB_EMPTY(head)          (RB_ROOT(head) == NULL)
+
+#define RB_SET(elm, parent, field) do {                                       \
+  RB_PARENT(elm, field) = parent;                                             \
+  RB_LEFT(elm, field) = RB_RIGHT(elm, field) = NULL;                          \
+  RB_COLOR(elm, field) = RB_RED;                                              \
+} while (/*CONSTCOND*/ 0)
+
+#define RB_SET_BLACKRED(black, red, field) do {                               \
+  RB_COLOR(black, field) = RB_BLACK;                                          \
+  RB_COLOR(red, field) = RB_RED;                                              \
+} while (/*CONSTCOND*/ 0)
+
+#ifndef RB_AUGMENT
+#define RB_AUGMENT(x)  do {} while (0)
+#endif
+
+#define RB_ROTATE_LEFT(head, elm, tmp, field) do {                            \
+  (tmp) = RB_RIGHT(elm, field);                                               \
+  if ((RB_RIGHT(elm, field) = RB_LEFT(tmp, field)) != NULL) {                 \
+    RB_PARENT(RB_LEFT(tmp, field), field) = (elm);                            \
+  }                                                                           \
+  RB_AUGMENT(elm);                                                            \
+  if ((RB_PARENT(tmp, field) = RB_PARENT(elm, field)) != NULL) {              \
+    if ((elm) == RB_LEFT(RB_PARENT(elm, field), field))                       \
+      RB_LEFT(RB_PARENT(elm, field), field) = (tmp);                          \
+    else                                                                      \
+      RB_RIGHT(RB_PARENT(elm, field), field) = (tmp);                         \
+  } else                                                                      \
+    (head)->rbh_root = (tmp);                                                 \
+  RB_LEFT(tmp, field) = (elm);                                                \
+  RB_PARENT(elm, field) = (tmp);                                              \
+  RB_AUGMENT(tmp);                                                            \
+  if ((RB_PARENT(tmp, field)))                                                \
+    RB_AUGMENT(RB_PARENT(tmp, field));                                        \
+} while (/*CONSTCOND*/ 0)
+
+#define RB_ROTATE_RIGHT(head, elm, tmp, field) do {                           \
+  (tmp) = RB_LEFT(elm, field);                                                \
+  if ((RB_LEFT(elm, field) = RB_RIGHT(tmp, field)) != NULL) {                 \
+    RB_PARENT(RB_RIGHT(tmp, field), field) = (elm);                           \
+  }                                                                           \
+  RB_AUGMENT(elm);                                                            \
+  if ((RB_PARENT(tmp, field) = RB_PARENT(elm, field)) != NULL) {              \
+    if ((elm) == RB_LEFT(RB_PARENT(elm, field), field))                       \
+      RB_LEFT(RB_PARENT(elm, field), field) = (tmp);                          \
+    else                                                                      \
+      RB_RIGHT(RB_PARENT(elm, field), field) = (tmp);                         \
+  } else                                                                      \
+    (head)->rbh_root = (tmp);                                                 \
+  RB_RIGHT(tmp, field) = (elm);                                               \
+  RB_PARENT(elm, field) = (tmp);                                              \
+  RB_AUGMENT(tmp);                                                            \
+  if ((RB_PARENT(tmp, field)))                                                \
+    RB_AUGMENT(RB_PARENT(tmp, field));                                        \
+} while (/*CONSTCOND*/ 0)
+
+/* Generates prototypes and inline functions */
+#define  RB_PROTOTYPE(name, type, field, cmp)                                 \
+  RB_PROTOTYPE_INTERNAL(name, type, field, cmp,)
+#define  RB_PROTOTYPE_STATIC(name, type, field, cmp)                          \
+  RB_PROTOTYPE_INTERNAL(name, type, field, cmp, UV__UNUSED static)
+#define RB_PROTOTYPE_INTERNAL(name, type, field, cmp, attr)                   \
+attr void name##_RB_INSERT_COLOR(struct name *, struct type *);               \
+attr void name##_RB_REMOVE_COLOR(struct name *, struct type *, struct type *);\
+attr struct type *name##_RB_REMOVE(struct name *, struct type *);             \
+attr struct type *name##_RB_INSERT(struct name *, struct type *);             \
+attr struct type *name##_RB_FIND(struct name *, struct type *);               \
+attr struct type *name##_RB_NFIND(struct name *, struct type *);              \
+attr struct type *name##_RB_NEXT(struct type *);                              \
+attr struct type *name##_RB_PREV(struct type *);                              \
+attr struct type *name##_RB_MINMAX(struct name *, int);                       \
+                                                                              \
+
+/* Main rb operation.
+ * Moves node close to the key of elm to top
+ */
+#define  RB_GENERATE(name, type, field, cmp)                                  \
+  RB_GENERATE_INTERNAL(name, type, field, cmp,)
+#define  RB_GENERATE_STATIC(name, type, field, cmp)                           \
+  RB_GENERATE_INTERNAL(name, type, field, cmp, UV__UNUSED static)
+#define RB_GENERATE_INTERNAL(name, type, field, cmp, attr)                    \
+attr void                                                                     \
+name##_RB_INSERT_COLOR(struct name *head, struct type *elm)                   \
+{                                                                             \
+  struct type *parent, *gparent, *tmp;                                        \
+  while ((parent = RB_PARENT(elm, field)) != NULL &&                          \
+      RB_COLOR(parent, field) == RB_RED) {                                    \
+    gparent = RB_PARENT(parent, field);                                       \
+    if (parent == RB_LEFT(gparent, field)) {                                  \
+      tmp = RB_RIGHT(gparent, field);                                         \
+      if (tmp && RB_COLOR(tmp, field) == RB_RED) {                            \
+        RB_COLOR(tmp, field) = RB_BLACK;                                      \
+        RB_SET_BLACKRED(parent, gparent, field);                              \
+        elm = gparent;                                                        \
+        continue;                                                             \
+      }                                                                       \
+      if (RB_RIGHT(parent, field) == elm) {                                   \
+        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
+        tmp = parent;                                                         \
+        parent = elm;                                                         \
+        elm = tmp;                                                            \
+      }                                                                       \
+      RB_SET_BLACKRED(parent, gparent, field);                                \
+      RB_ROTATE_RIGHT(head, gparent, tmp, field);                             \
+    } else {                                                                  \
+      tmp = RB_LEFT(gparent, field);                                          \
+      if (tmp && RB_COLOR(tmp, field) == RB_RED) {                            \
+        RB_COLOR(tmp, field) = RB_BLACK;                                      \
+        RB_SET_BLACKRED(parent, gparent, field);                              \
+        elm = gparent;                                                        \
+        continue;                                                             \
+      }                                                                       \
+      if (RB_LEFT(parent, field) == elm) {                                    \
+        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
+        tmp = parent;                                                         \
+        parent = elm;                                                         \
+        elm = tmp;                                                            \
+      }                                                                       \
+      RB_SET_BLACKRED(parent, gparent, field);                                \
+      RB_ROTATE_LEFT(head, gparent, tmp, field);                              \
+    }                                                                         \
+  }                                                                           \
+  RB_COLOR(head->rbh_root, field) = RB_BLACK;                                 \
+}                                                                             \
+                                                                              \
+attr void                                                                     \
+name##_RB_REMOVE_COLOR(struct name *head, struct type *parent,                \
+    struct type *elm)                                                         \
+{                                                                             \
+  struct type *tmp;                                                           \
+  while ((elm == NULL || RB_COLOR(elm, field) == RB_BLACK) &&                 \
+      elm != RB_ROOT(head)) {                                                 \
+    if (RB_LEFT(parent, field) == elm) {                                      \
+      tmp = RB_RIGHT(parent, field);                                          \
+      if (RB_COLOR(tmp, field) == RB_RED) {                                   \
+        RB_SET_BLACKRED(tmp, parent, field);                                  \
+        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
+        tmp = RB_RIGHT(parent, field);                                        \
+      }                                                                       \
+      if ((RB_LEFT(tmp, field) == NULL ||                                     \
+          RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) &&                \
+          (RB_RIGHT(tmp, field) == NULL ||                                    \
+          RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK)) {               \
+        RB_COLOR(tmp, field) = RB_RED;                                        \
+        elm = parent;                                                         \
+        parent = RB_PARENT(elm, field);                                       \
+      } else {                                                                \
+        if (RB_RIGHT(tmp, field) == NULL ||                                   \
+            RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK) {              \
+          struct type *oleft;                                                 \
+          if ((oleft = RB_LEFT(tmp, field))                                   \
+              != NULL)                                                        \
+            RB_COLOR(oleft, field) = RB_BLACK;                                \
+          RB_COLOR(tmp, field) = RB_RED;                                      \
+          RB_ROTATE_RIGHT(head, tmp, oleft, field);                           \
+          tmp = RB_RIGHT(parent, field);                                      \
+        }                                                                     \
+        RB_COLOR(tmp, field) = RB_COLOR(parent, field);                       \
+        RB_COLOR(parent, field) = RB_BLACK;                                   \
+        if (RB_RIGHT(tmp, field))                                             \
+          RB_COLOR(RB_RIGHT(tmp, field), field) = RB_BLACK;                   \
+        RB_ROTATE_LEFT(head, parent, tmp, field);                             \
+        elm = RB_ROOT(head);                                                  \
+        break;                                                                \
+      }                                                                       \
+    } else {                                                                  \
+      tmp = RB_LEFT(parent, field);                                           \
+      if (RB_COLOR(tmp, field) == RB_RED) {                                   \
+        RB_SET_BLACKRED(tmp, parent, field);                                  \
+        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
+        tmp = RB_LEFT(parent, field);                                         \
+      }                                                                       \
+      if ((RB_LEFT(tmp, field) == NULL ||                                     \
+          RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) &&                \
+          (RB_RIGHT(tmp, field) == NULL ||                                    \
+          RB_COLOR(RB_RIGHT(tmp, field), field) == RB_BLACK)) {               \
+        RB_COLOR(tmp, field) = RB_RED;                                        \
+        elm = parent;                                                         \
+        parent = RB_PARENT(elm, field);                                       \
+      } else {                                                                \
+        if (RB_LEFT(tmp, field) == NULL ||                                    \
+            RB_COLOR(RB_LEFT(tmp, field), field) == RB_BLACK) {               \
+          struct type *oright;                                                \
+          if ((oright = RB_RIGHT(tmp, field))                                 \
+              != NULL)                                                        \
+            RB_COLOR(oright, field) = RB_BLACK;                               \
+          RB_COLOR(tmp, field) = RB_RED;                                      \
+          RB_ROTATE_LEFT(head, tmp, oright, field);                           \
+          tmp = RB_LEFT(parent, field);                                       \
+        }                                                                     \
+        RB_COLOR(tmp, field) = RB_COLOR(parent, field);                       \
+        RB_COLOR(parent, field) = RB_BLACK;                                   \
+        if (RB_LEFT(tmp, field))                                              \
+          RB_COLOR(RB_LEFT(tmp, field), field) = RB_BLACK;                    \
+        RB_ROTATE_RIGHT(head, parent, tmp, field);                            \
+        elm = RB_ROOT(head);                                                  \
+        break;                                                                \
+      }                                                                       \
+    }                                                                         \
+  }                                                                           \
+  if (elm)                                                                    \
+    RB_COLOR(elm, field) = RB_BLACK;                                          \
+}                                                                             \
+                                                                              \
+attr struct type *                                                            \
+name##_RB_REMOVE(struct name *head, struct type *elm)                         \
+{                                                                             \
+  struct type *child, *parent, *old = elm;                                    \
+  int color;                                                                  \
+  if (RB_LEFT(elm, field) == NULL)                                            \
+    child = RB_RIGHT(elm, field);                                             \
+  else if (RB_RIGHT(elm, field) == NULL)                                      \
+    child = RB_LEFT(elm, field);                                              \
+  else {                                                                      \
+    struct type *left;                                                        \
+    elm = RB_RIGHT(elm, field);                                               \
+    while ((left = RB_LEFT(elm, field)) != NULL)                              \
+      elm = left;                                                             \
+    child = RB_RIGHT(elm, field);                                             \
+    parent = RB_PARENT(elm, field);                                           \
+    color = RB_COLOR(elm, field);                                             \
+    if (child)                                                                \
+      RB_PARENT(child, field) = parent;                                       \
+    if (parent) {                                                             \
+      if (RB_LEFT(parent, field) == elm)                                      \
+        RB_LEFT(parent, field) = child;                                       \
+      else                                                                    \
+        RB_RIGHT(parent, field) = child;                                      \
+      RB_AUGMENT(parent);                                                     \
+    } else                                                                    \
+      RB_ROOT(head) = child;                                                  \
+    if (RB_PARENT(elm, field) == old)                                         \
+      parent = elm;                                                           \
+    (elm)->field = (old)->field;                                              \
+    if (RB_PARENT(old, field)) {                                              \
+      if (RB_LEFT(RB_PARENT(old, field), field) == old)                       \
+        RB_LEFT(RB_PARENT(old, field), field) = elm;                          \
+      else                                                                    \
+        RB_RIGHT(RB_PARENT(old, field), field) = elm;                         \
+      RB_AUGMENT(RB_PARENT(old, field));                                      \
+    } else                                                                    \
+      RB_ROOT(head) = elm;                                                    \
+    RB_PARENT(RB_LEFT(old, field), field) = elm;                              \
+    if (RB_RIGHT(old, field))                                                 \
+      RB_PARENT(RB_RIGHT(old, field), field) = elm;                           \
+    if (parent) {                                                             \
+      left = parent;                                                          \
+      do {                                                                    \
+        RB_AUGMENT(left);                                                     \
+      } while ((left = RB_PARENT(left, field)) != NULL);                      \
+    }                                                                         \
+    goto color;                                                               \
+  }                                                                           \
+  parent = RB_PARENT(elm, field);                                             \
+  color = RB_COLOR(elm, field);                                               \
+  if (child)                                                                  \
+    RB_PARENT(child, field) = parent;                                         \
+  if (parent) {                                                               \
+    if (RB_LEFT(parent, field) == elm)                                        \
+      RB_LEFT(parent, field) = child;                                         \
+    else                                                                      \
+      RB_RIGHT(parent, field) = child;                                        \
+    RB_AUGMENT(parent);                                                       \
+  } else                                                                      \
+    RB_ROOT(head) = child;                                                    \
+color:                                                                        \
+  if (color == RB_BLACK)                                                      \
+    name##_RB_REMOVE_COLOR(head, parent, child);                              \
+  return (old);                                                               \
+}                                                                             \
+                                                                              \
+/* Inserts a node into the RB tree */                                         \
+attr struct type *                                                            \
+name##_RB_INSERT(struct name *head, struct type *elm)                         \
+{                                                                             \
+  struct type *tmp;                                                           \
+  struct type *parent = NULL;                                                 \
+  int comp = 0;                                                               \
+  tmp = RB_ROOT(head);                                                        \
+  while (tmp) {                                                               \
+    parent = tmp;                                                             \
+    comp = (cmp)(elm, parent);                                                \
+    if (comp < 0)                                                             \
+      tmp = RB_LEFT(tmp, field);                                              \
+    else if (comp > 0)                                                        \
+      tmp = RB_RIGHT(tmp, field);                                             \
+    else                                                                      \
+      return (tmp);                                                           \
+  }                                                                           \
+  RB_SET(elm, parent, field);                                                 \
+  if (parent != NULL) {                                                       \
+    if (comp < 0)                                                             \
+      RB_LEFT(parent, field) = elm;                                           \
+    else                                                                      \
+      RB_RIGHT(parent, field) = elm;                                          \
+    RB_AUGMENT(parent);                                                       \
+  } else                                                                      \
+    RB_ROOT(head) = elm;                                                      \
+  name##_RB_INSERT_COLOR(head, elm);                                          \
+  return (NULL);                                                              \
+}                                                                             \
+                                                                              \
+/* Finds the node with the same key as elm */                                 \
+attr struct type *                                                            \
+name##_RB_FIND(struct name *head, struct type *elm)                           \
+{                                                                             \
+  struct type *tmp = RB_ROOT(head);                                           \
+  int comp;                                                                   \
+  while (tmp) {                                                               \
+    comp = cmp(elm, tmp);                                                     \
+    if (comp < 0)                                                             \
+      tmp = RB_LEFT(tmp, field);                                              \
+    else if (comp > 0)                                                        \
+      tmp = RB_RIGHT(tmp, field);                                             \
+    else                                                                      \
+      return (tmp);                                                           \
+  }                                                                           \
+  return (NULL);                                                              \
+}                                                                             \
+                                                                              \
+/* Finds the first node greater than or equal to the search key */            \
+attr struct type *                                                            \
+name##_RB_NFIND(struct name *head, struct type *elm)                          \
+{                                                                             \
+  struct type *tmp = RB_ROOT(head);                                           \
+  struct type *res = NULL;                                                    \
+  int comp;                                                                   \
+  while (tmp) {                                                               \
+    comp = cmp(elm, tmp);                                                     \
+    if (comp < 0) {                                                           \
+      res = tmp;                                                              \
+      tmp = RB_LEFT(tmp, field);                                              \
+    }                                                                         \
+    else if (comp > 0)                                                        \
+      tmp = RB_RIGHT(tmp, field);                                             \
+    else                                                                      \
+      return (tmp);                                                           \
+  }                                                                           \
+  return (res);                                                               \
+}                                                                             \
+                                                                              \
+/* ARGSUSED */                                                                \
+attr struct type *                                                            \
+name##_RB_NEXT(struct type *elm)                                              \
+{                                                                             \
+  if (RB_RIGHT(elm, field)) {                                                 \
+    elm = RB_RIGHT(elm, field);                                               \
+    while (RB_LEFT(elm, field))                                               \
+      elm = RB_LEFT(elm, field);                                              \
+  } else {                                                                    \
+    if (RB_PARENT(elm, field) &&                                              \
+        (elm == RB_LEFT(RB_PARENT(elm, field), field)))                       \
+      elm = RB_PARENT(elm, field);                                            \
+    else {                                                                    \
+      while (RB_PARENT(elm, field) &&                                         \
+          (elm == RB_RIGHT(RB_PARENT(elm, field), field)))                    \
+        elm = RB_PARENT(elm, field);                                          \
+      elm = RB_PARENT(elm, field);                                            \
+    }                                                                         \
+  }                                                                           \
+  return (elm);                                                               \
+}                                                                             \
+                                                                              \
+/* ARGSUSED */                                                                \
+attr struct type *                                                            \
+name##_RB_PREV(struct type *elm)                                              \
+{                                                                             \
+  if (RB_LEFT(elm, field)) {                                                  \
+    elm = RB_LEFT(elm, field);                                                \
+    while (RB_RIGHT(elm, field))                                              \
+      elm = RB_RIGHT(elm, field);                                             \
+  } else {                                                                    \
+    if (RB_PARENT(elm, field) &&                                              \
+        (elm == RB_RIGHT(RB_PARENT(elm, field), field)))                      \
+      elm = RB_PARENT(elm, field);                                            \
+    else {                                                                    \
+      while (RB_PARENT(elm, field) &&                                         \
+          (elm == RB_LEFT(RB_PARENT(elm, field), field)))                     \
+        elm = RB_PARENT(elm, field);                                          \
+      elm = RB_PARENT(elm, field);                                            \
+    }                                                                         \
+  }                                                                           \
+  return (elm);                                                               \
+}                                                                             \
+                                                                              \
+attr struct type *                                                            \
+name##_RB_MINMAX(struct name *head, int val)                                  \
+{                                                                             \
+  struct type *tmp = RB_ROOT(head);                                           \
+  struct type *parent = NULL;                                                 \
+  while (tmp) {                                                               \
+    parent = tmp;                                                             \
+    if (val < 0)                                                              \
+      tmp = RB_LEFT(tmp, field);                                              \
+    else                                                                      \
+      tmp = RB_RIGHT(tmp, field);                                             \
+  }                                                                           \
+  return (parent);                                                            \
+}
+
+#define RB_NEGINF   -1
+#define RB_INF      1
+
+#define RB_INSERT(name, x, y)   name##_RB_INSERT(x, y)
+#define RB_REMOVE(name, x, y)   name##_RB_REMOVE(x, y)
+#define RB_FIND(name, x, y)     name##_RB_FIND(x, y)
+#define RB_NFIND(name, x, y)    name##_RB_NFIND(x, y)
+#define RB_NEXT(name, x, y)     name##_RB_NEXT(y)
+#define RB_PREV(name, x, y)     name##_RB_PREV(y)
+#define RB_MIN(name, x)         name##_RB_MINMAX(x, RB_NEGINF)
+#define RB_MAX(name, x)         name##_RB_MINMAX(x, RB_INF)
+
+#define RB_FOREACH(x, name, head)                                             \
+  for ((x) = RB_MIN(name, head);                                              \
+       (x) != NULL;                                                           \
+       (x) = name##_RB_NEXT(x))
+
+#define RB_FOREACH_FROM(x, name, y)                                           \
+  for ((x) = (y);                                                             \
+      ((x) != NULL) && ((y) = name##_RB_NEXT(x), (x) != NULL);                \
+       (x) = (y))
+
+#define RB_FOREACH_SAFE(x, name, head, y)                                     \
+  for ((x) = RB_MIN(name, head);                                              \
+      ((x) != NULL) && ((y) = name##_RB_NEXT(x), (x) != NULL);                \
+       (x) = (y))
+
+#define RB_FOREACH_REVERSE(x, name, head)                                     \
+  for ((x) = RB_MAX(name, head);                                              \
+       (x) != NULL;                                                           \
+       (x) = name##_RB_PREV(x))
+
+#define RB_FOREACH_REVERSE_FROM(x, name, y)                                   \
+  for ((x) = (y);                                                             \
+      ((x) != NULL) && ((y) = name##_RB_PREV(x), (x) != NULL);                \
+       (x) = (y))
+
+#define RB_FOREACH_REVERSE_SAFE(x, name, head, y)                             \
+  for ((x) = RB_MAX(name, head);                                              \
+      ((x) != NULL) && ((y) = name##_RB_PREV(x), (x) != NULL);                \
+       (x) = (y))
+
+#endif  /* UV_TREE_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/unix.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/unix.h
new file mode 100644
index 0000000..5dae6dd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/unix.h
@@ -0,0 +1,458 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_UNIX_H
+#define UV_UNIX_H
+
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+#include <dirent.h>
+
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <netinet/tcp.h>
+#include <arpa/inet.h>
+#include <netdb.h>
+
+#include <termios.h>
+#include <pwd.h>
+
+#if !defined(__MVS__)
+#include <semaphore.h>
+#endif
+#include <pthread.h>
+#include <signal.h>
+
+#include "uv/threadpool.h"
+
+#if defined(__linux__)
+# include "uv/linux.h"
+#elif defined(__PASE__)
+# include "uv/posix.h"
+#elif defined(__APPLE__)
+# include "uv/darwin.h"
+#elif defined(__DragonFly__)       || \
+      defined(__FreeBSD__)         || \
+      defined(__FreeBSD_kernel__)  || \
+      defined(__OpenBSD__)         || \
+      defined(__NetBSD__)
+# include "uv/bsd.h"
+#elif defined(__CYGWIN__) || defined(__MSYS__)
+# include "uv/posix.h"
+#endif
+
+#ifndef PTHREAD_BARRIER_SERIAL_THREAD
+# include "uv/pthread-barrier.h"
+#endif
+
+#ifndef NI_MAXHOST
+# define NI_MAXHOST 1025
+#endif
+
+#ifndef NI_MAXSERV
+# define NI_MAXSERV 32
+#endif
+
+#ifndef UV_IO_PRIVATE_PLATFORM_FIELDS
+# define UV_IO_PRIVATE_PLATFORM_FIELDS /* empty */
+#endif
+
+struct uv__io_s;
+struct uv_loop_s;
+
+typedef void (*uv__io_cb)(struct uv_loop_s* loop,
+                          struct uv__io_s* w,
+                          unsigned int events);
+typedef struct uv__io_s uv__io_t;
+
+struct uv__io_s {
+  uv__io_cb cb;
+  void* pending_queue[2];
+  void* watcher_queue[2];
+  unsigned int pevents; /* Pending event mask i.e. mask at next tick. */
+  unsigned int events;  /* Current event mask. */
+  int fd;
+  UV_IO_PRIVATE_PLATFORM_FIELDS
+};
+
+#ifndef UV_PLATFORM_SEM_T
+# define UV_PLATFORM_SEM_T sem_t
+#endif
+
+#ifndef UV_PLATFORM_LOOP_FIELDS
+# define UV_PLATFORM_LOOP_FIELDS /* empty */
+#endif
+
+#ifndef UV_PLATFORM_FS_EVENT_FIELDS
+# define UV_PLATFORM_FS_EVENT_FIELDS /* empty */
+#endif
+
+#ifndef UV_STREAM_PRIVATE_PLATFORM_FIELDS
+# define UV_STREAM_PRIVATE_PLATFORM_FIELDS /* empty */
+#endif
+
+/* Note: May be cast to struct iovec. See writev(2). */
+typedef struct uv_buf_t {
+  char* base;
+  size_t len;
+} uv_buf_t;
+
+typedef int uv_file;
+typedef int uv_os_sock_t;
+typedef int uv_os_fd_t;
+typedef pid_t uv_pid_t;
+
+#define UV_ONCE_INIT PTHREAD_ONCE_INIT
+
+typedef pthread_once_t uv_once_t;
+typedef pthread_t uv_thread_t;
+typedef pthread_mutex_t uv_mutex_t;
+typedef pthread_rwlock_t uv_rwlock_t;
+typedef UV_PLATFORM_SEM_T uv_sem_t;
+typedef pthread_cond_t uv_cond_t;
+typedef pthread_key_t uv_key_t;
+typedef pthread_barrier_t uv_barrier_t;
+
+
+/* Platform-specific definitions for uv_spawn support. */
+typedef gid_t uv_gid_t;
+typedef uid_t uv_uid_t;
+
+typedef struct dirent uv__dirent_t;
+
+#if defined(DT_UNKNOWN)
+# define HAVE_DIRENT_TYPES
+# if defined(DT_REG)
+#  define UV__DT_FILE DT_REG
+# else
+#  define UV__DT_FILE -1
+# endif
+# if defined(DT_DIR)
+#  define UV__DT_DIR DT_DIR
+# else
+#  define UV__DT_DIR -2
+# endif
+# if defined(DT_LNK)
+#  define UV__DT_LINK DT_LNK
+# else
+#  define UV__DT_LINK -3
+# endif
+# if defined(DT_FIFO)
+#  define UV__DT_FIFO DT_FIFO
+# else
+#  define UV__DT_FIFO -4
+# endif
+# if defined(DT_SOCK)
+#  define UV__DT_SOCKET DT_SOCK
+# else
+#  define UV__DT_SOCKET -5
+# endif
+# if defined(DT_CHR)
+#  define UV__DT_CHAR DT_CHR
+# else
+#  define UV__DT_CHAR -6
+# endif
+# if defined(DT_BLK)
+#  define UV__DT_BLOCK DT_BLK
+# else
+#  define UV__DT_BLOCK -7
+# endif
+#endif
+
+/* Platform-specific definitions for uv_dlopen support. */
+#define UV_DYNAMIC /* empty */
+
+typedef struct {
+  void* handle;
+  char* errmsg;
+} uv_lib_t;
+
+#define UV_LOOP_PRIVATE_FIELDS                                                \
+  unsigned long flags;                                                        \
+  int backend_fd;                                                             \
+  void* pending_queue[2];                                                     \
+  void* watcher_queue[2];                                                     \
+  uv__io_t** watchers;                                                        \
+  unsigned int nwatchers;                                                     \
+  unsigned int nfds;                                                          \
+  void* wq[2];                                                                \
+  uv_mutex_t wq_mutex;                                                        \
+  uv_async_t wq_async;                                                        \
+  uv_rwlock_t cloexec_lock;                                                   \
+  uv_handle_t* closing_handles;                                               \
+  void* process_handles[2];                                                   \
+  void* prepare_handles[2];                                                   \
+  void* check_handles[2];                                                     \
+  void* idle_handles[2];                                                      \
+  void* async_handles[2];                                                     \
+  void (*async_unused)(void);  /* TODO(bnoordhuis) Remove in libuv v2. */     \
+  uv__io_t async_io_watcher;                                                  \
+  int async_wfd;                                                              \
+  struct {                                                                    \
+    void* min;                                                                \
+    unsigned int nelts;                                                       \
+  } timer_heap;                                                               \
+  uint64_t timer_counter;                                                     \
+  uint64_t time;                                                              \
+  int signal_pipefd[2];                                                       \
+  uv__io_t signal_io_watcher;                                                 \
+  uv_signal_t child_watcher;                                                  \
+  int emfile_fd;                                                              \
+  UV_PLATFORM_LOOP_FIELDS                                                     \
+
+#define UV_REQ_TYPE_PRIVATE /* empty */
+
+#define UV_REQ_PRIVATE_FIELDS  /* empty */
+
+#define UV_PRIVATE_REQ_TYPES /* empty */
+
+#define UV_WRITE_PRIVATE_FIELDS                                               \
+  void* queue[2];                                                             \
+  unsigned int write_index;                                                   \
+  uv_buf_t* bufs;                                                             \
+  unsigned int nbufs;                                                         \
+  int error;                                                                  \
+  uv_buf_t bufsml[4];                                                         \
+
+#define UV_CONNECT_PRIVATE_FIELDS                                             \
+  void* queue[2];                                                             \
+
+#define UV_SHUTDOWN_PRIVATE_FIELDS /* empty */
+
+#define UV_UDP_SEND_PRIVATE_FIELDS                                            \
+  void* queue[2];                                                             \
+  struct sockaddr_storage addr;                                               \
+  unsigned int nbufs;                                                         \
+  uv_buf_t* bufs;                                                             \
+  ssize_t status;                                                             \
+  uv_udp_send_cb send_cb;                                                     \
+  uv_buf_t bufsml[4];                                                         \
+
+#define UV_HANDLE_PRIVATE_FIELDS                                              \
+  uv_handle_t* next_closing;                                                  \
+  unsigned int flags;                                                         \
+
+#define UV_STREAM_PRIVATE_FIELDS                                              \
+  uv_connect_t *connect_req;                                                  \
+  uv_shutdown_t *shutdown_req;                                                \
+  uv__io_t io_watcher;                                                        \
+  void* write_queue[2];                                                       \
+  void* write_completed_queue[2];                                             \
+  uv_connection_cb connection_cb;                                             \
+  int delayed_error;                                                          \
+  int accepted_fd;                                                            \
+  void* queued_fds;                                                           \
+  UV_STREAM_PRIVATE_PLATFORM_FIELDS                                           \
+
+#define UV_TCP_PRIVATE_FIELDS /* empty */
+
+#define UV_UDP_PRIVATE_FIELDS                                                 \
+  uv_alloc_cb alloc_cb;                                                       \
+  uv_udp_recv_cb recv_cb;                                                     \
+  uv__io_t io_watcher;                                                        \
+  void* write_queue[2];                                                       \
+  void* write_completed_queue[2];                                             \
+
+#define UV_PIPE_PRIVATE_FIELDS                                                \
+  const char* pipe_fname; /* strdup'ed */
+
+#define UV_POLL_PRIVATE_FIELDS                                                \
+  uv__io_t io_watcher;
+
+#define UV_PREPARE_PRIVATE_FIELDS                                             \
+  uv_prepare_cb prepare_cb;                                                   \
+  void* queue[2];                                                             \
+
+#define UV_CHECK_PRIVATE_FIELDS                                               \
+  uv_check_cb check_cb;                                                       \
+  void* queue[2];                                                             \
+
+#define UV_IDLE_PRIVATE_FIELDS                                                \
+  uv_idle_cb idle_cb;                                                         \
+  void* queue[2];                                                             \
+
+#define UV_ASYNC_PRIVATE_FIELDS                                               \
+  uv_async_cb async_cb;                                                       \
+  void* queue[2];                                                             \
+  int pending;                                                                \
+
+#define UV_TIMER_PRIVATE_FIELDS                                               \
+  uv_timer_cb timer_cb;                                                       \
+  void* heap_node[3];                                                         \
+  uint64_t timeout;                                                           \
+  uint64_t repeat;                                                            \
+  uint64_t start_id;
+
+#define UV_GETADDRINFO_PRIVATE_FIELDS                                         \
+  struct uv__work work_req;                                                   \
+  uv_getaddrinfo_cb cb;                                                       \
+  struct addrinfo* hints;                                                     \
+  char* hostname;                                                             \
+  char* service;                                                              \
+  struct addrinfo* addrinfo;                                                  \
+  int retcode;
+
+#define UV_GETNAMEINFO_PRIVATE_FIELDS                                         \
+  struct uv__work work_req;                                                   \
+  uv_getnameinfo_cb getnameinfo_cb;                                           \
+  struct sockaddr_storage storage;                                            \
+  int flags;                                                                  \
+  char host[NI_MAXHOST];                                                      \
+  char service[NI_MAXSERV];                                                   \
+  int retcode;
+
+#define UV_PROCESS_PRIVATE_FIELDS                                             \
+  void* queue[2];                                                             \
+  int status;                                                                 \
+
+#define UV_FS_PRIVATE_FIELDS                                                  \
+  const char *new_path;                                                       \
+  uv_file file;                                                               \
+  int flags;                                                                  \
+  mode_t mode;                                                                \
+  unsigned int nbufs;                                                         \
+  uv_buf_t* bufs;                                                             \
+  off_t off;                                                                  \
+  uv_uid_t uid;                                                               \
+  uv_gid_t gid;                                                               \
+  double atime;                                                               \
+  double mtime;                                                               \
+  struct uv__work work_req;                                                   \
+  uv_buf_t bufsml[4];                                                         \
+
+#define UV_WORK_PRIVATE_FIELDS                                                \
+  struct uv__work work_req;
+
+#define UV_TTY_PRIVATE_FIELDS                                                 \
+  struct termios orig_termios;                                                \
+  int mode;
+
+#define UV_SIGNAL_PRIVATE_FIELDS                                              \
+  /* RB_ENTRY(uv_signal_s) tree_entry; */                                     \
+  struct {                                                                    \
+    struct uv_signal_s* rbe_left;                                             \
+    struct uv_signal_s* rbe_right;                                            \
+    struct uv_signal_s* rbe_parent;                                           \
+    int rbe_color;                                                            \
+  } tree_entry;                                                               \
+  /* Use two counters here so we don have to fiddle with atomics. */          \
+  unsigned int caught_signals;                                                \
+  unsigned int dispatched_signals;
+
+#define UV_FS_EVENT_PRIVATE_FIELDS                                            \
+  uv_fs_event_cb cb;                                                          \
+  UV_PLATFORM_FS_EVENT_FIELDS                                                 \
+
+/* fs open() flags supported on this platform: */
+#if defined(O_APPEND)
+# define UV_FS_O_APPEND       O_APPEND
+#else
+# define UV_FS_O_APPEND       0
+#endif
+#if defined(O_CREAT)
+# define UV_FS_O_CREAT        O_CREAT
+#else
+# define UV_FS_O_CREAT        0
+#endif
+#if defined(O_DIRECT)
+# define UV_FS_O_DIRECT       O_DIRECT
+#else
+# define UV_FS_O_DIRECT       0
+#endif
+#if defined(O_DIRECTORY)
+# define UV_FS_O_DIRECTORY    O_DIRECTORY
+#else
+# define UV_FS_O_DIRECTORY    0
+#endif
+#if defined(O_DSYNC)
+# define UV_FS_O_DSYNC        O_DSYNC
+#else
+# define UV_FS_O_DSYNC        0
+#endif
+#if defined(O_EXCL)
+# define UV_FS_O_EXCL         O_EXCL
+#else
+# define UV_FS_O_EXCL         0
+#endif
+#if defined(O_EXLOCK)
+# define UV_FS_O_EXLOCK       O_EXLOCK
+#else
+# define UV_FS_O_EXLOCK       0
+#endif
+#if defined(O_NOATIME)
+# define UV_FS_O_NOATIME      O_NOATIME
+#else
+# define UV_FS_O_NOATIME      0
+#endif
+#if defined(O_NOCTTY)
+# define UV_FS_O_NOCTTY       O_NOCTTY
+#else
+# define UV_FS_O_NOCTTY       0
+#endif
+#if defined(O_NOFOLLOW)
+# define UV_FS_O_NOFOLLOW     O_NOFOLLOW
+#else
+# define UV_FS_O_NOFOLLOW     0
+#endif
+#if defined(O_NONBLOCK)
+# define UV_FS_O_NONBLOCK     O_NONBLOCK
+#else
+# define UV_FS_O_NONBLOCK     0
+#endif
+#if defined(O_RDONLY)
+# define UV_FS_O_RDONLY       O_RDONLY
+#else
+# define UV_FS_O_RDONLY       0
+#endif
+#if defined(O_RDWR)
+# define UV_FS_O_RDWR         O_RDWR
+#else
+# define UV_FS_O_RDWR         0
+#endif
+#if defined(O_SYMLINK)
+# define UV_FS_O_SYMLINK      O_SYMLINK
+#else
+# define UV_FS_O_SYMLINK      0
+#endif
+#if defined(O_SYNC)
+# define UV_FS_O_SYNC         O_SYNC
+#else
+# define UV_FS_O_SYNC         0
+#endif
+#if defined(O_TRUNC)
+# define UV_FS_O_TRUNC        O_TRUNC
+#else
+# define UV_FS_O_TRUNC        0
+#endif
+#if defined(O_WRONLY)
+# define UV_FS_O_WRONLY       O_WRONLY
+#else
+# define UV_FS_O_WRONLY       0
+#endif
+
+/* fs open() flags supported on other platforms: */
+#define UV_FS_O_RANDOM        0
+#define UV_FS_O_SHORT_LIVED   0
+#define UV_FS_O_SEQUENTIAL    0
+#define UV_FS_O_TEMPORARY     0
+
+#endif /* UV_UNIX_H */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/version.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/version.h
new file mode 100644
index 0000000..0b82971
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/version.h
@@ -0,0 +1,43 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_VERSION_H
+#define UV_VERSION_H
+
+ /*
+ * Versions with the same major number are ABI stable. API is allowed to
+ * evolve between minor releases, but only in a backwards compatible way.
+ * Make sure you update the -soname directives in configure.ac
+ * and uv.gyp whenever you bump UV_VERSION_MAJOR or UV_VERSION_MINOR (but
+ * not UV_VERSION_PATCH.)
+ */
+
+#define UV_VERSION_MAJOR 1
+#define UV_VERSION_MINOR 21
+#define UV_VERSION_PATCH 0
+#define UV_VERSION_IS_RELEASE 1
+#define UV_VERSION_SUFFIX ""
+
+#define UV_VERSION_HEX  ((UV_VERSION_MAJOR << 16) | \
+                         (UV_VERSION_MINOR <<  8) | \
+                         (UV_VERSION_PATCH))
+
+#endif /* UV_VERSION_H */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/win.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/win.h
new file mode 100644
index 0000000..87f1e78
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/uv/win.h
@@ -0,0 +1,673 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef _WIN32_WINNT
+# define _WIN32_WINNT   0x0600
+#endif
+
+#if !defined(_SSIZE_T_) && !defined(_SSIZE_T_DEFINED)
+typedef intptr_t ssize_t;
+# define _SSIZE_T_
+# define _SSIZE_T_DEFINED
+#endif
+
+#include <winsock2.h>
+
+#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
+typedef struct pollfd {
+  SOCKET fd;
+  short  events;
+  short  revents;
+} WSAPOLLFD, *PWSAPOLLFD, *LPWSAPOLLFD;
+#endif
+
+#ifndef LOCALE_INVARIANT
+# define LOCALE_INVARIANT 0x007f
+#endif
+
+#include <mswsock.h>
+#include <ws2tcpip.h>
+#include <windows.h>
+
+#include <process.h>
+#include <signal.h>
+#include <fcntl.h>
+#include <sys/stat.h>
+
+#include <stdint.h>
+
+#include "uv/tree.h"
+#include "uv/threadpool.h"
+
+#define MAX_PIPENAME_LEN 256
+
+#ifndef S_IFLNK
+# define S_IFLNK 0xA000
+#endif
+
+/* Additional signals supported by uv_signal and or uv_kill. The CRT defines
+ * the following signals already:
+ *
+ *   #define SIGINT           2
+ *   #define SIGILL           4
+ *   #define SIGABRT_COMPAT   6
+ *   #define SIGFPE           8
+ *   #define SIGSEGV         11
+ *   #define SIGTERM         15
+ *   #define SIGBREAK        21
+ *   #define SIGABRT         22
+ *
+ * The additional signals have values that are common on other Unix
+ * variants (Linux and Darwin)
+ */
+#define SIGHUP                1
+#define SIGKILL               9
+#define SIGWINCH             28
+
+/* The CRT defines SIGABRT_COMPAT as 6, which equals SIGABRT on many unix-like
+ * platforms. However MinGW doesn't define it, so we do. */
+#ifndef SIGABRT_COMPAT
+# define SIGABRT_COMPAT       6
+#endif
+
+/*
+ * Guids and typedefs for winsock extension functions
+ * Mingw32 doesn't have these :-(
+ */
+#ifndef WSAID_ACCEPTEX
+# define WSAID_ACCEPTEX                                                       \
+         {0xb5367df1, 0xcbac, 0x11cf,                                         \
+         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
+
+# define WSAID_CONNECTEX                                                      \
+         {0x25a207b9, 0xddf3, 0x4660,                                         \
+         {0x8e, 0xe9, 0x76, 0xe5, 0x8c, 0x74, 0x06, 0x3e}}
+
+# define WSAID_GETACCEPTEXSOCKADDRS                                           \
+         {0xb5367df2, 0xcbac, 0x11cf,                                         \
+         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
+
+# define WSAID_DISCONNECTEX                                                   \
+         {0x7fda2e11, 0x8630, 0x436f,                                         \
+         {0xa0, 0x31, 0xf5, 0x36, 0xa6, 0xee, 0xc1, 0x57}}
+
+# define WSAID_TRANSMITFILE                                                   \
+         {0xb5367df0, 0xcbac, 0x11cf,                                         \
+         {0x95, 0xca, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}}
+
+  typedef BOOL (PASCAL *LPFN_ACCEPTEX)
+                      (SOCKET sListenSocket,
+                       SOCKET sAcceptSocket,
+                       PVOID lpOutputBuffer,
+                       DWORD dwReceiveDataLength,
+                       DWORD dwLocalAddressLength,
+                       DWORD dwRemoteAddressLength,
+                       LPDWORD lpdwBytesReceived,
+                       LPOVERLAPPED lpOverlapped);
+
+  typedef BOOL (PASCAL *LPFN_CONNECTEX)
+                      (SOCKET s,
+                       const struct sockaddr* name,
+                       int namelen,
+                       PVOID lpSendBuffer,
+                       DWORD dwSendDataLength,
+                       LPDWORD lpdwBytesSent,
+                       LPOVERLAPPED lpOverlapped);
+
+  typedef void (PASCAL *LPFN_GETACCEPTEXSOCKADDRS)
+                      (PVOID lpOutputBuffer,
+                       DWORD dwReceiveDataLength,
+                       DWORD dwLocalAddressLength,
+                       DWORD dwRemoteAddressLength,
+                       LPSOCKADDR* LocalSockaddr,
+                       LPINT LocalSockaddrLength,
+                       LPSOCKADDR* RemoteSockaddr,
+                       LPINT RemoteSockaddrLength);
+
+  typedef BOOL (PASCAL *LPFN_DISCONNECTEX)
+                      (SOCKET hSocket,
+                       LPOVERLAPPED lpOverlapped,
+                       DWORD dwFlags,
+                       DWORD reserved);
+
+  typedef BOOL (PASCAL *LPFN_TRANSMITFILE)
+                      (SOCKET hSocket,
+                       HANDLE hFile,
+                       DWORD nNumberOfBytesToWrite,
+                       DWORD nNumberOfBytesPerSend,
+                       LPOVERLAPPED lpOverlapped,
+                       LPTRANSMIT_FILE_BUFFERS lpTransmitBuffers,
+                       DWORD dwFlags);
+
+  typedef PVOID RTL_SRWLOCK;
+  typedef RTL_SRWLOCK SRWLOCK, *PSRWLOCK;
+#endif
+
+typedef int (WSAAPI* LPFN_WSARECV)
+            (SOCKET socket,
+             LPWSABUF buffers,
+             DWORD buffer_count,
+             LPDWORD bytes,
+             LPDWORD flags,
+             LPWSAOVERLAPPED overlapped,
+             LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+
+typedef int (WSAAPI* LPFN_WSARECVFROM)
+            (SOCKET socket,
+             LPWSABUF buffers,
+             DWORD buffer_count,
+             LPDWORD bytes,
+             LPDWORD flags,
+             struct sockaddr* addr,
+             LPINT addr_len,
+             LPWSAOVERLAPPED overlapped,
+             LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+
+#ifndef _NTDEF_
+  typedef LONG NTSTATUS;
+  typedef NTSTATUS *PNTSTATUS;
+#endif
+
+#ifndef RTL_CONDITION_VARIABLE_INIT
+  typedef PVOID CONDITION_VARIABLE, *PCONDITION_VARIABLE;
+#endif
+
+typedef struct _AFD_POLL_HANDLE_INFO {
+  HANDLE Handle;
+  ULONG Events;
+  NTSTATUS Status;
+} AFD_POLL_HANDLE_INFO, *PAFD_POLL_HANDLE_INFO;
+
+typedef struct _AFD_POLL_INFO {
+  LARGE_INTEGER Timeout;
+  ULONG NumberOfHandles;
+  ULONG Exclusive;
+  AFD_POLL_HANDLE_INFO Handles[1];
+} AFD_POLL_INFO, *PAFD_POLL_INFO;
+
+#define UV_MSAFD_PROVIDER_COUNT 3
+
+
+/**
+ * It should be possible to cast uv_buf_t[] to WSABUF[]
+ * see http://msdn.microsoft.com/en-us/library/ms741542(v=vs.85).aspx
+ */
+typedef struct uv_buf_t {
+  ULONG len;
+  char* base;
+} uv_buf_t;
+
+typedef int uv_file;
+typedef SOCKET uv_os_sock_t;
+typedef HANDLE uv_os_fd_t;
+typedef int uv_pid_t;
+
+typedef HANDLE uv_thread_t;
+
+typedef HANDLE uv_sem_t;
+
+typedef CRITICAL_SECTION uv_mutex_t;
+
+/* This condition variable implementation is based on the SetEvent solution
+ * (section 3.2) at http://www.cs.wustl.edu/~schmidt/win32-cv-1.html
+ * We could not use the SignalObjectAndWait solution (section 3.4) because
+ * it want the 2nd argument (type uv_mutex_t) of uv_cond_wait() and
+ * uv_cond_timedwait() to be HANDLEs, but we use CRITICAL_SECTIONs.
+ */
+
+typedef union {
+  CONDITION_VARIABLE cond_var;
+  struct {
+    unsigned int waiters_count;
+    CRITICAL_SECTION waiters_count_lock;
+    HANDLE signal_event;
+    HANDLE broadcast_event;
+  } unused_; /* TODO: retained for ABI compatibility; remove me in v2.x. */
+} uv_cond_t;
+
+typedef union {
+  struct {
+    unsigned int num_readers_;
+    CRITICAL_SECTION num_readers_lock_;
+    HANDLE write_semaphore_;
+  } state_;
+  /* TODO: remove me in v2.x. */
+  struct {
+    SRWLOCK unused_;
+  } unused1_;
+  /* TODO: remove me in v2.x. */
+  struct {
+    uv_mutex_t unused1_;
+    uv_mutex_t unused2_;
+  } unused2_;
+} uv_rwlock_t;
+
+typedef struct {
+  unsigned int n;
+  unsigned int count;
+  uv_mutex_t mutex;
+  uv_sem_t turnstile1;
+  uv_sem_t turnstile2;
+} uv_barrier_t;
+
+typedef struct {
+  DWORD tls_index;
+} uv_key_t;
+
+#define UV_ONCE_INIT { 0, NULL }
+
+typedef struct uv_once_s {
+  unsigned char ran;
+  HANDLE event;
+} uv_once_t;
+
+/* Platform-specific definitions for uv_spawn support. */
+typedef unsigned char uv_uid_t;
+typedef unsigned char uv_gid_t;
+
+typedef struct uv__dirent_s {
+  int d_type;
+  char d_name[1];
+} uv__dirent_t;
+
+#define HAVE_DIRENT_TYPES
+#define UV__DT_DIR     UV_DIRENT_DIR
+#define UV__DT_FILE    UV_DIRENT_FILE
+#define UV__DT_LINK    UV_DIRENT_LINK
+#define UV__DT_FIFO    UV_DIRENT_FIFO
+#define UV__DT_SOCKET  UV_DIRENT_SOCKET
+#define UV__DT_CHAR    UV_DIRENT_CHAR
+#define UV__DT_BLOCK   UV_DIRENT_BLOCK
+
+/* Platform-specific definitions for uv_dlopen support. */
+#define UV_DYNAMIC FAR WINAPI
+typedef struct {
+  HMODULE handle;
+  char* errmsg;
+} uv_lib_t;
+
+RB_HEAD(uv_timer_tree_s, uv_timer_s);
+
+#define UV_LOOP_PRIVATE_FIELDS                                                \
+    /* The loop's I/O completion port */                                      \
+  HANDLE iocp;                                                                \
+  /* The current time according to the event loop. in msecs. */               \
+  uint64_t time;                                                              \
+  /* Tail of a single-linked circular queue of pending reqs. If the queue */  \
+  /* is empty, tail_ is NULL. If there is only one item, */                   \
+  /* tail_->next_req == tail_ */                                              \
+  uv_req_t* pending_reqs_tail;                                                \
+  /* Head of a single-linked list of closed handles */                        \
+  uv_handle_t* endgame_handles;                                               \
+  /* The head of the timers tree */                                           \
+  struct uv_timer_tree_s timers;                                              \
+    /* Lists of active loop (prepare / check / idle) watchers */              \
+  uv_prepare_t* prepare_handles;                                              \
+  uv_check_t* check_handles;                                                  \
+  uv_idle_t* idle_handles;                                                    \
+  /* This pointer will refer to the prepare/check/idle handle whose */        \
+  /* callback is scheduled to be called next. This is needed to allow */      \
+  /* safe removal from one of the lists above while that list being */        \
+  /* iterated over. */                                                        \
+  uv_prepare_t* next_prepare_handle;                                          \
+  uv_check_t* next_check_handle;                                              \
+  uv_idle_t* next_idle_handle;                                                \
+  /* This handle holds the peer sockets for the fast variant of uv_poll_t */  \
+  SOCKET poll_peer_sockets[UV_MSAFD_PROVIDER_COUNT];                          \
+  /* Counter to keep track of active tcp streams */                           \
+  unsigned int active_tcp_streams;                                            \
+  /* Counter to keep track of active udp streams */                           \
+  unsigned int active_udp_streams;                                            \
+  /* Counter to started timer */                                              \
+  uint64_t timer_counter;                                                     \
+  /* Threadpool */                                                            \
+  void* wq[2];                                                                \
+  uv_mutex_t wq_mutex;                                                        \
+  uv_async_t wq_async;
+
+#define UV_REQ_TYPE_PRIVATE                                                   \
+  /* TODO: remove the req suffix */                                           \
+  UV_ACCEPT,                                                                  \
+  UV_FS_EVENT_REQ,                                                            \
+  UV_POLL_REQ,                                                                \
+  UV_PROCESS_EXIT,                                                            \
+  UV_READ,                                                                    \
+  UV_UDP_RECV,                                                                \
+  UV_WAKEUP,                                                                  \
+  UV_SIGNAL_REQ,
+
+#define UV_REQ_PRIVATE_FIELDS                                                 \
+  union {                                                                     \
+    /* Used by I/O operations */                                              \
+    struct {                                                                  \
+      OVERLAPPED overlapped;                                                  \
+      size_t queued_bytes;                                                    \
+    } io;                                                                     \
+  } u;                                                                        \
+  struct uv_req_s* next_req;
+
+#define UV_WRITE_PRIVATE_FIELDS \
+  int coalesced;                \
+  uv_buf_t write_buffer;        \
+  HANDLE event_handle;          \
+  HANDLE wait_handle;
+
+#define UV_CONNECT_PRIVATE_FIELDS                                             \
+  /* empty */
+
+#define UV_SHUTDOWN_PRIVATE_FIELDS                                            \
+  /* empty */
+
+#define UV_UDP_SEND_PRIVATE_FIELDS                                            \
+  /* empty */
+
+#define UV_PRIVATE_REQ_TYPES                                                  \
+  typedef struct uv_pipe_accept_s {                                           \
+    UV_REQ_FIELDS                                                             \
+    HANDLE pipeHandle;                                                        \
+    struct uv_pipe_accept_s* next_pending;                                    \
+  } uv_pipe_accept_t;                                                         \
+                                                                              \
+  typedef struct uv_tcp_accept_s {                                            \
+    UV_REQ_FIELDS                                                             \
+    SOCKET accept_socket;                                                     \
+    char accept_buffer[sizeof(struct sockaddr_storage) * 2 + 32];             \
+    HANDLE event_handle;                                                      \
+    HANDLE wait_handle;                                                       \
+    struct uv_tcp_accept_s* next_pending;                                     \
+  } uv_tcp_accept_t;                                                          \
+                                                                              \
+  typedef struct uv_read_s {                                                  \
+    UV_REQ_FIELDS                                                             \
+    HANDLE event_handle;                                                      \
+    HANDLE wait_handle;                                                       \
+  } uv_read_t;
+
+#define uv_stream_connection_fields                                           \
+  unsigned int write_reqs_pending;                                            \
+  uv_shutdown_t* shutdown_req;
+
+#define uv_stream_server_fields                                               \
+  uv_connection_cb connection_cb;
+
+#define UV_STREAM_PRIVATE_FIELDS                                              \
+  unsigned int reqs_pending;                                                  \
+  int activecnt;                                                              \
+  uv_read_t read_req;                                                         \
+  union {                                                                     \
+    struct { uv_stream_connection_fields } conn;                              \
+    struct { uv_stream_server_fields     } serv;                              \
+  } stream;
+
+#define uv_tcp_server_fields                                                  \
+  uv_tcp_accept_t* accept_reqs;                                               \
+  unsigned int processed_accepts;                                             \
+  uv_tcp_accept_t* pending_accepts;                                           \
+  LPFN_ACCEPTEX func_acceptex;
+
+#define uv_tcp_connection_fields                                              \
+  uv_buf_t read_buffer;                                                       \
+  LPFN_CONNECTEX func_connectex;
+
+#define UV_TCP_PRIVATE_FIELDS                                                 \
+  SOCKET socket;                                                              \
+  int delayed_error;                                                          \
+  union {                                                                     \
+    struct { uv_tcp_server_fields } serv;                                     \
+    struct { uv_tcp_connection_fields } conn;                                 \
+  } tcp;
+
+#define UV_UDP_PRIVATE_FIELDS                                                 \
+  SOCKET socket;                                                              \
+  unsigned int reqs_pending;                                                  \
+  int activecnt;                                                              \
+  uv_req_t recv_req;                                                          \
+  uv_buf_t recv_buffer;                                                       \
+  struct sockaddr_storage recv_from;                                          \
+  int recv_from_len;                                                          \
+  uv_udp_recv_cb recv_cb;                                                     \
+  uv_alloc_cb alloc_cb;                                                       \
+  LPFN_WSARECV func_wsarecv;                                                  \
+  LPFN_WSARECVFROM func_wsarecvfrom;
+
+#define uv_pipe_server_fields                                                 \
+  int pending_instances;                                                      \
+  uv_pipe_accept_t* accept_reqs;                                              \
+  uv_pipe_accept_t* pending_accepts;
+
+#define uv_pipe_connection_fields                                             \
+  uv_timer_t* eof_timer;                                                      \
+  uv_write_t dummy; /* TODO: retained for ABI compat; remove this in v2.x. */ \
+  DWORD ipc_remote_pid;                                                       \
+  union {                                                                     \
+    uint32_t payload_remaining;                                               \
+    uint64_t dummy; /* TODO: retained for ABI compat; remove this in v2.x. */ \
+  } ipc_data_frame;                                                           \
+  void* ipc_xfer_queue[2];                                                    \
+  int ipc_xfer_queue_length;                                                  \
+  uv_write_t* non_overlapped_writes_tail;                                     \
+  CRITICAL_SECTION readfile_thread_lock;                                      \
+  volatile HANDLE readfile_thread_handle;
+
+#define UV_PIPE_PRIVATE_FIELDS                                                \
+  HANDLE handle;                                                              \
+  WCHAR* name;                                                                \
+  union {                                                                     \
+    struct { uv_pipe_server_fields } serv;                                    \
+    struct { uv_pipe_connection_fields } conn;                                \
+  } pipe;
+
+/* TODO: put the parser states in an union - TTY handles are always half-duplex
+ * so read-state can safely overlap write-state. */
+#define UV_TTY_PRIVATE_FIELDS                                                 \
+  HANDLE handle;                                                              \
+  union {                                                                     \
+    struct {                                                                  \
+      /* Used for readable TTY handles */                                     \
+      /* TODO: remove me in v2.x. */                                          \
+      HANDLE unused_;                                                         \
+      uv_buf_t read_line_buffer;                                              \
+      HANDLE read_raw_wait;                                                   \
+      /* Fields used for translating win keystrokes into vt100 characters */  \
+      char last_key[8];                                                       \
+      unsigned char last_key_offset;                                          \
+      unsigned char last_key_len;                                             \
+      WCHAR last_utf16_high_surrogate;                                        \
+      INPUT_RECORD last_input_record;                                         \
+    } rd;                                                                     \
+    struct {                                                                  \
+      /* Used for writable TTY handles */                                     \
+      /* utf8-to-utf16 conversion state */                                    \
+      unsigned int utf8_codepoint;                                            \
+      unsigned char utf8_bytes_left;                                          \
+      /* eol conversion state */                                              \
+      unsigned char previous_eol;                                             \
+      /* ansi parser state */                                                 \
+      unsigned char ansi_parser_state;                                        \
+      unsigned char ansi_csi_argc;                                            \
+      unsigned short ansi_csi_argv[4];                                        \
+      COORD saved_position;                                                   \
+      WORD saved_attributes;                                                  \
+    } wr;                                                                     \
+  } tty;
+
+#define UV_POLL_PRIVATE_FIELDS                                                \
+  SOCKET socket;                                                              \
+  /* Used in fast mode */                                                     \
+  SOCKET peer_socket;                                                         \
+  AFD_POLL_INFO afd_poll_info_1;                                              \
+  AFD_POLL_INFO afd_poll_info_2;                                              \
+  /* Used in fast and slow mode. */                                           \
+  uv_req_t poll_req_1;                                                        \
+  uv_req_t poll_req_2;                                                        \
+  unsigned char submitted_events_1;                                           \
+  unsigned char submitted_events_2;                                           \
+  unsigned char mask_events_1;                                                \
+  unsigned char mask_events_2;                                                \
+  unsigned char events;
+
+#define UV_TIMER_PRIVATE_FIELDS                                               \
+  RB_ENTRY(uv_timer_s) tree_entry;                                            \
+  uint64_t due;                                                               \
+  uint64_t repeat;                                                            \
+  uint64_t start_id;                                                          \
+  uv_timer_cb timer_cb;
+
+#define UV_ASYNC_PRIVATE_FIELDS                                               \
+  struct uv_req_s async_req;                                                  \
+  uv_async_cb async_cb;                                                       \
+  /* char to avoid alignment issues */                                        \
+  char volatile async_sent;
+
+#define UV_PREPARE_PRIVATE_FIELDS                                             \
+  uv_prepare_t* prepare_prev;                                                 \
+  uv_prepare_t* prepare_next;                                                 \
+  uv_prepare_cb prepare_cb;
+
+#define UV_CHECK_PRIVATE_FIELDS                                               \
+  uv_check_t* check_prev;                                                     \
+  uv_check_t* check_next;                                                     \
+  uv_check_cb check_cb;
+
+#define UV_IDLE_PRIVATE_FIELDS                                                \
+  uv_idle_t* idle_prev;                                                       \
+  uv_idle_t* idle_next;                                                       \
+  uv_idle_cb idle_cb;
+
+#define UV_HANDLE_PRIVATE_FIELDS                                              \
+  uv_handle_t* endgame_next;                                                  \
+  unsigned int flags;
+
+#define UV_GETADDRINFO_PRIVATE_FIELDS                                         \
+  struct uv__work work_req;                                                   \
+  uv_getaddrinfo_cb getaddrinfo_cb;                                           \
+  void* alloc;                                                                \
+  WCHAR* node;                                                                \
+  WCHAR* service;                                                             \
+  /* The addrinfoW field is used to store a pointer to the hints, and    */   \
+  /* later on to store the result of GetAddrInfoW. The final result will */   \
+  /* be converted to struct addrinfo* and stored in the addrinfo field.  */   \
+  struct addrinfoW* addrinfow;                                                \
+  struct addrinfo* addrinfo;                                                  \
+  int retcode;
+
+#define UV_GETNAMEINFO_PRIVATE_FIELDS                                         \
+  struct uv__work work_req;                                                   \
+  uv_getnameinfo_cb getnameinfo_cb;                                           \
+  struct sockaddr_storage storage;                                            \
+  int flags;                                                                  \
+  char host[NI_MAXHOST];                                                      \
+  char service[NI_MAXSERV];                                                   \
+  int retcode;
+
+#define UV_PROCESS_PRIVATE_FIELDS                                             \
+  struct uv_process_exit_s {                                                  \
+    UV_REQ_FIELDS                                                             \
+  } exit_req;                                                                 \
+  BYTE* child_stdio_buffer;                                                   \
+  int exit_signal;                                                            \
+  HANDLE wait_handle;                                                         \
+  HANDLE process_handle;                                                      \
+  volatile char exit_cb_pending;
+
+#define UV_FS_PRIVATE_FIELDS                                                  \
+  struct uv__work work_req;                                                   \
+  int flags;                                                                  \
+  DWORD sys_errno_;                                                           \
+  union {                                                                     \
+    /* TODO: remove me in 0.9. */                                             \
+    WCHAR* pathw;                                                             \
+    int fd;                                                                   \
+  } file;                                                                     \
+  union {                                                                     \
+    struct {                                                                  \
+      int mode;                                                               \
+      WCHAR* new_pathw;                                                       \
+      int file_flags;                                                         \
+      int fd_out;                                                             \
+      unsigned int nbufs;                                                     \
+      uv_buf_t* bufs;                                                         \
+      int64_t offset;                                                         \
+      uv_buf_t bufsml[4];                                                     \
+    } info;                                                                   \
+    struct {                                                                  \
+      double atime;                                                           \
+      double mtime;                                                           \
+    } time;                                                                   \
+  } fs;
+
+#define UV_WORK_PRIVATE_FIELDS                                                \
+  struct uv__work work_req;
+
+#define UV_FS_EVENT_PRIVATE_FIELDS                                            \
+  struct uv_fs_event_req_s {                                                  \
+    UV_REQ_FIELDS                                                             \
+  } req;                                                                      \
+  HANDLE dir_handle;                                                          \
+  int req_pending;                                                            \
+  uv_fs_event_cb cb;                                                          \
+  WCHAR* filew;                                                               \
+  WCHAR* short_filew;                                                         \
+  WCHAR* dirw;                                                                \
+  char* buffer;
+
+#define UV_SIGNAL_PRIVATE_FIELDS                                              \
+  RB_ENTRY(uv_signal_s) tree_entry;                                           \
+  struct uv_req_s signal_req;                                                 \
+  unsigned long pending_signum;
+
+#ifndef F_OK
+#define F_OK 0
+#endif
+#ifndef R_OK
+#define R_OK 4
+#endif
+#ifndef W_OK
+#define W_OK 2
+#endif
+#ifndef X_OK
+#define X_OK 1
+#endif
+
+/* fs open() flags supported on this platform: */
+#define UV_FS_O_APPEND       _O_APPEND
+#define UV_FS_O_CREAT        _O_CREAT
+#define UV_FS_O_EXCL         _O_EXCL
+#define UV_FS_O_RANDOM       _O_RANDOM
+#define UV_FS_O_RDONLY       _O_RDONLY
+#define UV_FS_O_RDWR         _O_RDWR
+#define UV_FS_O_SEQUENTIAL   _O_SEQUENTIAL
+#define UV_FS_O_SHORT_LIVED  _O_SHORT_LIVED
+#define UV_FS_O_TEMPORARY    _O_TEMPORARY
+#define UV_FS_O_TRUNC        _O_TRUNC
+#define UV_FS_O_WRONLY       _O_WRONLY
+
+/* fs open() flags supported on other platforms (or mapped on this platform): */
+#define UV_FS_O_DIRECT       0x02000000 /* FILE_FLAG_NO_BUFFERING */
+#define UV_FS_O_DIRECTORY    0
+#define UV_FS_O_DSYNC        0x04000000 /* FILE_FLAG_WRITE_THROUGH */
+#define UV_FS_O_EXLOCK       0x10000000 /* EXCLUSIVE SHARING MODE */
+#define UV_FS_O_NOATIME      0
+#define UV_FS_O_NOCTTY       0
+#define UV_FS_O_NOFOLLOW     0
+#define UV_FS_O_NONBLOCK     0
+#define UV_FS_O_SYMLINK      0
+#define UV_FS_O_SYNC         0x08000000 /* FILE_FLAG_WRITE_THROUGH */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/AlignOf.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/AlignOf.h
new file mode 100644
index 0000000..4ce34cd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/AlignOf.h
@@ -0,0 +1,146 @@
+//===--- AlignOf.h - Portable calculation of type alignment -----*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the AlignedCharArray and AlignedCharArrayUnion classes.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ALIGNOF_H
+#define WPIUTIL_WPI_ALIGNOF_H
+
+#include "wpi/Compiler.h"
+#include <cstddef>
+
+namespace wpi {
+
+/// \struct AlignedCharArray
+/// Helper for building an aligned character array type.
+///
+/// This template is used to explicitly build up a collection of aligned
+/// character array types. We have to build these up using a macro and explicit
+/// specialization to cope with MSVC (at least till 2015) where only an
+/// integer literal can be used to specify an alignment constraint. Once built
+/// up here, we can then begin to indirect between these using normal C++
+/// template parameters.
+
+// MSVC requires special handling here.
+#ifndef _MSC_VER
+
+template<std::size_t Alignment, std::size_t Size>
+struct AlignedCharArray {
+  LLVM_ALIGNAS(Alignment) char buffer[Size];
+};
+
+#else // _MSC_VER
+
+/// Create a type with an aligned char buffer.
+template<std::size_t Alignment, std::size_t Size>
+struct AlignedCharArray;
+
+// We provide special variations of this template for the most common
+// alignments because __declspec(align(...)) doesn't actually work when it is
+// a member of a by-value function argument in MSVC, even if the alignment
+// request is something reasonably like 8-byte or 16-byte. Note that we can't
+// even include the declspec with the union that forces the alignment because
+// MSVC warns on the existence of the declspec despite the union member forcing
+// proper alignment.
+
+template<std::size_t Size>
+struct AlignedCharArray<1, Size> {
+  union {
+    char aligned;
+    char buffer[Size];
+  };
+};
+
+template<std::size_t Size>
+struct AlignedCharArray<2, Size> {
+  union {
+    short aligned;
+    char buffer[Size];
+  };
+};
+
+template<std::size_t Size>
+struct AlignedCharArray<4, Size> {
+  union {
+    int aligned;
+    char buffer[Size];
+  };
+};
+
+template<std::size_t Size>
+struct AlignedCharArray<8, Size> {
+  union {
+    double aligned;
+    char buffer[Size];
+  };
+};
+
+
+// The rest of these are provided with a __declspec(align(...)) and we simply
+// can't pass them by-value as function arguments on MSVC.
+
+#define LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(x) \
+  template<std::size_t Size> \
+  struct AlignedCharArray<x, Size> { \
+    __declspec(align(x)) char buffer[Size]; \
+  };
+
+LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(16)
+LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(32)
+LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(64)
+LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT(128)
+
+#undef LLVM_ALIGNEDCHARARRAY_TEMPLATE_ALIGNMENT
+
+#endif // _MSC_VER
+
+namespace detail {
+template <typename T1,
+          typename T2 = char, typename T3 = char, typename T4 = char,
+          typename T5 = char, typename T6 = char, typename T7 = char,
+          typename T8 = char, typename T9 = char, typename T10 = char>
+class AlignerImpl {
+  T1 t1; T2 t2; T3 t3; T4 t4; T5 t5; T6 t6; T7 t7; T8 t8; T9 t9; T10 t10;
+
+  AlignerImpl() = delete;
+};
+
+template <typename T1,
+          typename T2 = char, typename T3 = char, typename T4 = char,
+          typename T5 = char, typename T6 = char, typename T7 = char,
+          typename T8 = char, typename T9 = char, typename T10 = char>
+union SizerImpl {
+  char arr1[sizeof(T1)], arr2[sizeof(T2)], arr3[sizeof(T3)], arr4[sizeof(T4)],
+       arr5[sizeof(T5)], arr6[sizeof(T6)], arr7[sizeof(T7)], arr8[sizeof(T8)],
+       arr9[sizeof(T9)], arr10[sizeof(T10)];
+};
+} // end namespace detail
+
+/// This union template exposes a suitably aligned and sized character
+/// array member which can hold elements of any of up to ten types.
+///
+/// These types may be arrays, structs, or any other types. The goal is to
+/// expose a char array buffer member which can be used as suitable storage for
+/// a placement new of any of these types. Support for more than ten types can
+/// be added at the cost of more boilerplate.
+template <typename T1,
+          typename T2 = char, typename T3 = char, typename T4 = char,
+          typename T5 = char, typename T6 = char, typename T7 = char,
+          typename T8 = char, typename T9 = char, typename T10 = char>
+struct AlignedCharArrayUnion : wpi::AlignedCharArray<
+    alignof(wpi::detail::AlignerImpl<T1, T2, T3, T4, T5,
+                                      T6, T7, T8, T9, T10>),
+    sizeof(::wpi::detail::SizerImpl<T1, T2, T3, T4, T5,
+                                     T6, T7, T8, T9, T10>)> {
+};
+} // end namespace wpi
+
+#endif // LLVM_SUPPORT_ALIGNOF_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ArrayRef.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ArrayRef.h
new file mode 100644
index 0000000..08f413d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ArrayRef.h
@@ -0,0 +1,541 @@
+//===- ArrayRef.h - Array Reference Wrapper ---------------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ARRAYREF_H
+#define WPIUTIL_WPI_ARRAYREF_H
+
+#include "wpi/Hashing.h"
+#include "wpi/optional.h"
+#include "wpi/SmallVector.h"
+#include "wpi/STLExtras.h"
+#include "wpi/Compiler.h"
+#include <algorithm>
+#include <array>
+#include <cassert>
+#include <cstddef>
+#include <initializer_list>
+#include <iterator>
+#include <memory>
+#include <type_traits>
+#include <vector>
+
+namespace wpi {
+  /// ArrayRef - Represent a constant reference to an array (0 or more elements
+  /// consecutively in memory), i.e. a start pointer and a length.  It allows
+  /// various APIs to take consecutive elements easily and conveniently.
+  ///
+  /// This class does not own the underlying data, it is expected to be used in
+  /// situations where the data resides in some other buffer, whose lifetime
+  /// extends past that of the ArrayRef. For this reason, it is not in general
+  /// safe to store an ArrayRef.
+  ///
+  /// This is intended to be trivially copyable, so it should be passed by
+  /// value.
+  template<typename T>
+  class LLVM_NODISCARD ArrayRef {
+  public:
+    using iterator = const T *;
+    using const_iterator = const T *;
+    using size_type = size_t;
+    using reverse_iterator = std::reverse_iterator<iterator>;
+    using value_type = T;
+
+  private:
+    /// The start of the array, in an external buffer.
+    const T *Data = nullptr;
+
+    /// The number of elements.
+    size_type Length = 0;
+
+  public:
+    /// @name Constructors
+    /// @{
+
+    /// Construct an empty ArrayRef.
+    /*implicit*/ ArrayRef() = default;
+
+    /// Construct an empty ArrayRef from nullopt.
+    /*implicit*/ ArrayRef(nullopt_t) {}
+
+    /// Construct an ArrayRef from a single element.
+    /*implicit*/ ArrayRef(const T &OneElt)
+      : Data(&OneElt), Length(1) {}
+
+    /// Construct an ArrayRef from a pointer and length.
+    /*implicit*/ ArrayRef(const T *data, size_t length)
+      : Data(data), Length(length) {}
+
+    /// Construct an ArrayRef from a range.
+    ArrayRef(const T *begin, const T *end)
+      : Data(begin), Length(end - begin) {}
+
+    /// Construct an ArrayRef from a SmallVector. This is templated in order to
+    /// avoid instantiating SmallVectorTemplateCommon<T> whenever we
+    /// copy-construct an ArrayRef.
+    template<typename U>
+    /*implicit*/ ArrayRef(const SmallVectorTemplateCommon<T, U> &Vec)
+      : Data(Vec.data()), Length(Vec.size()) {
+    }
+
+    /// Construct an ArrayRef from a std::vector.
+    template<typename A>
+    /*implicit*/ ArrayRef(const std::vector<T, A> &Vec)
+      : Data(Vec.data()), Length(Vec.size()) {}
+
+    /// Construct an ArrayRef from a std::array
+    template <size_t N>
+    /*implicit*/ constexpr ArrayRef(const std::array<T, N> &Arr)
+        : Data(Arr.data()), Length(N) {}
+
+    /// Construct an ArrayRef from a C array.
+    template <size_t N>
+    /*implicit*/ constexpr ArrayRef(const T (&Arr)[N]) : Data(Arr), Length(N) {}
+
+    /// Construct an ArrayRef from a std::initializer_list.
+    /*implicit*/ ArrayRef(const std::initializer_list<T> &Vec)
+    : Data(Vec.begin() == Vec.end() ? (T*)nullptr : Vec.begin()),
+      Length(Vec.size()) {}
+
+    /// Construct an ArrayRef<const T*> from ArrayRef<T*>. This uses SFINAE to
+    /// ensure that only ArrayRefs of pointers can be converted.
+    template <typename U>
+    ArrayRef(
+        const ArrayRef<U *> &A,
+        typename std::enable_if<
+           std::is_convertible<U *const *, T const *>::value>::type * = nullptr)
+      : Data(A.data()), Length(A.size()) {}
+
+    /// Construct an ArrayRef<const T*> from a SmallVector<T*>. This is
+    /// templated in order to avoid instantiating SmallVectorTemplateCommon<T>
+    /// whenever we copy-construct an ArrayRef.
+    template<typename U, typename DummyT>
+    /*implicit*/ ArrayRef(
+      const SmallVectorTemplateCommon<U *, DummyT> &Vec,
+      typename std::enable_if<
+          std::is_convertible<U *const *, T const *>::value>::type * = nullptr)
+      : Data(Vec.data()), Length(Vec.size()) {
+    }
+
+    /// Construct an ArrayRef<const T*> from std::vector<T*>. This uses SFINAE
+    /// to ensure that only vectors of pointers can be converted.
+    template<typename U, typename A>
+    ArrayRef(const std::vector<U *, A> &Vec,
+             typename std::enable_if<
+                 std::is_convertible<U *const *, T const *>::value>::type* = 0)
+      : Data(Vec.data()), Length(Vec.size()) {}
+
+    /// @}
+    /// @name Simple Operations
+    /// @{
+
+    iterator begin() const { return Data; }
+    iterator end() const { return Data + Length; }
+
+    reverse_iterator rbegin() const { return reverse_iterator(end()); }
+    reverse_iterator rend() const { return reverse_iterator(begin()); }
+
+    /// empty - Check if the array is empty.
+    bool empty() const { return Length == 0; }
+
+    const T *data() const { return Data; }
+
+    /// size - Get the array size.
+    size_t size() const { return Length; }
+
+    /// front - Get the first element.
+    const T &front() const {
+      assert(!empty());
+      return Data[0];
+    }
+
+    /// back - Get the last element.
+    const T &back() const {
+      assert(!empty());
+      return Data[Length-1];
+    }
+
+    // copy - Allocate copy in Allocator and return ArrayRef<T> to it.
+    template <typename Allocator> ArrayRef<T> copy(Allocator &A) {
+      T *Buff = A.template Allocate<T>(Length);
+      std::uninitialized_copy(begin(), end(), Buff);
+      return ArrayRef<T>(Buff, Length);
+    }
+
+    /// equals - Check for element-wise equality.
+    bool equals(ArrayRef RHS) const {
+      if (Length != RHS.Length)
+        return false;
+      return std::equal(begin(), end(), RHS.begin());
+    }
+
+    /// slice(n, m) - Chop off the first N elements of the array, and keep M
+    /// elements in the array.
+    ArrayRef<T> slice(size_t N, size_t M) const {
+      assert(N+M <= size() && "Invalid specifier");
+      return ArrayRef<T>(data()+N, M);
+    }
+
+    /// slice(n) - Chop off the first N elements of the array.
+    ArrayRef<T> slice(size_t N) const { return slice(N, size() - N); }
+
+    /// Drop the first \p N elements of the array.
+    ArrayRef<T> drop_front(size_t N = 1) const {
+      assert(size() >= N && "Dropping more elements than exist");
+      return slice(N, size() - N);
+    }
+
+    /// Drop the last \p N elements of the array.
+    ArrayRef<T> drop_back(size_t N = 1) const {
+      assert(size() >= N && "Dropping more elements than exist");
+      return slice(0, size() - N);
+    }
+
+    /// Return a copy of *this with the first N elements satisfying the
+    /// given predicate removed.
+    template <class PredicateT> ArrayRef<T> drop_while(PredicateT Pred) const {
+      return ArrayRef<T>(find_if_not(*this, Pred), end());
+    }
+
+    /// Return a copy of *this with the first N elements not satisfying
+    /// the given predicate removed.
+    template <class PredicateT> ArrayRef<T> drop_until(PredicateT Pred) const {
+      return ArrayRef<T>(find_if(*this, Pred), end());
+    }
+
+    /// Return a copy of *this with only the first \p N elements.
+    ArrayRef<T> take_front(size_t N = 1) const {
+      if (N >= size())
+        return *this;
+      return drop_back(size() - N);
+    }
+
+    /// Return a copy of *this with only the last \p N elements.
+    ArrayRef<T> take_back(size_t N = 1) const {
+      if (N >= size())
+        return *this;
+      return drop_front(size() - N);
+    }
+
+    /// Return the first N elements of this Array that satisfy the given
+    /// predicate.
+    template <class PredicateT> ArrayRef<T> take_while(PredicateT Pred) const {
+      return ArrayRef<T>(begin(), find_if_not(*this, Pred));
+    }
+
+    /// Return the first N elements of this Array that don't satisfy the
+    /// given predicate.
+    template <class PredicateT> ArrayRef<T> take_until(PredicateT Pred) const {
+      return ArrayRef<T>(begin(), find_if(*this, Pred));
+    }
+
+    /// @}
+    /// @name Operator Overloads
+    /// @{
+    const T &operator[](size_t Index) const {
+      assert(Index < Length && "Invalid index!");
+      return Data[Index];
+    }
+
+    /// Disallow accidental assignment from a temporary.
+    ///
+    /// The declaration here is extra complicated so that "arrayRef = {}"
+    /// continues to select the move assignment operator.
+    template <typename U>
+    typename std::enable_if<std::is_same<U, T>::value, ArrayRef<T>>::type &
+    operator=(U &&Temporary) = delete;
+
+    /// Disallow accidental assignment from a temporary.
+    ///
+    /// The declaration here is extra complicated so that "arrayRef = {}"
+    /// continues to select the move assignment operator.
+    template <typename U>
+    typename std::enable_if<std::is_same<U, T>::value, ArrayRef<T>>::type &
+    operator=(std::initializer_list<U>) = delete;
+
+    /// @}
+    /// @name Expensive Operations
+    /// @{
+    std::vector<T> vec() const {
+      return std::vector<T>(Data, Data+Length);
+    }
+
+    /// @}
+    /// @name Conversion operators
+    /// @{
+    operator std::vector<T>() const {
+      return std::vector<T>(Data, Data+Length);
+    }
+
+    /// @}
+  };
+
+  /// MutableArrayRef - Represent a mutable reference to an array (0 or more
+  /// elements consecutively in memory), i.e. a start pointer and a length.  It
+  /// allows various APIs to take and modify consecutive elements easily and
+  /// conveniently.
+  ///
+  /// This class does not own the underlying data, it is expected to be used in
+  /// situations where the data resides in some other buffer, whose lifetime
+  /// extends past that of the MutableArrayRef. For this reason, it is not in
+  /// general safe to store a MutableArrayRef.
+  ///
+  /// This is intended to be trivially copyable, so it should be passed by
+  /// value.
+  template<typename T>
+  class LLVM_NODISCARD MutableArrayRef : public ArrayRef<T> {
+  public:
+    using iterator = T *;
+    using reverse_iterator = std::reverse_iterator<iterator>;
+
+    /// Construct an empty MutableArrayRef.
+    /*implicit*/ MutableArrayRef() = default;
+
+    /// Construct an empty MutableArrayRef from nullopt.
+    /*implicit*/ MutableArrayRef(nullopt_t) : ArrayRef<T>() {}
+
+    /// Construct an MutableArrayRef from a single element.
+    /*implicit*/ MutableArrayRef(T &OneElt) : ArrayRef<T>(OneElt) {}
+
+    /// Construct an MutableArrayRef from a pointer and length.
+    /*implicit*/ MutableArrayRef(T *data, size_t length)
+      : ArrayRef<T>(data, length) {}
+
+    /// Construct an MutableArrayRef from a range.
+    MutableArrayRef(T *begin, T *end) : ArrayRef<T>(begin, end) {}
+
+    /// Construct an MutableArrayRef from a SmallVector.
+    /*implicit*/ MutableArrayRef(SmallVectorImpl<T> &Vec)
+    : ArrayRef<T>(Vec) {}
+
+    /// Construct a MutableArrayRef from a std::vector.
+    /*implicit*/ MutableArrayRef(std::vector<T> &Vec)
+    : ArrayRef<T>(Vec) {}
+
+    /// Construct an ArrayRef from a std::array
+    template <size_t N>
+    /*implicit*/ constexpr MutableArrayRef(std::array<T, N> &Arr)
+        : ArrayRef<T>(Arr) {}
+
+    /// Construct an MutableArrayRef from a C array.
+    template <size_t N>
+    /*implicit*/ constexpr MutableArrayRef(T (&Arr)[N]) : ArrayRef<T>(Arr) {}
+
+    T *data() const { return const_cast<T*>(ArrayRef<T>::data()); }
+
+    iterator begin() const { return data(); }
+    iterator end() const { return data() + this->size(); }
+
+    reverse_iterator rbegin() const { return reverse_iterator(end()); }
+    reverse_iterator rend() const { return reverse_iterator(begin()); }
+
+    /// front - Get the first element.
+    T &front() const {
+      assert(!this->empty());
+      return data()[0];
+    }
+
+    /// back - Get the last element.
+    T &back() const {
+      assert(!this->empty());
+      return data()[this->size()-1];
+    }
+
+    /// slice(n, m) - Chop off the first N elements of the array, and keep M
+    /// elements in the array.
+    MutableArrayRef<T> slice(size_t N, size_t M) const {
+      assert(N + M <= this->size() && "Invalid specifier");
+      return MutableArrayRef<T>(this->data() + N, M);
+    }
+
+    /// slice(n) - Chop off the first N elements of the array.
+    MutableArrayRef<T> slice(size_t N) const {
+      return slice(N, this->size() - N);
+    }
+
+    /// Drop the first \p N elements of the array.
+    MutableArrayRef<T> drop_front(size_t N = 1) const {
+      assert(this->size() >= N && "Dropping more elements than exist");
+      return slice(N, this->size() - N);
+    }
+
+    MutableArrayRef<T> drop_back(size_t N = 1) const {
+      assert(this->size() >= N && "Dropping more elements than exist");
+      return slice(0, this->size() - N);
+    }
+
+    /// Return a copy of *this with the first N elements satisfying the
+    /// given predicate removed.
+    template <class PredicateT>
+    MutableArrayRef<T> drop_while(PredicateT Pred) const {
+      return MutableArrayRef<T>(find_if_not(*this, Pred), end());
+    }
+
+    /// Return a copy of *this with the first N elements not satisfying
+    /// the given predicate removed.
+    template <class PredicateT>
+    MutableArrayRef<T> drop_until(PredicateT Pred) const {
+      return MutableArrayRef<T>(find_if(*this, Pred), end());
+    }
+
+    /// Return a copy of *this with only the first \p N elements.
+    MutableArrayRef<T> take_front(size_t N = 1) const {
+      if (N >= this->size())
+        return *this;
+      return drop_back(this->size() - N);
+    }
+
+    /// Return a copy of *this with only the last \p N elements.
+    MutableArrayRef<T> take_back(size_t N = 1) const {
+      if (N >= this->size())
+        return *this;
+      return drop_front(this->size() - N);
+    }
+
+    /// Return the first N elements of this Array that satisfy the given
+    /// predicate.
+    template <class PredicateT>
+    MutableArrayRef<T> take_while(PredicateT Pred) const {
+      return MutableArrayRef<T>(begin(), find_if_not(*this, Pred));
+    }
+
+    /// Return the first N elements of this Array that don't satisfy the
+    /// given predicate.
+    template <class PredicateT>
+    MutableArrayRef<T> take_until(PredicateT Pred) const {
+      return MutableArrayRef<T>(begin(), find_if(*this, Pred));
+    }
+
+    /// @}
+    /// @name Operator Overloads
+    /// @{
+    T &operator[](size_t Index) const {
+      assert(Index < this->size() && "Invalid index!");
+      return data()[Index];
+    }
+  };
+
+  /// This is a MutableArrayRef that owns its array.
+  template <typename T> class OwningArrayRef : public MutableArrayRef<T> {
+  public:
+    OwningArrayRef() = default;
+    OwningArrayRef(size_t Size) : MutableArrayRef<T>(new T[Size], Size) {}
+
+    OwningArrayRef(ArrayRef<T> Data)
+        : MutableArrayRef<T>(new T[Data.size()], Data.size()) {
+      std::copy(Data.begin(), Data.end(), this->begin());
+    }
+
+    OwningArrayRef(OwningArrayRef &&Other) { *this = Other; }
+
+    OwningArrayRef &operator=(OwningArrayRef &&Other) {
+      delete[] this->data();
+      this->MutableArrayRef<T>::operator=(Other);
+      Other.MutableArrayRef<T>::operator=(MutableArrayRef<T>());
+      return *this;
+    }
+
+    ~OwningArrayRef() { delete[] this->data(); }
+  };
+
+  /// @name ArrayRef Convenience constructors
+  /// @{
+
+  /// Construct an ArrayRef from a single element.
+  template<typename T>
+  ArrayRef<T> makeArrayRef(const T &OneElt) {
+    return OneElt;
+  }
+
+  /// Construct an ArrayRef from a pointer and length.
+  template<typename T>
+  ArrayRef<T> makeArrayRef(const T *data, size_t length) {
+    return ArrayRef<T>(data, length);
+  }
+
+  /// Construct an ArrayRef from a range.
+  template<typename T>
+  ArrayRef<T> makeArrayRef(const T *begin, const T *end) {
+    return ArrayRef<T>(begin, end);
+  }
+
+  /// Construct an ArrayRef from a SmallVector.
+  template <typename T>
+  ArrayRef<T> makeArrayRef(const SmallVectorImpl<T> &Vec) {
+    return Vec;
+  }
+
+  /// Construct an ArrayRef from a SmallVector.
+  template <typename T, unsigned N>
+  ArrayRef<T> makeArrayRef(const SmallVector<T, N> &Vec) {
+    return Vec;
+  }
+
+  /// Construct an ArrayRef from a std::vector.
+  template<typename T>
+  ArrayRef<T> makeArrayRef(const std::vector<T> &Vec) {
+    return Vec;
+  }
+
+  /// Construct an ArrayRef from an ArrayRef (no-op) (const)
+  template <typename T> ArrayRef<T> makeArrayRef(const ArrayRef<T> &Vec) {
+    return Vec;
+  }
+
+  /// Construct an ArrayRef from an ArrayRef (no-op)
+  template <typename T> ArrayRef<T> &makeArrayRef(ArrayRef<T> &Vec) {
+    return Vec;
+  }
+
+  /// Construct an ArrayRef from a C array.
+  template<typename T, size_t N>
+  ArrayRef<T> makeArrayRef(const T (&Arr)[N]) {
+    return ArrayRef<T>(Arr);
+  }
+
+  /// Construct a MutableArrayRef from a single element.
+  template<typename T>
+  MutableArrayRef<T> makeMutableArrayRef(T &OneElt) {
+    return OneElt;
+  }
+
+  /// Construct a MutableArrayRef from a pointer and length.
+  template<typename T>
+  MutableArrayRef<T> makeMutableArrayRef(T *data, size_t length) {
+    return MutableArrayRef<T>(data, length);
+  }
+
+  /// @}
+  /// @name ArrayRef Comparison Operators
+  /// @{
+
+  template<typename T>
+  inline bool operator==(ArrayRef<T> LHS, ArrayRef<T> RHS) {
+    return LHS.equals(RHS);
+  }
+
+  template<typename T>
+  inline bool operator!=(ArrayRef<T> LHS, ArrayRef<T> RHS) {
+    return !(LHS == RHS);
+  }
+
+  /// @}
+
+  // ArrayRefs can be treated like a POD type.
+  template <typename T> struct isPodLike;
+  template <typename T> struct isPodLike<ArrayRef<T>> {
+    static const bool value = true;
+  };
+
+  template <typename T> hash_code hash_value(ArrayRef<T> S) {
+    return hash_combine_range(S.begin(), S.end());
+  }
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_ARRAYREF_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Base64.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Base64.h
new file mode 100644
index 0000000..cdbf611
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Base64.h
@@ -0,0 +1,36 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_BASE64_H_
+#define WPIUTIL_WPI_BASE64_H_
+
+#include <cstddef>
+#include <string>
+
+#include "wpi/StringRef.h"
+
+namespace wpi {
+template <typename T>
+class SmallVectorImpl;
+class raw_ostream;
+
+size_t Base64Decode(raw_ostream& os, StringRef encoded);
+
+size_t Base64Decode(StringRef encoded, std::string* plain);
+
+StringRef Base64Decode(StringRef encoded, size_t* num_read,
+                       SmallVectorImpl<char>& buf);
+
+void Base64Encode(raw_ostream& os, StringRef plain);
+
+void Base64Encode(StringRef plain, std::string* encoded);
+
+StringRef Base64Encode(StringRef plain, SmallVectorImpl<char>& buf);
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_BASE64_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Compiler.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Compiler.h
new file mode 100644
index 0000000..6e13ef4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Compiler.h
@@ -0,0 +1,426 @@
+//===-- llvm/Support/Compiler.h - Compiler abstraction support --*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines several macros, based on the current compiler.  This allows
+// use of compiler-specific features in a way that remains portable.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_COMPILER_H
+#define WPIUTIL_WPI_COMPILER_H
+
+#if defined(_MSC_VER)
+#include <sal.h>
+#endif
+
+#ifndef __has_feature
+# define __has_feature(x) 0
+#endif
+
+#ifndef __has_extension
+# define __has_extension(x) 0
+#endif
+
+#ifndef __has_attribute
+# define __has_attribute(x) 0
+#endif
+
+#ifndef __has_cpp_attribute
+# define __has_cpp_attribute(x) 0
+#endif
+
+#ifndef __has_builtin
+# define __has_builtin(x) 0
+#endif
+
+/// \macro LLVM_GNUC_PREREQ
+/// Extend the default __GNUC_PREREQ even if glibc's features.h isn't
+/// available.
+#ifndef LLVM_GNUC_PREREQ
+# if defined(__GNUC__) && defined(__GNUC_MINOR__) && defined(__GNUC_PATCHLEVEL__)
+#  define LLVM_GNUC_PREREQ(maj, min, patch) \
+    ((__GNUC__ << 20) + (__GNUC_MINOR__ << 10) + __GNUC_PATCHLEVEL__ >= \
+     ((maj) << 20) + ((min) << 10) + (patch))
+# elif defined(__GNUC__) && defined(__GNUC_MINOR__)
+#  define LLVM_GNUC_PREREQ(maj, min, patch) \
+    ((__GNUC__ << 20) + (__GNUC_MINOR__ << 10) >= ((maj) << 20) + ((min) << 10))
+# else
+#  define LLVM_GNUC_PREREQ(maj, min, patch) 0
+# endif
+#endif
+
+/// \macro LLVM_MSC_PREREQ
+/// Is the compiler MSVC of at least the specified version?
+/// The common \param version values to check for are:
+///  * 1900: Microsoft Visual Studio 2015 / 14.0
+#ifndef LLVM_MSC_PREREQ
+#ifdef _MSC_VER
+#define LLVM_MSC_PREREQ(version) (_MSC_VER >= (version))
+
+// We require at least MSVC 2015.
+#if !LLVM_MSC_PREREQ(1900)
+#error wpiutil requires at least MSVC 2015.
+#endif
+
+#else
+#define LLVM_MSC_PREREQ(version) 0
+#endif
+#endif
+
+/// Does the compiler support ref-qualifiers for *this?
+///
+/// Sadly, this is separate from just rvalue reference support because GCC
+/// and MSVC implemented this later than everything else.
+#ifndef LLVM_HAS_RVALUE_REFERENCE_THIS
+#if __has_feature(cxx_rvalue_references) || LLVM_GNUC_PREREQ(4, 8, 1)
+#define LLVM_HAS_RVALUE_REFERENCE_THIS 1
+#else
+#define LLVM_HAS_RVALUE_REFERENCE_THIS 0
+#endif
+#endif
+
+/// Expands to '&' if ref-qualifiers for *this are supported.
+///
+/// This can be used to provide lvalue/rvalue overrides of member functions.
+/// The rvalue override should be guarded by LLVM_HAS_RVALUE_REFERENCE_THIS
+#ifndef LLVM_LVALUE_FUNCTION
+#if LLVM_HAS_RVALUE_REFERENCE_THIS
+#define LLVM_LVALUE_FUNCTION &
+#else
+#define LLVM_LVALUE_FUNCTION
+#endif
+#endif
+
+#ifndef LLVM_PREFETCH
+#if defined(__GNUC__)
+#define LLVM_PREFETCH(addr, rw, locality) __builtin_prefetch(addr, rw, locality)
+#else
+#define LLVM_PREFETCH(addr, rw, locality)
+#endif
+#endif
+
+#ifndef LLVM_ATTRIBUTE_USED
+#if __has_attribute(used) || LLVM_GNUC_PREREQ(3, 1, 0)
+#define LLVM_ATTRIBUTE_USED __attribute__((__used__))
+#else
+#define LLVM_ATTRIBUTE_USED
+#endif
+#endif
+
+/// LLVM_NODISCARD - Warn if a type or return value is discarded.
+#ifndef LLVM_NODISCARD
+#if __cplusplus > 201402L && __has_cpp_attribute(nodiscard)
+#define LLVM_NODISCARD [[nodiscard]]
+#elif !__cplusplus
+// Workaround for llvm.org/PR23435, since clang 3.6 and below emit a spurious
+// error when __has_cpp_attribute is given a scoped attribute in C mode.
+#define LLVM_NODISCARD
+#elif __has_cpp_attribute(clang::warn_unused_result)
+#define LLVM_NODISCARD [[clang::warn_unused_result]]
+#else
+#define LLVM_NODISCARD
+#endif
+#endif
+
+// Some compilers warn about unused functions. When a function is sometimes
+// used or not depending on build settings (e.g. a function only called from
+// within "assert"), this attribute can be used to suppress such warnings.
+//
+// However, it shouldn't be used for unused *variables*, as those have a much
+// more portable solution:
+//   (void)unused_var_name;
+// Prefer cast-to-void wherever it is sufficient.
+#ifndef LLVM_ATTRIBUTE_UNUSED
+#if __has_attribute(unused) || LLVM_GNUC_PREREQ(3, 1, 0)
+#define LLVM_ATTRIBUTE_UNUSED __attribute__((__unused__))
+#else
+#define LLVM_ATTRIBUTE_UNUSED
+#endif
+#endif
+
+#ifndef LLVM_READNONE
+// Prior to clang 3.2, clang did not accept any spelling of
+// __has_attribute(const), so assume it is supported.
+#if defined(__clang__) || defined(__GNUC__)
+// aka 'CONST' but following LLVM Conventions.
+#define LLVM_READNONE __attribute__((__const__))
+#else
+#define LLVM_READNONE
+#endif
+#endif
+
+#ifndef LLVM_READONLY
+#if __has_attribute(pure) || defined(__GNUC__)
+// aka 'PURE' but following LLVM Conventions.
+#define LLVM_READONLY __attribute__((__pure__))
+#else
+#define LLVM_READONLY
+#endif
+#endif
+
+#ifndef LLVM_LIKELY
+#if __has_builtin(__builtin_expect) || LLVM_GNUC_PREREQ(4, 0, 0)
+#define LLVM_LIKELY(EXPR) __builtin_expect((bool)(EXPR), true)
+#define LLVM_UNLIKELY(EXPR) __builtin_expect((bool)(EXPR), false)
+#else
+#define LLVM_LIKELY(EXPR) (EXPR)
+#define LLVM_UNLIKELY(EXPR) (EXPR)
+#endif
+#endif
+
+/// LLVM_ATTRIBUTE_NOINLINE - On compilers where we have a directive to do so,
+/// mark a method "not for inlining".
+#ifndef LLVM_ATTRIBUTE_NOINLINE
+#if __has_attribute(noinline) || LLVM_GNUC_PREREQ(3, 4, 0)
+#define LLVM_ATTRIBUTE_NOINLINE __attribute__((noinline))
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_NOINLINE __declspec(noinline)
+#else
+#define LLVM_ATTRIBUTE_NOINLINE
+#endif
+#endif
+
+/// LLVM_ATTRIBUTE_ALWAYS_INLINE - On compilers where we have a directive to do
+/// so, mark a method "always inline" because it is performance sensitive. GCC
+/// 3.4 supported this but is buggy in various cases and produces unimplemented
+/// errors, just use it in GCC 4.0 and later.
+#ifndef LLVM_ATTRIBUTE_ALWAYS_INLINE
+#if __has_attribute(always_inline) || LLVM_GNUC_PREREQ(4, 0, 0)
+#define LLVM_ATTRIBUTE_ALWAYS_INLINE __attribute__((always_inline)) inline
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_ALWAYS_INLINE __forceinline
+#else
+#define LLVM_ATTRIBUTE_ALWAYS_INLINE inline
+#endif
+#endif
+
+#ifndef LLVM_ATTRIBUTE_NORETURN
+#ifdef __GNUC__
+#define LLVM_ATTRIBUTE_NORETURN __attribute__((noreturn))
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_NORETURN __declspec(noreturn)
+#else
+#define LLVM_ATTRIBUTE_NORETURN
+#endif
+#endif
+
+#ifndef LLVM_ATTRIBUTE_RETURNS_NONNULL
+#if __has_attribute(returns_nonnull) || LLVM_GNUC_PREREQ(4, 9, 0)
+#define LLVM_ATTRIBUTE_RETURNS_NONNULL __attribute__((returns_nonnull))
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_RETURNS_NONNULL _Ret_notnull_
+#else
+#define LLVM_ATTRIBUTE_RETURNS_NONNULL
+#endif
+#endif
+
+/// \macro LLVM_ATTRIBUTE_RETURNS_NOALIAS Used to mark a function as returning a
+/// pointer that does not alias any other valid pointer.
+#ifndef LLVM_ATTRIBUTE_RETURNS_NOALIAS
+#ifdef __GNUC__
+#define LLVM_ATTRIBUTE_RETURNS_NOALIAS __attribute__((__malloc__))
+#elif defined(_MSC_VER)
+#define LLVM_ATTRIBUTE_RETURNS_NOALIAS __declspec(restrict)
+#else
+#define LLVM_ATTRIBUTE_RETURNS_NOALIAS
+#endif
+#endif
+
+/// LLVM_FALLTHROUGH - Mark fallthrough cases in switch statements.
+#ifndef LLVM_FALLTHROUGH
+#if __cplusplus > 201402L && __has_cpp_attribute(fallthrough)
+#define LLVM_FALLTHROUGH [[fallthrough]]
+#elif __has_cpp_attribute(gnu::fallthrough)
+#define LLVM_FALLTHROUGH [[gnu::fallthrough]]
+#elif !__cplusplus
+// Workaround for llvm.org/PR23435, since clang 3.6 and below emit a spurious
+// error when __has_cpp_attribute is given a scoped attribute in C mode.
+#define LLVM_FALLTHROUGH
+#elif __has_cpp_attribute(clang::fallthrough)
+#define LLVM_FALLTHROUGH [[clang::fallthrough]]
+#else
+#define LLVM_FALLTHROUGH
+#endif
+#endif
+
+/// LLVM_EXTENSION - Support compilers where we have a keyword to suppress
+/// pedantic diagnostics.
+#ifndef LLVM_EXTENSION
+#ifdef __GNUC__
+#define LLVM_EXTENSION __extension__
+#else
+#define LLVM_EXTENSION
+#endif
+#endif
+
+// LLVM_ATTRIBUTE_DEPRECATED(decl, "message")
+#ifndef LLVM_ATTRIBUTE_DEPRECATED
+#if __has_feature(attribute_deprecated_with_message)
+# define LLVM_ATTRIBUTE_DEPRECATED(decl, message) \
+  decl __attribute__((deprecated(message)))
+#elif defined(__GNUC__)
+# define LLVM_ATTRIBUTE_DEPRECATED(decl, message) \
+  decl __attribute__((deprecated))
+#elif defined(_MSC_VER)
+# define LLVM_ATTRIBUTE_DEPRECATED(decl, message) \
+  __declspec(deprecated(message)) decl
+#else
+# define LLVM_ATTRIBUTE_DEPRECATED(decl, message) \
+  decl
+#endif
+#endif
+
+/// LLVM_BUILTIN_UNREACHABLE - On compilers which support it, expands
+/// to an expression which states that it is undefined behavior for the
+/// compiler to reach this point.  Otherwise is not defined.
+#ifndef LLVM_BUILTIN_UNREACHABLE
+#if __has_builtin(__builtin_unreachable) || LLVM_GNUC_PREREQ(4, 5, 0)
+# define LLVM_BUILTIN_UNREACHABLE __builtin_unreachable()
+#elif defined(_MSC_VER)
+# define LLVM_BUILTIN_UNREACHABLE __assume(false)
+#endif
+#endif
+
+/// \macro LLVM_ASSUME_ALIGNED
+/// Returns a pointer with an assumed alignment.
+#ifndef LLVM_ASSUME_ALIGNED
+#if __has_builtin(__builtin_assume_aligned) || LLVM_GNUC_PREREQ(4, 7, 0)
+# define LLVM_ASSUME_ALIGNED(p, a) __builtin_assume_aligned(p, a)
+#elif defined(LLVM_BUILTIN_UNREACHABLE)
+// As of today, clang does not support __builtin_assume_aligned.
+# define LLVM_ASSUME_ALIGNED(p, a) \
+           (((uintptr_t(p) % (a)) == 0) ? (p) : (LLVM_BUILTIN_UNREACHABLE, (p)))
+#else
+# define LLVM_ASSUME_ALIGNED(p, a) (p)
+#endif
+#endif
+
+/// \macro LLVM_ALIGNAS
+/// Used to specify a minimum alignment for a structure or variable.
+#ifndef LLVM_ALIGNAS
+#if __GNUC__ && !__has_feature(cxx_alignas) && !LLVM_GNUC_PREREQ(4, 8, 1)
+# define LLVM_ALIGNAS(x) __attribute__((aligned(x)))
+#else
+# define LLVM_ALIGNAS(x) alignas(x)
+#endif
+#endif
+
+/// \macro LLVM_PACKED
+/// Used to specify a packed structure.
+/// LLVM_PACKED(
+///    struct A {
+///      int i;
+///      int j;
+///      int k;
+///      long long l;
+///   });
+///
+/// LLVM_PACKED_START
+/// struct B {
+///   int i;
+///   int j;
+///   int k;
+///   long long l;
+/// };
+/// LLVM_PACKED_END
+#ifndef LLVM_PACKED
+#ifdef _MSC_VER
+# define LLVM_PACKED(d) __pragma(pack(push, 1)) d __pragma(pack(pop))
+# define LLVM_PACKED_START __pragma(pack(push, 1))
+# define LLVM_PACKED_END   __pragma(pack(pop))
+#else
+# define LLVM_PACKED(d) d __attribute__((packed))
+# define LLVM_PACKED_START _Pragma("pack(push, 1)")
+# define LLVM_PACKED_END   _Pragma("pack(pop)")
+#endif
+#endif
+
+/// \macro LLVM_PTR_SIZE
+/// A constant integer equivalent to the value of sizeof(void*).
+/// Generally used in combination with LLVM_ALIGNAS or when doing computation in
+/// the preprocessor.
+#ifndef LLVM_PTR_SIZE
+#ifdef __SIZEOF_POINTER__
+# define LLVM_PTR_SIZE __SIZEOF_POINTER__
+#elif defined(_WIN64)
+# define LLVM_PTR_SIZE 8
+#elif defined(_WIN32)
+# define LLVM_PTR_SIZE 4
+#elif defined(_MSC_VER)
+# error "could not determine LLVM_PTR_SIZE as a constant int for MSVC"
+#else
+# define LLVM_PTR_SIZE sizeof(void *)
+#endif
+#endif
+
+/// \macro LLVM_NO_SANITIZE
+/// Disable a particular sanitizer for a function.
+#ifndef LLVM_NO_SANITIZE
+#if __has_attribute(no_sanitize)
+#define LLVM_NO_SANITIZE(KIND) __attribute__((no_sanitize(KIND)))
+#else
+#define LLVM_NO_SANITIZE(KIND)
+#endif
+#endif
+
+/// Mark debug helper function definitions like dump() that should not be
+/// stripped from debug builds.
+/// Note that you should also surround dump() functions with
+/// `#if !defined(NDEBUG) || defined(LLVM_ENABLE_DUMP)` so they do always
+/// get stripped in release builds.
+// FIXME: Move this to a private config.h as it's not usable in public headers.
+#ifndef LLVM_DUMP_METHOD
+#if !defined(NDEBUG) || defined(LLVM_ENABLE_DUMP)
+#define LLVM_DUMP_METHOD LLVM_ATTRIBUTE_NOINLINE LLVM_ATTRIBUTE_USED
+#else
+#define LLVM_DUMP_METHOD LLVM_ATTRIBUTE_NOINLINE
+#endif
+#endif
+
+/// \macro LLVM_PRETTY_FUNCTION
+/// Gets a user-friendly looking function signature for the current scope
+/// using the best available method on each platform.  The exact format of the
+/// resulting string is implementation specific and non-portable, so this should
+/// only be used, for example, for logging or diagnostics.
+#ifndef LLVM_PRETTY_FUNCTION
+#if defined(_MSC_VER)
+#define LLVM_PRETTY_FUNCTION __FUNCSIG__
+#elif defined(__GNUC__) || defined(__clang__)
+#define LLVM_PRETTY_FUNCTION __PRETTY_FUNCTION__
+#else
+#define LLVM_PRETTY_FUNCTION __func__
+#endif
+#endif
+
+/// \macro LLVM_THREAD_LOCAL
+/// A thread-local storage specifier which can be used with globals,
+/// extern globals, and static globals.
+///
+/// This is essentially an extremely restricted analog to C++11's thread_local
+/// support, and uses that when available. However, it falls back on
+/// platform-specific or vendor-provided extensions when necessary. These
+/// extensions don't support many of the C++11 thread_local's features. You
+/// should only use this for PODs that you can statically initialize to
+/// some constant value. In almost all circumstances this is most appropriate
+/// for use with a pointer, integer, or small aggregation of pointers and
+/// integers.
+#ifndef LLVM_THREAD_LOCAL
+#if __has_feature(cxx_thread_local)
+#define LLVM_THREAD_LOCAL thread_local
+#elif defined(_MSC_VER)
+// MSVC supports this with a __declspec.
+#define LLVM_THREAD_LOCAL __declspec(thread)
+#else
+// Clang, GCC, and other compatible compilers used __thread prior to C++11 and
+// we only need the restricted functionality that provides.
+#define LLVM_THREAD_LOCAL __thread
+#endif
+#endif
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ConcurrentQueue.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ConcurrentQueue.h
new file mode 100644
index 0000000..ff47d60
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ConcurrentQueue.h
@@ -0,0 +1,85 @@
+//
+// Copyright (c) 2013 Juan Palacios juan.palacios.puyana@gmail.com
+// Subject to the BSD 2-Clause License
+// - see < http://opensource.org/licenses/BSD-2-Clause>
+//
+
+#ifndef WPIUTIL_WPI_CONCURRENTQUEUE_H_
+#define WPIUTIL_WPI_CONCURRENTQUEUE_H_
+
+#include <queue>
+#include <thread>
+#include <utility>
+
+#include "wpi/condition_variable.h"
+#include "wpi/mutex.h"
+
+namespace wpi {
+
+template <typename T>
+class ConcurrentQueue {
+ public:
+  bool empty() const {
+    std::unique_lock<wpi::mutex> mlock(mutex_);
+    return queue_.empty();
+  }
+
+  typename std::queue<T>::size_type size() const {
+    std::unique_lock<wpi::mutex> mlock(mutex_);
+    return queue_.size();
+  }
+
+  T pop() {
+    std::unique_lock<wpi::mutex> mlock(mutex_);
+    while (queue_.empty()) {
+      cond_.wait(mlock);
+    }
+    auto item = std::move(queue_.front());
+    queue_.pop();
+    return item;
+  }
+
+  void pop(T& item) {
+    std::unique_lock<wpi::mutex> mlock(mutex_);
+    while (queue_.empty()) {
+      cond_.wait(mlock);
+    }
+    item = queue_.front();
+    queue_.pop();
+  }
+
+  void push(const T& item) {
+    std::unique_lock<wpi::mutex> mlock(mutex_);
+    queue_.push(item);
+    mlock.unlock();
+    cond_.notify_one();
+  }
+
+  void push(T&& item) {
+    std::unique_lock<wpi::mutex> mlock(mutex_);
+    queue_.push(std::forward<T>(item));
+    mlock.unlock();
+    cond_.notify_one();
+  }
+
+  template <typename... Args>
+  void emplace(Args&&... args) {
+    std::unique_lock<wpi::mutex> mlock(mutex_);
+    queue_.emplace(std::forward<Args>(args)...);
+    mlock.unlock();
+    cond_.notify_one();
+  }
+
+  ConcurrentQueue() = default;
+  ConcurrentQueue(const ConcurrentQueue&) = delete;
+  ConcurrentQueue& operator=(const ConcurrentQueue&) = delete;
+
+ private:
+  std::queue<T> queue_;
+  mutable wpi::mutex mutex_;
+  wpi::condition_variable cond_;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_CONCURRENTQUEUE_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ConvertUTF.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ConvertUTF.h
new file mode 100644
index 0000000..c09e71a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ConvertUTF.h
@@ -0,0 +1,250 @@
+/*===--- ConvertUTF.h - Universal Character Names conversions ---------------===
+ *
+ *                     The LLVM Compiler Infrastructure
+ *
+ * This file is distributed under the University of Illinois Open Source
+ * License. See LICENSE.TXT for details.
+ *
+ *==------------------------------------------------------------------------==*/
+/*
+ * Copyright 2001-2004 Unicode, Inc.
+ *
+ * Disclaimer
+ *
+ * This source code is provided as is by Unicode, Inc. No claims are
+ * made as to fitness for any particular purpose. No warranties of any
+ * kind are expressed or implied. The recipient agrees to determine
+ * applicability of information provided. If this file has been
+ * purchased on magnetic or optical media from Unicode, Inc., the
+ * sole remedy for any claim will be exchange of defective media
+ * within 90 days of receipt.
+ *
+ * Limitations on Rights to Redistribute This Code
+ *
+ * Unicode, Inc. hereby grants the right to freely use the information
+ * supplied in this file in the creation of products supporting the
+ * Unicode Standard, and to make copies of this file in any form
+ * for internal or external distribution as long as this notice
+ * remains attached.
+ */
+
+/* ---------------------------------------------------------------------
+
+    Conversions between UTF32, UTF-16, and UTF-8.  Header file.
+
+    Several funtions are included here, forming a complete set of
+    conversions between the three formats.  UTF-7 is not included
+    here, but is handled in a separate source file.
+
+    Each of these routines takes pointers to input buffers and output
+    buffers.  The input buffers are const.
+
+    Each routine converts the text between *sourceStart and sourceEnd,
+    putting the result into the buffer between *targetStart and
+    targetEnd. Note: the end pointers are *after* the last item: e.g.
+    *(sourceEnd - 1) is the last item.
+
+    The return result indicates whether the conversion was successful,
+    and if not, whether the problem was in the source or target buffers.
+    (Only the first encountered problem is indicated.)
+
+    After the conversion, *sourceStart and *targetStart are both
+    updated to point to the end of last text successfully converted in
+    the respective buffers.
+
+    Input parameters:
+        sourceStart - pointer to a pointer to the source buffer.
+                The contents of this are modified on return so that
+                it points at the next thing to be converted.
+        targetStart - similarly, pointer to pointer to the target buffer.
+        sourceEnd, targetEnd - respectively pointers to the ends of the
+                two buffers, for overflow checking only.
+
+    These conversion functions take a ConversionFlags argument. When this
+    flag is set to strict, both irregular sequences and isolated surrogates
+    will cause an error.  When the flag is set to lenient, both irregular
+    sequences and isolated surrogates are converted.
+
+    Whether the flag is strict or lenient, all illegal sequences will cause
+    an error return. This includes sequences such as: <F4 90 80 80>, <C0 80>,
+    or <A0> in UTF-8, and values above 0x10FFFF in UTF-32. Conformant code
+    must check for illegal sequences.
+
+    When the flag is set to lenient, characters over 0x10FFFF are converted
+    to the replacement character; otherwise (when the flag is set to strict)
+    they constitute an error.
+
+    Output parameters:
+        The value "sourceIllegal" is returned from some routines if the input
+        sequence is malformed.  When "sourceIllegal" is returned, the source
+        value will point to the illegal value that caused the problem. E.g.,
+        in UTF-8 when a sequence is malformed, it points to the start of the
+        malformed sequence.
+
+    Author: Mark E. Davis, 1994.
+    Rev History: Rick McGowan, fixes & updates May 2001.
+         Fixes & updates, Sept 2001.
+
+------------------------------------------------------------------------ */
+
+#ifndef LLVM_SUPPORT_CONVERTUTF_H
+#define LLVM_SUPPORT_CONVERTUTF_H
+
+#include "wpi/ArrayRef.h"
+#include "wpi/StringRef.h"
+
+#include <cstddef>
+#include <string>
+
+// Wrap everything in namespace wpi so that programs can link with wpiutil and
+// their own version of the unicode libraries.
+
+namespace wpi {
+
+/* ---------------------------------------------------------------------
+    The following 4 definitions are compiler-specific.
+    The C standard does not guarantee that wchar_t has at least
+    16 bits, so wchar_t is no less portable than unsigned short!
+    All should be unsigned values to avoid sign extension during
+    bit mask & shift operations.
+------------------------------------------------------------------------ */
+
+typedef unsigned int    UTF32;  /* at least 32 bits */
+typedef unsigned short  UTF16;  /* at least 16 bits */
+typedef unsigned char   UTF8;   /* typically 8 bits */
+typedef bool   Boolean; /* 0 or 1 */
+
+/* Some fundamental constants */
+#define UNI_REPLACEMENT_CHAR (UTF32)0x0000FFFD
+#define UNI_MAX_BMP (UTF32)0x0000FFFF
+#define UNI_MAX_UTF16 (UTF32)0x0010FFFF
+#define UNI_MAX_UTF32 (UTF32)0x7FFFFFFF
+#define UNI_MAX_LEGAL_UTF32 (UTF32)0x0010FFFF
+
+#define UNI_MAX_UTF8_BYTES_PER_CODE_POINT 4
+
+#define UNI_UTF16_BYTE_ORDER_MARK_NATIVE  0xFEFF
+#define UNI_UTF16_BYTE_ORDER_MARK_SWAPPED 0xFFFE
+
+typedef enum {
+  conversionOK,           /* conversion successful */
+  sourceExhausted,        /* partial character in source, but hit end */
+  targetExhausted,        /* insuff. room in target for conversion */
+  sourceIllegal           /* source sequence is illegal/malformed */
+} ConversionResult;
+
+typedef enum {
+  strictConversion = 0,
+  lenientConversion
+} ConversionFlags;
+
+ConversionResult ConvertUTF8toUTF16 (
+  const UTF8** sourceStart, const UTF8* sourceEnd,
+  UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags);
+
+/**
+ * Convert a partial UTF8 sequence to UTF32.  If the sequence ends in an
+ * incomplete code unit sequence, returns \c sourceExhausted.
+ */
+ConversionResult ConvertUTF8toUTF32Partial(
+  const UTF8** sourceStart, const UTF8* sourceEnd,
+  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
+
+/**
+ * Convert a partial UTF8 sequence to UTF32.  If the sequence ends in an
+ * incomplete code unit sequence, returns \c sourceIllegal.
+ */
+ConversionResult ConvertUTF8toUTF32(
+  const UTF8** sourceStart, const UTF8* sourceEnd,
+  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
+
+ConversionResult ConvertUTF16toUTF8 (
+  const UTF16** sourceStart, const UTF16* sourceEnd,
+  UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags);
+
+ConversionResult ConvertUTF32toUTF8 (
+  const UTF32** sourceStart, const UTF32* sourceEnd,
+  UTF8** targetStart, UTF8* targetEnd, ConversionFlags flags);
+
+ConversionResult ConvertUTF16toUTF32 (
+  const UTF16** sourceStart, const UTF16* sourceEnd,
+  UTF32** targetStart, UTF32* targetEnd, ConversionFlags flags);
+
+ConversionResult ConvertUTF32toUTF16 (
+  const UTF32** sourceStart, const UTF32* sourceEnd,
+  UTF16** targetStart, UTF16* targetEnd, ConversionFlags flags);
+
+Boolean isLegalUTF8Sequence(const UTF8 *source, const UTF8 *sourceEnd);
+
+Boolean isLegalUTF8String(const UTF8 **source, const UTF8 *sourceEnd);
+
+unsigned getNumBytesForUTF8(UTF8 firstByte);
+
+/*************************************************************************/
+/* Below are LLVM-specific wrappers of the functions above. */
+
+
+/**
+ * Convert an Unicode code point to UTF8 sequence.
+ *
+ * \param Source a Unicode code point.
+ * \param [in,out] ResultPtr pointer to the output buffer, needs to be at least
+ * \c UNI_MAX_UTF8_BYTES_PER_CODE_POINT bytes.  On success \c ResultPtr is
+ * updated one past end of the converted sequence.
+ *
+ * \returns true on success.
+ */
+bool ConvertCodePointToUTF8(unsigned Source, char *&ResultPtr);
+
+/**
+ * Convert the first UTF8 sequence in the given source buffer to a UTF32
+ * code point.
+ *
+ * \param [in,out] source A pointer to the source buffer. If the conversion
+ * succeeds, this pointer will be updated to point to the byte just past the
+ * end of the converted sequence.
+ * \param sourceEnd A pointer just past the end of the source buffer.
+ * \param [out] target The converted code
+ * \param flags Whether the conversion is strict or lenient.
+ *
+ * \returns conversionOK on success
+ *
+ * \sa ConvertUTF8toUTF32
+ */
+static inline ConversionResult convertUTF8Sequence(const UTF8 **source,
+                                                   const UTF8 *sourceEnd,
+                                                   UTF32 *target,
+                                                   ConversionFlags flags) {
+  if (*source == sourceEnd)
+    return sourceExhausted;
+  unsigned size = getNumBytesForUTF8(**source);
+  if ((ptrdiff_t)size > sourceEnd - *source)
+    return sourceExhausted;
+  return ConvertUTF8toUTF32(source, *source + size, &target, target + 1, flags);
+}
+
+/**
+ * Returns true if a blob of text starts with a UTF-16 big or little endian byte
+ * order mark.
+ */
+bool hasUTF16ByteOrderMark(ArrayRef<char> SrcBytes);
+
+/**
+ * Converts a UTF-16 string into a UTF-8 string.
+ *
+ * \returns true on success
+ */
+bool convertUTF16ToUTF8String(ArrayRef<UTF16> SrcUTF16,
+                              SmallVectorImpl<char> &DstUTF8);
+
+/**
+ * Converts a UTF-8 string into a UTF-16 string with native endianness.
+ *
+ * \returns true on success
+ */
+bool convertUTF8ToUTF16String(StringRef SrcUTF8,
+                              SmallVectorImpl<UTF16> &DstUTF16);
+
+} /* end namespace wpi */
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/DenseMap.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/DenseMap.h
new file mode 100644
index 0000000..2853217
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/DenseMap.h
@@ -0,0 +1,1199 @@
+//===- llvm/ADT/DenseMap.h - Dense probed hash table ------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the DenseMap class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_DENSEMAP_H
+#define WPIUTIL_WPI_DENSEMAP_H
+
+#include "wpi/DenseMapInfo.h"
+#include "wpi/EpochTracker.h"
+#include "wpi/AlignOf.h"
+#include "wpi/Compiler.h"
+#include "wpi/MathExtras.h"
+#include "wpi/PointerLikeTypeTraits.h"
+#include "wpi/type_traits.h"
+#include <algorithm>
+#include <cassert>
+#include <cstddef>
+#include <cstring>
+#include <iterator>
+#include <new>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+namespace detail {
+
+// We extend a pair to allow users to override the bucket type with their own
+// implementation without requiring two members.
+template <typename KeyT, typename ValueT>
+struct DenseMapPair : public std::pair<KeyT, ValueT> {
+  KeyT &getFirst() { return std::pair<KeyT, ValueT>::first; }
+  const KeyT &getFirst() const { return std::pair<KeyT, ValueT>::first; }
+  ValueT &getSecond() { return std::pair<KeyT, ValueT>::second; }
+  const ValueT &getSecond() const { return std::pair<KeyT, ValueT>::second; }
+};
+
+} // end namespace detail
+
+template <
+    typename KeyT, typename ValueT, typename KeyInfoT = DenseMapInfo<KeyT>,
+    typename Bucket = detail::DenseMapPair<KeyT, ValueT>, bool IsConst = false>
+class DenseMapIterator;
+
+template <typename DerivedT, typename KeyT, typename ValueT, typename KeyInfoT,
+          typename BucketT>
+class DenseMapBase : public DebugEpochBase {
+  template <typename T>
+  using const_arg_type_t = typename const_pointer_or_const_ref<T>::type;
+
+public:
+  using size_type = unsigned;
+  using key_type = KeyT;
+  using mapped_type = ValueT;
+  using value_type = BucketT;
+
+  using iterator = DenseMapIterator<KeyT, ValueT, KeyInfoT, BucketT>;
+  using const_iterator =
+      DenseMapIterator<KeyT, ValueT, KeyInfoT, BucketT, true>;
+
+  inline iterator begin() {
+    // When the map is empty, avoid the overhead of advancing/retreating past
+    // empty buckets.
+    if (empty())
+      return end();
+    return makeIterator(getBuckets(), getBucketsEnd(), *this);
+  }
+  inline iterator end() {
+    return makeIterator(getBucketsEnd(), getBucketsEnd(), *this, true);
+  }
+  inline const_iterator begin() const {
+    if (empty())
+      return end();
+    return makeConstIterator(getBuckets(), getBucketsEnd(), *this);
+  }
+  inline const_iterator end() const {
+    return makeConstIterator(getBucketsEnd(), getBucketsEnd(), *this, true);
+  }
+
+  LLVM_NODISCARD bool empty() const {
+    return getNumEntries() == 0;
+  }
+  unsigned size() const { return getNumEntries(); }
+
+  /// Grow the densemap so that it can contain at least \p NumEntries items
+  /// before resizing again.
+  void reserve(size_type NumEntries) {
+    auto NumBuckets = getMinBucketToReserveForEntries(NumEntries);
+    incrementEpoch();
+    if (NumBuckets > getNumBuckets())
+      grow(NumBuckets);
+  }
+
+  void clear() {
+    incrementEpoch();
+    if (getNumEntries() == 0 && getNumTombstones() == 0) return;
+
+    // If the capacity of the array is huge, and the # elements used is small,
+    // shrink the array.
+    if (getNumEntries() * 4 < getNumBuckets() && getNumBuckets() > 64) {
+      shrink_and_clear();
+      return;
+    }
+
+    const KeyT EmptyKey = getEmptyKey(), TombstoneKey = getTombstoneKey();
+    if (isPodLike<KeyT>::value && isPodLike<ValueT>::value) {
+      // Use a simpler loop when these are trivial types.
+      for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P)
+        P->getFirst() = EmptyKey;
+    } else {
+      unsigned NumEntries = getNumEntries();
+      for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P) {
+        if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey)) {
+          if (!KeyInfoT::isEqual(P->getFirst(), TombstoneKey)) {
+            P->getSecond().~ValueT();
+            --NumEntries;
+          }
+          P->getFirst() = EmptyKey;
+        }
+      }
+      assert(NumEntries == 0 && "Node count imbalance!");
+    }
+    setNumEntries(0);
+    setNumTombstones(0);
+  }
+
+  /// Return 1 if the specified key is in the map, 0 otherwise.
+  size_type count(const_arg_type_t<KeyT> Val) const {
+    const BucketT *TheBucket;
+    return LookupBucketFor(Val, TheBucket) ? 1 : 0;
+  }
+
+  iterator find(const_arg_type_t<KeyT> Val) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return makeIterator(TheBucket, getBucketsEnd(), *this, true);
+    return end();
+  }
+  const_iterator find(const_arg_type_t<KeyT> Val) const {
+    const BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return makeConstIterator(TheBucket, getBucketsEnd(), *this, true);
+    return end();
+  }
+
+  /// Alternate version of find() which allows a different, and possibly
+  /// less expensive, key type.
+  /// The DenseMapInfo is responsible for supplying methods
+  /// getHashValue(LookupKeyT) and isEqual(LookupKeyT, KeyT) for each key
+  /// type used.
+  template<class LookupKeyT>
+  iterator find_as(const LookupKeyT &Val) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return makeIterator(TheBucket, getBucketsEnd(), *this, true);
+    return end();
+  }
+  template<class LookupKeyT>
+  const_iterator find_as(const LookupKeyT &Val) const {
+    const BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return makeConstIterator(TheBucket, getBucketsEnd(), *this, true);
+    return end();
+  }
+
+  /// lookup - Return the entry for the specified key, or a default
+  /// constructed value if no such entry exists.
+  ValueT lookup(const_arg_type_t<KeyT> Val) const {
+    const BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return TheBucket->getSecond();
+    return ValueT();
+  }
+
+  // Inserts key,value pair into the map if the key isn't already in the map.
+  // If the key is already in the map, it returns false and doesn't update the
+  // value.
+  std::pair<iterator, bool> insert(const std::pair<KeyT, ValueT> &KV) {
+    return try_emplace(KV.first, KV.second);
+  }
+
+  // Inserts key,value pair into the map if the key isn't already in the map.
+  // If the key is already in the map, it returns false and doesn't update the
+  // value.
+  std::pair<iterator, bool> insert(std::pair<KeyT, ValueT> &&KV) {
+    return try_emplace(std::move(KV.first), std::move(KV.second));
+  }
+
+  // Inserts key,value pair into the map if the key isn't already in the map.
+  // The value is constructed in-place if the key is not in the map, otherwise
+  // it is not moved.
+  template <typename... Ts>
+  std::pair<iterator, bool> try_emplace(KeyT &&Key, Ts &&... Args) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Key, TheBucket))
+      return std::make_pair(
+               makeIterator(TheBucket, getBucketsEnd(), *this, true),
+               false); // Already in map.
+
+    // Otherwise, insert the new element.
+    TheBucket =
+        InsertIntoBucket(TheBucket, std::move(Key), std::forward<Ts>(Args)...);
+    return std::make_pair(
+             makeIterator(TheBucket, getBucketsEnd(), *this, true),
+             true);
+  }
+
+  // Inserts key,value pair into the map if the key isn't already in the map.
+  // The value is constructed in-place if the key is not in the map, otherwise
+  // it is not moved.
+  template <typename... Ts>
+  std::pair<iterator, bool> try_emplace(const KeyT &Key, Ts &&... Args) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Key, TheBucket))
+      return std::make_pair(
+               makeIterator(TheBucket, getBucketsEnd(), *this, true),
+               false); // Already in map.
+
+    // Otherwise, insert the new element.
+    TheBucket = InsertIntoBucket(TheBucket, Key, std::forward<Ts>(Args)...);
+    return std::make_pair(
+             makeIterator(TheBucket, getBucketsEnd(), *this, true),
+             true);
+  }
+
+  /// Alternate version of insert() which allows a different, and possibly
+  /// less expensive, key type.
+  /// The DenseMapInfo is responsible for supplying methods
+  /// getHashValue(LookupKeyT) and isEqual(LookupKeyT, KeyT) for each key
+  /// type used.
+  template <typename LookupKeyT>
+  std::pair<iterator, bool> insert_as(std::pair<KeyT, ValueT> &&KV,
+                                      const LookupKeyT &Val) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Val, TheBucket))
+      return std::make_pair(
+               makeIterator(TheBucket, getBucketsEnd(), *this, true),
+               false); // Already in map.
+
+    // Otherwise, insert the new element.
+    TheBucket = InsertIntoBucketWithLookup(TheBucket, std::move(KV.first),
+                                           std::move(KV.second), Val);
+    return std::make_pair(
+             makeIterator(TheBucket, getBucketsEnd(), *this, true),
+             true);
+  }
+
+  /// insert - Range insertion of pairs.
+  template<typename InputIt>
+  void insert(InputIt I, InputIt E) {
+    for (; I != E; ++I)
+      insert(*I);
+  }
+
+  bool erase(const KeyT &Val) {
+    BucketT *TheBucket;
+    if (!LookupBucketFor(Val, TheBucket))
+      return false; // not in map.
+
+    TheBucket->getSecond().~ValueT();
+    TheBucket->getFirst() = getTombstoneKey();
+    decrementNumEntries();
+    incrementNumTombstones();
+    return true;
+  }
+  void erase(iterator I) {
+    BucketT *TheBucket = &*I;
+    TheBucket->getSecond().~ValueT();
+    TheBucket->getFirst() = getTombstoneKey();
+    decrementNumEntries();
+    incrementNumTombstones();
+  }
+
+  value_type& FindAndConstruct(const KeyT &Key) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Key, TheBucket))
+      return *TheBucket;
+
+    return *InsertIntoBucket(TheBucket, Key);
+  }
+
+  ValueT &operator[](const KeyT &Key) {
+    return FindAndConstruct(Key).second;
+  }
+
+  value_type& FindAndConstruct(KeyT &&Key) {
+    BucketT *TheBucket;
+    if (LookupBucketFor(Key, TheBucket))
+      return *TheBucket;
+
+    return *InsertIntoBucket(TheBucket, std::move(Key));
+  }
+
+  ValueT &operator[](KeyT &&Key) {
+    return FindAndConstruct(std::move(Key)).second;
+  }
+
+  /// isPointerIntoBucketsArray - Return true if the specified pointer points
+  /// somewhere into the DenseMap's array of buckets (i.e. either to a key or
+  /// value in the DenseMap).
+  bool isPointerIntoBucketsArray(const void *Ptr) const {
+    return Ptr >= getBuckets() && Ptr < getBucketsEnd();
+  }
+
+  /// getPointerIntoBucketsArray() - Return an opaque pointer into the buckets
+  /// array.  In conjunction with the previous method, this can be used to
+  /// determine whether an insertion caused the DenseMap to reallocate.
+  const void *getPointerIntoBucketsArray() const { return getBuckets(); }
+
+protected:
+  DenseMapBase() = default;
+
+  void destroyAll() {
+    if (getNumBuckets() == 0) // Nothing to do.
+      return;
+
+    const KeyT EmptyKey = getEmptyKey(), TombstoneKey = getTombstoneKey();
+    for (BucketT *P = getBuckets(), *E = getBucketsEnd(); P != E; ++P) {
+      if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey) &&
+          !KeyInfoT::isEqual(P->getFirst(), TombstoneKey))
+        P->getSecond().~ValueT();
+      P->getFirst().~KeyT();
+    }
+  }
+
+  void initEmpty() {
+    setNumEntries(0);
+    setNumTombstones(0);
+
+    assert((getNumBuckets() & (getNumBuckets()-1)) == 0 &&
+           "# initial buckets must be a power of two!");
+    const KeyT EmptyKey = getEmptyKey();
+    for (BucketT *B = getBuckets(), *E = getBucketsEnd(); B != E; ++B)
+      ::new (&B->getFirst()) KeyT(EmptyKey);
+  }
+
+  /// Returns the number of buckets to allocate to ensure that the DenseMap can
+  /// accommodate \p NumEntries without need to grow().
+  unsigned getMinBucketToReserveForEntries(unsigned NumEntries) {
+    // Ensure that "NumEntries * 4 < NumBuckets * 3"
+    if (NumEntries == 0)
+      return 0;
+    // +1 is required because of the strict equality.
+    // For example if NumEntries is 48, we need to return 401.
+    return NextPowerOf2(NumEntries * 4 / 3 + 1);
+  }
+
+  void moveFromOldBuckets(BucketT *OldBucketsBegin, BucketT *OldBucketsEnd) {
+    initEmpty();
+
+    // Insert all the old elements.
+    const KeyT EmptyKey = getEmptyKey();
+    const KeyT TombstoneKey = getTombstoneKey();
+    for (BucketT *B = OldBucketsBegin, *E = OldBucketsEnd; B != E; ++B) {
+      if (!KeyInfoT::isEqual(B->getFirst(), EmptyKey) &&
+          !KeyInfoT::isEqual(B->getFirst(), TombstoneKey)) {
+        // Insert the key/value into the new table.
+        BucketT *DestBucket;
+        bool FoundVal = LookupBucketFor(B->getFirst(), DestBucket);
+        (void)FoundVal; // silence warning.
+        assert(!FoundVal && "Key already in new map?");
+        DestBucket->getFirst() = std::move(B->getFirst());
+        ::new (&DestBucket->getSecond()) ValueT(std::move(B->getSecond()));
+        incrementNumEntries();
+
+        // Free the value.
+        B->getSecond().~ValueT();
+      }
+      B->getFirst().~KeyT();
+    }
+  }
+
+  template <typename OtherBaseT>
+  void copyFrom(
+      const DenseMapBase<OtherBaseT, KeyT, ValueT, KeyInfoT, BucketT> &other) {
+    assert(&other != this);
+    assert(getNumBuckets() == other.getNumBuckets());
+
+    setNumEntries(other.getNumEntries());
+    setNumTombstones(other.getNumTombstones());
+
+    if (isPodLike<KeyT>::value && isPodLike<ValueT>::value)
+      memcpy(getBuckets(), other.getBuckets(),
+             getNumBuckets() * sizeof(BucketT));
+    else
+      for (size_t i = 0; i < getNumBuckets(); ++i) {
+        ::new (&getBuckets()[i].getFirst())
+            KeyT(other.getBuckets()[i].getFirst());
+        if (!KeyInfoT::isEqual(getBuckets()[i].getFirst(), getEmptyKey()) &&
+            !KeyInfoT::isEqual(getBuckets()[i].getFirst(), getTombstoneKey()))
+          ::new (&getBuckets()[i].getSecond())
+              ValueT(other.getBuckets()[i].getSecond());
+      }
+  }
+
+  static unsigned getHashValue(const KeyT &Val) {
+    return KeyInfoT::getHashValue(Val);
+  }
+
+  template<typename LookupKeyT>
+  static unsigned getHashValue(const LookupKeyT &Val) {
+    return KeyInfoT::getHashValue(Val);
+  }
+
+  static const KeyT getEmptyKey() {
+    static_assert(std::is_base_of<DenseMapBase, DerivedT>::value,
+                  "Must pass the derived type to this template!");
+    return KeyInfoT::getEmptyKey();
+  }
+
+  static const KeyT getTombstoneKey() {
+    return KeyInfoT::getTombstoneKey();
+  }
+
+private:
+  iterator makeIterator(BucketT *P, BucketT *E,
+                        DebugEpochBase &Epoch,
+                        bool NoAdvance=false) {
+    return iterator(P, E, Epoch, NoAdvance);
+  }
+
+  const_iterator makeConstIterator(const BucketT *P, const BucketT *E,
+                                   const DebugEpochBase &Epoch,
+                                   const bool NoAdvance=false) const {
+    return const_iterator(P, E, Epoch, NoAdvance);
+  }
+
+  unsigned getNumEntries() const {
+    return static_cast<const DerivedT *>(this)->getNumEntries();
+  }
+
+  void setNumEntries(unsigned Num) {
+    static_cast<DerivedT *>(this)->setNumEntries(Num);
+  }
+
+  void incrementNumEntries() {
+    setNumEntries(getNumEntries() + 1);
+  }
+
+  void decrementNumEntries() {
+    setNumEntries(getNumEntries() - 1);
+  }
+
+  unsigned getNumTombstones() const {
+    return static_cast<const DerivedT *>(this)->getNumTombstones();
+  }
+
+  void setNumTombstones(unsigned Num) {
+    static_cast<DerivedT *>(this)->setNumTombstones(Num);
+  }
+
+  void incrementNumTombstones() {
+    setNumTombstones(getNumTombstones() + 1);
+  }
+
+  void decrementNumTombstones() {
+    setNumTombstones(getNumTombstones() - 1);
+  }
+
+  const BucketT *getBuckets() const {
+    return static_cast<const DerivedT *>(this)->getBuckets();
+  }
+
+  BucketT *getBuckets() {
+    return static_cast<DerivedT *>(this)->getBuckets();
+  }
+
+  unsigned getNumBuckets() const {
+    return static_cast<const DerivedT *>(this)->getNumBuckets();
+  }
+
+  BucketT *getBucketsEnd() {
+    return getBuckets() + getNumBuckets();
+  }
+
+  const BucketT *getBucketsEnd() const {
+    return getBuckets() + getNumBuckets();
+  }
+
+  void grow(unsigned AtLeast) {
+    static_cast<DerivedT *>(this)->grow(AtLeast);
+  }
+
+  void shrink_and_clear() {
+    static_cast<DerivedT *>(this)->shrink_and_clear();
+  }
+
+  template <typename KeyArg, typename... ValueArgs>
+  BucketT *InsertIntoBucket(BucketT *TheBucket, KeyArg &&Key,
+                            ValueArgs &&... Values) {
+    TheBucket = InsertIntoBucketImpl(Key, Key, TheBucket);
+
+    TheBucket->getFirst() = std::forward<KeyArg>(Key);
+    ::new (&TheBucket->getSecond()) ValueT(std::forward<ValueArgs>(Values)...);
+    return TheBucket;
+  }
+
+  template <typename LookupKeyT>
+  BucketT *InsertIntoBucketWithLookup(BucketT *TheBucket, KeyT &&Key,
+                                      ValueT &&Value, LookupKeyT &Lookup) {
+    TheBucket = InsertIntoBucketImpl(Key, Lookup, TheBucket);
+
+    TheBucket->getFirst() = std::move(Key);
+    ::new (&TheBucket->getSecond()) ValueT(std::move(Value));
+    return TheBucket;
+  }
+
+  template <typename LookupKeyT>
+  BucketT *InsertIntoBucketImpl(const KeyT &Key, const LookupKeyT &Lookup,
+                                BucketT *TheBucket) {
+    incrementEpoch();
+
+    // If the load of the hash table is more than 3/4, or if fewer than 1/8 of
+    // the buckets are empty (meaning that many are filled with tombstones),
+    // grow the table.
+    //
+    // The later case is tricky.  For example, if we had one empty bucket with
+    // tons of tombstones, failing lookups (e.g. for insertion) would have to
+    // probe almost the entire table until it found the empty bucket.  If the
+    // table completely filled with tombstones, no lookup would ever succeed,
+    // causing infinite loops in lookup.
+    unsigned NewNumEntries = getNumEntries() + 1;
+    unsigned NumBuckets = getNumBuckets();
+    if (LLVM_UNLIKELY(NewNumEntries * 4 >= NumBuckets * 3)) {
+      this->grow(NumBuckets * 2);
+      LookupBucketFor(Lookup, TheBucket);
+      NumBuckets = getNumBuckets();
+    } else if (LLVM_UNLIKELY(NumBuckets-(NewNumEntries+getNumTombstones()) <=
+                             NumBuckets/8)) {
+      this->grow(NumBuckets);
+      LookupBucketFor(Lookup, TheBucket);
+    }
+    assert(TheBucket);
+
+    // Only update the state after we've grown our bucket space appropriately
+    // so that when growing buckets we have self-consistent entry count.
+    incrementNumEntries();
+
+    // If we are writing over a tombstone, remember this.
+    const KeyT EmptyKey = getEmptyKey();
+    if (!KeyInfoT::isEqual(TheBucket->getFirst(), EmptyKey))
+      decrementNumTombstones();
+
+    return TheBucket;
+  }
+
+  /// LookupBucketFor - Lookup the appropriate bucket for Val, returning it in
+  /// FoundBucket.  If the bucket contains the key and a value, this returns
+  /// true, otherwise it returns a bucket with an empty marker or tombstone and
+  /// returns false.
+  template<typename LookupKeyT>
+  bool LookupBucketFor(const LookupKeyT &Val,
+                       const BucketT *&FoundBucket) const {
+    const BucketT *BucketsPtr = getBuckets();
+    const unsigned NumBuckets = getNumBuckets();
+
+    if (NumBuckets == 0) {
+      FoundBucket = nullptr;
+      return false;
+    }
+
+    // FoundTombstone - Keep track of whether we find a tombstone while probing.
+    const BucketT *FoundTombstone = nullptr;
+    const KeyT EmptyKey = getEmptyKey();
+    const KeyT TombstoneKey = getTombstoneKey();
+    assert(!KeyInfoT::isEqual(Val, EmptyKey) &&
+           !KeyInfoT::isEqual(Val, TombstoneKey) &&
+           "Empty/Tombstone value shouldn't be inserted into map!");
+
+    unsigned BucketNo = getHashValue(Val) & (NumBuckets-1);
+    unsigned ProbeAmt = 1;
+    while (true) {
+      const BucketT *ThisBucket = BucketsPtr + BucketNo;
+      // Found Val's bucket?  If so, return it.
+      if (LLVM_LIKELY(KeyInfoT::isEqual(Val, ThisBucket->getFirst()))) {
+        FoundBucket = ThisBucket;
+        return true;
+      }
+
+      // If we found an empty bucket, the key doesn't exist in the set.
+      // Insert it and return the default value.
+      if (LLVM_LIKELY(KeyInfoT::isEqual(ThisBucket->getFirst(), EmptyKey))) {
+        // If we've already seen a tombstone while probing, fill it in instead
+        // of the empty bucket we eventually probed to.
+        FoundBucket = FoundTombstone ? FoundTombstone : ThisBucket;
+        return false;
+      }
+
+      // If this is a tombstone, remember it.  If Val ends up not in the map, we
+      // prefer to return it than something that would require more probing.
+      if (KeyInfoT::isEqual(ThisBucket->getFirst(), TombstoneKey) &&
+          !FoundTombstone)
+        FoundTombstone = ThisBucket;  // Remember the first tombstone found.
+
+      // Otherwise, it's a hash collision or a tombstone, continue quadratic
+      // probing.
+      BucketNo += ProbeAmt++;
+      BucketNo &= (NumBuckets-1);
+    }
+  }
+
+  template <typename LookupKeyT>
+  bool LookupBucketFor(const LookupKeyT &Val, BucketT *&FoundBucket) {
+    const BucketT *ConstFoundBucket;
+    bool Result = const_cast<const DenseMapBase *>(this)
+      ->LookupBucketFor(Val, ConstFoundBucket);
+    FoundBucket = const_cast<BucketT *>(ConstFoundBucket);
+    return Result;
+  }
+
+public:
+  /// Return the approximate size (in bytes) of the actual map.
+  /// This is just the raw memory used by DenseMap.
+  /// If entries are pointers to objects, the size of the referenced objects
+  /// are not included.
+  size_t getMemorySize() const {
+    return getNumBuckets() * sizeof(BucketT);
+  }
+};
+
+template <typename KeyT, typename ValueT,
+          typename KeyInfoT = DenseMapInfo<KeyT>,
+          typename BucketT = detail::DenseMapPair<KeyT, ValueT>>
+class DenseMap : public DenseMapBase<DenseMap<KeyT, ValueT, KeyInfoT, BucketT>,
+                                     KeyT, ValueT, KeyInfoT, BucketT> {
+  friend class DenseMapBase<DenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
+
+  // Lift some types from the dependent base class into this class for
+  // simplicity of referring to them.
+  using BaseT = DenseMapBase<DenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
+
+  BucketT *Buckets;
+  unsigned NumEntries;
+  unsigned NumTombstones;
+  unsigned NumBuckets;
+
+public:
+  /// Create a DenseMap wth an optional \p InitialReserve that guarantee that
+  /// this number of elements can be inserted in the map without grow()
+  explicit DenseMap(unsigned InitialReserve = 0) { init(InitialReserve); }
+
+  DenseMap(const DenseMap &other) : BaseT() {
+    init(0);
+    copyFrom(other);
+  }
+
+  DenseMap(DenseMap &&other) : BaseT() {
+    init(0);
+    swap(other);
+  }
+
+  template<typename InputIt>
+  DenseMap(const InputIt &I, const InputIt &E) {
+    init(std::distance(I, E));
+    this->insert(I, E);
+  }
+
+  ~DenseMap() {
+    this->destroyAll();
+    operator delete(Buckets);
+  }
+
+  void swap(DenseMap& RHS) {
+    this->incrementEpoch();
+    RHS.incrementEpoch();
+    std::swap(Buckets, RHS.Buckets);
+    std::swap(NumEntries, RHS.NumEntries);
+    std::swap(NumTombstones, RHS.NumTombstones);
+    std::swap(NumBuckets, RHS.NumBuckets);
+  }
+
+  DenseMap& operator=(const DenseMap& other) {
+    if (&other != this)
+      copyFrom(other);
+    return *this;
+  }
+
+  DenseMap& operator=(DenseMap &&other) {
+    this->destroyAll();
+    operator delete(Buckets);
+    init(0);
+    swap(other);
+    return *this;
+  }
+
+  void copyFrom(const DenseMap& other) {
+    this->destroyAll();
+    operator delete(Buckets);
+    if (allocateBuckets(other.NumBuckets)) {
+      this->BaseT::copyFrom(other);
+    } else {
+      NumEntries = 0;
+      NumTombstones = 0;
+    }
+  }
+
+  void init(unsigned InitNumEntries) {
+    auto InitBuckets = BaseT::getMinBucketToReserveForEntries(InitNumEntries);
+    if (allocateBuckets(InitBuckets)) {
+      this->BaseT::initEmpty();
+    } else {
+      NumEntries = 0;
+      NumTombstones = 0;
+    }
+  }
+
+  void grow(unsigned AtLeast) {
+    unsigned OldNumBuckets = NumBuckets;
+    BucketT *OldBuckets = Buckets;
+
+    allocateBuckets(std::max<unsigned>(64, static_cast<unsigned>(NextPowerOf2(AtLeast-1))));
+    assert(Buckets);
+    if (!OldBuckets) {
+      this->BaseT::initEmpty();
+      return;
+    }
+
+    this->moveFromOldBuckets(OldBuckets, OldBuckets+OldNumBuckets);
+
+    // Free the old table.
+    operator delete(OldBuckets);
+  }
+
+  void shrink_and_clear() {
+    unsigned OldNumEntries = NumEntries;
+    this->destroyAll();
+
+    // Reduce the number of buckets.
+    unsigned NewNumBuckets = 0;
+    if (OldNumEntries)
+      NewNumBuckets = std::max(64, 1 << (Log2_32_Ceil(OldNumEntries) + 1));
+    if (NewNumBuckets == NumBuckets) {
+      this->BaseT::initEmpty();
+      return;
+    }
+
+    operator delete(Buckets);
+    init(NewNumBuckets);
+  }
+
+private:
+  unsigned getNumEntries() const {
+    return NumEntries;
+  }
+
+  void setNumEntries(unsigned Num) {
+    NumEntries = Num;
+  }
+
+  unsigned getNumTombstones() const {
+    return NumTombstones;
+  }
+
+  void setNumTombstones(unsigned Num) {
+    NumTombstones = Num;
+  }
+
+  BucketT *getBuckets() const {
+    return Buckets;
+  }
+
+  unsigned getNumBuckets() const {
+    return NumBuckets;
+  }
+
+  bool allocateBuckets(unsigned Num) {
+    NumBuckets = Num;
+    if (NumBuckets == 0) {
+      Buckets = nullptr;
+      return false;
+    }
+
+    Buckets = static_cast<BucketT*>(operator new(sizeof(BucketT) * NumBuckets));
+    return true;
+  }
+};
+
+template <typename KeyT, typename ValueT, unsigned InlineBuckets = 4,
+          typename KeyInfoT = DenseMapInfo<KeyT>,
+          typename BucketT = detail::DenseMapPair<KeyT, ValueT>>
+class SmallDenseMap
+    : public DenseMapBase<
+          SmallDenseMap<KeyT, ValueT, InlineBuckets, KeyInfoT, BucketT>, KeyT,
+          ValueT, KeyInfoT, BucketT> {
+  friend class DenseMapBase<SmallDenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
+
+  // Lift some types from the dependent base class into this class for
+  // simplicity of referring to them.
+  using BaseT = DenseMapBase<SmallDenseMap, KeyT, ValueT, KeyInfoT, BucketT>;
+
+  static_assert(isPowerOf2_64(InlineBuckets),
+                "InlineBuckets must be a power of 2.");
+
+  unsigned Small : 1;
+  unsigned NumEntries : 31;
+  unsigned NumTombstones;
+
+  struct LargeRep {
+    BucketT *Buckets;
+    unsigned NumBuckets;
+  };
+
+  /// A "union" of an inline bucket array and the struct representing
+  /// a large bucket. This union will be discriminated by the 'Small' bit.
+  AlignedCharArrayUnion<BucketT[InlineBuckets], LargeRep> storage;
+
+public:
+  explicit SmallDenseMap(unsigned NumInitBuckets = 0) {
+    init(NumInitBuckets);
+  }
+
+  SmallDenseMap(const SmallDenseMap &other) : BaseT() {
+    init(0);
+    copyFrom(other);
+  }
+
+  SmallDenseMap(SmallDenseMap &&other) : BaseT() {
+    init(0);
+    swap(other);
+  }
+
+  template<typename InputIt>
+  SmallDenseMap(const InputIt &I, const InputIt &E) {
+    init(NextPowerOf2(std::distance(I, E)));
+    this->insert(I, E);
+  }
+
+  ~SmallDenseMap() {
+    this->destroyAll();
+    deallocateBuckets();
+  }
+
+  void swap(SmallDenseMap& RHS) {
+    unsigned TmpNumEntries = RHS.NumEntries;
+    RHS.NumEntries = NumEntries;
+    NumEntries = TmpNumEntries;
+    std::swap(NumTombstones, RHS.NumTombstones);
+
+    const KeyT EmptyKey = this->getEmptyKey();
+    const KeyT TombstoneKey = this->getTombstoneKey();
+    if (Small && RHS.Small) {
+      // If we're swapping inline bucket arrays, we have to cope with some of
+      // the tricky bits of DenseMap's storage system: the buckets are not
+      // fully initialized. Thus we swap every key, but we may have
+      // a one-directional move of the value.
+      for (unsigned i = 0, e = InlineBuckets; i != e; ++i) {
+        BucketT *LHSB = &getInlineBuckets()[i],
+                *RHSB = &RHS.getInlineBuckets()[i];
+        bool hasLHSValue = (!KeyInfoT::isEqual(LHSB->getFirst(), EmptyKey) &&
+                            !KeyInfoT::isEqual(LHSB->getFirst(), TombstoneKey));
+        bool hasRHSValue = (!KeyInfoT::isEqual(RHSB->getFirst(), EmptyKey) &&
+                            !KeyInfoT::isEqual(RHSB->getFirst(), TombstoneKey));
+        if (hasLHSValue && hasRHSValue) {
+          // Swap together if we can...
+          std::swap(*LHSB, *RHSB);
+          continue;
+        }
+        // Swap separately and handle any assymetry.
+        std::swap(LHSB->getFirst(), RHSB->getFirst());
+        if (hasLHSValue) {
+          ::new (&RHSB->getSecond()) ValueT(std::move(LHSB->getSecond()));
+          LHSB->getSecond().~ValueT();
+        } else if (hasRHSValue) {
+          ::new (&LHSB->getSecond()) ValueT(std::move(RHSB->getSecond()));
+          RHSB->getSecond().~ValueT();
+        }
+      }
+      return;
+    }
+    if (!Small && !RHS.Small) {
+      std::swap(getLargeRep()->Buckets, RHS.getLargeRep()->Buckets);
+      std::swap(getLargeRep()->NumBuckets, RHS.getLargeRep()->NumBuckets);
+      return;
+    }
+
+    SmallDenseMap &SmallSide = Small ? *this : RHS;
+    SmallDenseMap &LargeSide = Small ? RHS : *this;
+
+    // First stash the large side's rep and move the small side across.
+    LargeRep TmpRep = std::move(*LargeSide.getLargeRep());
+    LargeSide.getLargeRep()->~LargeRep();
+    LargeSide.Small = true;
+    // This is similar to the standard move-from-old-buckets, but the bucket
+    // count hasn't actually rotated in this case. So we have to carefully
+    // move construct the keys and values into their new locations, but there
+    // is no need to re-hash things.
+    for (unsigned i = 0, e = InlineBuckets; i != e; ++i) {
+      BucketT *NewB = &LargeSide.getInlineBuckets()[i],
+              *OldB = &SmallSide.getInlineBuckets()[i];
+      ::new (&NewB->getFirst()) KeyT(std::move(OldB->getFirst()));
+      OldB->getFirst().~KeyT();
+      if (!KeyInfoT::isEqual(NewB->getFirst(), EmptyKey) &&
+          !KeyInfoT::isEqual(NewB->getFirst(), TombstoneKey)) {
+        ::new (&NewB->getSecond()) ValueT(std::move(OldB->getSecond()));
+        OldB->getSecond().~ValueT();
+      }
+    }
+
+    // The hard part of moving the small buckets across is done, just move
+    // the TmpRep into its new home.
+    SmallSide.Small = false;
+    new (SmallSide.getLargeRep()) LargeRep(std::move(TmpRep));
+  }
+
+  SmallDenseMap& operator=(const SmallDenseMap& other) {
+    if (&other != this)
+      copyFrom(other);
+    return *this;
+  }
+
+  SmallDenseMap& operator=(SmallDenseMap &&other) {
+    this->destroyAll();
+    deallocateBuckets();
+    init(0);
+    swap(other);
+    return *this;
+  }
+
+  void copyFrom(const SmallDenseMap& other) {
+    this->destroyAll();
+    deallocateBuckets();
+    Small = true;
+    if (other.getNumBuckets() > InlineBuckets) {
+      Small = false;
+      new (getLargeRep()) LargeRep(allocateBuckets(other.getNumBuckets()));
+    }
+    this->BaseT::copyFrom(other);
+  }
+
+  void init(unsigned InitBuckets) {
+    Small = true;
+    if (InitBuckets > InlineBuckets) {
+      Small = false;
+      new (getLargeRep()) LargeRep(allocateBuckets(InitBuckets));
+    }
+    this->BaseT::initEmpty();
+  }
+
+  void grow(unsigned AtLeast) {
+    if (AtLeast >= InlineBuckets)
+      AtLeast = std::max<unsigned>(64, NextPowerOf2(AtLeast-1));
+
+    if (Small) {
+      if (AtLeast < InlineBuckets)
+        return; // Nothing to do.
+
+      // First move the inline buckets into a temporary storage.
+      AlignedCharArrayUnion<BucketT[InlineBuckets]> TmpStorage;
+      BucketT *TmpBegin = reinterpret_cast<BucketT *>(TmpStorage.buffer);
+      BucketT *TmpEnd = TmpBegin;
+
+      // Loop over the buckets, moving non-empty, non-tombstones into the
+      // temporary storage. Have the loop move the TmpEnd forward as it goes.
+      const KeyT EmptyKey = this->getEmptyKey();
+      const KeyT TombstoneKey = this->getTombstoneKey();
+      for (BucketT *P = getBuckets(), *E = P + InlineBuckets; P != E; ++P) {
+        if (!KeyInfoT::isEqual(P->getFirst(), EmptyKey) &&
+            !KeyInfoT::isEqual(P->getFirst(), TombstoneKey)) {
+          assert(size_t(TmpEnd - TmpBegin) < InlineBuckets &&
+                 "Too many inline buckets!");
+          ::new (&TmpEnd->getFirst()) KeyT(std::move(P->getFirst()));
+          ::new (&TmpEnd->getSecond()) ValueT(std::move(P->getSecond()));
+          ++TmpEnd;
+          P->getSecond().~ValueT();
+        }
+        P->getFirst().~KeyT();
+      }
+
+      // Now make this map use the large rep, and move all the entries back
+      // into it.
+      Small = false;
+      new (getLargeRep()) LargeRep(allocateBuckets(AtLeast));
+      this->moveFromOldBuckets(TmpBegin, TmpEnd);
+      return;
+    }
+
+    LargeRep OldRep = std::move(*getLargeRep());
+    getLargeRep()->~LargeRep();
+    if (AtLeast <= InlineBuckets) {
+      Small = true;
+    } else {
+      new (getLargeRep()) LargeRep(allocateBuckets(AtLeast));
+    }
+
+    this->moveFromOldBuckets(OldRep.Buckets, OldRep.Buckets+OldRep.NumBuckets);
+
+    // Free the old table.
+    operator delete(OldRep.Buckets);
+  }
+
+  void shrink_and_clear() {
+    unsigned OldSize = this->size();
+    this->destroyAll();
+
+    // Reduce the number of buckets.
+    unsigned NewNumBuckets = 0;
+    if (OldSize) {
+      NewNumBuckets = 1 << (Log2_32_Ceil(OldSize) + 1);
+      if (NewNumBuckets > InlineBuckets && NewNumBuckets < 64u)
+        NewNumBuckets = 64;
+    }
+    if ((Small && NewNumBuckets <= InlineBuckets) ||
+        (!Small && NewNumBuckets == getLargeRep()->NumBuckets)) {
+      this->BaseT::initEmpty();
+      return;
+    }
+
+    deallocateBuckets();
+    init(NewNumBuckets);
+  }
+
+private:
+  unsigned getNumEntries() const {
+    return NumEntries;
+  }
+
+  void setNumEntries(unsigned Num) {
+    // NumEntries is hardcoded to be 31 bits wide.
+    assert(Num < (1U << 31) && "Cannot support more than 1<<31 entries");
+    NumEntries = Num;
+  }
+
+  unsigned getNumTombstones() const {
+    return NumTombstones;
+  }
+
+  void setNumTombstones(unsigned Num) {
+    NumTombstones = Num;
+  }
+
+  const BucketT *getInlineBuckets() const {
+    assert(Small);
+    // Note that this cast does not violate aliasing rules as we assert that
+    // the memory's dynamic type is the small, inline bucket buffer, and the
+    // 'storage.buffer' static type is 'char *'.
+    return reinterpret_cast<const BucketT *>(storage.buffer);
+  }
+
+  BucketT *getInlineBuckets() {
+    return const_cast<BucketT *>(
+      const_cast<const SmallDenseMap *>(this)->getInlineBuckets());
+  }
+
+  const LargeRep *getLargeRep() const {
+    assert(!Small);
+    // Note, same rule about aliasing as with getInlineBuckets.
+    return reinterpret_cast<const LargeRep *>(storage.buffer);
+  }
+
+  LargeRep *getLargeRep() {
+    return const_cast<LargeRep *>(
+      const_cast<const SmallDenseMap *>(this)->getLargeRep());
+  }
+
+  const BucketT *getBuckets() const {
+    return Small ? getInlineBuckets() : getLargeRep()->Buckets;
+  }
+
+  BucketT *getBuckets() {
+    return const_cast<BucketT *>(
+      const_cast<const SmallDenseMap *>(this)->getBuckets());
+  }
+
+  unsigned getNumBuckets() const {
+    return Small ? InlineBuckets : getLargeRep()->NumBuckets;
+  }
+
+  void deallocateBuckets() {
+    if (Small)
+      return;
+
+    operator delete(getLargeRep()->Buckets);
+    getLargeRep()->~LargeRep();
+  }
+
+  LargeRep allocateBuckets(unsigned Num) {
+    assert(Num > InlineBuckets && "Must allocate more buckets than are inline");
+    LargeRep Rep = {
+      static_cast<BucketT*>(operator new(sizeof(BucketT) * Num)), Num
+    };
+    return Rep;
+  }
+};
+
+template <typename KeyT, typename ValueT, typename KeyInfoT, typename Bucket,
+          bool IsConst>
+class DenseMapIterator : DebugEpochBase::HandleBase {
+  friend class DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, true>;
+  friend class DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, false>;
+
+  using ConstIterator = DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, true>;
+
+public:
+  using difference_type = ptrdiff_t;
+  using value_type =
+      typename std::conditional<IsConst, const Bucket, Bucket>::type;
+  using pointer = value_type *;
+  using reference = value_type &;
+  using iterator_category = std::forward_iterator_tag;
+
+private:
+  pointer Ptr = nullptr;
+  pointer End = nullptr;
+
+public:
+  DenseMapIterator() = default;
+
+  DenseMapIterator(pointer Pos, pointer E, const DebugEpochBase &Epoch,
+                   bool NoAdvance = false)
+      : DebugEpochBase::HandleBase(&Epoch), Ptr(Pos), End(E) {
+    assert(isHandleInSync() && "invalid construction!");
+
+    if (NoAdvance) return;
+    AdvancePastEmptyBuckets();
+  }
+
+  // Converting ctor from non-const iterators to const iterators. SFINAE'd out
+  // for const iterator destinations so it doesn't end up as a user defined copy
+  // constructor.
+  template <bool IsConstSrc,
+            typename = typename std::enable_if<!IsConstSrc && IsConst>::type>
+  DenseMapIterator(
+      const DenseMapIterator<KeyT, ValueT, KeyInfoT, Bucket, IsConstSrc> &I)
+      : DebugEpochBase::HandleBase(I), Ptr(I.Ptr), End(I.End) {}
+
+  reference operator*() const {
+    assert(isHandleInSync() && "invalid iterator access!");
+    return *Ptr;
+  }
+  pointer operator->() const {
+    assert(isHandleInSync() && "invalid iterator access!");
+    return Ptr;
+  }
+
+  bool operator==(const ConstIterator &RHS) const {
+    assert((!Ptr || isHandleInSync()) && "handle not in sync!");
+    assert((!RHS.Ptr || RHS.isHandleInSync()) && "handle not in sync!");
+    assert(getEpochAddress() == RHS.getEpochAddress() &&
+           "comparing incomparable iterators!");
+    return Ptr == RHS.Ptr;
+  }
+  bool operator!=(const ConstIterator &RHS) const {
+    assert((!Ptr || isHandleInSync()) && "handle not in sync!");
+    assert((!RHS.Ptr || RHS.isHandleInSync()) && "handle not in sync!");
+    assert(getEpochAddress() == RHS.getEpochAddress() &&
+           "comparing incomparable iterators!");
+    return Ptr != RHS.Ptr;
+  }
+
+  inline DenseMapIterator& operator++() {  // Preincrement
+    assert(isHandleInSync() && "invalid iterator access!");
+    ++Ptr;
+    AdvancePastEmptyBuckets();
+    return *this;
+  }
+  DenseMapIterator operator++(int) {  // Postincrement
+    assert(isHandleInSync() && "invalid iterator access!");
+    DenseMapIterator tmp = *this; ++*this; return tmp;
+  }
+
+private:
+  void AdvancePastEmptyBuckets() {
+    assert(Ptr <= End);
+    const KeyT Empty = KeyInfoT::getEmptyKey();
+    const KeyT Tombstone = KeyInfoT::getTombstoneKey();
+
+    while (Ptr != End && (KeyInfoT::isEqual(Ptr->getFirst(), Empty) ||
+                          KeyInfoT::isEqual(Ptr->getFirst(), Tombstone)))
+      ++Ptr;
+  }
+
+  void RetreatPastEmptyBuckets() {
+    assert(Ptr >= End);
+    const KeyT Empty = KeyInfoT::getEmptyKey();
+    const KeyT Tombstone = KeyInfoT::getTombstoneKey();
+
+    while (Ptr != End && (KeyInfoT::isEqual(Ptr[-1].getFirst(), Empty) ||
+                          KeyInfoT::isEqual(Ptr[-1].getFirst(), Tombstone)))
+      --Ptr;
+  }
+};
+
+template <typename KeyT, typename ValueT, typename KeyInfoT>
+inline size_t capacity_in_bytes(const DenseMap<KeyT, ValueT, KeyInfoT> &X) {
+  return X.getMemorySize();
+}
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_DENSEMAP_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/DenseMapInfo.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/DenseMapInfo.h
new file mode 100644
index 0000000..e4bf986
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/DenseMapInfo.h
@@ -0,0 +1,267 @@
+//===- llvm/ADT/DenseMapInfo.h - Type traits for DenseMap -------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines DenseMapInfo traits for DenseMap.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_DENSEMAPINFO_H
+#define WPIUTIL_WPI_DENSEMAPINFO_H
+
+#include "wpi/ArrayRef.h"
+#include "wpi/Hashing.h"
+#include "wpi/StringRef.h"
+#include "wpi/PointerLikeTypeTraits.h"
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <utility>
+
+namespace wpi {
+
+template<typename T>
+struct DenseMapInfo {
+  //static inline T getEmptyKey();
+  //static inline T getTombstoneKey();
+  //static unsigned getHashValue(const T &Val);
+  //static bool isEqual(const T &LHS, const T &RHS);
+};
+
+// Provide DenseMapInfo for all pointers.
+template<typename T>
+struct DenseMapInfo<T*> {
+  static inline T* getEmptyKey() {
+    uintptr_t Val = static_cast<uintptr_t>(-1);
+    Val <<= PointerLikeTypeTraits<T*>::NumLowBitsAvailable;
+    return reinterpret_cast<T*>(Val);
+  }
+
+  static inline T* getTombstoneKey() {
+    uintptr_t Val = static_cast<uintptr_t>(-2);
+    Val <<= PointerLikeTypeTraits<T*>::NumLowBitsAvailable;
+    return reinterpret_cast<T*>(Val);
+  }
+
+  static unsigned getHashValue(const T *PtrVal) {
+    return (unsigned((uintptr_t)PtrVal) >> 4) ^
+           (unsigned((uintptr_t)PtrVal) >> 9);
+  }
+
+  static bool isEqual(const T *LHS, const T *RHS) { return LHS == RHS; }
+};
+
+// Provide DenseMapInfo for chars.
+template<> struct DenseMapInfo<char> {
+  static inline char getEmptyKey() { return ~0; }
+  static inline char getTombstoneKey() { return ~0 - 1; }
+  static unsigned getHashValue(const char& Val) { return Val * 37U; }
+
+  static bool isEqual(const char &LHS, const char &RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned shorts.
+template <> struct DenseMapInfo<unsigned short> {
+  static inline unsigned short getEmptyKey() { return 0xFFFF; }
+  static inline unsigned short getTombstoneKey() { return 0xFFFF - 1; }
+  static unsigned getHashValue(const unsigned short &Val) { return Val * 37U; }
+
+  static bool isEqual(const unsigned short &LHS, const unsigned short &RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned ints.
+template<> struct DenseMapInfo<unsigned> {
+  static inline unsigned getEmptyKey() { return ~0U; }
+  static inline unsigned getTombstoneKey() { return ~0U - 1; }
+  static unsigned getHashValue(const unsigned& Val) { return Val * 37U; }
+
+  static bool isEqual(const unsigned& LHS, const unsigned& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned longs.
+template<> struct DenseMapInfo<unsigned long> {
+  static inline unsigned long getEmptyKey() { return ~0UL; }
+  static inline unsigned long getTombstoneKey() { return ~0UL - 1L; }
+
+  static unsigned getHashValue(const unsigned long& Val) {
+    return (unsigned)(Val * 37UL);
+  }
+
+  static bool isEqual(const unsigned long& LHS, const unsigned long& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for unsigned long longs.
+template<> struct DenseMapInfo<unsigned long long> {
+  static inline unsigned long long getEmptyKey() { return ~0ULL; }
+  static inline unsigned long long getTombstoneKey() { return ~0ULL - 1ULL; }
+
+  static unsigned getHashValue(const unsigned long long& Val) {
+    return (unsigned)(Val * 37ULL);
+  }
+
+  static bool isEqual(const unsigned long long& LHS,
+                      const unsigned long long& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for shorts.
+template <> struct DenseMapInfo<short> {
+  static inline short getEmptyKey() { return 0x7FFF; }
+  static inline short getTombstoneKey() { return -0x7FFF - 1; }
+  static unsigned getHashValue(const short &Val) { return Val * 37U; }
+  static bool isEqual(const short &LHS, const short &RHS) { return LHS == RHS; }
+};
+
+// Provide DenseMapInfo for ints.
+template<> struct DenseMapInfo<int> {
+  static inline int getEmptyKey() { return 0x7fffffff; }
+  static inline int getTombstoneKey() { return -0x7fffffff - 1; }
+  static unsigned getHashValue(const int& Val) { return (unsigned)(Val * 37U); }
+
+  static bool isEqual(const int& LHS, const int& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for longs.
+template<> struct DenseMapInfo<long> {
+  static inline long getEmptyKey() {
+    return (1UL << (sizeof(long) * 8 - 1)) - 1UL;
+  }
+
+  static inline long getTombstoneKey() { return getEmptyKey() - 1L; }
+
+  static unsigned getHashValue(const long& Val) {
+    return (unsigned)(Val * 37UL);
+  }
+
+  static bool isEqual(const long& LHS, const long& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for long longs.
+template<> struct DenseMapInfo<long long> {
+  static inline long long getEmptyKey() { return 0x7fffffffffffffffLL; }
+  static inline long long getTombstoneKey() { return -0x7fffffffffffffffLL-1; }
+
+  static unsigned getHashValue(const long long& Val) {
+    return (unsigned)(Val * 37ULL);
+  }
+
+  static bool isEqual(const long long& LHS,
+                      const long long& RHS) {
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for all pairs whose members have info.
+template<typename T, typename U>
+struct DenseMapInfo<std::pair<T, U>> {
+  using Pair = std::pair<T, U>;
+  using FirstInfo = DenseMapInfo<T>;
+  using SecondInfo = DenseMapInfo<U>;
+
+  static inline Pair getEmptyKey() {
+    return std::make_pair(FirstInfo::getEmptyKey(),
+                          SecondInfo::getEmptyKey());
+  }
+
+  static inline Pair getTombstoneKey() {
+    return std::make_pair(FirstInfo::getTombstoneKey(),
+                          SecondInfo::getTombstoneKey());
+  }
+
+  static unsigned getHashValue(const Pair& PairVal) {
+    uint64_t key = (uint64_t)FirstInfo::getHashValue(PairVal.first) << 32
+          | (uint64_t)SecondInfo::getHashValue(PairVal.second);
+    key += ~(key << 32);
+    key ^= (key >> 22);
+    key += ~(key << 13);
+    key ^= (key >> 8);
+    key += (key << 3);
+    key ^= (key >> 15);
+    key += ~(key << 27);
+    key ^= (key >> 31);
+    return (unsigned)key;
+  }
+
+  static bool isEqual(const Pair &LHS, const Pair &RHS) {
+    return FirstInfo::isEqual(LHS.first, RHS.first) &&
+           SecondInfo::isEqual(LHS.second, RHS.second);
+  }
+};
+
+// Provide DenseMapInfo for StringRefs.
+template <> struct DenseMapInfo<StringRef> {
+  static inline StringRef getEmptyKey() {
+    return StringRef(reinterpret_cast<const char *>(~static_cast<uintptr_t>(0)),
+                     0);
+  }
+
+  static inline StringRef getTombstoneKey() {
+    return StringRef(reinterpret_cast<const char *>(~static_cast<uintptr_t>(1)),
+                     0);
+  }
+
+  static unsigned getHashValue(StringRef Val) {
+    assert(Val.data() != getEmptyKey().data() && "Cannot hash the empty key!");
+    assert(Val.data() != getTombstoneKey().data() &&
+           "Cannot hash the tombstone key!");
+    return (unsigned)(hash_value(Val));
+  }
+
+  static bool isEqual(StringRef LHS, StringRef RHS) {
+    if (RHS.data() == getEmptyKey().data())
+      return LHS.data() == getEmptyKey().data();
+    if (RHS.data() == getTombstoneKey().data())
+      return LHS.data() == getTombstoneKey().data();
+    return LHS == RHS;
+  }
+};
+
+// Provide DenseMapInfo for ArrayRefs.
+template <typename T> struct DenseMapInfo<ArrayRef<T>> {
+  static inline ArrayRef<T> getEmptyKey() {
+    return ArrayRef<T>(reinterpret_cast<const T *>(~static_cast<uintptr_t>(0)),
+                       size_t(0));
+  }
+
+  static inline ArrayRef<T> getTombstoneKey() {
+    return ArrayRef<T>(reinterpret_cast<const T *>(~static_cast<uintptr_t>(1)),
+                       size_t(0));
+  }
+
+  static unsigned getHashValue(ArrayRef<T> Val) {
+    assert(Val.data() != getEmptyKey().data() && "Cannot hash the empty key!");
+    assert(Val.data() != getTombstoneKey().data() &&
+           "Cannot hash the tombstone key!");
+    return (unsigned)(hash_value(Val));
+  }
+
+  static bool isEqual(ArrayRef<T> LHS, ArrayRef<T> RHS) {
+    if (RHS.data() == getEmptyKey().data())
+      return LHS.data() == getEmptyKey().data();
+    if (RHS.data() == getTombstoneKey().data())
+      return LHS.data() == getTombstoneKey().data();
+    return LHS == RHS;
+  }
+};
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_DENSEMAPINFO_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/EpochTracker.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/EpochTracker.h
new file mode 100644
index 0000000..b26800b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/EpochTracker.h
@@ -0,0 +1,97 @@
+//===- llvm/ADT/EpochTracker.h - ADT epoch tracking --------------*- C++ -*-==//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the DebugEpochBase and DebugEpochBase::HandleBase classes.
+// These can be used to write iterators that are fail-fast when LLVM is built
+// with asserts enabled.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_EPOCH_TRACKER_H
+#define WPIUTIL_WPI_EPOCH_TRACKER_H
+
+#include <cstdint>
+
+namespace wpi {
+
+#ifdef NDEBUG //ifndef LLVM_ENABLE_ABI_BREAKING_CHECKS
+
+class DebugEpochBase {
+public:
+  void incrementEpoch() {}
+
+  class HandleBase {
+  public:
+    HandleBase() = default;
+    explicit HandleBase(const DebugEpochBase *) {}
+    bool isHandleInSync() const { return true; }
+    const void *getEpochAddress() const { return nullptr; }
+  };
+};
+
+#else
+
+/// A base class for data structure classes wishing to make iterators
+/// ("handles") pointing into themselves fail-fast.  When building without
+/// asserts, this class is empty and does nothing.
+///
+/// DebugEpochBase does not by itself track handles pointing into itself.  The
+/// expectation is that routines touching the handles will poll on
+/// isHandleInSync at appropriate points to assert that the handle they're using
+/// is still valid.
+///
+class DebugEpochBase {
+  uint64_t Epoch;
+
+public:
+  DebugEpochBase() : Epoch(0) {}
+
+  /// Calling incrementEpoch invalidates all handles pointing into the
+  /// calling instance.
+  void incrementEpoch() { ++Epoch; }
+
+  /// The destructor calls incrementEpoch to make use-after-free bugs
+  /// more likely to crash deterministically.
+  ~DebugEpochBase() { incrementEpoch(); }
+
+  /// A base class for iterator classes ("handles") that wish to poll for
+  /// iterator invalidating modifications in the underlying data structure.
+  /// When LLVM is built without asserts, this class is empty and does nothing.
+  ///
+  /// HandleBase does not track the parent data structure by itself.  It expects
+  /// the routines modifying the data structure to call incrementEpoch when they
+  /// make an iterator-invalidating modification.
+  ///
+  class HandleBase {
+    const uint64_t *EpochAddress;
+    uint64_t EpochAtCreation;
+
+  public:
+    HandleBase() : EpochAddress(nullptr), EpochAtCreation(UINT64_MAX) {}
+
+    explicit HandleBase(const DebugEpochBase *Parent)
+        : EpochAddress(&Parent->Epoch), EpochAtCreation(Parent->Epoch) {}
+
+    /// Returns true if the DebugEpochBase this Handle is linked to has
+    /// not called incrementEpoch on itself since the creation of this
+    /// HandleBase instance.
+    bool isHandleInSync() const { return *EpochAddress == EpochAtCreation; }
+
+    /// Returns a pointer to the epoch word stored in the data structure
+    /// this handle points into.  Can be used to check if two iterators point
+    /// into the same data structure.
+    const void *getEpochAddress() const { return EpochAddress; }
+  };
+};
+
+#endif // LLVM_ENABLE_ABI_BREAKING_CHECKS
+
+} // namespace wpi
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ErrorOr.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ErrorOr.h
new file mode 100644
index 0000000..1a878d1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/ErrorOr.h
@@ -0,0 +1,291 @@
+//===- llvm/Support/ErrorOr.h - Error Smart Pointer -------------*- C++ -*-===//
+//
+//                             The LLVM Linker
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+///
+/// \file
+///
+/// Provides ErrorOr<T> smart pointer.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ERROROR_H
+#define WPIUTIL_WPI_ERROROR_H
+
+#include "wpi/AlignOf.h"
+#include <cassert>
+#include <system_error>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+/// Stores a reference that can be changed.
+template <typename T>
+class ReferenceStorage {
+  T *Storage;
+
+public:
+  ReferenceStorage(T &Ref) : Storage(&Ref) {}
+
+  operator T &() const { return *Storage; }
+  T &get() const { return *Storage; }
+};
+
+/// Represents either an error or a value T.
+///
+/// ErrorOr<T> is a pointer-like class that represents the result of an
+/// operation. The result is either an error, or a value of type T. This is
+/// designed to emulate the usage of returning a pointer where nullptr indicates
+/// failure. However instead of just knowing that the operation failed, we also
+/// have an error_code and optional user data that describes why it failed.
+///
+/// It is used like the following.
+/// \code
+///   ErrorOr<Buffer> getBuffer();
+///
+///   auto buffer = getBuffer();
+///   if (error_code ec = buffer.getError())
+///     return ec;
+///   buffer->write("adena");
+/// \endcode
+///
+///
+/// Implicit conversion to bool returns true if there is a usable value. The
+/// unary * and -> operators provide pointer like access to the value. Accessing
+/// the value when there is an error has undefined behavior.
+///
+/// When T is a reference type the behavior is slightly different. The reference
+/// is held in a std::reference_wrapper<std::remove_reference<T>::type>, and
+/// there is special handling to make operator -> work as if T was not a
+/// reference.
+///
+/// T cannot be a rvalue reference.
+template<class T>
+class ErrorOr {
+  template <class OtherT> friend class ErrorOr;
+
+  static const bool isRef = std::is_reference<T>::value;
+
+  using wrap = ReferenceStorage<typename std::remove_reference<T>::type>;
+
+public:
+  using storage_type = typename std::conditional<isRef, wrap, T>::type;
+
+private:
+  using reference = typename std::remove_reference<T>::type &;
+  using const_reference = const typename std::remove_reference<T>::type &;
+  using pointer = typename std::remove_reference<T>::type *;
+  using const_pointer = const typename std::remove_reference<T>::type *;
+
+public:
+  template <class E>
+  ErrorOr(E ErrorCode,
+          typename std::enable_if<std::is_error_code_enum<E>::value ||
+                                      std::is_error_condition_enum<E>::value,
+                                  void *>::type = nullptr)
+      : HasError(true) {
+    new (getErrorStorage()) std::error_code(make_error_code(ErrorCode));
+  }
+
+  ErrorOr(std::error_code EC) : HasError(true) {
+    new (getErrorStorage()) std::error_code(EC);
+  }
+
+  template <class OtherT>
+  ErrorOr(OtherT &&Val,
+          typename std::enable_if<std::is_convertible<OtherT, T>::value>::type
+              * = nullptr)
+      : HasError(false) {
+    new (getStorage()) storage_type(std::forward<OtherT>(Val));
+  }
+
+  ErrorOr(const ErrorOr &Other) {
+    copyConstruct(Other);
+  }
+
+  template <class OtherT>
+  ErrorOr(
+      const ErrorOr<OtherT> &Other,
+      typename std::enable_if<std::is_convertible<OtherT, T>::value>::type * =
+          nullptr) {
+    copyConstruct(Other);
+  }
+
+  template <class OtherT>
+  explicit ErrorOr(
+      const ErrorOr<OtherT> &Other,
+      typename std::enable_if<
+          !std::is_convertible<OtherT, const T &>::value>::type * = nullptr) {
+    copyConstruct(Other);
+  }
+
+  ErrorOr(ErrorOr &&Other) {
+    moveConstruct(std::move(Other));
+  }
+
+  template <class OtherT>
+  ErrorOr(
+      ErrorOr<OtherT> &&Other,
+      typename std::enable_if<std::is_convertible<OtherT, T>::value>::type * =
+          nullptr) {
+    moveConstruct(std::move(Other));
+  }
+
+  // This might eventually need SFINAE but it's more complex than is_convertible
+  // & I'm too lazy to write it right now.
+  template <class OtherT>
+  explicit ErrorOr(
+      ErrorOr<OtherT> &&Other,
+      typename std::enable_if<!std::is_convertible<OtherT, T>::value>::type * =
+          nullptr) {
+    moveConstruct(std::move(Other));
+  }
+
+  ErrorOr &operator=(const ErrorOr &Other) {
+    copyAssign(Other);
+    return *this;
+  }
+
+  ErrorOr &operator=(ErrorOr &&Other) {
+    moveAssign(std::move(Other));
+    return *this;
+  }
+
+  ~ErrorOr() {
+    if (!HasError)
+      getStorage()->~storage_type();
+  }
+
+  /// Return false if there is an error.
+  explicit operator bool() const {
+    return !HasError;
+  }
+
+  reference get() { return *getStorage(); }
+  const_reference get() const { return const_cast<ErrorOr<T> *>(this)->get(); }
+
+  std::error_code getError() const {
+    return HasError ? *getErrorStorage() : std::error_code();
+  }
+
+  pointer operator ->() {
+    return toPointer(getStorage());
+  }
+
+  const_pointer operator->() const { return toPointer(getStorage()); }
+
+  reference operator *() {
+    return *getStorage();
+  }
+
+  const_reference operator*() const { return *getStorage(); }
+
+private:
+  template <class OtherT>
+  void copyConstruct(const ErrorOr<OtherT> &Other) {
+    if (!Other.HasError) {
+      // Get the other value.
+      HasError = false;
+      new (getStorage()) storage_type(*Other.getStorage());
+    } else {
+      // Get other's error.
+      HasError = true;
+      new (getErrorStorage()) std::error_code(Other.getError());
+    }
+  }
+
+  template <class T1>
+  static bool compareThisIfSameType(const T1 &a, const T1 &b) {
+    return &a == &b;
+  }
+
+  template <class T1, class T2>
+  static bool compareThisIfSameType(const T1 &a, const T2 &b) {
+    return false;
+  }
+
+  template <class OtherT>
+  void copyAssign(const ErrorOr<OtherT> &Other) {
+    if (compareThisIfSameType(*this, Other))
+      return;
+
+    this->~ErrorOr();
+    new (this) ErrorOr(Other);
+  }
+
+  template <class OtherT>
+  void moveConstruct(ErrorOr<OtherT> &&Other) {
+    if (!Other.HasError) {
+      // Get the other value.
+      HasError = false;
+      new (getStorage()) storage_type(std::move(*Other.getStorage()));
+    } else {
+      // Get other's error.
+      HasError = true;
+      new (getErrorStorage()) std::error_code(Other.getError());
+    }
+  }
+
+  template <class OtherT>
+  void moveAssign(ErrorOr<OtherT> &&Other) {
+    if (compareThisIfSameType(*this, Other))
+      return;
+
+    this->~ErrorOr();
+    new (this) ErrorOr(std::move(Other));
+  }
+
+  pointer toPointer(pointer Val) {
+    return Val;
+  }
+
+  const_pointer toPointer(const_pointer Val) const { return Val; }
+
+  pointer toPointer(wrap *Val) {
+    return &Val->get();
+  }
+
+  const_pointer toPointer(const wrap *Val) const { return &Val->get(); }
+
+  storage_type *getStorage() {
+    assert(!HasError && "Cannot get value when an error exists!");
+    return reinterpret_cast<storage_type*>(TStorage.buffer);
+  }
+
+  const storage_type *getStorage() const {
+    assert(!HasError && "Cannot get value when an error exists!");
+    return reinterpret_cast<const storage_type*>(TStorage.buffer);
+  }
+
+  std::error_code *getErrorStorage() {
+    assert(HasError && "Cannot get error when a value exists!");
+    return reinterpret_cast<std::error_code *>(ErrorStorage.buffer);
+  }
+
+  const std::error_code *getErrorStorage() const {
+    return const_cast<ErrorOr<T> *>(this)->getErrorStorage();
+  }
+
+  union {
+    AlignedCharArrayUnion<storage_type> TStorage;
+    AlignedCharArrayUnion<std::error_code> ErrorStorage;
+  };
+  bool HasError : 1;
+};
+
+template <class T, class E>
+typename std::enable_if<std::is_error_code_enum<E>::value ||
+                            std::is_error_condition_enum<E>::value,
+                        bool>::type
+operator==(const ErrorOr<T> &Err, E Code) {
+  return Err.getError() == Code;
+}
+
+} // end namespace wpi
+
+#endif // LLVM_SUPPORT_ERROROR_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/EventLoopRunner.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/EventLoopRunner.h
new file mode 100644
index 0000000..8150091
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/EventLoopRunner.h
@@ -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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_EVENTLOOPRUNNER_H_
+#define WPIUTIL_WPI_EVENTLOOPRUNNER_H_
+
+#include <functional>
+#include <memory>
+
+#include "wpi/SafeThread.h"
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+
+/**
+ * Executes an event loop on a separate thread.
+ */
+class EventLoopRunner {
+ public:
+  using LoopFunc = std::function<void(uv::Loop&)>;
+
+  EventLoopRunner();
+  virtual ~EventLoopRunner();
+
+  /**
+   * Stop the loop.  Once the loop is stopped it cannot be restarted.
+   * This function does not return until the loop has exited.
+   */
+  void Stop();
+
+  /**
+   * Run a function asynchronously (once) on the loop.
+   * This is safe to call from any thread, but is NOT safe to call from the
+   * provided function (it will deadlock).
+   * @param func function to execute on the loop
+   */
+  void ExecAsync(LoopFunc func);
+
+  /**
+   * Run a function synchronously (once) on the loop.
+   * This is safe to call from any thread, but is NOT safe to call from the
+   * provided function (it will deadlock).
+   * This does not return until the function finishes executing.
+   * @param func function to execute on the loop
+   */
+  void ExecSync(LoopFunc func);
+
+  /**
+   * Get the loop.  If the loop thread is not running, returns nullptr.
+   * @return The loop
+   */
+  std::shared_ptr<uv::Loop> GetLoop();
+
+ private:
+  class Thread;
+  SafeThreadOwner<Thread> m_owner;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_EVENTLOOPRUNNER_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/FileSystem.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/FileSystem.h
new file mode 100644
index 0000000..626aaaa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/FileSystem.h
@@ -0,0 +1,785 @@
+//===- llvm/Support/FileSystem.h - File System OS Concept -------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file declares the wpi::sys::fs namespace. It is designed after
+// TR2/boost filesystem (v3), but modified to remove exception handling and the
+// path class.
+//
+// All functions return an error_code and their actual work via the last out
+// argument. The out argument is defined if and only if errc::success is
+// returned. A function may return any error code in the generic or system
+// category. However, they shall be equivalent to any error conditions listed
+// in each functions respective documentation if the condition applies. [ note:
+// this does not guarantee that error_code will be in the set of explicitly
+// listed codes, but it does guarantee that if any of the explicitly listed
+// errors occur, the correct error_code will be used ]. All functions may
+// return errc::not_enough_memory if there is not enough memory to complete the
+// operation.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_FILESYSTEM_H
+#define WPIUTIL_WPI_FILESYSTEM_H
+
+#include "wpi/SmallString.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+#include "wpi/ErrorOr.h"
+#include <cassert>
+#include <cstdint>
+#include <ctime>
+#include <memory>
+#include <stack>
+#include <string>
+#include <system_error>
+#include <tuple>
+#include <vector>
+
+#include <sys/stat.h>
+
+namespace wpi {
+namespace sys {
+namespace fs {
+
+/// An enumeration for the file system's view of the type.
+enum class file_type {
+  status_error,
+  file_not_found,
+  regular_file,
+  directory_file,
+  symlink_file,
+  block_file,
+  character_file,
+  fifo_file,
+  socket_file,
+  type_unknown
+};
+
+enum perms {
+  no_perms = 0,
+  owner_read = 0400,
+  owner_write = 0200,
+  owner_exe = 0100,
+  owner_all = owner_read | owner_write | owner_exe,
+  group_read = 040,
+  group_write = 020,
+  group_exe = 010,
+  group_all = group_read | group_write | group_exe,
+  others_read = 04,
+  others_write = 02,
+  others_exe = 01,
+  others_all = others_read | others_write | others_exe,
+  all_read = owner_read | group_read | others_read,
+  all_write = owner_write | group_write | others_write,
+  all_exe = owner_exe | group_exe | others_exe,
+  all_all = owner_all | group_all | others_all,
+  set_uid_on_exe = 04000,
+  set_gid_on_exe = 02000,
+  sticky_bit = 01000,
+  all_perms = all_all | set_uid_on_exe | set_gid_on_exe | sticky_bit,
+  perms_not_known = 0xFFFF
+};
+
+// Helper functions so that you can use & and | to manipulate perms bits:
+inline perms operator|(perms l, perms r) {
+  return static_cast<perms>(static_cast<unsigned short>(l) |
+                            static_cast<unsigned short>(r));
+}
+inline perms operator&(perms l, perms r) {
+  return static_cast<perms>(static_cast<unsigned short>(l) &
+                            static_cast<unsigned short>(r));
+}
+inline perms &operator|=(perms &l, perms r) {
+  l = l | r;
+  return l;
+}
+inline perms &operator&=(perms &l, perms r) {
+  l = l & r;
+  return l;
+}
+inline perms operator~(perms x) {
+  // Avoid UB by explicitly truncating the (unsigned) ~ result.
+  return static_cast<perms>(
+      static_cast<unsigned short>(~static_cast<unsigned short>(x)));
+}
+
+class UniqueID {
+  uint64_t Device;
+  uint64_t File;
+
+public:
+  UniqueID() = default;
+  UniqueID(uint64_t Device, uint64_t File) : Device(Device), File(File) {}
+
+  bool operator==(const UniqueID &Other) const {
+    return Device == Other.Device && File == Other.File;
+  }
+  bool operator!=(const UniqueID &Other) const { return !(*this == Other); }
+  bool operator<(const UniqueID &Other) const {
+    return std::tie(Device, File) < std::tie(Other.Device, Other.File);
+  }
+
+  uint64_t getDevice() const { return Device; }
+  uint64_t getFile() const { return File; }
+};
+
+/// Represents the result of a call to directory_iterator::status(). This is a
+/// subset of the information returned by a regular sys::fs::status() call, and
+/// represents the information provided by Windows FileFirstFile/FindNextFile.
+class basic_file_status {
+protected:
+  #ifndef _WIN32
+  time_t fs_st_atime = 0;
+  time_t fs_st_mtime = 0;
+  uid_t fs_st_uid = 0;
+  gid_t fs_st_gid = 0;
+  off_t fs_st_size = 0;
+  #else
+  uint32_t LastAccessedTimeHigh = 0;
+  uint32_t LastAccessedTimeLow = 0;
+  uint32_t LastWriteTimeHigh = 0;
+  uint32_t LastWriteTimeLow = 0;
+  uint32_t FileSizeHigh = 0;
+  uint32_t FileSizeLow = 0;
+  #endif
+  file_type Type = file_type::status_error;
+  perms Perms = perms_not_known;
+
+public:
+  basic_file_status() = default;
+
+  explicit basic_file_status(file_type Type) : Type(Type) {}
+
+  #ifndef _WIN32
+  basic_file_status(file_type Type, perms Perms, time_t ATime, time_t MTime,
+                    uid_t UID, gid_t GID, off_t Size)
+      : fs_st_atime(ATime), fs_st_mtime(MTime), fs_st_uid(UID), fs_st_gid(GID),
+        fs_st_size(Size), Type(Type), Perms(Perms) {}
+  #else
+  basic_file_status(file_type Type, perms Perms, uint32_t LastAccessTimeHigh,
+                    uint32_t LastAccessTimeLow, uint32_t LastWriteTimeHigh,
+                    uint32_t LastWriteTimeLow, uint32_t FileSizeHigh,
+                    uint32_t FileSizeLow)
+      : LastAccessedTimeHigh(LastAccessTimeHigh),
+        LastAccessedTimeLow(LastAccessTimeLow),
+        LastWriteTimeHigh(LastWriteTimeHigh),
+        LastWriteTimeLow(LastWriteTimeLow), FileSizeHigh(FileSizeHigh),
+        FileSizeLow(FileSizeLow), Type(Type), Perms(Perms) {}
+  #endif
+
+  // getters
+  file_type type() const { return Type; }
+  perms permissions() const { return Perms; }
+
+  #ifndef _WIN32
+  uint32_t getUser() const { return fs_st_uid; }
+  uint32_t getGroup() const { return fs_st_gid; }
+  uint64_t getSize() const { return fs_st_size; }
+  #else
+  uint32_t getUser() const {
+    return 9999; // Not applicable to Windows, so...
+  }
+
+  uint32_t getGroup() const {
+    return 9999; // Not applicable to Windows, so...
+  }
+
+  uint64_t getSize() const {
+    return (uint64_t(FileSizeHigh) << 32) + FileSizeLow;
+  }
+  #endif
+
+  // setters
+  void type(file_type v) { Type = v; }
+  void permissions(perms p) { Perms = p; }
+};
+
+/// Represents the result of a call to sys::fs::status().
+class file_status : public basic_file_status {
+  friend bool equivalent(file_status A, file_status B);
+
+  #ifndef _WIN32
+  dev_t fs_st_dev = 0;
+  nlink_t fs_st_nlinks = 0;
+  ino_t fs_st_ino = 0;
+  #else
+  uint32_t NumLinks = 0;
+  uint32_t VolumeSerialNumber = 0;
+  uint32_t FileIndexHigh = 0;
+  uint32_t FileIndexLow = 0;
+  #endif
+
+public:
+  file_status() = default;
+
+  explicit file_status(file_type Type) : basic_file_status(Type) {}
+
+  #ifndef _WIN32
+  file_status(file_type Type, perms Perms, dev_t Dev, nlink_t Links, ino_t Ino,
+              time_t ATime, time_t MTime, uid_t UID, gid_t GID, off_t Size)
+      : basic_file_status(Type, Perms, ATime, MTime, UID, GID, Size),
+        fs_st_dev(Dev), fs_st_nlinks(Links), fs_st_ino(Ino) {}
+  #else
+  file_status(file_type Type, perms Perms, uint32_t LinkCount,
+              uint32_t LastAccessTimeHigh, uint32_t LastAccessTimeLow,
+              uint32_t LastWriteTimeHigh, uint32_t LastWriteTimeLow,
+              uint32_t VolumeSerialNumber, uint32_t FileSizeHigh,
+              uint32_t FileSizeLow, uint32_t FileIndexHigh,
+              uint32_t FileIndexLow)
+      : basic_file_status(Type, Perms, LastAccessTimeHigh, LastAccessTimeLow,
+                          LastWriteTimeHigh, LastWriteTimeLow, FileSizeHigh,
+                          FileSizeLow),
+        NumLinks(LinkCount), VolumeSerialNumber(VolumeSerialNumber),
+        FileIndexHigh(FileIndexHigh), FileIndexLow(FileIndexLow) {}
+  #endif
+
+  UniqueID getUniqueID() const;
+  uint32_t getLinkCount() const;
+};
+
+/// @}
+/// @name Physical Operators
+/// @{
+
+/// Make \a path an absolute path.
+///
+/// Makes \a path absolute using the \a current_directory if it is not already.
+/// An empty \a path will result in the \a current_directory.
+///
+/// /absolute/path   => /absolute/path
+/// relative/../path => <current-directory>/relative/../path
+///
+/// @param path A path that is modified to be an absolute path.
+/// @returns errc::success if \a path has been made absolute, otherwise a
+///          platform-specific error_code.
+std::error_code make_absolute(const Twine &current_directory,
+                              SmallVectorImpl<char> &path);
+
+/// Make \a path an absolute path.
+///
+/// Makes \a path absolute using the current directory if it is not already. An
+/// empty \a path will result in the current directory.
+///
+/// /absolute/path   => /absolute/path
+/// relative/../path => <current-directory>/relative/../path
+///
+/// @param path A path that is modified to be an absolute path.
+/// @returns errc::success if \a path has been made absolute, otherwise a
+///          platform-specific error_code.
+std::error_code make_absolute(SmallVectorImpl<char> &path);
+
+/// Get the current path.
+///
+/// @param result Holds the current path on return.
+/// @returns errc::success if the current path has been stored in result,
+///          otherwise a platform-specific error_code.
+std::error_code current_path(SmallVectorImpl<char> &result);
+
+/// @}
+/// @name Physical Observers
+/// @{
+
+/// Does file exist?
+///
+/// @param status A basic_file_status previously returned from stat.
+/// @returns True if the file represented by status exists, false if it does
+///          not.
+bool exists(const basic_file_status &status);
+
+enum class AccessMode { Exist, Write, Execute };
+
+/// Can the file be accessed?
+///
+/// @param Path Input path.
+/// @returns errc::success if the path can be accessed, otherwise a
+///          platform-specific error_code.
+std::error_code access(const Twine &Path, AccessMode Mode);
+
+/// Does file exist?
+///
+/// @param Path Input path.
+/// @returns True if it exists, false otherwise.
+inline bool exists(const Twine &Path) {
+  return !access(Path, AccessMode::Exist);
+}
+
+/// Can we write this file?
+///
+/// @param Path Input path.
+/// @returns True if we can write to it, false otherwise.
+inline bool can_write(const Twine &Path) {
+  return !access(Path, AccessMode::Write);
+}
+
+/// Do file_status's represent the same thing?
+///
+/// @param A Input file_status.
+/// @param B Input file_status.
+///
+/// assert(status_known(A) || status_known(B));
+///
+/// @returns True if A and B both represent the same file system entity, false
+///          otherwise.
+bool equivalent(file_status A, file_status B);
+
+/// Do paths represent the same thing?
+///
+/// assert(status_known(A) || status_known(B));
+///
+/// @param A Input path A.
+/// @param B Input path B.
+/// @param result Set to true if stat(A) and stat(B) have the same device and
+///               inode (or equivalent).
+/// @returns errc::success if result has been successfully set, otherwise a
+///          platform-specific error_code.
+std::error_code equivalent(const Twine &A, const Twine &B, bool &result);
+
+/// Simpler version of equivalent for clients that don't need to
+///        differentiate between an error and false.
+inline bool equivalent(const Twine &A, const Twine &B) {
+  bool result;
+  return !equivalent(A, B, result) && result;
+}
+
+/// Does status represent a directory?
+///
+/// @param status A basic_file_status previously returned from status.
+/// @returns status.type() == file_type::directory_file.
+bool is_directory(const basic_file_status &status);
+
+/// Is path a directory?
+///
+/// @param path Input path.
+/// @param result Set to true if \a path is a directory (after following
+///               symlinks, false if it is not. Undefined otherwise.
+/// @returns errc::success if result has been successfully set, otherwise a
+///          platform-specific error_code.
+std::error_code is_directory(const Twine &path, bool &result);
+
+/// Simpler version of is_directory for clients that don't need to
+///        differentiate between an error and false.
+inline bool is_directory(const Twine &Path) {
+  bool Result;
+  return !is_directory(Path, Result) && Result;
+}
+
+/// Does status represent a regular file?
+///
+/// @param status A basic_file_status previously returned from status.
+/// @returns status_known(status) && status.type() == file_type::regular_file.
+bool is_regular_file(const basic_file_status &status);
+
+/// Is path a regular file?
+///
+/// @param path Input path.
+/// @param result Set to true if \a path is a regular file (after following
+///               symlinks), false if it is not. Undefined otherwise.
+/// @returns errc::success if result has been successfully set, otherwise a
+///          platform-specific error_code.
+std::error_code is_regular_file(const Twine &path, bool &result);
+
+/// Simpler version of is_regular_file for clients that don't need to
+///        differentiate between an error and false.
+inline bool is_regular_file(const Twine &Path) {
+  bool Result;
+  if (is_regular_file(Path, Result))
+    return false;
+  return Result;
+}
+
+/// Does status represent a symlink file?
+///
+/// @param status A basic_file_status previously returned from status.
+/// @returns status_known(status) && status.type() == file_type::symlink_file.
+bool is_symlink_file(const basic_file_status &status);
+
+/// Is path a symlink file?
+///
+/// @param path Input path.
+/// @param result Set to true if \a path is a symlink file, false if it is not.
+///               Undefined otherwise.
+/// @returns errc::success if result has been successfully set, otherwise a
+///          platform-specific error_code.
+std::error_code is_symlink_file(const Twine &path, bool &result);
+
+/// Simpler version of is_symlink_file for clients that don't need to
+///        differentiate between an error and false.
+inline bool is_symlink_file(const Twine &Path) {
+  bool Result;
+  if (is_symlink_file(Path, Result))
+    return false;
+  return Result;
+}
+
+/// Does this status represent something that exists but is not a
+///        directory or regular file?
+///
+/// @param status A basic_file_status previously returned from status.
+/// @returns exists(s) && !is_regular_file(s) && !is_directory(s)
+bool is_other(const basic_file_status &status);
+
+/// Is path something that exists but is not a directory,
+///        regular file, or symlink?
+///
+/// @param path Input path.
+/// @param result Set to true if \a path exists, but is not a directory, regular
+///               file, or a symlink, false if it does not. Undefined otherwise.
+/// @returns errc::success if result has been successfully set, otherwise a
+///          platform-specific error_code.
+std::error_code is_other(const Twine &path, bool &result);
+
+/// Get file status as if by POSIX stat().
+///
+/// @param path Input path.
+/// @param result Set to the file status.
+/// @param follow When true, follows symlinks.  Otherwise, the symlink itself is
+///               statted.
+/// @returns errc::success if result has been successfully set, otherwise a
+///          platform-specific error_code.
+std::error_code status(const Twine &path, file_status &result,
+                       bool follow = true);
+
+/// A version for when a file descriptor is already available.
+std::error_code status(int FD, file_status &Result);
+
+/// Is status available?
+///
+/// @param s Input file status.
+/// @returns True if status() != status_error.
+bool status_known(const basic_file_status &s);
+
+/// Is status available?
+///
+/// @param path Input path.
+/// @param result Set to true if status() != status_error.
+/// @returns errc::success if result has been successfully set, otherwise a
+///          platform-specific error_code.
+std::error_code status_known(const Twine &path, bool &result);
+
+enum OpenFlags : unsigned {
+  F_None = 0,
+
+  /// F_Excl - When opening a file, this flag makes raw_fd_ostream
+  /// report an error if the file already exists.
+  F_Excl = 1,
+
+  /// F_Append - When opening a file, if it already exists append to the
+  /// existing file instead of returning an error.  This may not be specified
+  /// with F_Excl.
+  F_Append = 2,
+
+  /// F_NoTrunc - When opening a file, if it already exists don't truncate
+  /// the file contents.  F_Append implies F_NoTrunc, but F_Append seeks to
+  /// the end of the file, which F_NoTrunc doesn't.
+  F_NoTrunc = 4,
+
+  /// The file should be opened in text mode on platforms that make this
+  /// distinction.
+  F_Text = 8,
+
+  /// Open the file for read and write.
+  F_RW = 16,
+
+  /// Delete the file on close. Only makes a difference on windows.
+  F_Delete = 32
+};
+
+inline OpenFlags operator|(OpenFlags A, OpenFlags B) {
+  return OpenFlags(unsigned(A) | unsigned(B));
+}
+
+inline OpenFlags &operator|=(OpenFlags &A, OpenFlags B) {
+  A = A | B;
+  return A;
+}
+
+/// @brief Opens the file with the given name in a write-only or read-write
+/// mode, returning its open file descriptor. If the file does not exist, it
+/// is created.
+///
+/// The caller is responsible for closing the file descriptor once they are
+/// finished with it.
+///
+/// @param Name The path of the file to open, relative or absolute.
+/// @param ResultFD If the file could be opened successfully, its descriptor
+///                 is stored in this location. Otherwise, this is set to -1.
+/// @param Flags Additional flags used to determine whether the file should be
+///              opened in, for example, read-write or in write-only mode.
+/// @param Mode The access permissions of the file, represented in octal.
+/// @returns errc::success if \a Name has been opened, otherwise a
+///          platform-specific error_code.
+std::error_code openFileForWrite(const Twine &Name, int &ResultFD,
+                                 OpenFlags Flags, unsigned Mode = 0666);
+
+/// @brief Opens the file with the given name in a read-only mode, returning
+/// its open file descriptor.
+///
+/// The caller is responsible for closing the file descriptor once they are
+/// finished with it.
+///
+/// @param Name The path of the file to open, relative or absolute.
+/// @param ResultFD If the file could be opened successfully, its descriptor
+///                 is stored in this location. Otherwise, this is set to -1.
+/// @param RealPath If nonnull, extra work is done to determine the real path
+///                 of the opened file, and that path is stored in this
+///                 location.
+/// @returns errc::success if \a Name has been opened, otherwise a
+///          platform-specific error_code.
+std::error_code openFileForRead(const Twine &Name, int &ResultFD,
+                                SmallVectorImpl<char> *RealPath = nullptr);
+
+std::error_code getUniqueID(const Twine Path, UniqueID &Result);
+
+/// @}
+/// @name Iterators
+/// @{
+
+/// directory_entry - A single entry in a directory. Caches the status either
+/// from the result of the iteration syscall, or the first time status is
+/// called.
+class directory_entry {
+  std::string Path;
+  bool FollowSymlinks;
+  basic_file_status Status;
+
+public:
+  explicit directory_entry(const Twine &path, bool follow_symlinks = true,
+                           basic_file_status st = basic_file_status())
+      : Path(path.str()), FollowSymlinks(follow_symlinks), Status(st) {}
+
+  directory_entry() = default;
+
+  void assign(const Twine &path, basic_file_status st = basic_file_status()) {
+    Path = path.str();
+    Status = st;
+  }
+
+  void replace_filename(const Twine &filename,
+                        basic_file_status st = basic_file_status());
+
+  const std::string &path() const { return Path; }
+  ErrorOr<basic_file_status> status() const;
+
+  bool operator==(const directory_entry& rhs) const { return Path == rhs.Path; }
+  bool operator!=(const directory_entry& rhs) const { return !(*this == rhs); }
+  bool operator< (const directory_entry& rhs) const;
+  bool operator<=(const directory_entry& rhs) const;
+  bool operator> (const directory_entry& rhs) const;
+  bool operator>=(const directory_entry& rhs) const;
+};
+
+namespace detail {
+
+  struct DirIterState;
+
+  std::error_code directory_iterator_construct(DirIterState &, StringRef, bool);
+  std::error_code directory_iterator_increment(DirIterState &);
+  std::error_code directory_iterator_destruct(DirIterState &);
+
+  /// Keeps state for the directory_iterator.
+  struct DirIterState {
+    ~DirIterState() {
+      directory_iterator_destruct(*this);
+    }
+
+    intptr_t IterationHandle = 0;
+    directory_entry CurrentEntry;
+  };
+
+} // end namespace detail
+
+/// directory_iterator - Iterates through the entries in path. There is no
+/// operator++ because we need an error_code. If it's really needed we can make
+/// it call report_fatal_error on error.
+class directory_iterator {
+  std::shared_ptr<detail::DirIterState> State;
+  bool FollowSymlinks = true;
+
+public:
+  explicit directory_iterator(const Twine &path, std::error_code &ec,
+                              bool follow_symlinks = true)
+      : FollowSymlinks(follow_symlinks) {
+    State = std::make_shared<detail::DirIterState>();
+    SmallString<128> path_storage;
+    ec = detail::directory_iterator_construct(
+        *State, path.toStringRef(path_storage), FollowSymlinks);
+    update_error_code_for_current_entry(ec);
+  }
+
+  explicit directory_iterator(const directory_entry &de, std::error_code &ec,
+                              bool follow_symlinks = true)
+      : FollowSymlinks(follow_symlinks) {
+    State = std::make_shared<detail::DirIterState>();
+    ec = detail::directory_iterator_construct(
+        *State, de.path(), FollowSymlinks);
+    update_error_code_for_current_entry(ec);
+  }
+
+  /// Construct end iterator.
+  directory_iterator() = default;
+
+  // No operator++ because we need error_code.
+  directory_iterator &increment(std::error_code &ec) {
+    ec = directory_iterator_increment(*State);
+    update_error_code_for_current_entry(ec);
+    return *this;
+  }
+
+  const directory_entry &operator*() const { return State->CurrentEntry; }
+  const directory_entry *operator->() const { return &State->CurrentEntry; }
+
+  bool operator==(const directory_iterator &RHS) const {
+    if (State == RHS.State)
+      return true;
+    if (!RHS.State)
+      return State->CurrentEntry == directory_entry();
+    if (!State)
+      return RHS.State->CurrentEntry == directory_entry();
+    return State->CurrentEntry == RHS.State->CurrentEntry;
+  }
+
+  bool operator!=(const directory_iterator &RHS) const {
+    return !(*this == RHS);
+  }
+  // Other members as required by
+  // C++ Std, 24.1.1 Input iterators [input.iterators]
+
+private:
+  // Checks if current entry is valid and populates error code. For example,
+  // current entry may not exist due to broken symbol links.
+  void update_error_code_for_current_entry(std::error_code &ec) {
+    // Bail out if error has already occured earlier to avoid overwriting it.
+    if (ec)
+      return;
+
+    // Empty directory entry is used to mark the end of an interation, it's not
+    // an error.
+    if (State->CurrentEntry == directory_entry())
+      return;
+
+    ErrorOr<basic_file_status> status = State->CurrentEntry.status();
+    if (!status)
+      ec = status.getError();
+  }
+};
+
+namespace detail {
+
+  /// Keeps state for the recursive_directory_iterator.
+  struct RecDirIterState {
+    std::stack<directory_iterator, std::vector<directory_iterator>> Stack;
+    uint16_t Level = 0;
+    bool HasNoPushRequest = false;
+  };
+
+} // end namespace detail
+
+/// recursive_directory_iterator - Same as directory_iterator except for it
+/// recurses down into child directories.
+class recursive_directory_iterator {
+  std::shared_ptr<detail::RecDirIterState> State;
+  bool Follow;
+
+public:
+  recursive_directory_iterator() = default;
+  explicit recursive_directory_iterator(const Twine &path, std::error_code &ec,
+                                        bool follow_symlinks = true)
+      : State(std::make_shared<detail::RecDirIterState>()),
+        Follow(follow_symlinks) {
+    State->Stack.push(directory_iterator(path, ec, Follow));
+    if (State->Stack.top() == directory_iterator())
+      State.reset();
+  }
+
+  // No operator++ because we need error_code.
+  recursive_directory_iterator &increment(std::error_code &ec) {
+    const directory_iterator end_itr = {};
+
+    if (State->HasNoPushRequest)
+      State->HasNoPushRequest = false;
+    else {
+      ErrorOr<basic_file_status> status = State->Stack.top()->status();
+      if (status && is_directory(*status)) {
+        State->Stack.push(directory_iterator(*State->Stack.top(), ec, Follow));
+        if (State->Stack.top() != end_itr) {
+          ++State->Level;
+          return *this;
+        }
+        State->Stack.pop();
+      }
+    }
+
+    while (!State->Stack.empty()
+           && State->Stack.top().increment(ec) == end_itr) {
+      State->Stack.pop();
+      --State->Level;
+    }
+
+    // Check if we are done. If so, create an end iterator.
+    if (State->Stack.empty())
+      State.reset();
+
+    return *this;
+  }
+
+  const directory_entry &operator*() const { return *State->Stack.top(); }
+  const directory_entry *operator->() const { return &*State->Stack.top(); }
+
+  // observers
+  /// Gets the current level. Starting path is at level 0.
+  int level() const { return State->Level; }
+
+  /// Returns true if no_push has been called for this directory_entry.
+  bool no_push_request() const { return State->HasNoPushRequest; }
+
+  // modifiers
+  /// Goes up one level if Level > 0.
+  void pop() {
+    assert(State && "Cannot pop an end iterator!");
+    assert(State->Level > 0 && "Cannot pop an iterator with level < 1");
+
+    const directory_iterator end_itr = {};
+    std::error_code ec;
+    do {
+      if (ec) {
+        //report_fatal_error("Error incrementing directory iterator.");
+        while (!State->Stack.empty()) State->Stack.pop();
+        break;
+      }
+      State->Stack.pop();
+      --State->Level;
+    } while (!State->Stack.empty()
+             && State->Stack.top().increment(ec) == end_itr);
+
+    // Check if we are done. If so, create an end iterator.
+    if (State->Stack.empty())
+      State.reset();
+  }
+
+  /// Does not go down into the current directory_entry.
+  void no_push() { State->HasNoPushRequest = true; }
+
+  bool operator==(const recursive_directory_iterator &RHS) const {
+    return State == RHS.State;
+  }
+
+  bool operator!=(const recursive_directory_iterator &RHS) const {
+    return !(*this == RHS);
+  }
+  // Other members as required by
+  // C++ Std, 24.1.1 Input iterators [input.iterators]
+};
+
+/// @}
+
+} // end namespace fs
+} // end namespace sys
+} // end namespace wpi
+
+#endif // LLVM_SUPPORT_FILESYSTEM_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Format.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Format.h
new file mode 100644
index 0000000..34dd8d8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Format.h
@@ -0,0 +1,264 @@
+//===- Format.h - Efficient printf-style formatting for streams -*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the format() function, which can be used with other
+// LLVM subsystems to provide printf-style formatting.  This gives all the power
+// and risk of printf.  This can be used like this (with raw_ostreams as an
+// example):
+//
+//    OS << "mynumber: " << format("%4.5f", 1234.412) << '\n';
+//
+// Or if you prefer:
+//
+//  OS << format("mynumber: %4.5f\n", 1234.412);
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_FORMAT_H
+#define WPIUTIL_WPI_FORMAT_H
+
+#include "wpi/ArrayRef.h"
+#include "wpi/STLExtras.h"
+#include "wpi/StringRef.h"
+#include <cassert>
+#include <cstdint>
+#include <cstdio>
+#include <tuple>
+
+namespace wpi {
+
+/// This is a helper class used for handling formatted output.  It is the
+/// abstract base class of a templated derived class.
+class format_object_base {
+protected:
+  const char *Fmt;
+  ~format_object_base() = default; // Disallow polymorphic deletion.
+  format_object_base(const format_object_base &) = default;
+  virtual void home(); // Out of line virtual method.
+
+  /// Call snprintf() for this object, on the given buffer and size.
+  virtual int snprint(char *Buffer, unsigned BufferSize) const = 0;
+
+public:
+  format_object_base(const char *fmt) : Fmt(fmt) {}
+
+  /// Format the object into the specified buffer.  On success, this returns
+  /// the length of the formatted string.  If the buffer is too small, this
+  /// returns a length to retry with, which will be larger than BufferSize.
+  unsigned print(char *Buffer, unsigned BufferSize) const {
+    assert(BufferSize && "Invalid buffer size!");
+
+    // Print the string, leaving room for the terminating null.
+    int N = snprint(Buffer, BufferSize);
+
+    // VC++ and old GlibC return negative on overflow, just double the size.
+    if (N < 0)
+      return BufferSize * 2;
+
+    // Other implementations yield number of bytes needed, not including the
+    // final '\0'.
+    if (unsigned(N) >= BufferSize)
+      return N + 1;
+
+    // Otherwise N is the length of output (not including the final '\0').
+    return N;
+  }
+};
+
+/// These are templated helper classes used by the format function that
+/// capture the object to be formatted and the format string. When actually
+/// printed, this synthesizes the string into a temporary buffer provided and
+/// returns whether or not it is big enough.
+
+// Helper to validate that format() parameters are scalars or pointers.
+template <typename... Args> struct validate_format_parameters;
+template <typename Arg, typename... Args>
+struct validate_format_parameters<Arg, Args...> {
+  static_assert(std::is_scalar<Arg>::value,
+                "format can't be used with non fundamental / non pointer type");
+  validate_format_parameters() { validate_format_parameters<Args...>(); }
+};
+template <> struct validate_format_parameters<> {};
+
+template <typename... Ts>
+class format_object final : public format_object_base {
+  std::tuple<Ts...> Vals;
+
+  template <std::size_t... Is>
+  int snprint_tuple(char *Buffer, unsigned BufferSize,
+                    index_sequence<Is...>) const {
+#ifdef _MSC_VER
+    return _snprintf(Buffer, BufferSize, Fmt, std::get<Is>(Vals)...);
+#else
+#ifdef __GNUC__
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wformat-nonliteral"
+#endif
+    return snprintf(Buffer, BufferSize, Fmt, std::get<Is>(Vals)...);
+#ifdef __GNUC__
+#pragma GCC diagnostic pop
+#endif
+#endif
+  }
+
+public:
+  format_object(const char *fmt, const Ts &... vals)
+      : format_object_base(fmt), Vals(vals...) {
+    validate_format_parameters<Ts...>();
+  }
+
+  int snprint(char *Buffer, unsigned BufferSize) const override {
+    return snprint_tuple(Buffer, BufferSize, index_sequence_for<Ts...>());
+  }
+};
+
+/// These are helper functions used to produce formatted output.  They use
+/// template type deduction to construct the appropriate instance of the
+/// format_object class to simplify their construction.
+///
+/// This is typically used like:
+/// \code
+///   OS << format("%0.4f", myfloat) << '\n';
+/// \endcode
+
+template <typename... Ts>
+inline format_object<Ts...> format(const char *Fmt, const Ts &... Vals) {
+  return format_object<Ts...>(Fmt, Vals...);
+}
+
+/// This is a helper class for left_justify, right_justify, and center_justify.
+class FormattedString {
+public:
+  enum Justification { JustifyNone, JustifyLeft, JustifyRight, JustifyCenter };
+  FormattedString(StringRef S, unsigned W, Justification J)
+      : Str(S), Width(W), Justify(J) {}
+
+private:
+  StringRef Str;
+  unsigned Width;
+  Justification Justify;
+  friend class raw_ostream;
+};
+
+/// left_justify - append spaces after string so total output is
+/// \p Width characters.  If \p Str is larger that \p Width, full string
+/// is written with no padding.
+inline FormattedString left_justify(StringRef Str, unsigned Width) {
+  return FormattedString(Str, Width, FormattedString::JustifyLeft);
+}
+
+/// right_justify - add spaces before string so total output is
+/// \p Width characters.  If \p Str is larger that \p Width, full string
+/// is written with no padding.
+inline FormattedString right_justify(StringRef Str, unsigned Width) {
+  return FormattedString(Str, Width, FormattedString::JustifyRight);
+}
+
+/// center_justify - add spaces before and after string so total output is
+/// \p Width characters.  If \p Str is larger that \p Width, full string
+/// is written with no padding.
+inline FormattedString center_justify(StringRef Str, unsigned Width) {
+  return FormattedString(Str, Width, FormattedString::JustifyCenter);
+}
+
+/// This is a helper class used for format_hex() and format_decimal().
+class FormattedNumber {
+  uint64_t HexValue;
+  int64_t DecValue;
+  unsigned Width;
+  bool Hex;
+  bool Upper;
+  bool HexPrefix;
+  friend class raw_ostream;
+
+public:
+  FormattedNumber(uint64_t HV, int64_t DV, unsigned W, bool H, bool U,
+                  bool Prefix)
+      : HexValue(HV), DecValue(DV), Width(W), Hex(H), Upper(U),
+        HexPrefix(Prefix) {}
+};
+
+/// format_hex - Output \p N as a fixed width hexadecimal. If number will not
+/// fit in width, full number is still printed.  Examples:
+///   OS << format_hex(255, 4)              => 0xff
+///   OS << format_hex(255, 4, true)        => 0xFF
+///   OS << format_hex(255, 6)              => 0x00ff
+///   OS << format_hex(255, 2)              => 0xff
+inline FormattedNumber format_hex(uint64_t N, unsigned Width,
+                                  bool Upper = false) {
+  assert(Width <= 18 && "hex width must be <= 18");
+  return FormattedNumber(N, 0, Width, true, Upper, true);
+}
+
+/// format_hex_no_prefix - Output \p N as a fixed width hexadecimal. Does not
+/// prepend '0x' to the outputted string.  If number will not fit in width,
+/// full number is still printed.  Examples:
+///   OS << format_hex_no_prefix(255, 2)              => ff
+///   OS << format_hex_no_prefix(255, 2, true)        => FF
+///   OS << format_hex_no_prefix(255, 4)              => 00ff
+///   OS << format_hex_no_prefix(255, 1)              => ff
+inline FormattedNumber format_hex_no_prefix(uint64_t N, unsigned Width,
+                                            bool Upper = false) {
+  assert(Width <= 16 && "hex width must be <= 16");
+  return FormattedNumber(N, 0, Width, true, Upper, false);
+}
+
+/// format_decimal - Output \p N as a right justified, fixed-width decimal. If
+/// number will not fit in width, full number is still printed.  Examples:
+///   OS << format_decimal(0, 5)     => "    0"
+///   OS << format_decimal(255, 5)   => "  255"
+///   OS << format_decimal(-1, 3)    => " -1"
+///   OS << format_decimal(12345, 3) => "12345"
+inline FormattedNumber format_decimal(int64_t N, unsigned Width) {
+  return FormattedNumber(0, N, Width, false, false, false);
+}
+
+class FormattedBytes {
+  ArrayRef<uint8_t> Bytes;
+
+  // If not nullopt, display offsets for each line relative to starting value.
+  optional<uint64_t> FirstByteOffset;
+  uint32_t IndentLevel;  // Number of characters to indent each line.
+  uint32_t NumPerLine;   // Number of bytes to show per line.
+  uint8_t ByteGroupSize; // How many hex bytes are grouped without spaces
+  bool Upper;            // Show offset and hex bytes as upper case.
+  bool ASCII;            // Show the ASCII bytes for the hex bytes to the right.
+  friend class raw_ostream;
+
+public:
+  FormattedBytes(ArrayRef<uint8_t> B, uint32_t IL, optional<uint64_t> O,
+                 uint32_t NPL, uint8_t BGS, bool U, bool A)
+      : Bytes(B), FirstByteOffset(O), IndentLevel(IL), NumPerLine(NPL),
+        ByteGroupSize(BGS), Upper(U), ASCII(A) {
+
+    if (ByteGroupSize > NumPerLine)
+      ByteGroupSize = NumPerLine;
+  }
+};
+
+inline FormattedBytes
+format_bytes(ArrayRef<uint8_t> Bytes, optional<uint64_t> FirstByteOffset = nullopt,
+             uint32_t NumPerLine = 16, uint8_t ByteGroupSize = 4,
+             uint32_t IndentLevel = 0, bool Upper = false) {
+  return FormattedBytes(Bytes, IndentLevel, FirstByteOffset, NumPerLine,
+                        ByteGroupSize, Upper, false);
+}
+
+inline FormattedBytes
+format_bytes_with_ascii(ArrayRef<uint8_t> Bytes,
+                        optional<uint64_t> FirstByteOffset = nullopt,
+                        uint32_t NumPerLine = 16, uint8_t ByteGroupSize = 4,
+                        uint32_t IndentLevel = 0, bool Upper = false) {
+  return FormattedBytes(Bytes, IndentLevel, FirstByteOffset, NumPerLine,
+                        ByteGroupSize, Upper, true);
+}
+
+} // end namespace wpi
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Hashing.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Hashing.h
new file mode 100644
index 0000000..8ae30d1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Hashing.h
@@ -0,0 +1,659 @@
+//===-- llvm/ADT/Hashing.h - Utilities for hashing --------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements the newly proposed standard C++ interfaces for hashing
+// arbitrary data and building hash functions for user-defined types. This
+// interface was originally proposed in N3333[1] and is currently under review
+// for inclusion in a future TR and/or standard.
+//
+// The primary interfaces provide are comprised of one type and three functions:
+//
+//  -- 'hash_code' class is an opaque type representing the hash code for some
+//     data. It is the intended product of hashing, and can be used to implement
+//     hash tables, checksumming, and other common uses of hashes. It is not an
+//     integer type (although it can be converted to one) because it is risky
+//     to assume much about the internals of a hash_code. In particular, each
+//     execution of the program has a high probability of producing a different
+//     hash_code for a given input. Thus their values are not stable to save or
+//     persist, and should only be used during the execution for the
+//     construction of hashing datastructures.
+//
+//  -- 'hash_value' is a function designed to be overloaded for each
+//     user-defined type which wishes to be used within a hashing context. It
+//     should be overloaded within the user-defined type's namespace and found
+//     via ADL. Overloads for primitive types are provided by this library.
+//
+//  -- 'hash_combine' and 'hash_combine_range' are functions designed to aid
+//      programmers in easily and intuitively combining a set of data into
+//      a single hash_code for their object. They should only logically be used
+//      within the implementation of a 'hash_value' routine or similar context.
+//
+// Note that 'hash_combine_range' contains very special logic for hashing
+// a contiguous array of integers or pointers. This logic is *extremely* fast,
+// on a modern Intel "Gainestown" Xeon (Nehalem uarch) @2.2 GHz, these were
+// benchmarked at over 6.5 GiB/s for large keys, and <20 cycles/hash for keys
+// under 32-bytes.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_HASHING_H
+#define WPIUTIL_WPI_HASHING_H
+
+#include "wpi/type_traits.h"
+#include <algorithm>
+#include <cassert>
+#include <cstdint>
+#include <cstring>
+#include <string>
+#include <utility>
+
+namespace wpi {
+
+/// An opaque object representing a hash code.
+///
+/// This object represents the result of hashing some entity. It is intended to
+/// be used to implement hashtables or other hashing-based data structures.
+/// While it wraps and exposes a numeric value, this value should not be
+/// trusted to be stable or predictable across processes or executions.
+///
+/// In order to obtain the hash_code for an object 'x':
+/// \code
+///   using wpi::hash_value;
+///   wpi::hash_code code = hash_value(x);
+/// \endcode
+class hash_code {
+  size_t value;
+
+public:
+  /// Default construct a hash_code.
+  /// Note that this leaves the value uninitialized.
+  hash_code() = default;
+
+  /// Form a hash code directly from a numerical value.
+  hash_code(size_t value) : value(value) {}
+
+  /// Convert the hash code to its numerical value for use.
+  /*explicit*/ operator size_t() const { return value; }
+
+  friend bool operator==(const hash_code &lhs, const hash_code &rhs) {
+    return lhs.value == rhs.value;
+  }
+  friend bool operator!=(const hash_code &lhs, const hash_code &rhs) {
+    return lhs.value != rhs.value;
+  }
+
+  /// Allow a hash_code to be directly run through hash_value.
+  friend size_t hash_value(const hash_code &code) { return code.value; }
+};
+
+/// Compute a hash_code for any integer value.
+///
+/// Note that this function is intended to compute the same hash_code for
+/// a particular value without regard to the pre-promotion type. This is in
+/// contrast to hash_combine which may produce different hash_codes for
+/// differing argument types even if they would implicit promote to a common
+/// type without changing the value.
+template <typename T>
+typename std::enable_if<is_integral_or_enum<T>::value, hash_code>::type
+hash_value(T value);
+
+/// Compute a hash_code for a pointer's address.
+///
+/// N.B.: This hashes the *address*. Not the value and not the type.
+template <typename T> hash_code hash_value(const T *ptr);
+
+/// Compute a hash_code for a pair of objects.
+template <typename T, typename U>
+hash_code hash_value(const std::pair<T, U> &arg);
+
+/// Compute a hash_code for a standard string.
+template <typename T>
+hash_code hash_value(const std::basic_string<T> &arg);
+
+
+/// Override the execution seed with a fixed value.
+///
+/// This hashing library uses a per-execution seed designed to change on each
+/// run with high probability in order to ensure that the hash codes are not
+/// attackable and to ensure that output which is intended to be stable does
+/// not rely on the particulars of the hash codes produced.
+///
+/// That said, there are use cases where it is important to be able to
+/// reproduce *exactly* a specific behavior. To that end, we provide a function
+/// which will forcibly set the seed to a fixed value. This must be done at the
+/// start of the program, before any hashes are computed. Also, it cannot be
+/// undone. This makes it thread-hostile and very hard to use outside of
+/// immediately on start of a simple program designed for reproducible
+/// behavior.
+void set_fixed_execution_hash_seed(size_t fixed_value);
+
+
+// All of the implementation details of actually computing the various hash
+// code values are held within this namespace. These routines are included in
+// the header file mainly to allow inlining and constant propagation.
+namespace hashing {
+namespace detail {
+
+inline uint64_t fetch64(const char *p) {
+  uint64_t result;
+  memcpy(&result, p, sizeof(result));
+  //if (sys::IsBigEndianHost)
+  //  sys::swapByteOrder(result);
+  return result;
+}
+
+inline uint32_t fetch32(const char *p) {
+  uint32_t result;
+  memcpy(&result, p, sizeof(result));
+  //if (sys::IsBigEndianHost)
+  //  sys::swapByteOrder(result);
+  return result;
+}
+
+/// Some primes between 2^63 and 2^64 for various uses.
+static const uint64_t k0 = 0xc3a5c85c97cb3127ULL;
+static const uint64_t k1 = 0xb492b66fbe98f273ULL;
+static const uint64_t k2 = 0x9ae16a3b2f90404fULL;
+static const uint64_t k3 = 0xc949d7c7509e6557ULL;
+
+/// Bitwise right rotate.
+/// Normally this will compile to a single instruction, especially if the
+/// shift is a manifest constant.
+inline uint64_t rotate(uint64_t val, size_t shift) {
+  // Avoid shifting by 64: doing so yields an undefined result.
+  return shift == 0 ? val : ((val >> shift) | (val << (64 - shift)));
+}
+
+inline uint64_t shift_mix(uint64_t val) {
+  return val ^ (val >> 47);
+}
+
+inline uint64_t hash_16_bytes(uint64_t low, uint64_t high) {
+  // Murmur-inspired hashing.
+  const uint64_t kMul = 0x9ddfea08eb382d69ULL;
+  uint64_t a = (low ^ high) * kMul;
+  a ^= (a >> 47);
+  uint64_t b = (high ^ a) * kMul;
+  b ^= (b >> 47);
+  b *= kMul;
+  return b;
+}
+
+inline uint64_t hash_1to3_bytes(const char *s, size_t len, uint64_t seed) {
+  uint8_t a = s[0];
+  uint8_t b = s[len >> 1];
+  uint8_t c = s[len - 1];
+  uint32_t y = static_cast<uint32_t>(a) + (static_cast<uint32_t>(b) << 8);
+  uint32_t z = len + (static_cast<uint32_t>(c) << 2);
+  return shift_mix(y * k2 ^ z * k3 ^ seed) * k2;
+}
+
+inline uint64_t hash_4to8_bytes(const char *s, size_t len, uint64_t seed) {
+  uint64_t a = fetch32(s);
+  return hash_16_bytes(len + (a << 3), seed ^ fetch32(s + len - 4));
+}
+
+inline uint64_t hash_9to16_bytes(const char *s, size_t len, uint64_t seed) {
+  uint64_t a = fetch64(s);
+  uint64_t b = fetch64(s + len - 8);
+  return hash_16_bytes(seed ^ a, rotate(b + len, len)) ^ b;
+}
+
+inline uint64_t hash_17to32_bytes(const char *s, size_t len, uint64_t seed) {
+  uint64_t a = fetch64(s) * k1;
+  uint64_t b = fetch64(s + 8);
+  uint64_t c = fetch64(s + len - 8) * k2;
+  uint64_t d = fetch64(s + len - 16) * k0;
+  return hash_16_bytes(rotate(a - b, 43) + rotate(c ^ seed, 30) + d,
+                       a + rotate(b ^ k3, 20) - c + len + seed);
+}
+
+inline uint64_t hash_33to64_bytes(const char *s, size_t len, uint64_t seed) {
+  uint64_t z = fetch64(s + 24);
+  uint64_t a = fetch64(s) + (len + fetch64(s + len - 16)) * k0;
+  uint64_t b = rotate(a + z, 52);
+  uint64_t c = rotate(a, 37);
+  a += fetch64(s + 8);
+  c += rotate(a, 7);
+  a += fetch64(s + 16);
+  uint64_t vf = a + z;
+  uint64_t vs = b + rotate(a, 31) + c;
+  a = fetch64(s + 16) + fetch64(s + len - 32);
+  z = fetch64(s + len - 8);
+  b = rotate(a + z, 52);
+  c = rotate(a, 37);
+  a += fetch64(s + len - 24);
+  c += rotate(a, 7);
+  a += fetch64(s + len - 16);
+  uint64_t wf = a + z;
+  uint64_t ws = b + rotate(a, 31) + c;
+  uint64_t r = shift_mix((vf + ws) * k2 + (wf + vs) * k0);
+  return shift_mix((seed ^ (r * k0)) + vs) * k2;
+}
+
+inline uint64_t hash_short(const char *s, size_t length, uint64_t seed) {
+  if (length >= 4 && length <= 8)
+    return hash_4to8_bytes(s, length, seed);
+  if (length > 8 && length <= 16)
+    return hash_9to16_bytes(s, length, seed);
+  if (length > 16 && length <= 32)
+    return hash_17to32_bytes(s, length, seed);
+  if (length > 32)
+    return hash_33to64_bytes(s, length, seed);
+  if (length != 0)
+    return hash_1to3_bytes(s, length, seed);
+
+  return k2 ^ seed;
+}
+
+/// The intermediate state used during hashing.
+/// Currently, the algorithm for computing hash codes is based on CityHash and
+/// keeps 56 bytes of arbitrary state.
+struct hash_state {
+  uint64_t h0, h1, h2, h3, h4, h5, h6;
+
+  /// Create a new hash_state structure and initialize it based on the
+  /// seed and the first 64-byte chunk.
+  /// This effectively performs the initial mix.
+  static hash_state create(const char *s, uint64_t seed) {
+    hash_state state = {
+      0, seed, hash_16_bytes(seed, k1), rotate(seed ^ k1, 49),
+      seed * k1, shift_mix(seed), 0 };
+    state.h6 = hash_16_bytes(state.h4, state.h5);
+    state.mix(s);
+    return state;
+  }
+
+  /// Mix 32-bytes from the input sequence into the 16-bytes of 'a'
+  /// and 'b', including whatever is already in 'a' and 'b'.
+  static void mix_32_bytes(const char *s, uint64_t &a, uint64_t &b) {
+    a += fetch64(s);
+    uint64_t c = fetch64(s + 24);
+    b = rotate(b + a + c, 21);
+    uint64_t d = a;
+    a += fetch64(s + 8) + fetch64(s + 16);
+    b += rotate(a, 44) + d;
+    a += c;
+  }
+
+  /// Mix in a 64-byte buffer of data.
+  /// We mix all 64 bytes even when the chunk length is smaller, but we
+  /// record the actual length.
+  void mix(const char *s) {
+    h0 = rotate(h0 + h1 + h3 + fetch64(s + 8), 37) * k1;
+    h1 = rotate(h1 + h4 + fetch64(s + 48), 42) * k1;
+    h0 ^= h6;
+    h1 += h3 + fetch64(s + 40);
+    h2 = rotate(h2 + h5, 33) * k1;
+    h3 = h4 * k1;
+    h4 = h0 + h5;
+    mix_32_bytes(s, h3, h4);
+    h5 = h2 + h6;
+    h6 = h1 + fetch64(s + 16);
+    mix_32_bytes(s + 32, h5, h6);
+    std::swap(h2, h0);
+  }
+
+  /// Compute the final 64-bit hash code value based on the current
+  /// state and the length of bytes hashed.
+  uint64_t finalize(size_t length) {
+    return hash_16_bytes(hash_16_bytes(h3, h5) + shift_mix(h1) * k1 + h2,
+                         hash_16_bytes(h4, h6) + shift_mix(length) * k1 + h0);
+  }
+};
+
+
+/// A global, fixed seed-override variable.
+///
+/// This variable can be set using the \see wpi::set_fixed_execution_seed
+/// function. See that function for details. Do not, under any circumstances,
+/// set or read this variable.
+extern size_t fixed_seed_override;
+
+inline size_t get_execution_seed() {
+  // FIXME: This needs to be a per-execution seed. This is just a placeholder
+  // implementation. Switching to a per-execution seed is likely to flush out
+  // instability bugs and so will happen as its own commit.
+  //
+  // However, if there is a fixed seed override set the first time this is
+  // called, return that instead of the per-execution seed.
+  const uint64_t seed_prime = 0xff51afd7ed558ccdULL;
+  static size_t seed = fixed_seed_override ? fixed_seed_override
+                                           : (size_t)seed_prime;
+  return seed;
+}
+
+
+/// Trait to indicate whether a type's bits can be hashed directly.
+///
+/// A type trait which is true if we want to combine values for hashing by
+/// reading the underlying data. It is false if values of this type must
+/// first be passed to hash_value, and the resulting hash_codes combined.
+//
+// FIXME: We want to replace is_integral_or_enum and is_pointer here with
+// a predicate which asserts that comparing the underlying storage of two
+// values of the type for equality is equivalent to comparing the two values
+// for equality. For all the platforms we care about, this holds for integers
+// and pointers, but there are platforms where it doesn't and we would like to
+// support user-defined types which happen to satisfy this property.
+template <typename T> struct is_hashable_data
+  : std::integral_constant<bool, ((is_integral_or_enum<T>::value ||
+                                   std::is_pointer<T>::value) &&
+                                  64 % sizeof(T) == 0)> {};
+
+// Special case std::pair to detect when both types are viable and when there
+// is no alignment-derived padding in the pair. This is a bit of a lie because
+// std::pair isn't truly POD, but it's close enough in all reasonable
+// implementations for our use case of hashing the underlying data.
+template <typename T, typename U> struct is_hashable_data<std::pair<T, U> >
+  : std::integral_constant<bool, (is_hashable_data<T>::value &&
+                                  is_hashable_data<U>::value &&
+                                  (sizeof(T) + sizeof(U)) ==
+                                   sizeof(std::pair<T, U>))> {};
+
+/// Helper to get the hashable data representation for a type.
+/// This variant is enabled when the type itself can be used.
+template <typename T>
+typename std::enable_if<is_hashable_data<T>::value, T>::type
+get_hashable_data(const T &value) {
+  return value;
+}
+/// Helper to get the hashable data representation for a type.
+/// This variant is enabled when we must first call hash_value and use the
+/// result as our data.
+template <typename T>
+typename std::enable_if<!is_hashable_data<T>::value, size_t>::type
+get_hashable_data(const T &value) {
+  using ::wpi::hash_value;
+  return hash_value(value);
+}
+
+/// Helper to store data from a value into a buffer and advance the
+/// pointer into that buffer.
+///
+/// This routine first checks whether there is enough space in the provided
+/// buffer, and if not immediately returns false. If there is space, it
+/// copies the underlying bytes of value into the buffer, advances the
+/// buffer_ptr past the copied bytes, and returns true.
+template <typename T>
+bool store_and_advance(char *&buffer_ptr, char *buffer_end, const T& value,
+                       size_t offset = 0) {
+  size_t store_size = sizeof(value) - offset;
+  if (buffer_ptr + store_size > buffer_end)
+    return false;
+  const char *value_data = reinterpret_cast<const char *>(&value);
+  memcpy(buffer_ptr, value_data + offset, store_size);
+  buffer_ptr += store_size;
+  return true;
+}
+
+/// Implement the combining of integral values into a hash_code.
+///
+/// This overload is selected when the value type of the iterator is
+/// integral. Rather than computing a hash_code for each object and then
+/// combining them, this (as an optimization) directly combines the integers.
+template <typename InputIteratorT>
+hash_code hash_combine_range_impl(InputIteratorT first, InputIteratorT last) {
+  const size_t seed = get_execution_seed();
+  char buffer[64], *buffer_ptr = buffer;
+  char *const buffer_end = std::end(buffer);
+  while (first != last && store_and_advance(buffer_ptr, buffer_end,
+                                            get_hashable_data(*first)))
+    ++first;
+  if (first == last)
+    return hash_short(buffer, buffer_ptr - buffer, seed);
+  assert(buffer_ptr == buffer_end);
+
+  hash_state state = state.create(buffer, seed);
+  size_t length = 64;
+  while (first != last) {
+    // Fill up the buffer. We don't clear it, which re-mixes the last round
+    // when only a partial 64-byte chunk is left.
+    buffer_ptr = buffer;
+    while (first != last && store_and_advance(buffer_ptr, buffer_end,
+                                              get_hashable_data(*first)))
+      ++first;
+
+    // Rotate the buffer if we did a partial fill in order to simulate doing
+    // a mix of the last 64-bytes. That is how the algorithm works when we
+    // have a contiguous byte sequence, and we want to emulate that here.
+    std::rotate(buffer, buffer_ptr, buffer_end);
+
+    // Mix this chunk into the current state.
+    state.mix(buffer);
+    length += buffer_ptr - buffer;
+  };
+
+  return state.finalize(length);
+}
+
+/// Implement the combining of integral values into a hash_code.
+///
+/// This overload is selected when the value type of the iterator is integral
+/// and when the input iterator is actually a pointer. Rather than computing
+/// a hash_code for each object and then combining them, this (as an
+/// optimization) directly combines the integers. Also, because the integers
+/// are stored in contiguous memory, this routine avoids copying each value
+/// and directly reads from the underlying memory.
+template <typename ValueT>
+typename std::enable_if<is_hashable_data<ValueT>::value, hash_code>::type
+hash_combine_range_impl(ValueT *first, ValueT *last) {
+  const size_t seed = get_execution_seed();
+  const char *s_begin = reinterpret_cast<const char *>(first);
+  const char *s_end = reinterpret_cast<const char *>(last);
+  const size_t length = std::distance(s_begin, s_end);
+  if (length <= 64)
+    return hash_short(s_begin, length, seed);
+
+  const char *s_aligned_end = s_begin + (length & ~63);
+  hash_state state = state.create(s_begin, seed);
+  s_begin += 64;
+  while (s_begin != s_aligned_end) {
+    state.mix(s_begin);
+    s_begin += 64;
+  }
+  if (length & 63)
+    state.mix(s_end - 64);
+
+  return state.finalize(length);
+}
+
+} // namespace detail
+} // namespace hashing
+
+
+/// Compute a hash_code for a sequence of values.
+///
+/// This hashes a sequence of values. It produces the same hash_code as
+/// 'hash_combine(a, b, c, ...)', but can run over arbitrary sized sequences
+/// and is significantly faster given pointers and types which can be hashed as
+/// a sequence of bytes.
+template <typename InputIteratorT>
+hash_code hash_combine_range(InputIteratorT first, InputIteratorT last) {
+  return ::wpi::hashing::detail::hash_combine_range_impl(first, last);
+}
+
+
+// Implementation details for hash_combine.
+namespace hashing {
+namespace detail {
+
+/// Helper class to manage the recursive combining of hash_combine
+/// arguments.
+///
+/// This class exists to manage the state and various calls involved in the
+/// recursive combining of arguments used in hash_combine. It is particularly
+/// useful at minimizing the code in the recursive calls to ease the pain
+/// caused by a lack of variadic functions.
+struct hash_combine_recursive_helper {
+  char buffer[64];
+  hash_state state;
+  const size_t seed;
+
+public:
+  /// Construct a recursive hash combining helper.
+  ///
+  /// This sets up the state for a recursive hash combine, including getting
+  /// the seed and buffer setup.
+  hash_combine_recursive_helper()
+    : seed(get_execution_seed()) {}
+
+  /// Combine one chunk of data into the current in-flight hash.
+  ///
+  /// This merges one chunk of data into the hash. First it tries to buffer
+  /// the data. If the buffer is full, it hashes the buffer into its
+  /// hash_state, empties it, and then merges the new chunk in. This also
+  /// handles cases where the data straddles the end of the buffer.
+  template <typename T>
+  char *combine_data(size_t &length, char *buffer_ptr, char *buffer_end, T data) {
+    if (!store_and_advance(buffer_ptr, buffer_end, data)) {
+      // Check for skew which prevents the buffer from being packed, and do
+      // a partial store into the buffer to fill it. This is only a concern
+      // with the variadic combine because that formation can have varying
+      // argument types.
+      size_t partial_store_size = buffer_end - buffer_ptr;
+      memcpy(buffer_ptr, &data, partial_store_size);
+
+      // If the store fails, our buffer is full and ready to hash. We have to
+      // either initialize the hash state (on the first full buffer) or mix
+      // this buffer into the existing hash state. Length tracks the *hashed*
+      // length, not the buffered length.
+      if (length == 0) {
+        state = state.create(buffer, seed);
+        length = 64;
+      } else {
+        // Mix this chunk into the current state and bump length up by 64.
+        state.mix(buffer);
+        length += 64;
+      }
+      // Reset the buffer_ptr to the head of the buffer for the next chunk of
+      // data.
+      buffer_ptr = buffer;
+
+      // Try again to store into the buffer -- this cannot fail as we only
+      // store types smaller than the buffer.
+      if (!store_and_advance(buffer_ptr, buffer_end, data,
+                             partial_store_size))
+        abort();
+    }
+    return buffer_ptr;
+  }
+
+  /// Recursive, variadic combining method.
+  ///
+  /// This function recurses through each argument, combining that argument
+  /// into a single hash.
+  template <typename T, typename ...Ts>
+  hash_code combine(size_t length, char *buffer_ptr, char *buffer_end,
+                    const T &arg, const Ts &...args) {
+    buffer_ptr = combine_data(length, buffer_ptr, buffer_end, get_hashable_data(arg));
+
+    // Recurse to the next argument.
+    return combine(length, buffer_ptr, buffer_end, args...);
+  }
+
+  /// Base case for recursive, variadic combining.
+  ///
+  /// The base case when combining arguments recursively is reached when all
+  /// arguments have been handled. It flushes the remaining buffer and
+  /// constructs a hash_code.
+  hash_code combine(size_t length, char *buffer_ptr, char *buffer_end) {
+    // Check whether the entire set of values fit in the buffer. If so, we'll
+    // use the optimized short hashing routine and skip state entirely.
+    if (length == 0)
+      return hash_short(buffer, buffer_ptr - buffer, seed);
+
+    // Mix the final buffer, rotating it if we did a partial fill in order to
+    // simulate doing a mix of the last 64-bytes. That is how the algorithm
+    // works when we have a contiguous byte sequence, and we want to emulate
+    // that here.
+    std::rotate(buffer, buffer_ptr, buffer_end);
+
+    // Mix this chunk into the current state.
+    state.mix(buffer);
+    length += buffer_ptr - buffer;
+
+    return state.finalize(length);
+  }
+};
+
+} // namespace detail
+} // namespace hashing
+
+/// Combine values into a single hash_code.
+///
+/// This routine accepts a varying number of arguments of any type. It will
+/// attempt to combine them into a single hash_code. For user-defined types it
+/// attempts to call a \see hash_value overload (via ADL) for the type. For
+/// integer and pointer types it directly combines their data into the
+/// resulting hash_code.
+///
+/// The result is suitable for returning from a user's hash_value
+/// *implementation* for their user-defined type. Consumers of a type should
+/// *not* call this routine, they should instead call 'hash_value'.
+template <typename ...Ts> hash_code hash_combine(const Ts &...args) {
+  // Recursively hash each argument using a helper class.
+  ::wpi::hashing::detail::hash_combine_recursive_helper helper;
+  return helper.combine(0, helper.buffer, helper.buffer + 64, args...);
+}
+
+// Implementation details for implementations of hash_value overloads provided
+// here.
+namespace hashing {
+namespace detail {
+
+/// Helper to hash the value of a single integer.
+///
+/// Overloads for smaller integer types are not provided to ensure consistent
+/// behavior in the presence of integral promotions. Essentially,
+/// "hash_value('4')" and "hash_value('0' + 4)" should be the same.
+inline hash_code hash_integer_value(uint64_t value) {
+  // Similar to hash_4to8_bytes but using a seed instead of length.
+  const uint64_t seed = get_execution_seed();
+  const char *s = reinterpret_cast<const char *>(&value);
+  const uint64_t a = fetch32(s);
+  return hash_16_bytes(seed + (a << 3), fetch32(s + 4));
+}
+
+} // namespace detail
+} // namespace hashing
+
+// Declared and documented above, but defined here so that any of the hashing
+// infrastructure is available.
+template <typename T>
+typename std::enable_if<is_integral_or_enum<T>::value, hash_code>::type
+hash_value(T value) {
+  return ::wpi::hashing::detail::hash_integer_value(
+      static_cast<uint64_t>(value));
+}
+
+// Declared and documented above, but defined here so that any of the hashing
+// infrastructure is available.
+template <typename T> hash_code hash_value(const T *ptr) {
+  return ::wpi::hashing::detail::hash_integer_value(
+    reinterpret_cast<uintptr_t>(ptr));
+}
+
+// Declared and documented above, but defined here so that any of the hashing
+// infrastructure is available.
+template <typename T, typename U>
+hash_code hash_value(const std::pair<T, U> &arg) {
+  return hash_combine(arg.first, arg.second);
+}
+
+// Declared and documented above, but defined here so that any of the hashing
+// infrastructure is available.
+template <typename T>
+hash_code hash_value(const std::basic_string<T> &arg) {
+  return hash_combine_range(arg.begin(), arg.end());
+}
+
+} // namespace wpi
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpParser.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpParser.h
new file mode 100644
index 0000000..b8b39de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpParser.h
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_HTTPPARSER_H_
+#define WPIUTIL_WPI_HTTPPARSER_H_
+
+#include <stdint.h>
+
+#include "wpi/Signal.h"
+#include "wpi/SmallString.h"
+#include "wpi/StringRef.h"
+#include "wpi/http_parser.h"
+
+namespace wpi {
+
+/**
+ * HTTP protocol parser.  Performs incremental parsing with callbacks for each
+ * part of the HTTP protocol.  As this is incremental, it's suitable for use
+ * with event based frameworks that provide arbitrary chunks of data.
+ */
+class HttpParser {
+ public:
+  enum Type {
+    kRequest = HTTP_REQUEST,
+    kResponse = HTTP_RESPONSE,
+    kBoth = HTTP_BOTH
+  };
+
+  /**
+   * Returns the library version. Bits 16-23 contain the major version number,
+   * bits 8-15 the minor version number and bits 0-7 the patch level.
+   */
+  static uint32_t GetParserVersion();
+
+  /**
+   * Constructor.
+   * @param type Type of parser (request or response or both)
+   */
+  explicit HttpParser(Type type);
+
+  /**
+   * Reset the parser to initial state.
+   * This allows reusing the same parser object from request to request.
+   * @param type Type of parser (request or response or both)
+   */
+  void Reset(Type type);
+
+  /**
+   * Set the maximum accepted length for URLs, field names, and field values.
+   * The default is 1024.
+   * @param len maximum length
+   */
+  void SetMaxLength(size_t len) { m_maxLength = len; }
+
+  /**
+   * Executes the parser.  An empty input is treated as EOF.
+   * @param in input data
+   * @return Trailing input data after the parse.
+   */
+  StringRef Execute(StringRef in) {
+    return in.drop_front(
+        http_parser_execute(&m_parser, &m_settings, in.data(), in.size()));
+  }
+
+  /**
+   * Get HTTP major version.
+   */
+  unsigned int GetMajor() const { return m_parser.http_major; }
+
+  /**
+   * Get HTTP minor version.
+   */
+  unsigned int GetMinor() const { return m_parser.http_minor; }
+
+  /**
+   * Get HTTP status code.  Valid only on responses.  Valid in and after
+   * the OnStatus() callback has been called.
+   */
+  unsigned int GetStatusCode() const { return m_parser.status_code; }
+
+  /**
+   * Get HTTP method.  Valid only on requests.
+   */
+  http_method GetMethod() const {
+    return static_cast<http_method>(m_parser.method);
+  }
+
+  /**
+   * Determine if an error occurred.
+   * @return False if no error.
+   */
+  bool HasError() const { return m_parser.http_errno != HPE_OK; }
+
+  /**
+   * Get error number.
+   */
+  http_errno GetError() const {
+    return static_cast<http_errno>(m_parser.http_errno);
+  }
+
+  /**
+   * Abort the parse.  Call this from a callback handler to indicate an error.
+   * This will result in GetError() returning one of the callback-related
+   * errors (e.g. HPE_CB_message_begin).
+   */
+  void Abort() { m_aborted = true; }
+
+  /**
+   * Determine if an upgrade header was present and the parser has exited
+   * because of that.  Should be checked when Execute() returns in addition to
+   * checking GetError().
+   * @return True if upgrade header, false otherwise.
+   */
+  bool IsUpgrade() const { return m_parser.upgrade; }
+
+  /**
+   * If this returns false in the headersComplete or messageComplete
+   * callback, then this should be the last message on the connection.
+   * If you are the server, respond with the "Connection: close" header.
+   * If you are the client, close the connection.
+   */
+  bool ShouldKeepAlive() const { return http_should_keep_alive(&m_parser); }
+
+  /**
+   * Pause the parser.
+   * @param paused True to pause, false to unpause.
+   */
+  void Pause(bool paused) { http_parser_pause(&m_parser, paused); }
+
+  /**
+   * Checks if this is the final chunk of the body.
+   */
+  bool IsBodyFinal() const { return http_body_is_final(&m_parser); }
+
+  /**
+   * Get URL.  Valid in and after the url callback has been called.
+   */
+  StringRef GetUrl() const { return m_urlBuf; }
+
+  /**
+   * Message begin callback.
+   */
+  sig::Signal<> messageBegin;
+
+  /**
+   * URL callback.
+   *
+   * The parameter to the callback is the complete URL string.
+   */
+  sig::Signal<StringRef> url;
+
+  /**
+   * Status callback.
+   *
+   * The parameter to the callback is the complete status string.
+   * GetStatusCode() can be used to get the numeric status code.
+   */
+  sig::Signal<StringRef> status;
+
+  /**
+   * Header field callback.
+   *
+   * The parameters to the callback are the field name and field value.
+   */
+  sig::Signal<StringRef, StringRef> header;
+
+  /**
+   * Headers complete callback.
+   *
+   * The parameter to the callback is whether the connection should be kept
+   * alive.  If this is false, then this should be the last message on the
+   * connection.  If you are the server, respond with the "Connection: close"
+   * header.  If you are the client, close the connection.
+   */
+  sig::Signal<bool> headersComplete;
+
+  /**
+   * Body data callback.
+   *
+   * The parameters to the callback is the data chunk and whether this is the
+   * final chunk of data in the message.  Note this callback will be called
+   * multiple times arbitrarily (e.g. it's possible that it may be called with
+   * just a few characters at a time).
+   */
+  sig::Signal<StringRef, bool> body;
+
+  /**
+   * Headers complete callback.
+   *
+   * The parameter to the callback is whether the connection should be kept
+   * alive.  If this is false, then this should be the last message on the
+   * connection.  If you are the server, respond with the "Connection: close"
+   * header.  If you are the client, close the connection.
+   */
+  sig::Signal<bool> messageComplete;
+
+  /**
+   * Chunk header callback.
+   *
+   * The parameter to the callback is the chunk size.
+   */
+  sig::Signal<uint64_t> chunkHeader;
+
+  /**
+   * Chunk complete callback.
+   */
+  sig::Signal<> chunkComplete;
+
+ private:
+  http_parser m_parser;
+  http_parser_settings m_settings;
+
+  size_t m_maxLength = 1024;
+  enum { kStart, kUrl, kStatus, kField, kValue } m_state = kStart;
+  SmallString<128> m_urlBuf;
+  SmallString<32> m_fieldBuf;
+  SmallString<128> m_valueBuf;
+
+  bool m_aborted = false;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_HTTPPARSER_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpServerConnection.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpServerConnection.h
new file mode 100644
index 0000000..c49c2a2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpServerConnection.h
@@ -0,0 +1,153 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_HTTPSERVERCONNECTION_H_
+#define WPIUTIL_WPI_HTTPSERVERCONNECTION_H_
+
+#include <memory>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/HttpParser.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+#include "wpi/uv/Stream.h"
+
+namespace wpi {
+
+class raw_ostream;
+
+class HttpServerConnection {
+ public:
+  explicit HttpServerConnection(std::shared_ptr<uv::Stream> stream);
+  virtual ~HttpServerConnection() = default;
+
+ protected:
+  /**
+   * Process an incoming HTTP request.  This is called after the incoming
+   * message completes (e.g. from the HttpParser::messageComplete callback).
+   *
+   * The implementation should read request details from m_request and call the
+   * appropriate Send() functions to send a response back to the client.
+   */
+  virtual void ProcessRequest() = 0;
+
+  /**
+   * Build common response headers.
+   *
+   * Called by SendHeader() to send headers common to every response.
+   * Each line must be terminated with \r\n.
+   *
+   * The default implementation sends the following:
+   * "Server: WebServer/1.0\r\n"
+   * "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, "
+   * "post-check=0, max-age=0\r\n"
+   * "Pragma: no-cache\r\n"
+   * "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n"
+   *
+   * These parameters should ensure the browser does not cache the response.
+   * A browser should connect for each file and not serve files from its cache.
+   *
+   * @param os response stream
+   */
+  virtual void BuildCommonHeaders(raw_ostream& os);
+
+  /**
+   * Build HTTP response header, along with other header information like
+   * mimetype.  Calls BuildCommonHeaders().
+   *
+   * @param os response stream
+   * @param code HTTP response code (e.g. 200)
+   * @param codeText HTTP response code text (e.g. "OK")
+   * @param contentType MIME content type (e.g. "text/plain")
+   * @param contentLength Length of content.  If 0 is provided, m_keepAlive will
+   *                      be set to false.
+   * @param extra Extra HTTP headers to send, including final "\r\n"
+   */
+  void BuildHeader(raw_ostream& os, int code, const Twine& codeText,
+                   const Twine& contentType, uint64_t contentLength,
+                   const Twine& extra = Twine{});
+
+  /**
+   * Send data to client.
+   *
+   * This is a convenience wrapper around m_stream.Write() to provide
+   * auto-close functionality.
+   *
+   * @param bufs Buffers to write.  Deallocate() will be called on each
+   *             buffer after the write completes.  If different behavior
+   *             is desired, call m_stream.Write() directly instead.
+   * @param closeAfter close the connection after the write completes
+   */
+  void SendData(ArrayRef<uv::Buffer> bufs, bool closeAfter = false);
+
+  /**
+   * Send HTTP response, along with other header information like mimetype.
+   * Calls BuildHeader().
+   *
+   * @param code HTTP response code (e.g. 200)
+   * @param codeText HTTP response code text (e.g. "OK")
+   * @param contentType MIME content type (e.g. "text/plain")
+   * @param content Response message content
+   * @param extraHeader Extra HTTP headers to send, including final "\r\n"
+   */
+  void SendResponse(int code, const Twine& codeText, const Twine& contentType,
+                    StringRef content, const Twine& extraHeader = Twine{});
+
+  /**
+   * Send HTTP response from static data, along with other header information
+   * like mimetype.  Calls BuildHeader().  Supports gzip pre-compressed data
+   * (it will decompress if the client does not accept gzip encoded data).
+   * Unlike SendResponse(), content is not copied and its contents must remain
+   * valid for an unspecified lifetime.
+   *
+   * @param code HTTP response code (e.g. 200)
+   * @param codeText HTTP response code text (e.g. "OK")
+   * @param contentType MIME content type (e.g. "text/plain")
+   * @param content Response message content
+   * @param gzipped True if content is gzip compressed
+   * @param extraHeader Extra HTTP headers to send, including final "\r\n"
+   */
+  void SendStaticResponse(int code, const Twine& codeText,
+                          const Twine& contentType, StringRef content,
+                          bool gzipped, const Twine& extraHeader = Twine{});
+
+  /**
+   * Send error header and message.
+   * This provides standard code responses for 400, 401, 403, 404, 500, and 503.
+   * Other codes will be reported as 501.  For arbitrary code handling, use
+   * SendResponse() instead.
+   *
+   * @param code HTTP error code (e.g. 404)
+   * @param message Additional message text
+   */
+  void SendError(int code, const Twine& message = Twine{});
+
+  /** The HTTP request. */
+  HttpParser m_request{HttpParser::kRequest};
+
+  /** Whether the connection should be kept alive. */
+  bool m_keepAlive = false;
+
+  /** If gzip is an acceptable encoding for responses. */
+  bool m_acceptGzip = false;
+
+  /** The underlying stream for the connection. */
+  uv::Stream& m_stream;
+
+  /** The header reader connection. */
+  sig::ScopedConnection m_dataConn;
+
+  /** The end stream connection. */
+  sig::ScopedConnection m_endConn;
+
+  /** The message complete connection. */
+  sig::Connection m_messageCompleteConn;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_HTTPSERVERCONNECTION_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpUtil.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpUtil.h
new file mode 100644
index 0000000..b0668eb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpUtil.h
@@ -0,0 +1,191 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_HTTPUTIL_H_
+#define WPIUTIL_WPI_HTTPUTIL_H_
+
+#include <memory>
+#include <string>
+#include <utility>
+#include <vector>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/NetworkStream.h"
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringMap.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+#include "wpi/raw_istream.h"
+#include "wpi/raw_socket_istream.h"
+#include "wpi/raw_socket_ostream.h"
+
+namespace wpi {
+
+// Unescape a %xx-encoded URI.
+// @param buf Buffer for output
+// @param error Set to true if an error occurred
+// @return Escaped string
+StringRef UnescapeURI(const Twine& str, SmallVectorImpl<char>& buf,
+                      bool* error);
+
+// Escape a string with %xx-encoding.
+// @param buf Buffer for output
+// @param spacePlus If true, encodes spaces to '+' rather than "%20"
+// @return Escaped string
+StringRef EscapeURI(const Twine& str, SmallVectorImpl<char>& buf,
+                    bool spacePlus = true);
+
+// Parse a set of HTTP headers.  Saves just the Content-Type and Content-Length
+// fields.
+// @param is Input stream
+// @param contentType If not null, Content-Type contents are saved here.
+// @param contentLength If not null, Content-Length contents are saved here.
+// @return False if error occurred in input stream
+bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl<char>* contentType,
+                      SmallVectorImpl<char>* contentLength);
+
+// Look for a MIME multi-part boundary.  On return, the input stream will
+// be located at the character following the boundary (usually "\r\n").
+// @param is Input stream
+// @param boundary Boundary string to scan for (not including "--" prefix)
+// @param saveBuf If not null, all scanned characters up to but not including
+//     the boundary are saved to this string
+// @return False if error occurred on input stream, true if boundary found.
+bool FindMultipartBoundary(wpi::raw_istream& is, StringRef boundary,
+                           std::string* saveBuf);
+
+class HttpLocation {
+ public:
+  HttpLocation() = default;
+  HttpLocation(const Twine& url_, bool* error, std::string* errorMsg);
+
+  std::string url;       // retain copy
+  std::string user;      // unescaped
+  std::string password;  // unescaped
+  std::string host;
+  int port;
+  std::string path;  // escaped, not including leading '/'
+  std::vector<std::pair<std::string, std::string>> params;  // unescaped
+  std::string fragment;
+};
+
+class HttpRequest {
+ public:
+  HttpRequest() = default;
+
+  explicit HttpRequest(const HttpLocation& loc)
+      : host{loc.host}, port{loc.port} {
+    SetPath(loc.path, loc.params);
+    SetAuth(loc);
+  }
+
+  template <typename T>
+  HttpRequest(const HttpLocation& loc, const T& extraParams);
+
+  HttpRequest(const HttpLocation& loc, StringRef path_)
+      : host{loc.host}, port{loc.port}, path{path_} {
+    SetAuth(loc);
+  }
+
+  template <typename T>
+  HttpRequest(const HttpLocation& loc, StringRef path_, const T& params)
+      : host{loc.host}, port{loc.port} {
+    SetPath(path_, params);
+    SetAuth(loc);
+  }
+
+  SmallString<128> host;
+  int port;
+  std::string auth;
+  SmallString<128> path;
+
+ private:
+  void SetAuth(const HttpLocation& loc);
+  template <typename T>
+  void SetPath(StringRef path_, const T& params);
+
+  template <typename T>
+  static StringRef GetFirst(const T& elem) {
+    return elem.first;
+  }
+  template <typename T>
+  static StringRef GetFirst(const StringMapEntry<T>& elem) {
+    return elem.getKey();
+  }
+  template <typename T>
+  static StringRef GetSecond(const T& elem) {
+    return elem.second;
+  }
+};
+
+class HttpConnection {
+ public:
+  HttpConnection(std::unique_ptr<wpi::NetworkStream> stream_, int timeout)
+      : stream{std::move(stream_)}, is{*stream, timeout}, os{*stream, true} {}
+
+  bool Handshake(const HttpRequest& request, std::string* warnMsg);
+
+  std::unique_ptr<wpi::NetworkStream> stream;
+  wpi::raw_socket_istream is;
+  wpi::raw_socket_ostream os;
+
+  // Valid after Handshake() is successful
+  SmallString<64> contentType;
+  SmallString<64> contentLength;
+
+  explicit operator bool() const { return stream && !is.has_error(); }
+};
+
+class HttpMultipartScanner {
+ public:
+  explicit HttpMultipartScanner(StringRef boundary, bool saveSkipped = false) {
+    Reset(saveSkipped);
+    SetBoundary(boundary);
+  }
+
+  // Change the boundary.  This is only safe to do when IsDone() is true (or
+  // immediately after construction).
+  void SetBoundary(StringRef boundary);
+
+  // Reset the scanner.  This allows reuse of internal buffers.
+  void Reset(bool saveSkipped = false);
+
+  // Execute the scanner.  Will automatically call Reset() on entry if IsDone()
+  // is true.
+  // @param in input data
+  // @return the input not consumed; empty if all input consumed
+  StringRef Execute(StringRef in);
+
+  // Returns true when the boundary has been found.
+  bool IsDone() const { return m_state == kDone; }
+
+  // Get the skipped data.  Will be empty if saveSkipped was false.
+  StringRef GetSkipped() const {
+    return m_saveSkipped ? StringRef{m_buf} : StringRef{};
+  }
+
+ private:
+  SmallString<64> m_boundaryWith, m_boundaryWithout;
+
+  // Internal state
+  enum State { kBoundary, kPadding, kDone };
+  State m_state;
+  size_t m_posWith, m_posWithout;
+  enum Dashes { kUnknown, kWith, kWithout };
+  Dashes m_dashes;
+
+  // Buffer
+  bool m_saveSkipped;
+  std::string m_buf;
+};
+
+}  // namespace wpi
+
+#include "HttpUtil.inl"
+
+#endif  // WPIUTIL_WPI_HTTPUTIL_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpUtil.inl b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpUtil.inl
new file mode 100644
index 0000000..cfeb9b3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/HttpUtil.inl
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2015. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_SUPPORT_HTTPUTIL_INL_
+#define WPIUTIL_SUPPORT_HTTPUTIL_INL_
+
+namespace wpi {
+
+template <typename T>
+HttpRequest::HttpRequest(const HttpLocation& loc, const T& extraParams)
+    : host{loc.host}, port{loc.port} {
+  StringMap<StringRef> params;
+  for (const auto& p : loc.params)
+    params.insert(std::make_pair(GetFirst(p), GetSecond(p)));
+  for (const auto& p : extraParams)
+    params.insert(std::make_pair(GetFirst(p), GetSecond(p)));
+  SetPath(loc.path, params);
+  SetAuth(loc);
+}
+
+template <typename T>
+void HttpRequest::SetPath(StringRef path_, const T& params) {
+  // Build location including query string
+  raw_svector_ostream pathOs{path};
+  pathOs << path_;
+  bool first = true;
+  for (const auto& param : params) {
+    if (first) {
+      pathOs << '?';
+      first = false;
+    } else {
+      pathOs << '&';
+    }
+    SmallString<64> escapeBuf;
+    pathOs << EscapeURI(GetFirst(param), escapeBuf);
+    if (!GetSecond(param).empty()) {
+      pathOs << '=' << EscapeURI(GetSecond(param), escapeBuf);
+    }
+  }
+}
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_SUPPORT_HTTPUTIL_INL_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/IntrusiveRefCntPtr.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/IntrusiveRefCntPtr.h
new file mode 100644
index 0000000..c677c10
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/IntrusiveRefCntPtr.h
@@ -0,0 +1,270 @@
+//==- llvm/ADT/IntrusiveRefCntPtr.h - Smart Refcounting Pointer --*- C++ -*-==//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the RefCountedBase, ThreadSafeRefCountedBase, and
+// IntrusiveRefCntPtr classes.
+//
+// IntrusiveRefCntPtr is a smart pointer to an object which maintains a
+// reference count.  (ThreadSafe)RefCountedBase is a mixin class that adds a
+// refcount member variable and methods for updating the refcount.  An object
+// that inherits from (ThreadSafe)RefCountedBase deletes itself when its
+// refcount hits zero.
+//
+// For example:
+//
+//   class MyClass : public RefCountedBase<MyClass> {};
+//
+//   void foo() {
+//     // Constructing an IntrusiveRefCntPtr increases the pointee's refcount by
+//     // 1 (from 0 in this case).
+//     IntrusiveRefCntPtr<MyClass> Ptr1(new MyClass());
+//
+//     // Copying an IntrusiveRefCntPtr increases the pointee's refcount by 1.
+//     IntrusiveRefCntPtr<MyClass> Ptr2(Ptr1);
+//
+//     // Constructing an IntrusiveRefCntPtr has no effect on the object's
+//     // refcount.  After a move, the moved-from pointer is null.
+//     IntrusiveRefCntPtr<MyClass> Ptr3(std::move(Ptr1));
+//     assert(Ptr1 == nullptr);
+//
+//     // Clearing an IntrusiveRefCntPtr decreases the pointee's refcount by 1.
+//     Ptr2.reset();
+//
+//     // The object deletes itself when we return from the function, because
+//     // Ptr3's destructor decrements its refcount to 0.
+//   }
+//
+// You can use IntrusiveRefCntPtr with isa<T>(), dyn_cast<T>(), etc.:
+//
+//   IntrusiveRefCntPtr<MyClass> Ptr(new MyClass());
+//   OtherClass *Other = dyn_cast<OtherClass>(Ptr);  // Ptr.get() not required
+//
+// IntrusiveRefCntPtr works with any class that
+//
+//  - inherits from (ThreadSafe)RefCountedBase,
+//  - has Retain() and Release() methods, or
+//  - specializes IntrusiveRefCntPtrInfo.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_INTRUSIVEREFCNTPTR_H
+#define WPIUTIL_WPI_INTRUSIVEREFCNTPTR_H
+
+#include <atomic>
+#include <cassert>
+#include <cstddef>
+
+namespace wpi {
+
+/// A CRTP mixin class that adds reference counting to a type.
+///
+/// The lifetime of an object which inherits from RefCountedBase is managed by
+/// calls to Release() and Retain(), which increment and decrement the object's
+/// refcount, respectively.  When a Release() call decrements the refcount to 0,
+/// the object deletes itself.
+template <class Derived> class RefCountedBase {
+  mutable unsigned RefCount = 0;
+
+public:
+  RefCountedBase() = default;
+  RefCountedBase(const RefCountedBase &) {}
+
+  void Retain() const { ++RefCount; }
+
+  void Release() const {
+    assert(RefCount > 0 && "Reference count is already zero.");
+    if (--RefCount == 0)
+      delete static_cast<const Derived *>(this);
+  }
+};
+
+/// A thread-safe version of \c RefCountedBase.
+template <class Derived> class ThreadSafeRefCountedBase {
+  mutable std::atomic<int> RefCount;
+
+protected:
+  ThreadSafeRefCountedBase() : RefCount(0) {}
+
+public:
+  void Retain() const { RefCount.fetch_add(1, std::memory_order_relaxed); }
+
+  void Release() const {
+    int NewRefCount = RefCount.fetch_sub(1, std::memory_order_acq_rel) - 1;
+    assert(NewRefCount >= 0 && "Reference count was already zero.");
+    if (NewRefCount == 0)
+      delete static_cast<const Derived *>(this);
+  }
+};
+
+/// Class you can specialize to provide custom retain/release functionality for
+/// a type.
+///
+/// Usually specializing this class is not necessary, as IntrusiveRefCntPtr
+/// works with any type which defines Retain() and Release() functions -- you
+/// can define those functions yourself if RefCountedBase doesn't work for you.
+///
+/// One case when you might want to specialize this type is if you have
+///  - Foo.h defines type Foo and includes Bar.h, and
+///  - Bar.h uses IntrusiveRefCntPtr<Foo> in inline functions.
+///
+/// Because Foo.h includes Bar.h, Bar.h can't include Foo.h in order to pull in
+/// the declaration of Foo.  Without the declaration of Foo, normally Bar.h
+/// wouldn't be able to use IntrusiveRefCntPtr<Foo>, which wants to call
+/// T::Retain and T::Release.
+///
+/// To resolve this, Bar.h could include a third header, FooFwd.h, which
+/// forward-declares Foo and specializes IntrusiveRefCntPtrInfo<Foo>.  Then
+/// Bar.h could use IntrusiveRefCntPtr<Foo>, although it still couldn't call any
+/// functions on Foo itself, because Foo would be an incomplete type.
+template <typename T> struct IntrusiveRefCntPtrInfo {
+  static void retain(T *obj) { obj->Retain(); }
+  static void release(T *obj) { obj->Release(); }
+};
+
+/// A smart pointer to a reference-counted object that inherits from
+/// RefCountedBase or ThreadSafeRefCountedBase.
+///
+/// This class increments its pointee's reference count when it is created, and
+/// decrements its refcount when it's destroyed (or is changed to point to a
+/// different object).
+template <typename T> class IntrusiveRefCntPtr {
+  T *Obj = nullptr;
+
+public:
+  using element_type = T;
+
+  explicit IntrusiveRefCntPtr() = default;
+  IntrusiveRefCntPtr(T *obj) : Obj(obj) { retain(); }
+  IntrusiveRefCntPtr(const IntrusiveRefCntPtr &S) : Obj(S.Obj) { retain(); }
+  IntrusiveRefCntPtr(IntrusiveRefCntPtr &&S) : Obj(S.Obj) { S.Obj = nullptr; }
+
+  template <class X>
+  IntrusiveRefCntPtr(IntrusiveRefCntPtr<X> &&S) : Obj(S.get()) {
+    S.Obj = nullptr;
+  }
+
+  template <class X>
+  IntrusiveRefCntPtr(const IntrusiveRefCntPtr<X> &S) : Obj(S.get()) {
+    retain();
+  }
+
+  ~IntrusiveRefCntPtr() { release(); }
+
+  IntrusiveRefCntPtr &operator=(IntrusiveRefCntPtr S) {
+    swap(S);
+    return *this;
+  }
+
+  T &operator*() const { return *Obj; }
+  T *operator->() const { return Obj; }
+  T *get() const { return Obj; }
+  explicit operator bool() const { return Obj; }
+
+  void swap(IntrusiveRefCntPtr &other) {
+    T *tmp = other.Obj;
+    other.Obj = Obj;
+    Obj = tmp;
+  }
+
+  void reset() {
+    release();
+    Obj = nullptr;
+  }
+
+  void resetWithoutRelease() { Obj = nullptr; }
+
+private:
+  void retain() {
+    if (Obj)
+      IntrusiveRefCntPtrInfo<T>::retain(Obj);
+  }
+
+  void release() {
+    if (Obj)
+      IntrusiveRefCntPtrInfo<T>::release(Obj);
+  }
+
+  template <typename X> friend class IntrusiveRefCntPtr;
+};
+
+template <class T, class U>
+inline bool operator==(const IntrusiveRefCntPtr<T> &A,
+                       const IntrusiveRefCntPtr<U> &B) {
+  return A.get() == B.get();
+}
+
+template <class T, class U>
+inline bool operator!=(const IntrusiveRefCntPtr<T> &A,
+                       const IntrusiveRefCntPtr<U> &B) {
+  return A.get() != B.get();
+}
+
+template <class T, class U>
+inline bool operator==(const IntrusiveRefCntPtr<T> &A, U *B) {
+  return A.get() == B;
+}
+
+template <class T, class U>
+inline bool operator!=(const IntrusiveRefCntPtr<T> &A, U *B) {
+  return A.get() != B;
+}
+
+template <class T, class U>
+inline bool operator==(T *A, const IntrusiveRefCntPtr<U> &B) {
+  return A == B.get();
+}
+
+template <class T, class U>
+inline bool operator!=(T *A, const IntrusiveRefCntPtr<U> &B) {
+  return A != B.get();
+}
+
+template <class T>
+bool operator==(std::nullptr_t A, const IntrusiveRefCntPtr<T> &B) {
+  return !B;
+}
+
+template <class T>
+bool operator==(const IntrusiveRefCntPtr<T> &A, std::nullptr_t B) {
+  return B == A;
+}
+
+template <class T>
+bool operator!=(std::nullptr_t A, const IntrusiveRefCntPtr<T> &B) {
+  return !(A == B);
+}
+
+template <class T>
+bool operator!=(const IntrusiveRefCntPtr<T> &A, std::nullptr_t B) {
+  return !(A == B);
+}
+
+// Make IntrusiveRefCntPtr work with dyn_cast, isa, and the other idioms from
+// Casting.h.
+template <typename From> struct simplify_type;
+
+template <class T> struct simplify_type<IntrusiveRefCntPtr<T>> {
+  using SimpleType = T *;
+
+  static SimpleType getSimplifiedValue(IntrusiveRefCntPtr<T> &Val) {
+    return Val.get();
+  }
+};
+
+template <class T> struct simplify_type<const IntrusiveRefCntPtr<T>> {
+  using SimpleType = /*const*/ T *;
+
+  static SimpleType getSimplifiedValue(const IntrusiveRefCntPtr<T> &Val) {
+    return Val.get();
+  }
+};
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_INTRUSIVEREFCNTPTR_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Logger.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Logger.h
new file mode 100644
index 0000000..20aa8ee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Logger.h
@@ -0,0 +1,100 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_LOGGER_H_
+#define WPIUTIL_WPI_LOGGER_H_
+
+#include <functional>
+
+#include "wpi/SmallString.h"
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+enum LogLevel {
+  WPI_LOG_CRITICAL = 50,
+  WPI_LOG_ERROR = 40,
+  WPI_LOG_WARNING = 30,
+  WPI_LOG_INFO = 20,
+  WPI_LOG_DEBUG = 10,
+  WPI_LOG_DEBUG1 = 9,
+  WPI_LOG_DEBUG2 = 8,
+  WPI_LOG_DEBUG3 = 7,
+  WPI_LOG_DEBUG4 = 6
+};
+
+class Logger {
+ public:
+  using LogFunc = std::function<void(unsigned int level, const char* file,
+                                     unsigned int line, const char* msg)>;
+
+  Logger() = default;
+  explicit Logger(const LogFunc& func) : m_func(func) {}
+  Logger(const LogFunc& func, unsigned int min_level)
+      : m_func(func), m_min_level(min_level) {}
+
+  void SetLogger(LogFunc func) { m_func = func; }
+
+  void set_min_level(unsigned int level) { m_min_level = level; }
+  unsigned int min_level() const { return m_min_level; }
+
+  void Log(unsigned int level, const char* file, unsigned int line,
+           const char* msg) {
+    if (!m_func || level < m_min_level) return;
+    m_func(level, file, line, msg);
+  }
+
+  bool HasLogger() const { return m_func != nullptr; }
+
+ private:
+  LogFunc m_func;
+  unsigned int m_min_level = 20;
+};
+
+#define WPI_LOG(logger_inst, level, x)                                 \
+  do {                                                                 \
+    ::wpi::Logger& WPI_logger_ = logger_inst;                          \
+    if (WPI_logger_.min_level() <= static_cast<unsigned int>(level) && \
+        WPI_logger_.HasLogger()) {                                     \
+      ::wpi::SmallString<128> log_buf_;                                \
+      ::wpi::raw_svector_ostream log_os_{log_buf_};                    \
+      log_os_ << x;                                                    \
+      WPI_logger_.Log(level, __FILE__, __LINE__, log_buf_.c_str());    \
+    }                                                                  \
+  } while (0)
+
+#define WPI_ERROR(inst, x) WPI_LOG(inst, ::wpi::WPI_LOG_ERROR, x)
+#define WPI_WARNING(inst, x) WPI_LOG(inst, ::wpi::WPI_LOG_WARNING, x)
+#define WPI_INFO(inst, x) WPI_LOG(inst, ::wpi::WPI_LOG_INFO, x)
+
+#ifdef NDEBUG
+#define WPI_DEBUG(inst, x) \
+  do {                     \
+  } while (0)
+#define WPI_DEBUG1(inst, x) \
+  do {                      \
+  } while (0)
+#define WPI_DEBUG2(inst, x) \
+  do {                      \
+  } while (0)
+#define WPI_DEBUG3(inst, x) \
+  do {                      \
+  } while (0)
+#define WPI_DEBUG4(inst, x) \
+  do {                      \
+  } while (0)
+#else
+#define WPI_DEBUG(inst, x) WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG, x)
+#define WPI_DEBUG1(inst, x) WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG1, x)
+#define WPI_DEBUG2(inst, x) WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG2, x)
+#define WPI_DEBUG3(inst, x) WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG3, x)
+#define WPI_DEBUG4(inst, x) WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG4, x)
+#endif
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_LOGGER_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/MapVector.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/MapVector.h
new file mode 100644
index 0000000..34e0267
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/MapVector.h
@@ -0,0 +1,240 @@
+//===- llvm/ADT/MapVector.h - Map w/ deterministic value order --*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file implements a map that provides insertion order iteration. The
+// interface is purposefully minimal. The key is assumed to be cheap to copy
+// and 2 copies are kept, one for indexing in a DenseMap, one for iteration in
+// a std::vector.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_MAPVECTOR_H
+#define WPIUTIL_WPI_MAPVECTOR_H
+
+#include "wpi/DenseMap.h"
+#include "wpi/SmallVector.h"
+#include <algorithm>
+#include <cassert>
+#include <cstddef>
+#include <iterator>
+#include <type_traits>
+#include <utility>
+#include <vector>
+
+namespace wpi {
+
+/// This class implements a map that also provides access to all stored values
+/// in a deterministic order. The values are kept in a std::vector and the
+/// mapping is done with DenseMap from Keys to indexes in that vector.
+template<typename KeyT, typename ValueT,
+         typename MapType = DenseMap<KeyT, unsigned>,
+         typename VectorType = std::vector<std::pair<KeyT, ValueT>>>
+class MapVector {
+  MapType Map;
+  VectorType Vector;
+
+  static_assert(
+      std::is_integral<typename MapType::mapped_type>::value,
+      "The mapped_type of the specified Map must be an integral type");
+
+public:
+  using value_type = typename VectorType::value_type;
+  using size_type = typename VectorType::size_type;
+
+  using iterator = typename VectorType::iterator;
+  using const_iterator = typename VectorType::const_iterator;
+  using reverse_iterator = typename VectorType::reverse_iterator;
+  using const_reverse_iterator = typename VectorType::const_reverse_iterator;
+
+  /// Clear the MapVector and return the underlying vector.
+  VectorType takeVector() {
+    Map.clear();
+    return std::move(Vector);
+  }
+
+  size_type size() const { return Vector.size(); }
+
+  /// Grow the MapVector so that it can contain at least \p NumEntries items
+  /// before resizing again.
+  void reserve(size_type NumEntries) {
+    Map.reserve(NumEntries);
+    Vector.reserve(NumEntries);
+  }
+
+  iterator begin() { return Vector.begin(); }
+  const_iterator begin() const { return Vector.begin(); }
+  iterator end() { return Vector.end(); }
+  const_iterator end() const { return Vector.end(); }
+
+  reverse_iterator rbegin() { return Vector.rbegin(); }
+  const_reverse_iterator rbegin() const { return Vector.rbegin(); }
+  reverse_iterator rend() { return Vector.rend(); }
+  const_reverse_iterator rend() const { return Vector.rend(); }
+
+  bool empty() const {
+    return Vector.empty();
+  }
+
+  std::pair<KeyT, ValueT>       &front()       { return Vector.front(); }
+  const std::pair<KeyT, ValueT> &front() const { return Vector.front(); }
+  std::pair<KeyT, ValueT>       &back()        { return Vector.back(); }
+  const std::pair<KeyT, ValueT> &back()  const { return Vector.back(); }
+
+  void clear() {
+    Map.clear();
+    Vector.clear();
+  }
+
+  void swap(MapVector &RHS) {
+    std::swap(Map, RHS.Map);
+    std::swap(Vector, RHS.Vector);
+  }
+
+  ValueT &operator[](const KeyT &Key) {
+    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(Key, 0);
+    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
+    auto &I = Result.first->second;
+    if (Result.second) {
+      Vector.push_back(std::make_pair(Key, ValueT()));
+      I = Vector.size() - 1;
+    }
+    return Vector[I].second;
+  }
+
+  // Returns a copy of the value.  Only allowed if ValueT is copyable.
+  ValueT lookup(const KeyT &Key) const {
+    static_assert(std::is_copy_constructible<ValueT>::value,
+                  "Cannot call lookup() if ValueT is not copyable.");
+    typename MapType::const_iterator Pos = Map.find(Key);
+    return Pos == Map.end()? ValueT() : Vector[Pos->second].second;
+  }
+
+  std::pair<iterator, bool> insert(const std::pair<KeyT, ValueT> &KV) {
+    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(KV.first, 0);
+    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
+    auto &I = Result.first->second;
+    if (Result.second) {
+      Vector.push_back(std::make_pair(KV.first, KV.second));
+      I = Vector.size() - 1;
+      return std::make_pair(std::prev(end()), true);
+    }
+    return std::make_pair(begin() + I, false);
+  }
+
+  std::pair<iterator, bool> insert(std::pair<KeyT, ValueT> &&KV) {
+    // Copy KV.first into the map, then move it into the vector.
+    std::pair<KeyT, typename MapType::mapped_type> Pair = std::make_pair(KV.first, 0);
+    std::pair<typename MapType::iterator, bool> Result = Map.insert(Pair);
+    auto &I = Result.first->second;
+    if (Result.second) {
+      Vector.push_back(std::move(KV));
+      I = Vector.size() - 1;
+      return std::make_pair(std::prev(end()), true);
+    }
+    return std::make_pair(begin() + I, false);
+  }
+
+  size_type count(const KeyT &Key) const {
+    typename MapType::const_iterator Pos = Map.find(Key);
+    return Pos == Map.end()? 0 : 1;
+  }
+
+  iterator find(const KeyT &Key) {
+    typename MapType::const_iterator Pos = Map.find(Key);
+    return Pos == Map.end()? Vector.end() :
+                            (Vector.begin() + Pos->second);
+  }
+
+  const_iterator find(const KeyT &Key) const {
+    typename MapType::const_iterator Pos = Map.find(Key);
+    return Pos == Map.end()? Vector.end() :
+                            (Vector.begin() + Pos->second);
+  }
+
+  /// Remove the last element from the vector.
+  void pop_back() {
+    typename MapType::iterator Pos = Map.find(Vector.back().first);
+    Map.erase(Pos);
+    Vector.pop_back();
+  }
+
+  /// Remove the element given by Iterator.
+  ///
+  /// Returns an iterator to the element following the one which was removed,
+  /// which may be end().
+  ///
+  /// \note This is a deceivingly expensive operation (linear time).  It's
+  /// usually better to use \a remove_if() if possible.
+  typename VectorType::iterator erase(typename VectorType::iterator Iterator) {
+    Map.erase(Iterator->first);
+    auto Next = Vector.erase(Iterator);
+    if (Next == Vector.end())
+      return Next;
+
+    // Update indices in the map.
+    size_t Index = Next - Vector.begin();
+    for (auto &I : Map) {
+      assert(I.second != Index && "Index was already erased!");
+      if (I.second > Index)
+        --I.second;
+    }
+    return Next;
+  }
+
+  /// Remove all elements with the key value Key.
+  ///
+  /// Returns the number of elements removed.
+  size_type erase(const KeyT &Key) {
+    auto Iterator = find(Key);
+    if (Iterator == end())
+      return 0;
+    erase(Iterator);
+    return 1;
+  }
+
+  /// Remove the elements that match the predicate.
+  ///
+  /// Erase all elements that match \c Pred in a single pass.  Takes linear
+  /// time.
+  template <class Predicate> void remove_if(Predicate Pred);
+};
+
+template <typename KeyT, typename ValueT, typename MapType, typename VectorType>
+template <class Function>
+void MapVector<KeyT, ValueT, MapType, VectorType>::remove_if(Function Pred) {
+  auto O = Vector.begin();
+  for (auto I = O, E = Vector.end(); I != E; ++I) {
+    if (Pred(*I)) {
+      // Erase from the map.
+      Map.erase(I->first);
+      continue;
+    }
+
+    if (I != O) {
+      // Move the value and update the index in the map.
+      *O = std::move(*I);
+      Map[O->first] = O - Vector.begin();
+    }
+    ++O;
+  }
+  // Erase trailing entries in the vector.
+  Vector.erase(O, Vector.end());
+}
+
+/// A MapVector that performs no allocations if smaller than a certain
+/// size.
+template <typename KeyT, typename ValueT, unsigned N>
+struct SmallMapVector
+    : MapVector<KeyT, ValueT, SmallDenseMap<KeyT, unsigned, N>,
+                SmallVector<std::pair<KeyT, ValueT>, N>> {
+};
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_MAPVECTOR_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/MathExtras.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/MathExtras.h
new file mode 100644
index 0000000..1ab43aa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/MathExtras.h
@@ -0,0 +1,826 @@
+//===-- llvm/Support/MathExtras.h - Useful math functions -------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file contains some functions that are useful for math stuff.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_MATHEXTRAS_H
+#define WPIUTIL_WPI_MATHEXTRAS_H
+
+#include "wpi/Compiler.h"
+#include <cstdint>
+#include <algorithm>
+#include <cassert>
+#include <climits>
+#include <cmath>
+#include <cstring>
+#include <limits>
+#include <type_traits>
+
+#ifdef _MSC_VER
+#include <intrin.h>
+#endif
+
+namespace wpi {
+/// The behavior an operation has on an input of 0.
+enum ZeroBehavior {
+  /// The returned value is undefined.
+  ZB_Undefined,
+  /// The returned value is numeric_limits<T>::max()
+  ZB_Max,
+  /// The returned value is numeric_limits<T>::digits
+  ZB_Width
+};
+
+namespace detail {
+template <typename T, std::size_t SizeOfT> struct TrailingZerosCounter {
+  static std::size_t count(T Val, ZeroBehavior) {
+    if (!Val)
+      return std::numeric_limits<T>::digits;
+    if (Val & 0x1)
+      return 0;
+
+    // Bisection method.
+    std::size_t ZeroBits = 0;
+    T Shift = std::numeric_limits<T>::digits >> 1;
+    T Mask = std::numeric_limits<T>::max() >> Shift;
+    while (Shift) {
+      if ((Val & Mask) == 0) {
+        Val >>= Shift;
+        ZeroBits |= Shift;
+      }
+      Shift >>= 1;
+      Mask >>= Shift;
+    }
+    return ZeroBits;
+  }
+};
+
+#if __GNUC__ >= 4 || defined(_MSC_VER)
+template <typename T> struct TrailingZerosCounter<T, 4> {
+  static std::size_t count(T Val, ZeroBehavior ZB) {
+    if (ZB != ZB_Undefined && Val == 0)
+      return 32;
+
+#if __has_builtin(__builtin_ctz) || LLVM_GNUC_PREREQ(4, 0, 0)
+    return __builtin_ctz(Val);
+#elif defined(_MSC_VER)
+    unsigned long Index;
+    _BitScanForward(&Index, Val);
+    return Index;
+#endif
+  }
+};
+
+#if !defined(_MSC_VER) || defined(_M_X64)
+template <typename T> struct TrailingZerosCounter<T, 8> {
+  static std::size_t count(T Val, ZeroBehavior ZB) {
+    if (ZB != ZB_Undefined && Val == 0)
+      return 64;
+
+#if __has_builtin(__builtin_ctzll) || LLVM_GNUC_PREREQ(4, 0, 0)
+    return __builtin_ctzll(Val);
+#elif defined(_MSC_VER)
+    unsigned long Index;
+    _BitScanForward64(&Index, Val);
+    return Index;
+#endif
+  }
+};
+#endif
+#endif
+} // namespace detail
+
+/// Count number of 0's from the least significant bit to the most
+///   stopping at the first 1.
+///
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of 0. Only ZB_Width and ZB_Undefined are
+///   valid arguments.
+template <typename T>
+std::size_t countTrailingZeros(T Val, ZeroBehavior ZB = ZB_Width) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return wpi::detail::TrailingZerosCounter<T, sizeof(T)>::count(Val, ZB);
+}
+
+namespace detail {
+template <typename T, std::size_t SizeOfT> struct LeadingZerosCounter {
+  static std::size_t count(T Val, ZeroBehavior) {
+    if (!Val)
+      return std::numeric_limits<T>::digits;
+
+    // Bisection method.
+    std::size_t ZeroBits = 0;
+    for (T Shift = std::numeric_limits<T>::digits >> 1; Shift; Shift >>= 1) {
+      T Tmp = Val >> Shift;
+      if (Tmp)
+        Val = Tmp;
+      else
+        ZeroBits |= Shift;
+    }
+    return ZeroBits;
+  }
+};
+
+#if __GNUC__ >= 4 || defined(_MSC_VER)
+template <typename T> struct LeadingZerosCounter<T, 4> {
+  static std::size_t count(T Val, ZeroBehavior ZB) {
+    if (ZB != ZB_Undefined && Val == 0)
+      return 32;
+
+#if __has_builtin(__builtin_clz) || LLVM_GNUC_PREREQ(4, 0, 0)
+    return __builtin_clz(Val);
+#elif defined(_MSC_VER)
+    unsigned long Index;
+    _BitScanReverse(&Index, Val);
+    return Index ^ 31;
+#endif
+  }
+};
+
+#if !defined(_MSC_VER) || defined(_M_X64)
+template <typename T> struct LeadingZerosCounter<T, 8> {
+  static std::size_t count(T Val, ZeroBehavior ZB) {
+    if (ZB != ZB_Undefined && Val == 0)
+      return 64;
+
+#if __has_builtin(__builtin_clzll) || LLVM_GNUC_PREREQ(4, 0, 0)
+    return __builtin_clzll(Val);
+#elif defined(_MSC_VER)
+    unsigned long Index;
+    _BitScanReverse64(&Index, Val);
+    return Index ^ 63;
+#endif
+  }
+};
+#endif
+#endif
+} // namespace detail
+
+/// Count number of 0's from the most significant bit to the least
+///   stopping at the first 1.
+///
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of 0. Only ZB_Width and ZB_Undefined are
+///   valid arguments.
+template <typename T>
+std::size_t countLeadingZeros(T Val, ZeroBehavior ZB = ZB_Width) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return wpi::detail::LeadingZerosCounter<T, sizeof(T)>::count(Val, ZB);
+}
+
+/// Get the index of the first set bit starting from the least
+///   significant bit.
+///
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of 0. Only ZB_Max and ZB_Undefined are
+///   valid arguments.
+template <typename T> T findFirstSet(T Val, ZeroBehavior ZB = ZB_Max) {
+  if (ZB == ZB_Max && Val == 0)
+    return std::numeric_limits<T>::max();
+
+  return countTrailingZeros(Val, ZB_Undefined);
+}
+
+/// Create a bitmask with the N right-most bits set to 1, and all other
+/// bits set to 0.  Only unsigned types are allowed.
+template <typename T> T maskTrailingOnes(unsigned N) {
+  static_assert(std::is_unsigned<T>::value, "Invalid type!");
+  const unsigned Bits = CHAR_BIT * sizeof(T);
+  assert(N <= Bits && "Invalid bit index");
+  return N == 0 ? 0 : (T(-1) >> (Bits - N));
+}
+
+/// Create a bitmask with the N left-most bits set to 1, and all other
+/// bits set to 0.  Only unsigned types are allowed.
+template <typename T> T maskLeadingOnes(unsigned N) {
+  return ~maskTrailingOnes<T>(CHAR_BIT * sizeof(T) - N);
+}
+
+/// Create a bitmask with the N right-most bits set to 0, and all other
+/// bits set to 1.  Only unsigned types are allowed.
+template <typename T> T maskTrailingZeros(unsigned N) {
+  return maskLeadingOnes<T>(CHAR_BIT * sizeof(T) - N);
+}
+
+/// Create a bitmask with the N left-most bits set to 0, and all other
+/// bits set to 1.  Only unsigned types are allowed.
+template <typename T> T maskLeadingZeros(unsigned N) {
+  return maskTrailingOnes<T>(CHAR_BIT * sizeof(T) - N);
+}
+
+/// Get the index of the last set bit starting from the least
+///   significant bit.
+///
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of 0. Only ZB_Max and ZB_Undefined are
+///   valid arguments.
+template <typename T> T findLastSet(T Val, ZeroBehavior ZB = ZB_Max) {
+  if (ZB == ZB_Max && Val == 0)
+    return std::numeric_limits<T>::max();
+
+  // Use ^ instead of - because both gcc and llvm can remove the associated ^
+  // in the __builtin_clz intrinsic on x86.
+  return countLeadingZeros(Val, ZB_Undefined) ^
+         (std::numeric_limits<T>::digits - 1);
+}
+
+/// Macro compressed bit reversal table for 256 bits.
+///
+/// http://graphics.stanford.edu/~seander/bithacks.html#BitReverseTable
+static const unsigned char BitReverseTable256[256] = {
+#define R2(n) n, n + 2 * 64, n + 1 * 64, n + 3 * 64
+#define R4(n) R2(n), R2(n + 2 * 16), R2(n + 1 * 16), R2(n + 3 * 16)
+#define R6(n) R4(n), R4(n + 2 * 4), R4(n + 1 * 4), R4(n + 3 * 4)
+  R6(0), R6(2), R6(1), R6(3)
+#undef R2
+#undef R4
+#undef R6
+};
+
+/// Reverse the bits in \p Val.
+template <typename T>
+T reverseBits(T Val) {
+  unsigned char in[sizeof(Val)];
+  unsigned char out[sizeof(Val)];
+  std::memcpy(in, &Val, sizeof(Val));
+  for (unsigned i = 0; i < sizeof(Val); ++i)
+    out[(sizeof(Val) - i) - 1] = BitReverseTable256[in[i]];
+  std::memcpy(&Val, out, sizeof(Val));
+  return Val;
+}
+
+// NOTE: The following support functions use the _32/_64 extensions instead of
+// type overloading so that signed and unsigned integers can be used without
+// ambiguity.
+
+/// Return the high 32 bits of a 64 bit value.
+constexpr inline uint32_t Hi_32(uint64_t Value) {
+  return static_cast<uint32_t>(Value >> 32);
+}
+
+/// Return the low 32 bits of a 64 bit value.
+constexpr inline uint32_t Lo_32(uint64_t Value) {
+  return static_cast<uint32_t>(Value);
+}
+
+/// Make a 64-bit integer from a high / low pair of 32-bit integers.
+constexpr inline uint64_t Make_64(uint32_t High, uint32_t Low) {
+  return ((uint64_t)High << 32) | (uint64_t)Low;
+}
+
+/// Checks if an integer fits into the given bit width.
+template <unsigned N> constexpr inline bool isInt(int64_t x) {
+  return N >= 64 || (-(INT64_C(1)<<(N-1)) <= x && x < (INT64_C(1)<<(N-1)));
+}
+// Template specializations to get better code for common cases.
+template <> constexpr inline bool isInt<8>(int64_t x) {
+  return static_cast<int8_t>(x) == x;
+}
+template <> constexpr inline bool isInt<16>(int64_t x) {
+  return static_cast<int16_t>(x) == x;
+}
+template <> constexpr inline bool isInt<32>(int64_t x) {
+  return static_cast<int32_t>(x) == x;
+}
+
+/// Checks if a signed integer is an N bit number shifted left by S.
+template <unsigned N, unsigned S>
+constexpr inline bool isShiftedInt(int64_t x) {
+  static_assert(
+      N > 0, "isShiftedInt<0> doesn't make sense (refers to a 0-bit number.");
+  static_assert(N + S <= 64, "isShiftedInt<N, S> with N + S > 64 is too wide.");
+  return isInt<N + S>(x) && (x % (UINT64_C(1) << S) == 0);
+}
+
+/// Checks if an unsigned integer fits into the given bit width.
+///
+/// This is written as two functions rather than as simply
+///
+///   return N >= 64 || X < (UINT64_C(1) << N);
+///
+/// to keep MSVC from (incorrectly) warning on isUInt<64> that we're shifting
+/// left too many places.
+template <unsigned N>
+constexpr inline typename std::enable_if<(N < 64), bool>::type
+isUInt(uint64_t X) {
+  static_assert(N > 0, "isUInt<0> doesn't make sense");
+  return X < (UINT64_C(1) << (N));
+}
+template <unsigned N>
+constexpr inline typename std::enable_if<N >= 64, bool>::type
+isUInt(uint64_t X) {
+  return true;
+}
+
+// Template specializations to get better code for common cases.
+template <> constexpr inline bool isUInt<8>(uint64_t x) {
+  return static_cast<uint8_t>(x) == x;
+}
+template <> constexpr inline bool isUInt<16>(uint64_t x) {
+  return static_cast<uint16_t>(x) == x;
+}
+template <> constexpr inline bool isUInt<32>(uint64_t x) {
+  return static_cast<uint32_t>(x) == x;
+}
+
+/// Checks if a unsigned integer is an N bit number shifted left by S.
+template <unsigned N, unsigned S>
+constexpr inline bool isShiftedUInt(uint64_t x) {
+  static_assert(
+      N > 0, "isShiftedUInt<0> doesn't make sense (refers to a 0-bit number)");
+  static_assert(N + S <= 64,
+                "isShiftedUInt<N, S> with N + S > 64 is too wide.");
+  // Per the two static_asserts above, S must be strictly less than 64.  So
+  // 1 << S is not undefined behavior.
+  return isUInt<N + S>(x) && (x % (UINT64_C(1) << S) == 0);
+}
+
+/// Gets the maximum value for a N-bit unsigned integer.
+inline uint64_t maxUIntN(uint64_t N) {
+  assert(N > 0 && N <= 64 && "integer width out of range");
+
+  // uint64_t(1) << 64 is undefined behavior, so we can't do
+  //   (uint64_t(1) << N) - 1
+  // without checking first that N != 64.  But this works and doesn't have a
+  // branch.
+  return UINT64_MAX >> (64 - N);
+}
+
+/// Gets the minimum value for a N-bit signed integer.
+inline int64_t minIntN(int64_t N) {
+  assert(N > 0 && N <= 64 && "integer width out of range");
+
+  return -(UINT64_C(1)<<(N-1));
+}
+
+/// Gets the maximum value for a N-bit signed integer.
+inline int64_t maxIntN(int64_t N) {
+  assert(N > 0 && N <= 64 && "integer width out of range");
+
+  // This relies on two's complement wraparound when N == 64, so we convert to
+  // int64_t only at the very end to avoid UB.
+  return (UINT64_C(1) << (N - 1)) - 1;
+}
+
+/// Checks if an unsigned integer fits into the given (dynamic) bit width.
+inline bool isUIntN(unsigned N, uint64_t x) {
+  return N >= 64 || x <= maxUIntN(N);
+}
+
+/// Checks if an signed integer fits into the given (dynamic) bit width.
+inline bool isIntN(unsigned N, int64_t x) {
+  return N >= 64 || (minIntN(N) <= x && x <= maxIntN(N));
+}
+
+/// Return true if the argument is a non-empty sequence of ones starting at the
+/// least significant bit with the remainder zero (32 bit version).
+/// Ex. isMask_32(0x0000FFFFU) == true.
+constexpr inline bool isMask_32(uint32_t Value) {
+  return Value && ((Value + 1) & Value) == 0;
+}
+
+/// Return true if the argument is a non-empty sequence of ones starting at the
+/// least significant bit with the remainder zero (64 bit version).
+constexpr inline bool isMask_64(uint64_t Value) {
+  return Value && ((Value + 1) & Value) == 0;
+}
+
+/// Return true if the argument contains a non-empty sequence of ones with the
+/// remainder zero (32 bit version.) Ex. isShiftedMask_32(0x0000FF00U) == true.
+constexpr inline bool isShiftedMask_32(uint32_t Value) {
+  return Value && isMask_32((Value - 1) | Value);
+}
+
+/// Return true if the argument contains a non-empty sequence of ones with the
+/// remainder zero (64 bit version.)
+constexpr inline bool isShiftedMask_64(uint64_t Value) {
+  return Value && isMask_64((Value - 1) | Value);
+}
+
+/// Return true if the argument is a power of two > 0.
+/// Ex. isPowerOf2_32(0x00100000U) == true (32 bit edition.)
+constexpr inline bool isPowerOf2_32(uint32_t Value) {
+  return Value && !(Value & (Value - 1));
+}
+
+/// Return true if the argument is a power of two > 0 (64 bit edition.)
+constexpr inline bool isPowerOf2_64(uint64_t Value) {
+  return Value && !(Value & (Value - 1));
+}
+
+/// Count the number of ones from the most significant bit to the first
+/// zero bit.
+///
+/// Ex. countLeadingOnes(0xFF0FFF00) == 8.
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of all ones. Only ZB_Width and
+/// ZB_Undefined are valid arguments.
+template <typename T>
+std::size_t countLeadingOnes(T Value, ZeroBehavior ZB = ZB_Width) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return countLeadingZeros<T>(~Value, ZB);
+}
+
+/// Count the number of ones from the least significant bit to the first
+/// zero bit.
+///
+/// Ex. countTrailingOnes(0x00FF00FF) == 8.
+/// Only unsigned integral types are allowed.
+///
+/// \param ZB the behavior on an input of all ones. Only ZB_Width and
+/// ZB_Undefined are valid arguments.
+template <typename T>
+std::size_t countTrailingOnes(T Value, ZeroBehavior ZB = ZB_Width) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return countTrailingZeros<T>(~Value, ZB);
+}
+
+namespace detail {
+template <typename T, std::size_t SizeOfT> struct PopulationCounter {
+  static unsigned count(T Value) {
+    // Generic version, forward to 32 bits.
+    static_assert(SizeOfT <= 4, "Not implemented!");
+#if __GNUC__ >= 4
+    return __builtin_popcount(Value);
+#else
+    uint32_t v = Value;
+    v = v - ((v >> 1) & 0x55555555);
+    v = (v & 0x33333333) + ((v >> 2) & 0x33333333);
+    return ((v + (v >> 4) & 0xF0F0F0F) * 0x1010101) >> 24;
+#endif
+  }
+};
+
+template <typename T> struct PopulationCounter<T, 8> {
+  static unsigned count(T Value) {
+#if __GNUC__ >= 4
+    return __builtin_popcountll(Value);
+#else
+    uint64_t v = Value;
+    v = v - ((v >> 1) & 0x5555555555555555ULL);
+    v = (v & 0x3333333333333333ULL) + ((v >> 2) & 0x3333333333333333ULL);
+    v = (v + (v >> 4)) & 0x0F0F0F0F0F0F0F0FULL;
+    return unsigned((uint64_t)(v * 0x0101010101010101ULL) >> 56);
+#endif
+  }
+};
+} // namespace detail
+
+/// Count the number of set bits in a value.
+/// Ex. countPopulation(0xF000F000) = 8
+/// Returns 0 if the word is zero.
+template <typename T>
+inline unsigned countPopulation(T Value) {
+  static_assert(std::numeric_limits<T>::is_integer &&
+                    !std::numeric_limits<T>::is_signed,
+                "Only unsigned integral types are allowed.");
+  return detail::PopulationCounter<T, sizeof(T)>::count(Value);
+}
+
+/// Return the log base 2 of the specified value.
+inline double Log2(double Value) {
+#if defined(__ANDROID_API__) && __ANDROID_API__ < 18
+  return __builtin_log(Value) / __builtin_log(2.0);
+#else
+  return std::log2(Value);
+#endif
+}
+
+/// Return the floor log base 2 of the specified value, -1 if the value is zero.
+/// (32 bit edition.)
+/// Ex. Log2_32(32) == 5, Log2_32(1) == 0, Log2_32(0) == -1, Log2_32(6) == 2
+inline unsigned Log2_32(uint32_t Value) {
+  return 31 - countLeadingZeros(Value);
+}
+
+/// Return the floor log base 2 of the specified value, -1 if the value is zero.
+/// (64 bit edition.)
+inline unsigned Log2_64(uint64_t Value) {
+  return 63 - countLeadingZeros(Value);
+}
+
+/// Return the ceil log base 2 of the specified value, 32 if the value is zero.
+/// (32 bit edition).
+/// Ex. Log2_32_Ceil(32) == 5, Log2_32_Ceil(1) == 0, Log2_32_Ceil(6) == 3
+inline unsigned Log2_32_Ceil(uint32_t Value) {
+  return 32 - countLeadingZeros(Value - 1);
+}
+
+/// Return the ceil log base 2 of the specified value, 64 if the value is zero.
+/// (64 bit edition.)
+inline unsigned Log2_64_Ceil(uint64_t Value) {
+  return 64 - countLeadingZeros(Value - 1);
+}
+
+/// Return the greatest common divisor of the values using Euclid's algorithm.
+inline uint64_t GreatestCommonDivisor64(uint64_t A, uint64_t B) {
+  while (B) {
+    uint64_t T = B;
+    B = A % B;
+    A = T;
+  }
+  return A;
+}
+
+/// This function takes a 64-bit integer and returns the bit equivalent double.
+inline double BitsToDouble(uint64_t Bits) {
+  double D;
+  static_assert(sizeof(uint64_t) == sizeof(double), "Unexpected type sizes");
+  memcpy(&D, &Bits, sizeof(Bits));
+  return D;
+}
+
+/// This function takes a 32-bit integer and returns the bit equivalent float.
+inline float BitsToFloat(uint32_t Bits) {
+  float F;
+  static_assert(sizeof(uint32_t) == sizeof(float), "Unexpected type sizes");
+  memcpy(&F, &Bits, sizeof(Bits));
+  return F;
+}
+
+/// This function takes a double and returns the bit equivalent 64-bit integer.
+/// Note that copying doubles around changes the bits of NaNs on some hosts,
+/// notably x86, so this routine cannot be used if these bits are needed.
+inline uint64_t DoubleToBits(double Double) {
+  uint64_t Bits;
+  static_assert(sizeof(uint64_t) == sizeof(double), "Unexpected type sizes");
+  memcpy(&Bits, &Double, sizeof(Double));
+  return Bits;
+}
+
+/// This function takes a float and returns the bit equivalent 32-bit integer.
+/// Note that copying floats around changes the bits of NaNs on some hosts,
+/// notably x86, so this routine cannot be used if these bits are needed.
+inline uint32_t FloatToBits(float Float) {
+  uint32_t Bits;
+  static_assert(sizeof(uint32_t) == sizeof(float), "Unexpected type sizes");
+  memcpy(&Bits, &Float, sizeof(Float));
+  return Bits;
+}
+
+/// A and B are either alignments or offsets. Return the minimum alignment that
+/// may be assumed after adding the two together.
+constexpr inline uint64_t MinAlign(uint64_t A, uint64_t B) {
+  // The largest power of 2 that divides both A and B.
+  //
+  // Replace "-Value" by "1+~Value" in the following commented code to avoid
+  // MSVC warning C4146
+  //    return (A | B) & -(A | B);
+  return (A | B) & (1 + ~(A | B));
+}
+
+/// Aligns \c Addr to \c Alignment bytes, rounding up.
+///
+/// Alignment should be a power of two.  This method rounds up, so
+/// alignAddr(7, 4) == 8 and alignAddr(8, 4) == 8.
+inline uintptr_t alignAddr(const void *Addr, size_t Alignment) {
+  assert(Alignment && isPowerOf2_64((uint64_t)Alignment) &&
+         "Alignment is not a power of two!");
+
+  assert((uintptr_t)Addr + Alignment - 1 >= (uintptr_t)Addr);
+
+  return (((uintptr_t)Addr + Alignment - 1) & ~(uintptr_t)(Alignment - 1));
+}
+
+/// Returns the necessary adjustment for aligning \c Ptr to \c Alignment
+/// bytes, rounding up.
+inline size_t alignmentAdjustment(const void *Ptr, size_t Alignment) {
+  return alignAddr(Ptr, Alignment) - (uintptr_t)Ptr;
+}
+
+/// Returns the next power of two (in 64-bits) that is strictly greater than A.
+/// Returns zero on overflow.
+inline uint64_t NextPowerOf2(uint64_t A) {
+  A |= (A >> 1);
+  A |= (A >> 2);
+  A |= (A >> 4);
+  A |= (A >> 8);
+  A |= (A >> 16);
+  A |= (A >> 32);
+  return A + 1;
+}
+
+/// Returns the power of two which is less than or equal to the given value.
+/// Essentially, it is a floor operation across the domain of powers of two.
+inline uint64_t PowerOf2Floor(uint64_t A) {
+  if (!A) return 0;
+  return 1ull << (63 - countLeadingZeros(A, ZB_Undefined));
+}
+
+/// Returns the power of two which is greater than or equal to the given value.
+/// Essentially, it is a ceil operation across the domain of powers of two.
+inline uint64_t PowerOf2Ceil(uint64_t A) {
+  if (!A)
+    return 0;
+  return NextPowerOf2(A - 1);
+}
+
+/// Returns the next integer (mod 2**64) that is greater than or equal to
+/// \p Value and is a multiple of \p Align. \p Align must be non-zero.
+///
+/// If non-zero \p Skew is specified, the return value will be a minimal
+/// integer that is greater than or equal to \p Value and equal to
+/// \p Align * N + \p Skew for some integer N. If \p Skew is larger than
+/// \p Align, its value is adjusted to '\p Skew mod \p Align'.
+///
+/// Examples:
+/// \code
+///   alignTo(5, 8) = 8
+///   alignTo(17, 8) = 24
+///   alignTo(~0LL, 8) = 0
+///   alignTo(321, 255) = 510
+///
+///   alignTo(5, 8, 7) = 7
+///   alignTo(17, 8, 1) = 17
+///   alignTo(~0LL, 8, 3) = 3
+///   alignTo(321, 255, 42) = 552
+/// \endcode
+inline uint64_t alignTo(uint64_t Value, uint64_t Align, uint64_t Skew = 0) {
+  assert(Align != 0u && "Align can't be 0.");
+  Skew %= Align;
+  return (Value + Align - 1 - Skew) / Align * Align + Skew;
+}
+
+/// Returns the next integer (mod 2**64) that is greater than or equal to
+/// \p Value and is a multiple of \c Align. \c Align must be non-zero.
+template <uint64_t Align> constexpr inline uint64_t alignTo(uint64_t Value) {
+  static_assert(Align != 0u, "Align must be non-zero");
+  return (Value + Align - 1) / Align * Align;
+}
+
+/// Returns the integer ceil(Numerator / Denominator).
+inline uint64_t divideCeil(uint64_t Numerator, uint64_t Denominator) {
+  return alignTo(Numerator, Denominator) / Denominator;
+}
+
+/// \c alignTo for contexts where a constant expression is required.
+/// \sa alignTo
+///
+/// \todo FIXME: remove when \c constexpr becomes really \c constexpr
+template <uint64_t Align>
+struct AlignTo {
+  static_assert(Align != 0u, "Align must be non-zero");
+  template <uint64_t Value>
+  struct from_value {
+    static const uint64_t value = (Value + Align - 1) / Align * Align;
+  };
+};
+
+/// Returns the largest uint64_t less than or equal to \p Value and is
+/// \p Skew mod \p Align. \p Align must be non-zero
+inline uint64_t alignDown(uint64_t Value, uint64_t Align, uint64_t Skew = 0) {
+  assert(Align != 0u && "Align can't be 0.");
+  Skew %= Align;
+  return (Value - Skew) / Align * Align + Skew;
+}
+
+/// Returns the offset to the next integer (mod 2**64) that is greater than
+/// or equal to \p Value and is a multiple of \p Align. \p Align must be
+/// non-zero.
+inline uint64_t OffsetToAlignment(uint64_t Value, uint64_t Align) {
+  return alignTo(Value, Align) - Value;
+}
+
+/// Sign-extend the number in the bottom B bits of X to a 32-bit integer.
+/// Requires 0 < B <= 32.
+template <unsigned B> constexpr inline int32_t SignExtend32(uint32_t X) {
+  static_assert(B > 0, "Bit width can't be 0.");
+  static_assert(B <= 32, "Bit width out of range.");
+  return int32_t(X << (32 - B)) >> (32 - B);
+}
+
+/// Sign-extend the number in the bottom B bits of X to a 32-bit integer.
+/// Requires 0 < B < 32.
+inline int32_t SignExtend32(uint32_t X, unsigned B) {
+  assert(B > 0 && "Bit width can't be 0.");
+  assert(B <= 32 && "Bit width out of range.");
+  return int32_t(X << (32 - B)) >> (32 - B);
+}
+
+/// Sign-extend the number in the bottom B bits of X to a 64-bit integer.
+/// Requires 0 < B < 64.
+template <unsigned B> constexpr inline int64_t SignExtend64(uint64_t x) {
+  static_assert(B > 0, "Bit width can't be 0.");
+  static_assert(B <= 64, "Bit width out of range.");
+  return int64_t(x << (64 - B)) >> (64 - B);
+}
+
+/// Sign-extend the number in the bottom B bits of X to a 64-bit integer.
+/// Requires 0 < B < 64.
+inline int64_t SignExtend64(uint64_t X, unsigned B) {
+  assert(B > 0 && "Bit width can't be 0.");
+  assert(B <= 64 && "Bit width out of range.");
+  return int64_t(X << (64 - B)) >> (64 - B);
+}
+
+/// Subtract two unsigned integers, X and Y, of type T and return the absolute
+/// value of the result.
+template <typename T>
+typename std::enable_if<std::is_unsigned<T>::value, T>::type
+AbsoluteDifference(T X, T Y) {
+  return std::max(X, Y) - std::min(X, Y);
+}
+
+/// Add two unsigned integers, X and Y, of type T.  Clamp the result to the
+/// maximum representable value of T on overflow.  ResultOverflowed indicates if
+/// the result is larger than the maximum representable value of type T.
+template <typename T>
+typename std::enable_if<std::is_unsigned<T>::value, T>::type
+SaturatingAdd(T X, T Y, bool *ResultOverflowed = nullptr) {
+  bool Dummy;
+  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
+  // Hacker's Delight, p. 29
+  T Z = X + Y;
+  Overflowed = (Z < X || Z < Y);
+  if (Overflowed)
+    return std::numeric_limits<T>::max();
+  else
+    return Z;
+}
+
+/// Multiply two unsigned integers, X and Y, of type T.  Clamp the result to the
+/// maximum representable value of T on overflow.  ResultOverflowed indicates if
+/// the result is larger than the maximum representable value of type T.
+template <typename T>
+typename std::enable_if<std::is_unsigned<T>::value, T>::type
+SaturatingMultiply(T X, T Y, bool *ResultOverflowed = nullptr) {
+  bool Dummy;
+  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
+
+  // Hacker's Delight, p. 30 has a different algorithm, but we don't use that
+  // because it fails for uint16_t (where multiplication can have undefined
+  // behavior due to promotion to int), and requires a division in addition
+  // to the multiplication.
+
+  Overflowed = false;
+
+  // Log2(Z) would be either Log2Z or Log2Z + 1.
+  // Special case: if X or Y is 0, Log2_64 gives -1, and Log2Z
+  // will necessarily be less than Log2Max as desired.
+  int Log2Z = Log2_64(X) + Log2_64(Y);
+  const T Max = std::numeric_limits<T>::max();
+  int Log2Max = Log2_64(Max);
+  if (Log2Z < Log2Max) {
+    return X * Y;
+  }
+  if (Log2Z > Log2Max) {
+    Overflowed = true;
+    return Max;
+  }
+
+  // We're going to use the top bit, and maybe overflow one
+  // bit past it. Multiply all but the bottom bit then add
+  // that on at the end.
+  T Z = (X >> 1) * Y;
+  if (Z & ~(Max >> 1)) {
+    Overflowed = true;
+    return Max;
+  }
+  Z <<= 1;
+  if (X & 1)
+    return SaturatingAdd(Z, Y, ResultOverflowed);
+
+  return Z;
+}
+
+/// Multiply two unsigned integers, X and Y, and add the unsigned integer, A to
+/// the product. Clamp the result to the maximum representable value of T on
+/// overflow. ResultOverflowed indicates if the result is larger than the
+/// maximum representable value of type T.
+template <typename T>
+typename std::enable_if<std::is_unsigned<T>::value, T>::type
+SaturatingMultiplyAdd(T X, T Y, T A, bool *ResultOverflowed = nullptr) {
+  bool Dummy;
+  bool &Overflowed = ResultOverflowed ? *ResultOverflowed : Dummy;
+
+  T Product = SaturatingMultiply(X, Y, &Overflowed);
+  if (Overflowed)
+    return Product;
+
+  return SaturatingAdd(A, Product, &Overflowed);
+}
+
+} // namespace wpi
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NativeFormatting.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NativeFormatting.h
new file mode 100644
index 0000000..3407e75
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NativeFormatting.h
@@ -0,0 +1,49 @@
+//===- NativeFormatting.h - Low level formatting helpers ---------*- C++-*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_NATIVE_FORMATTING_H
+#define WPIUTIL_WPI_NATIVE_FORMATTING_H
+
+#include "wpi/optional.h"
+#include "wpi/raw_ostream.h"
+
+#include <cstdint>
+
+namespace wpi {
+enum class FloatStyle { Exponent, ExponentUpper, Fixed, Percent };
+enum class IntegerStyle {
+  Integer,
+  Number,
+};
+enum class HexPrintStyle { Upper, Lower, PrefixUpper, PrefixLower };
+
+size_t getDefaultPrecision(FloatStyle Style);
+
+bool isPrefixedHexStyle(HexPrintStyle S);
+
+void write_integer(raw_ostream &S, unsigned int N, size_t MinDigits,
+                   IntegerStyle Style);
+void write_integer(raw_ostream &S, int N, size_t MinDigits, IntegerStyle Style);
+void write_integer(raw_ostream &S, unsigned long N, size_t MinDigits,
+                   IntegerStyle Style);
+void write_integer(raw_ostream &S, long N, size_t MinDigits,
+                   IntegerStyle Style);
+void write_integer(raw_ostream &S, unsigned long long N, size_t MinDigits,
+                   IntegerStyle Style);
+void write_integer(raw_ostream &S, long long N, size_t MinDigits,
+                   IntegerStyle Style);
+
+void write_hex(raw_ostream &S, uint64_t N, HexPrintStyle Style,
+               optional<size_t> Width = nullopt);
+void write_double(raw_ostream &S, double D, FloatStyle Style,
+                  optional<size_t> Precision = nullopt);
+}
+
+#endif
+
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NetworkAcceptor.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NetworkAcceptor.h
new file mode 100644
index 0000000..dd09e2d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NetworkAcceptor.h
@@ -0,0 +1,32 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_NETWORKACCEPTOR_H_
+#define WPIUTIL_WPI_NETWORKACCEPTOR_H_
+
+#include <memory>
+
+#include "wpi/NetworkStream.h"
+
+namespace wpi {
+
+class NetworkAcceptor {
+ public:
+  NetworkAcceptor() = default;
+  virtual ~NetworkAcceptor() = default;
+
+  virtual int start() = 0;
+  virtual void shutdown() = 0;
+  virtual std::unique_ptr<NetworkStream> accept() = 0;
+
+  NetworkAcceptor(const NetworkAcceptor&) = delete;
+  NetworkAcceptor& operator=(const NetworkAcceptor&) = delete;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_NETWORKACCEPTOR_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NetworkStream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NetworkStream.h
new file mode 100644
index 0000000..1177167
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/NetworkStream.h
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_NETWORKSTREAM_H_
+#define WPIUTIL_WPI_NETWORKSTREAM_H_
+
+#include <cstddef>
+
+#include "wpi/StringRef.h"
+
+namespace wpi {
+
+class NetworkStream {
+ public:
+  NetworkStream() = default;
+  virtual ~NetworkStream() = default;
+
+  enum Error {
+    kConnectionClosed = 0,
+    kConnectionReset = -1,
+    kConnectionTimedOut = -2,
+    kWouldBlock = -3
+  };
+
+  virtual size_t send(const char* buffer, size_t len, Error* err) = 0;
+  virtual size_t receive(char* buffer, size_t len, Error* err,
+                         int timeout = 0) = 0;
+  virtual void close() = 0;
+
+  virtual StringRef getPeerIP() const = 0;
+  virtual int getPeerPort() const = 0;
+  virtual void setNoDelay() = 0;
+
+  // returns false on failure
+  virtual bool setBlocking(bool enabled) = 0;
+  virtual int getNativeHandle() const = 0;
+
+  NetworkStream(const NetworkStream&) = delete;
+  NetworkStream& operator=(const NetworkStream&) = delete;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_NETWORKSTREAM_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Path.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Path.h
new file mode 100644
index 0000000..8f62369
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Path.h
@@ -0,0 +1,474 @@
+//===- llvm/Support/Path.h - Path Operating System Concept ------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file declares the wpi::sys::path namespace. It is designed after
+// TR2/boost filesystem (v3), but modified to remove exception handling and the
+// path class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_PATH_H_
+#define WPIUTIL_WPI_PATH_H_
+
+#include "wpi/Twine.h"
+#include "wpi/iterator.h"
+#include <cstdint>
+#include <iterator>
+
+namespace wpi {
+namespace sys {
+namespace path {
+
+enum class Style { windows, posix, native };
+
+/// @name Lexical Component Iterator
+/// @{
+
+/// Path iterator.
+///
+/// This is an input iterator that iterates over the individual components in
+/// \a path. The traversal order is as follows:
+/// * The root-name element, if present.
+/// * The root-directory element, if present.
+/// * Each successive filename element, if present.
+/// * Dot, if one or more trailing non-root slash characters are present.
+/// Traversing backwards is possible with \a reverse_iterator
+///
+/// Iteration examples. Each component is separated by ',':
+/// @code
+///   /          => /
+///   /foo       => /,foo
+///   foo/       => foo,.
+///   /foo/bar   => /,foo,bar
+///   ../        => ..,.
+///   C:\foo\bar => C:,/,foo,bar
+/// @endcode
+class const_iterator
+    : public iterator_facade_base<const_iterator, std::input_iterator_tag,
+                                  const StringRef> {
+  StringRef Path;      ///< The entire path.
+  StringRef Component; ///< The current component. Not necessarily in Path.
+  size_t    Position;  ///< The iterators current position within Path.
+  Style S;             ///< The path style to use.
+
+  // An end iterator has Position = Path.size() + 1.
+  friend const_iterator begin(StringRef path, Style style);
+  friend const_iterator end(StringRef path);
+
+public:
+  reference operator*() const { return Component; }
+  const_iterator &operator++();    // preincrement
+  bool operator==(const const_iterator &RHS) const;
+
+  /// Difference in bytes between this and RHS.
+  ptrdiff_t operator-(const const_iterator &RHS) const;
+};
+
+/// Reverse path iterator.
+///
+/// This is an input iterator that iterates over the individual components in
+/// \a path in reverse order. The traversal order is exactly reversed from that
+/// of \a const_iterator
+class reverse_iterator
+    : public iterator_facade_base<reverse_iterator, std::input_iterator_tag,
+                                  const StringRef> {
+  StringRef Path;      ///< The entire path.
+  StringRef Component; ///< The current component. Not necessarily in Path.
+  size_t    Position;  ///< The iterators current position within Path.
+  Style S;             ///< The path style to use.
+
+  friend reverse_iterator rbegin(StringRef path, Style style);
+  friend reverse_iterator rend(StringRef path);
+
+public:
+  reference operator*() const { return Component; }
+  reverse_iterator &operator++();    // preincrement
+  bool operator==(const reverse_iterator &RHS) const;
+
+  /// Difference in bytes between this and RHS.
+  ptrdiff_t operator-(const reverse_iterator &RHS) const;
+};
+
+/// Get begin iterator over \a path.
+/// @param path Input path.
+/// @returns Iterator initialized with the first component of \a path.
+const_iterator begin(StringRef path, Style style = Style::native);
+
+/// Get end iterator over \a path.
+/// @param path Input path.
+/// @returns Iterator initialized to the end of \a path.
+const_iterator end(StringRef path);
+
+/// Get reverse begin iterator over \a path.
+/// @param path Input path.
+/// @returns Iterator initialized with the first reverse component of \a path.
+reverse_iterator rbegin(StringRef path, Style style = Style::native);
+
+/// Get reverse end iterator over \a path.
+/// @param path Input path.
+/// @returns Iterator initialized to the reverse end of \a path.
+reverse_iterator rend(StringRef path);
+
+/// @}
+/// @name Lexical Modifiers
+/// @{
+
+/// Remove the last component from \a path unless it is the root dir.
+///
+/// @code
+///   directory/filename.cpp => directory/
+///   directory/             => directory
+///   filename.cpp           => <empty>
+///   /                      => /
+/// @endcode
+///
+/// @param path A path that is modified to not have a file component.
+void remove_filename(SmallVectorImpl<char> &path, Style style = Style::native);
+
+/// Replace the file extension of \a path with \a extension.
+///
+/// @code
+///   ./filename.cpp => ./filename.extension
+///   ./filename     => ./filename.extension
+///   ./             => ./.extension
+/// @endcode
+///
+/// @param path A path that has its extension replaced with \a extension.
+/// @param extension The extension to be added. It may be empty. It may also
+///                  optionally start with a '.', if it does not, one will be
+///                  prepended.
+void replace_extension(SmallVectorImpl<char> &path, const Twine &extension,
+                       Style style = Style::native);
+
+/// Replace matching path prefix with another path.
+///
+/// @code
+///   /foo, /old, /new => /foo
+///   /old/foo, /old, /new => /new/foo
+///   /foo, <empty>, /new => /new/foo
+///   /old/foo, /old, <empty> => /foo
+/// @endcode
+///
+/// @param Path If \a Path starts with \a OldPrefix modify to instead
+///        start with \a NewPrefix.
+/// @param OldPrefix The path prefix to strip from \a Path.
+/// @param NewPrefix The path prefix to replace \a NewPrefix with.
+void replace_path_prefix(SmallVectorImpl<char> &Path,
+                         const StringRef &OldPrefix, const StringRef &NewPrefix,
+                         Style style = Style::native);
+
+/// Append to path.
+///
+/// @code
+///   /foo  + bar/f => /foo/bar/f
+///   /foo/ + bar/f => /foo/bar/f
+///   foo   + bar/f => foo/bar/f
+/// @endcode
+///
+/// @param path Set to \a path + \a component.
+/// @param a The component to be appended to \a path.
+void append(SmallVectorImpl<char> &path, const Twine &a,
+                                         const Twine &b = "",
+                                         const Twine &c = "",
+                                         const Twine &d = "");
+
+void append(SmallVectorImpl<char> &path, Style style, const Twine &a,
+            const Twine &b = "", const Twine &c = "", const Twine &d = "");
+
+/// Append to path.
+///
+/// @code
+///   /foo  + [bar,f] => /foo/bar/f
+///   /foo/ + [bar,f] => /foo/bar/f
+///   foo   + [bar,f] => foo/bar/f
+/// @endcode
+///
+/// @param path Set to \a path + [\a begin, \a end).
+/// @param begin Start of components to append.
+/// @param end One past the end of components to append.
+void append(SmallVectorImpl<char> &path, const_iterator begin,
+            const_iterator end, Style style = Style::native);
+
+/// @}
+/// @name Transforms (or some other better name)
+/// @{
+
+/// Convert path to the native form. This is used to give paths to users and
+/// operating system calls in the platform's normal way. For example, on Windows
+/// all '/' are converted to '\'.
+///
+/// @param path A path that is transformed to native format.
+/// @param result Holds the result of the transformation.
+void native(const Twine &path, SmallVectorImpl<char> &result,
+            Style style = Style::native);
+
+/// Convert path to the native form in place. This is used to give paths to
+/// users and operating system calls in the platform's normal way. For example,
+/// on Windows all '/' are converted to '\'.
+///
+/// @param path A path that is transformed to native format.
+void native(SmallVectorImpl<char> &path, Style style = Style::native);
+
+/// Replaces backslashes with slashes if Windows.
+///
+/// @param path processed path
+/// @result The result of replacing backslashes with forward slashes if Windows.
+/// On Unix, this function is a no-op because backslashes are valid path
+/// chracters.
+std::string convert_to_slash(StringRef path, Style style = Style::native);
+
+/// @}
+/// @name Lexical Observers
+/// @{
+
+/// Get root name.
+///
+/// @code
+///   //net/hello => //net
+///   c:/hello    => c: (on Windows, on other platforms nothing)
+///   /hello      => <empty>
+/// @endcode
+///
+/// @param path Input path.
+/// @result The root name of \a path if it has one, otherwise "".
+StringRef root_name(StringRef path, Style style = Style::native);
+
+/// Get root directory.
+///
+/// @code
+///   /goo/hello => /
+///   c:/hello   => /
+///   d/file.txt => <empty>
+/// @endcode
+///
+/// @param path Input path.
+/// @result The root directory of \a path if it has one, otherwise
+///               "".
+StringRef root_directory(StringRef path, Style style = Style::native);
+
+/// Get root path.
+///
+/// Equivalent to root_name + root_directory.
+///
+/// @param path Input path.
+/// @result The root path of \a path if it has one, otherwise "".
+StringRef root_path(StringRef path, Style style = Style::native);
+
+/// Get relative path.
+///
+/// @code
+///   C:\hello\world => hello\world
+///   foo/bar        => foo/bar
+///   /foo/bar       => foo/bar
+/// @endcode
+///
+/// @param path Input path.
+/// @result The path starting after root_path if one exists, otherwise "".
+StringRef relative_path(StringRef path, Style style = Style::native);
+
+/// Get parent path.
+///
+/// @code
+///   /          => <empty>
+///   /foo       => /
+///   foo/../bar => foo/..
+/// @endcode
+///
+/// @param path Input path.
+/// @result The parent path of \a path if one exists, otherwise "".
+StringRef parent_path(StringRef path, Style style = Style::native);
+
+/// Get filename.
+///
+/// @code
+///   /foo.txt    => foo.txt
+///   .          => .
+///   ..         => ..
+///   /          => /
+/// @endcode
+///
+/// @param path Input path.
+/// @result The filename part of \a path. This is defined as the last component
+///         of \a path.
+StringRef filename(StringRef path, Style style = Style::native);
+
+/// Get stem.
+///
+/// If filename contains a dot but not solely one or two dots, result is the
+/// substring of filename ending at (but not including) the last dot. Otherwise
+/// it is filename.
+///
+/// @code
+///   /foo/bar.txt => bar
+///   /foo/bar     => bar
+///   /foo/.txt    => <empty>
+///   /foo/.       => .
+///   /foo/..      => ..
+/// @endcode
+///
+/// @param path Input path.
+/// @result The stem of \a path.
+StringRef stem(StringRef path, Style style = Style::native);
+
+/// Get extension.
+///
+/// If filename contains a dot but not solely one or two dots, result is the
+/// substring of filename starting at (and including) the last dot, and ending
+/// at the end of \a path. Otherwise "".
+///
+/// @code
+///   /foo/bar.txt => .txt
+///   /foo/bar     => <empty>
+///   /foo/.txt    => .txt
+/// @endcode
+///
+/// @param path Input path.
+/// @result The extension of \a path.
+StringRef extension(StringRef path, Style style = Style::native);
+
+/// Check whether the given char is a path separator on the host OS.
+///
+/// @param value a character
+/// @result true if \a value is a path separator character on the host OS
+bool is_separator(char value, Style style = Style::native);
+
+/// Return the preferred separator for this platform.
+///
+/// @result StringRef of the preferred separator, null-terminated.
+StringRef get_separator(Style style = Style::native);
+
+/// Get the typical temporary directory for the system, e.g.,
+/// "/var/tmp" or "C:/TEMP"
+///
+/// @param erasedOnReboot Whether to favor a path that is erased on reboot
+/// rather than one that potentially persists longer. This parameter will be
+/// ignored if the user or system has set the typical environment variable
+/// (e.g., TEMP on Windows, TMPDIR on *nix) to specify a temporary directory.
+///
+/// @param result Holds the resulting path name.
+void system_temp_directory(bool erasedOnReboot, SmallVectorImpl<char> &result);
+
+/// Get the user's home directory.
+///
+/// @param result Holds the resulting path name.
+/// @result True if a home directory is set, false otherwise.
+bool home_directory(SmallVectorImpl<char> &result);
+
+/// Get the user's cache directory.
+///
+/// Expect the resulting path to be a directory shared with other
+/// applications/services used by the user. Params \p Path1 to \p Path3 can be
+/// used to append additional directory names to the resulting path. Recommended
+/// pattern is <user_cache_directory>/<vendor>/<application>.
+///
+/// @param Result Holds the resulting path.
+/// @param Path1 Additional path to be appended to the user's cache directory
+/// path. "" can be used to append nothing.
+/// @param Path2 Second additional path to be appended.
+/// @param Path3 Third additional path to be appended.
+/// @result True if a cache directory path is set, false otherwise.
+bool user_cache_directory(SmallVectorImpl<char> &Result, const Twine &Path1,
+                          const Twine &Path2 = "", const Twine &Path3 = "");
+
+/// Has root name?
+///
+/// root_name != ""
+///
+/// @param path Input path.
+/// @result True if the path has a root name, false otherwise.
+bool has_root_name(const Twine &path, Style style = Style::native);
+
+/// Has root directory?
+///
+/// root_directory != ""
+///
+/// @param path Input path.
+/// @result True if the path has a root directory, false otherwise.
+bool has_root_directory(const Twine &path, Style style = Style::native);
+
+/// Has root path?
+///
+/// root_path != ""
+///
+/// @param path Input path.
+/// @result True if the path has a root path, false otherwise.
+bool has_root_path(const Twine &path, Style style = Style::native);
+
+/// Has relative path?
+///
+/// relative_path != ""
+///
+/// @param path Input path.
+/// @result True if the path has a relative path, false otherwise.
+bool has_relative_path(const Twine &path, Style style = Style::native);
+
+/// Has parent path?
+///
+/// parent_path != ""
+///
+/// @param path Input path.
+/// @result True if the path has a parent path, false otherwise.
+bool has_parent_path(const Twine &path, Style style = Style::native);
+
+/// Has filename?
+///
+/// filename != ""
+///
+/// @param path Input path.
+/// @result True if the path has a filename, false otherwise.
+bool has_filename(const Twine &path, Style style = Style::native);
+
+/// Has stem?
+///
+/// stem != ""
+///
+/// @param path Input path.
+/// @result True if the path has a stem, false otherwise.
+bool has_stem(const Twine &path, Style style = Style::native);
+
+/// Has extension?
+///
+/// extension != ""
+///
+/// @param path Input path.
+/// @result True if the path has a extension, false otherwise.
+bool has_extension(const Twine &path, Style style = Style::native);
+
+/// Is path absolute?
+///
+/// @param path Input path.
+/// @result True if the path is absolute, false if it is not.
+bool is_absolute(const Twine &path, Style style = Style::native);
+
+/// Is path relative?
+///
+/// @param path Input path.
+/// @result True if the path is relative, false if it is not.
+bool is_relative(const Twine &path, Style style = Style::native);
+
+/// Remove redundant leading "./" pieces and consecutive separators.
+///
+/// @param path Input path.
+/// @result The cleaned-up \a path.
+StringRef remove_leading_dotslash(StringRef path, Style style = Style::native);
+
+/// In-place remove any './' and optionally '../' components from a path.
+///
+/// @param path processed path
+/// @param remove_dot_dot specify if '../' (except for leading "../") should be
+/// removed
+/// @result True if path was changed
+bool remove_dots(SmallVectorImpl<char> &path, bool remove_dot_dot = false,
+                 Style style = Style::native);
+
+} // end namespace path
+} // end namespace sys
+} // end namespace wpi
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/PointerLikeTypeTraits.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/PointerLikeTypeTraits.h
new file mode 100644
index 0000000..9098954
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/PointerLikeTypeTraits.h
@@ -0,0 +1,117 @@
+//===- llvm/Support/PointerLikeTypeTraits.h - Pointer Traits ----*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the PointerLikeTypeTraits class.  This allows data
+// structures to reason about pointers and other things that are pointer sized.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_POINTERLIKETYPETRAITS_H
+#define WPIUTIL_WPI_POINTERLIKETYPETRAITS_H
+
+#include <cstdint>
+#include <cstdlib>
+#include <type_traits>
+
+namespace wpi {
+
+/// A traits type that is used to handle pointer types and things that are just
+/// wrappers for pointers as a uniform entity.
+template <typename T> struct PointerLikeTypeTraits;
+
+namespace detail {
+/// A tiny meta function to compute the log2 of a compile time constant.
+template <size_t N>
+struct ConstantLog2
+    : std::integral_constant<size_t, ConstantLog2<N / 2>::value + 1> {};
+template <> struct ConstantLog2<1> : std::integral_constant<size_t, 0> {};
+
+// Provide a trait to check if T is pointer-like.
+template <typename T, typename U = void> struct HasPointerLikeTypeTraits {
+  static const bool value = false;
+};
+
+// sizeof(T) is valid only for a complete T.
+template <typename T> struct HasPointerLikeTypeTraits<
+  T, decltype((sizeof(PointerLikeTypeTraits<T>) + sizeof(T)), void())> {
+  static const bool value = true;
+};
+
+template <typename T> struct IsPointerLike {
+  static const bool value = HasPointerLikeTypeTraits<T>::value;
+};
+
+template <typename T> struct IsPointerLike<T *> {
+  static const bool value = true;
+};
+} // namespace detail
+
+// Provide PointerLikeTypeTraits for non-cvr pointers.
+template <typename T> struct PointerLikeTypeTraits<T *> {
+  static inline void *getAsVoidPointer(T *P) { return P; }
+  static inline T *getFromVoidPointer(void *P) { return static_cast<T *>(P); }
+
+  enum { NumLowBitsAvailable = detail::ConstantLog2<alignof(T)>::value };
+};
+
+template <> struct PointerLikeTypeTraits<void *> {
+  static inline void *getAsVoidPointer(void *P) { return P; }
+  static inline void *getFromVoidPointer(void *P) { return P; }
+
+  /// Note, we assume here that void* is related to raw malloc'ed memory and
+  /// that malloc returns objects at least 4-byte aligned. However, this may be
+  /// wrong, or pointers may be from something other than malloc. In this case,
+  /// you should specify a real typed pointer or avoid this template.
+  ///
+  /// All clients should use assertions to do a run-time check to ensure that
+  /// this is actually true.
+  enum { NumLowBitsAvailable = 2 };
+};
+
+// Provide PointerLikeTypeTraits for const things.
+template <typename T> struct PointerLikeTypeTraits<const T> {
+  typedef PointerLikeTypeTraits<T> NonConst;
+
+  static inline const void *getAsVoidPointer(const T P) {
+    return NonConst::getAsVoidPointer(P);
+  }
+  static inline const T getFromVoidPointer(const void *P) {
+    return NonConst::getFromVoidPointer(const_cast<void *>(P));
+  }
+  enum { NumLowBitsAvailable = NonConst::NumLowBitsAvailable };
+};
+
+// Provide PointerLikeTypeTraits for const pointers.
+template <typename T> struct PointerLikeTypeTraits<const T *> {
+  typedef PointerLikeTypeTraits<T *> NonConst;
+
+  static inline const void *getAsVoidPointer(const T *P) {
+    return NonConst::getAsVoidPointer(const_cast<T *>(P));
+  }
+  static inline const T *getFromVoidPointer(const void *P) {
+    return NonConst::getFromVoidPointer(const_cast<void *>(P));
+  }
+  enum { NumLowBitsAvailable = NonConst::NumLowBitsAvailable };
+};
+
+// Provide PointerLikeTypeTraits for uintptr_t.
+template <> struct PointerLikeTypeTraits<uintptr_t> {
+  static inline void *getAsVoidPointer(uintptr_t P) {
+    return reinterpret_cast<void *>(P);
+  }
+  static inline uintptr_t getFromVoidPointer(void *P) {
+    return reinterpret_cast<uintptr_t>(P);
+  }
+  // No bits are available!
+  enum { NumLowBitsAvailable = 0 };
+};
+
+} // end namespace wpi
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/PriorityQueue.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/PriorityQueue.h
new file mode 100644
index 0000000..37585a3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/PriorityQueue.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_PRIORITYQUEUE_H_
+#define WPIUTIL_WPI_PRIORITYQUEUE_H_
+
+#include <algorithm>
+#include <functional>
+#include <queue>
+#include <vector>
+
+namespace wpi {
+
+/**
+ * This class adds a method for removing all elements from the priority queue
+ * matching the given value.
+ */
+template <class T, class Container = std::vector<T>,
+          class Compare = std::less<typename Container::value_type>>
+class PriorityQueue : public std::priority_queue<T, Container, Compare> {
+ public:
+  bool remove(const T& value) {
+    auto it = std::find(this->c.begin(), this->c.end(), value);
+    if (it != this->c.end()) {
+      this->c.erase(it);
+      std::make_heap(this->c.begin(), this->c.end(), this->comp);
+      return true;
+    } else {
+      return false;
+    }
+  }
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_PRIORITYQUEUE_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/STLExtras.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/STLExtras.h
new file mode 100644
index 0000000..b020222
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/STLExtras.h
@@ -0,0 +1,1222 @@
+//===- llvm/ADT/STLExtras.h - Useful STL related functions ------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file contains some templates that are useful if you are working with the
+// STL at all.
+//
+// No library is required when using these functions.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_STLEXTRAS_H
+#define WPIUTIL_WPI_STLEXTRAS_H
+
+#include "wpi/SmallVector.h"
+#include "wpi/iterator.h"
+#include "wpi/iterator_range.h"
+#include "wpi/optional.h"
+#include <algorithm>
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <cstdlib>
+#include <functional>
+#include <initializer_list>
+#include <iterator>
+#include <limits>
+#include <memory>
+#include <tuple>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+// Only used by compiler if both template types are the same.  Useful when
+// using SFINAE to test for the existence of member functions.
+template <typename T, T> struct SameType;
+
+namespace detail {
+
+template <typename RangeT>
+using IterOfRange = decltype(std::begin(std::declval<RangeT &>()));
+
+template <typename RangeT>
+using ValueOfRange = typename std::remove_reference<decltype(
+    *std::begin(std::declval<RangeT &>()))>::type;
+
+} // end namespace detail
+
+//===----------------------------------------------------------------------===//
+//     Extra additions to <functional>
+//===----------------------------------------------------------------------===//
+
+template <class Ty> struct identity {
+  using argument_type = Ty;
+
+  Ty &operator()(Ty &self) const {
+    return self;
+  }
+  const Ty &operator()(const Ty &self) const {
+    return self;
+  }
+};
+
+template <class Ty> struct less_ptr {
+  bool operator()(const Ty* left, const Ty* right) const {
+    return *left < *right;
+  }
+};
+
+template <class Ty> struct greater_ptr {
+  bool operator()(const Ty* left, const Ty* right) const {
+    return *right < *left;
+  }
+};
+
+/// An efficient, type-erasing, non-owning reference to a callable. This is
+/// intended for use as the type of a function parameter that is not used
+/// after the function in question returns.
+///
+/// This class does not own the callable, so it is not in general safe to store
+/// a function_ref.
+template<typename Fn> class function_ref;
+
+template<typename Ret, typename ...Params>
+class function_ref<Ret(Params...)> {
+  Ret (*callback)(intptr_t callable, Params ...params) = nullptr;
+  intptr_t callable;
+
+  template<typename Callable>
+  static Ret callback_fn(intptr_t callable, Params ...params) {
+    return (*reinterpret_cast<Callable*>(callable))(
+        std::forward<Params>(params)...);
+  }
+
+public:
+  function_ref() = default;
+  function_ref(std::nullptr_t) {}
+
+  template <typename Callable>
+  function_ref(Callable &&callable,
+               typename std::enable_if<
+                   !std::is_same<typename std::remove_reference<Callable>::type,
+                                 function_ref>::value>::type * = nullptr)
+      : callback(callback_fn<typename std::remove_reference<Callable>::type>),
+        callable(reinterpret_cast<intptr_t>(&callable)) {}
+
+  Ret operator()(Params ...params) const {
+    return callback(callable, std::forward<Params>(params)...);
+  }
+
+  explicit operator bool() const { return callback; }
+};
+
+// deleter - Very very very simple method that is used to invoke operator
+// delete on something.  It is used like this:
+//
+//   for_each(V.begin(), B.end(), deleter<Interval>);
+template <class T>
+inline void deleter(T *Ptr) {
+  delete Ptr;
+}
+
+//===----------------------------------------------------------------------===//
+//     Extra additions to <iterator>
+//===----------------------------------------------------------------------===//
+
+namespace adl_detail {
+
+using std::begin;
+
+template <typename ContainerTy>
+auto adl_begin(ContainerTy &&container)
+    -> decltype(begin(std::forward<ContainerTy>(container))) {
+  return begin(std::forward<ContainerTy>(container));
+}
+
+using std::end;
+
+template <typename ContainerTy>
+auto adl_end(ContainerTy &&container)
+    -> decltype(end(std::forward<ContainerTy>(container))) {
+  return end(std::forward<ContainerTy>(container));
+}
+
+using std::swap;
+
+template <typename T>
+void adl_swap(T &&lhs, T &&rhs) noexcept(noexcept(swap(std::declval<T>(),
+                                                       std::declval<T>()))) {
+  swap(std::forward<T>(lhs), std::forward<T>(rhs));
+}
+
+} // end namespace adl_detail
+
+template <typename ContainerTy>
+auto adl_begin(ContainerTy &&container)
+    -> decltype(adl_detail::adl_begin(std::forward<ContainerTy>(container))) {
+  return adl_detail::adl_begin(std::forward<ContainerTy>(container));
+}
+
+template <typename ContainerTy>
+auto adl_end(ContainerTy &&container)
+    -> decltype(adl_detail::adl_end(std::forward<ContainerTy>(container))) {
+  return adl_detail::adl_end(std::forward<ContainerTy>(container));
+}
+
+template <typename T>
+void adl_swap(T &&lhs, T &&rhs) noexcept(
+    noexcept(adl_detail::adl_swap(std::declval<T>(), std::declval<T>()))) {
+  adl_detail::adl_swap(std::forward<T>(lhs), std::forward<T>(rhs));
+}
+
+// mapped_iterator - This is a simple iterator adapter that causes a function to
+// be applied whenever operator* is invoked on the iterator.
+
+template <typename ItTy, typename FuncTy,
+          typename FuncReturnTy =
+            decltype(std::declval<FuncTy>()(*std::declval<ItTy>()))>
+class mapped_iterator
+    : public iterator_adaptor_base<
+             mapped_iterator<ItTy, FuncTy>, ItTy,
+             typename std::iterator_traits<ItTy>::iterator_category,
+             typename std::remove_reference<FuncReturnTy>::type> {
+public:
+  mapped_iterator(ItTy U, FuncTy F)
+    : mapped_iterator::iterator_adaptor_base(std::move(U)), F(std::move(F)) {}
+
+  ItTy getCurrent() { return this->I; }
+
+  FuncReturnTy operator*() { return F(*this->I); }
+
+private:
+  FuncTy F;
+};
+
+// map_iterator - Provide a convenient way to create mapped_iterators, just like
+// make_pair is useful for creating pairs...
+template <class ItTy, class FuncTy>
+inline mapped_iterator<ItTy, FuncTy> map_iterator(ItTy I, FuncTy F) {
+  return mapped_iterator<ItTy, FuncTy>(std::move(I), std::move(F));
+}
+
+/// Helper to determine if type T has a member called rbegin().
+template <typename Ty> class has_rbegin_impl {
+  using yes = char[1];
+  using no = char[2];
+
+  template <typename Inner>
+  static yes& test(Inner *I, decltype(I->rbegin()) * = nullptr);
+
+  template <typename>
+  static no& test(...);
+
+public:
+  static const bool value = sizeof(test<Ty>(nullptr)) == sizeof(yes);
+};
+
+/// Metafunction to determine if T& or T has a member called rbegin().
+template <typename Ty>
+struct has_rbegin : has_rbegin_impl<typename std::remove_reference<Ty>::type> {
+};
+
+// Returns an iterator_range over the given container which iterates in reverse.
+// Note that the container must have rbegin()/rend() methods for this to work.
+template <typename ContainerTy>
+auto reverse(ContainerTy &&C,
+             typename std::enable_if<has_rbegin<ContainerTy>::value>::type * =
+                 nullptr) -> decltype(make_range(C.rbegin(), C.rend())) {
+  return make_range(C.rbegin(), C.rend());
+}
+
+// Returns a std::reverse_iterator wrapped around the given iterator.
+template <typename IteratorTy>
+std::reverse_iterator<IteratorTy> make_reverse_iterator(IteratorTy It) {
+  return std::reverse_iterator<IteratorTy>(It);
+}
+
+// Returns an iterator_range over the given container which iterates in reverse.
+// Note that the container must have begin()/end() methods which return
+// bidirectional iterators for this to work.
+template <typename ContainerTy>
+auto reverse(
+    ContainerTy &&C,
+    typename std::enable_if<!has_rbegin<ContainerTy>::value>::type * = nullptr)
+    -> decltype(make_range(wpi::make_reverse_iterator(std::end(C)),
+                           wpi::make_reverse_iterator(std::begin(C)))) {
+  return make_range(wpi::make_reverse_iterator(std::end(C)),
+                    wpi::make_reverse_iterator(std::begin(C)));
+}
+
+/// An iterator adaptor that filters the elements of given inner iterators.
+///
+/// The predicate parameter should be a callable object that accepts the wrapped
+/// iterator's reference type and returns a bool. When incrementing or
+/// decrementing the iterator, it will call the predicate on each element and
+/// skip any where it returns false.
+///
+/// \code
+///   int A[] = { 1, 2, 3, 4 };
+///   auto R = make_filter_range(A, [](int N) { return N % 2 == 1; });
+///   // R contains { 1, 3 }.
+/// \endcode
+///
+/// Note: filter_iterator_base implements support for forward iteration.
+/// filter_iterator_impl exists to provide support for bidirectional iteration,
+/// conditional on whether the wrapped iterator supports it.
+template <typename WrappedIteratorT, typename PredicateT, typename IterTag>
+class filter_iterator_base
+    : public iterator_adaptor_base<
+          filter_iterator_base<WrappedIteratorT, PredicateT, IterTag>,
+          WrappedIteratorT,
+          typename std::common_type<
+              IterTag, typename std::iterator_traits<
+                           WrappedIteratorT>::iterator_category>::type> {
+  using BaseT = iterator_adaptor_base<
+      filter_iterator_base<WrappedIteratorT, PredicateT, IterTag>,
+      WrappedIteratorT,
+      typename std::common_type<
+          IterTag, typename std::iterator_traits<
+                       WrappedIteratorT>::iterator_category>::type>;
+
+protected:
+  WrappedIteratorT End;
+  PredicateT Pred;
+
+  void findNextValid() {
+    while (this->I != End && !Pred(*this->I))
+      BaseT::operator++();
+  }
+
+  // Construct the iterator. The begin iterator needs to know where the end
+  // is, so that it can properly stop when it gets there. The end iterator only
+  // needs the predicate to support bidirectional iteration.
+  filter_iterator_base(WrappedIteratorT Begin, WrappedIteratorT End,
+                       PredicateT Pred)
+      : BaseT(Begin), End(End), Pred(Pred) {
+    findNextValid();
+  }
+
+public:
+  using BaseT::operator++;
+
+  filter_iterator_base &operator++() {
+    BaseT::operator++();
+    findNextValid();
+    return *this;
+  }
+};
+
+/// Specialization of filter_iterator_base for forward iteration only.
+template <typename WrappedIteratorT, typename PredicateT,
+          typename IterTag = std::forward_iterator_tag>
+class filter_iterator_impl
+    : public filter_iterator_base<WrappedIteratorT, PredicateT, IterTag> {
+  using BaseT = filter_iterator_base<WrappedIteratorT, PredicateT, IterTag>;
+
+public:
+  filter_iterator_impl(WrappedIteratorT Begin, WrappedIteratorT End,
+                       PredicateT Pred)
+      : BaseT(Begin, End, Pred) {}
+};
+
+/// Specialization of filter_iterator_base for bidirectional iteration.
+template <typename WrappedIteratorT, typename PredicateT>
+class filter_iterator_impl<WrappedIteratorT, PredicateT,
+                           std::bidirectional_iterator_tag>
+    : public filter_iterator_base<WrappedIteratorT, PredicateT,
+                                  std::bidirectional_iterator_tag> {
+  using BaseT = filter_iterator_base<WrappedIteratorT, PredicateT,
+                                     std::bidirectional_iterator_tag>;
+  void findPrevValid() {
+    while (!this->Pred(*this->I))
+      BaseT::operator--();
+  }
+
+public:
+  using BaseT::operator--;
+
+  filter_iterator_impl(WrappedIteratorT Begin, WrappedIteratorT End,
+                       PredicateT Pred)
+      : BaseT(Begin, End, Pred) {}
+
+  filter_iterator_impl &operator--() {
+    BaseT::operator--();
+    findPrevValid();
+    return *this;
+  }
+};
+
+namespace detail {
+
+template <bool is_bidirectional> struct fwd_or_bidi_tag_impl {
+  using type = std::forward_iterator_tag;
+};
+
+template <> struct fwd_or_bidi_tag_impl<true> {
+  using type = std::bidirectional_iterator_tag;
+};
+
+/// Helper which sets its type member to forward_iterator_tag if the category
+/// of \p IterT does not derive from bidirectional_iterator_tag, and to
+/// bidirectional_iterator_tag otherwise.
+template <typename IterT> struct fwd_or_bidi_tag {
+  using type = typename fwd_or_bidi_tag_impl<std::is_base_of<
+      std::bidirectional_iterator_tag,
+      typename std::iterator_traits<IterT>::iterator_category>::value>::type;
+};
+
+} // namespace detail
+
+/// Defines filter_iterator to a suitable specialization of
+/// filter_iterator_impl, based on the underlying iterator's category.
+template <typename WrappedIteratorT, typename PredicateT>
+using filter_iterator = filter_iterator_impl<
+    WrappedIteratorT, PredicateT,
+    typename detail::fwd_or_bidi_tag<WrappedIteratorT>::type>;
+
+/// Convenience function that takes a range of elements and a predicate,
+/// and return a new filter_iterator range.
+///
+/// FIXME: Currently if RangeT && is a rvalue reference to a temporary, the
+/// lifetime of that temporary is not kept by the returned range object, and the
+/// temporary is going to be dropped on the floor after the make_iterator_range
+/// full expression that contains this function call.
+template <typename RangeT, typename PredicateT>
+iterator_range<filter_iterator<detail::IterOfRange<RangeT>, PredicateT>>
+make_filter_range(RangeT &&Range, PredicateT Pred) {
+  using FilterIteratorT =
+      filter_iterator<detail::IterOfRange<RangeT>, PredicateT>;
+  return make_range(
+      FilterIteratorT(std::begin(std::forward<RangeT>(Range)),
+                      std::end(std::forward<RangeT>(Range)), Pred),
+      FilterIteratorT(std::end(std::forward<RangeT>(Range)),
+                      std::end(std::forward<RangeT>(Range)), Pred));
+}
+
+// forward declarations required by zip_shortest/zip_first
+template <typename R, typename UnaryPredicate>
+bool all_of(R &&range, UnaryPredicate P);
+
+template <size_t... I> struct index_sequence;
+
+template <class... Ts> struct index_sequence_for;
+
+namespace detail {
+
+using std::declval;
+
+// We have to alias this since inlining the actual type at the usage site
+// in the parameter list of iterator_facade_base<> below ICEs MSVC 2017.
+template<typename... Iters> struct ZipTupleType {
+  using type = std::tuple<decltype(*declval<Iters>())...>;
+};
+
+template <typename ZipType, typename... Iters>
+using zip_traits = iterator_facade_base<
+    ZipType, typename std::common_type<std::bidirectional_iterator_tag,
+                                       typename std::iterator_traits<
+                                           Iters>::iterator_category...>::type,
+    // ^ TODO: Implement random access methods.
+    typename ZipTupleType<Iters...>::type,
+    typename std::iterator_traits<typename std::tuple_element<
+        0, std::tuple<Iters...>>::type>::difference_type,
+    // ^ FIXME: This follows boost::make_zip_iterator's assumption that all
+    // inner iterators have the same difference_type. It would fail if, for
+    // instance, the second field's difference_type were non-numeric while the
+    // first is.
+    typename ZipTupleType<Iters...>::type *,
+    typename ZipTupleType<Iters...>::type>;
+
+template <typename ZipType, typename... Iters>
+struct zip_common : public zip_traits<ZipType, Iters...> {
+  using Base = zip_traits<ZipType, Iters...>;
+  using value_type = typename Base::value_type;
+
+  std::tuple<Iters...> iterators;
+
+protected:
+  template <size_t... Ns> value_type deref(index_sequence<Ns...>) const {
+    return value_type(*std::get<Ns>(iterators)...);
+  }
+
+  template <size_t... Ns>
+  decltype(iterators) tup_inc(index_sequence<Ns...>) const {
+    return std::tuple<Iters...>(std::next(std::get<Ns>(iterators))...);
+  }
+
+  template <size_t... Ns>
+  decltype(iterators) tup_dec(index_sequence<Ns...>) const {
+    return std::tuple<Iters...>(std::prev(std::get<Ns>(iterators))...);
+  }
+
+public:
+  zip_common(Iters &&... ts) : iterators(std::forward<Iters>(ts)...) {}
+
+  value_type operator*() { return deref(index_sequence_for<Iters...>{}); }
+
+  const value_type operator*() const {
+    return deref(index_sequence_for<Iters...>{});
+  }
+
+  ZipType &operator++() {
+    iterators = tup_inc(index_sequence_for<Iters...>{});
+    return *reinterpret_cast<ZipType *>(this);
+  }
+
+  ZipType &operator--() {
+    static_assert(Base::IsBidirectional,
+                  "All inner iterators must be at least bidirectional.");
+    iterators = tup_dec(index_sequence_for<Iters...>{});
+    return *reinterpret_cast<ZipType *>(this);
+  }
+};
+
+template <typename... Iters>
+struct zip_first : public zip_common<zip_first<Iters...>, Iters...> {
+  using Base = zip_common<zip_first<Iters...>, Iters...>;
+
+  bool operator==(const zip_first<Iters...> &other) const {
+    return std::get<0>(this->iterators) == std::get<0>(other.iterators);
+  }
+
+  zip_first(Iters &&... ts) : Base(std::forward<Iters>(ts)...) {}
+};
+
+template <typename... Iters>
+class zip_shortest : public zip_common<zip_shortest<Iters...>, Iters...> {
+  template <size_t... Ns>
+  bool test(const zip_shortest<Iters...> &other, index_sequence<Ns...>) const {
+    return all_of(std::initializer_list<bool>{std::get<Ns>(this->iterators) !=
+                                              std::get<Ns>(other.iterators)...},
+                  identity<bool>{});
+  }
+
+public:
+  using Base = zip_common<zip_shortest<Iters...>, Iters...>;
+
+  zip_shortest(Iters &&... ts) : Base(std::forward<Iters>(ts)...) {}
+
+  bool operator==(const zip_shortest<Iters...> &other) const {
+    return !test(other, index_sequence_for<Iters...>{});
+  }
+};
+
+template <template <typename...> class ItType, typename... Args> class zippy {
+public:
+  using iterator = ItType<decltype(std::begin(std::declval<Args>()))...>;
+  using iterator_category = typename iterator::iterator_category;
+  using value_type = typename iterator::value_type;
+  using difference_type = typename iterator::difference_type;
+  using pointer = typename iterator::pointer;
+  using reference = typename iterator::reference;
+
+private:
+  std::tuple<Args...> ts;
+
+  template <size_t... Ns> iterator begin_impl(index_sequence<Ns...>) const {
+    return iterator(std::begin(std::get<Ns>(ts))...);
+  }
+  template <size_t... Ns> iterator end_impl(index_sequence<Ns...>) const {
+    return iterator(std::end(std::get<Ns>(ts))...);
+  }
+
+public:
+  zippy(Args &&... ts_) : ts(std::forward<Args>(ts_)...) {}
+
+  iterator begin() const { return begin_impl(index_sequence_for<Args...>{}); }
+  iterator end() const { return end_impl(index_sequence_for<Args...>{}); }
+};
+
+} // end namespace detail
+
+/// zip iterator for two or more iteratable types.
+template <typename T, typename U, typename... Args>
+detail::zippy<detail::zip_shortest, T, U, Args...> zip(T &&t, U &&u,
+                                                       Args &&... args) {
+  return detail::zippy<detail::zip_shortest, T, U, Args...>(
+      std::forward<T>(t), std::forward<U>(u), std::forward<Args>(args)...);
+}
+
+/// zip iterator that, for the sake of efficiency, assumes the first iteratee to
+/// be the shortest.
+template <typename T, typename U, typename... Args>
+detail::zippy<detail::zip_first, T, U, Args...> zip_first(T &&t, U &&u,
+                                                          Args &&... args) {
+  return detail::zippy<detail::zip_first, T, U, Args...>(
+      std::forward<T>(t), std::forward<U>(u), std::forward<Args>(args)...);
+}
+
+/// Iterator wrapper that concatenates sequences together.
+///
+/// This can concatenate different iterators, even with different types, into
+/// a single iterator provided the value types of all the concatenated
+/// iterators expose `reference` and `pointer` types that can be converted to
+/// `ValueT &` and `ValueT *` respectively. It doesn't support more
+/// interesting/customized pointer or reference types.
+///
+/// Currently this only supports forward or higher iterator categories as
+/// inputs and always exposes a forward iterator interface.
+template <typename ValueT, typename... IterTs>
+class concat_iterator
+    : public iterator_facade_base<concat_iterator<ValueT, IterTs...>,
+                                  std::forward_iterator_tag, ValueT> {
+  using BaseT = typename concat_iterator::iterator_facade_base;
+
+  /// We store both the current and end iterators for each concatenated
+  /// sequence in a tuple of pairs.
+  ///
+  /// Note that something like iterator_range seems nice at first here, but the
+  /// range properties are of little benefit and end up getting in the way
+  /// because we need to do mutation on the current iterators.
+  std::tuple<std::pair<IterTs, IterTs>...> IterPairs;
+
+  /// Attempts to increment a specific iterator.
+  ///
+  /// Returns true if it was able to increment the iterator. Returns false if
+  /// the iterator is already at the end iterator.
+  template <size_t Index> bool incrementHelper() {
+    auto &IterPair = std::get<Index>(IterPairs);
+    if (IterPair.first == IterPair.second)
+      return false;
+
+    ++IterPair.first;
+    return true;
+  }
+
+  /// Increments the first non-end iterator.
+  ///
+  /// It is an error to call this with all iterators at the end.
+  template <size_t... Ns> void increment(index_sequence<Ns...>) {
+    // Build a sequence of functions to increment each iterator if possible.
+    bool (concat_iterator::*IncrementHelperFns[])() = {
+        &concat_iterator::incrementHelper<Ns>...};
+
+    // Loop over them, and stop as soon as we succeed at incrementing one.
+    for (auto &IncrementHelperFn : IncrementHelperFns)
+      if ((this->*IncrementHelperFn)())
+        return;
+
+    assert(false && "Attempted to increment an end concat iterator!");
+  }
+
+  /// Returns null if the specified iterator is at the end. Otherwise,
+  /// dereferences the iterator and returns the address of the resulting
+  /// reference.
+  template <size_t Index> ValueT *getHelper() const {
+    auto &IterPair = std::get<Index>(IterPairs);
+    if (IterPair.first == IterPair.second)
+      return nullptr;
+
+    return &*IterPair.first;
+  }
+
+  /// Finds the first non-end iterator, dereferences, and returns the resulting
+  /// reference.
+  ///
+  /// It is an error to call this with all iterators at the end.
+  template <size_t... Ns> ValueT &get(index_sequence<Ns...>) const {
+    // Build a sequence of functions to get from iterator if possible.
+    ValueT *(concat_iterator::*GetHelperFns[])() const = {
+        &concat_iterator::getHelper<Ns>...};
+
+    // Loop over them, and return the first result we find.
+    for (auto &GetHelperFn : GetHelperFns)
+      if (ValueT *P = (this->*GetHelperFn)())
+        return *P;
+
+    assert(false && "Attempted to get a pointer from an end concat iterator!");
+  }
+
+public:
+  /// Constructs an iterator from a squence of ranges.
+  ///
+  /// We need the full range to know how to switch between each of the
+  /// iterators.
+  template <typename... RangeTs>
+  explicit concat_iterator(RangeTs &&... Ranges)
+      : IterPairs({std::begin(Ranges), std::end(Ranges)}...) {}
+
+  using BaseT::operator++;
+
+  concat_iterator &operator++() {
+    increment(index_sequence_for<IterTs...>());
+    return *this;
+  }
+
+  ValueT &operator*() const { return get(index_sequence_for<IterTs...>()); }
+
+  bool operator==(const concat_iterator &RHS) const {
+    return IterPairs == RHS.IterPairs;
+  }
+};
+
+namespace detail {
+
+/// Helper to store a sequence of ranges being concatenated and access them.
+///
+/// This is designed to facilitate providing actual storage when temporaries
+/// are passed into the constructor such that we can use it as part of range
+/// based for loops.
+template <typename ValueT, typename... RangeTs> class concat_range {
+public:
+  using iterator =
+      concat_iterator<ValueT,
+                      decltype(std::begin(std::declval<RangeTs &>()))...>;
+
+private:
+  std::tuple<RangeTs...> Ranges;
+
+  template <size_t... Ns> iterator begin_impl(index_sequence<Ns...>) {
+    return iterator(std::get<Ns>(Ranges)...);
+  }
+  template <size_t... Ns> iterator end_impl(index_sequence<Ns...>) {
+    return iterator(make_range(std::end(std::get<Ns>(Ranges)),
+                               std::end(std::get<Ns>(Ranges)))...);
+  }
+
+public:
+  concat_range(RangeTs &&... Ranges)
+      : Ranges(std::forward<RangeTs>(Ranges)...) {}
+
+  iterator begin() { return begin_impl(index_sequence_for<RangeTs...>{}); }
+  iterator end() { return end_impl(index_sequence_for<RangeTs...>{}); }
+};
+
+} // end namespace detail
+
+/// Concatenated range across two or more ranges.
+///
+/// The desired value type must be explicitly specified.
+template <typename ValueT, typename... RangeTs>
+detail::concat_range<ValueT, RangeTs...> concat(RangeTs &&... Ranges) {
+  static_assert(sizeof...(RangeTs) > 1,
+                "Need more than one range to concatenate!");
+  return detail::concat_range<ValueT, RangeTs...>(
+      std::forward<RangeTs>(Ranges)...);
+}
+
+//===----------------------------------------------------------------------===//
+//     Extra additions to <utility>
+//===----------------------------------------------------------------------===//
+
+/// Function object to check whether the first component of a std::pair
+/// compares less than the first component of another std::pair.
+struct less_first {
+  template <typename T> bool operator()(const T &lhs, const T &rhs) const {
+    return lhs.first < rhs.first;
+  }
+};
+
+/// Function object to check whether the second component of a std::pair
+/// compares less than the second component of another std::pair.
+struct less_second {
+  template <typename T> bool operator()(const T &lhs, const T &rhs) const {
+    return lhs.second < rhs.second;
+  }
+};
+
+// A subset of N3658. More stuff can be added as-needed.
+
+/// Represents a compile-time sequence of integers.
+template <class T, T... I> struct integer_sequence {
+  using value_type = T;
+
+  static constexpr size_t size() { return sizeof...(I); }
+};
+
+/// Alias for the common case of a sequence of size_ts.
+template <size_t... I>
+struct index_sequence : integer_sequence<std::size_t, I...> {};
+
+template <std::size_t N, std::size_t... I>
+struct build_index_impl : build_index_impl<N - 1, N - 1, I...> {};
+template <std::size_t... I>
+struct build_index_impl<0, I...> : index_sequence<I...> {};
+
+/// Creates a compile-time integer sequence for a parameter pack.
+template <class... Ts>
+struct index_sequence_for : build_index_impl<sizeof...(Ts)> {};
+
+/// Utility type to build an inheritance chain that makes it easy to rank
+/// overload candidates.
+template <int N> struct rank : rank<N - 1> {};
+template <> struct rank<0> {};
+
+/// traits class for checking whether type T is one of any of the given
+/// types in the variadic list.
+template <typename T, typename... Ts> struct is_one_of {
+  static const bool value = false;
+};
+
+template <typename T, typename U, typename... Ts>
+struct is_one_of<T, U, Ts...> {
+  static const bool value =
+      std::is_same<T, U>::value || is_one_of<T, Ts...>::value;
+};
+
+/// traits class for checking whether type T is a base class for all
+///  the given types in the variadic list.
+template <typename T, typename... Ts> struct are_base_of {
+  static const bool value = true;
+};
+
+template <typename T, typename U, typename... Ts>
+struct are_base_of<T, U, Ts...> {
+  static const bool value =
+      std::is_base_of<T, U>::value && are_base_of<T, Ts...>::value;
+};
+
+//===----------------------------------------------------------------------===//
+//     Extra additions for arrays
+//===----------------------------------------------------------------------===//
+
+/// Find the length of an array.
+template <class T, std::size_t N>
+constexpr inline size_t array_lengthof(T (&)[N]) {
+  return N;
+}
+
+/// Adapt std::less<T> for array_pod_sort.
+template<typename T>
+inline int array_pod_sort_comparator(const void *P1, const void *P2) {
+  if (std::less<T>()(*reinterpret_cast<const T*>(P1),
+                     *reinterpret_cast<const T*>(P2)))
+    return -1;
+  if (std::less<T>()(*reinterpret_cast<const T*>(P2),
+                     *reinterpret_cast<const T*>(P1)))
+    return 1;
+  return 0;
+}
+
+/// get_array_pod_sort_comparator - This is an internal helper function used to
+/// get type deduction of T right.
+template<typename T>
+inline int (*get_array_pod_sort_comparator(const T &))
+             (const void*, const void*) {
+  return array_pod_sort_comparator<T>;
+}
+
+/// array_pod_sort - This sorts an array with the specified start and end
+/// extent.  This is just like std::sort, except that it calls qsort instead of
+/// using an inlined template.  qsort is slightly slower than std::sort, but
+/// most sorts are not performance critical in LLVM and std::sort has to be
+/// template instantiated for each type, leading to significant measured code
+/// bloat.  This function should generally be used instead of std::sort where
+/// possible.
+///
+/// This function assumes that you have simple POD-like types that can be
+/// compared with std::less and can be moved with memcpy.  If this isn't true,
+/// you should use std::sort.
+///
+/// NOTE: If qsort_r were portable, we could allow a custom comparator and
+/// default to std::less.
+template<class IteratorTy>
+inline void array_pod_sort(IteratorTy Start, IteratorTy End) {
+  // Don't inefficiently call qsort with one element or trigger undefined
+  // behavior with an empty sequence.
+  auto NElts = End - Start;
+  if (NElts <= 1) return;
+  qsort(&*Start, NElts, sizeof(*Start), get_array_pod_sort_comparator(*Start));
+}
+
+template <class IteratorTy>
+inline void array_pod_sort(
+    IteratorTy Start, IteratorTy End,
+    int (*Compare)(
+        const typename std::iterator_traits<IteratorTy>::value_type *,
+        const typename std::iterator_traits<IteratorTy>::value_type *)) {
+  // Don't inefficiently call qsort with one element or trigger undefined
+  // behavior with an empty sequence.
+  auto NElts = End - Start;
+  if (NElts <= 1) return;
+  qsort(&*Start, NElts, sizeof(*Start),
+        reinterpret_cast<int (*)(const void *, const void *)>(Compare));
+}
+
+//===----------------------------------------------------------------------===//
+//     Extra additions to <algorithm>
+//===----------------------------------------------------------------------===//
+
+/// For a container of pointers, deletes the pointers and then clears the
+/// container.
+template<typename Container>
+void DeleteContainerPointers(Container &C) {
+  for (auto V : C)
+    delete V;
+  C.clear();
+}
+
+/// In a container of pairs (usually a map) whose second element is a pointer,
+/// deletes the second elements and then clears the container.
+template<typename Container>
+void DeleteContainerSeconds(Container &C) {
+  for (auto &V : C)
+    delete V.second;
+  C.clear();
+}
+
+/// Provide wrappers to std::for_each which take ranges instead of having to
+/// pass begin/end explicitly.
+template <typename R, typename UnaryPredicate>
+UnaryPredicate for_each(R &&Range, UnaryPredicate P) {
+  return std::for_each(adl_begin(Range), adl_end(Range), P);
+}
+
+/// Provide wrappers to std::all_of which take ranges instead of having to pass
+/// begin/end explicitly.
+template <typename R, typename UnaryPredicate>
+bool all_of(R &&Range, UnaryPredicate P) {
+  return std::all_of(adl_begin(Range), adl_end(Range), P);
+}
+
+/// Provide wrappers to std::any_of which take ranges instead of having to pass
+/// begin/end explicitly.
+template <typename R, typename UnaryPredicate>
+bool any_of(R &&Range, UnaryPredicate P) {
+  return std::any_of(adl_begin(Range), adl_end(Range), P);
+}
+
+/// Provide wrappers to std::none_of which take ranges instead of having to pass
+/// begin/end explicitly.
+template <typename R, typename UnaryPredicate>
+bool none_of(R &&Range, UnaryPredicate P) {
+  return std::none_of(adl_begin(Range), adl_end(Range), P);
+}
+
+/// Provide wrappers to std::find which take ranges instead of having to pass
+/// begin/end explicitly.
+template <typename R, typename T>
+auto find(R &&Range, const T &Val) -> decltype(adl_begin(Range)) {
+  return std::find(adl_begin(Range), adl_end(Range), Val);
+}
+
+/// Provide wrappers to std::find_if which take ranges instead of having to pass
+/// begin/end explicitly.
+template <typename R, typename UnaryPredicate>
+auto find_if(R &&Range, UnaryPredicate P) -> decltype(adl_begin(Range)) {
+  return std::find_if(adl_begin(Range), adl_end(Range), P);
+}
+
+template <typename R, typename UnaryPredicate>
+auto find_if_not(R &&Range, UnaryPredicate P) -> decltype(adl_begin(Range)) {
+  return std::find_if_not(adl_begin(Range), adl_end(Range), P);
+}
+
+/// Provide wrappers to std::remove_if which take ranges instead of having to
+/// pass begin/end explicitly.
+template <typename R, typename UnaryPredicate>
+auto remove_if(R &&Range, UnaryPredicate P) -> decltype(adl_begin(Range)) {
+  return std::remove_if(adl_begin(Range), adl_end(Range), P);
+}
+
+/// Provide wrappers to std::copy_if which take ranges instead of having to
+/// pass begin/end explicitly.
+template <typename R, typename OutputIt, typename UnaryPredicate>
+OutputIt copy_if(R &&Range, OutputIt Out, UnaryPredicate P) {
+  return std::copy_if(adl_begin(Range), adl_end(Range), Out, P);
+}
+
+template <typename R, typename OutputIt>
+OutputIt copy(R &&Range, OutputIt Out) {
+  return std::copy(adl_begin(Range), adl_end(Range), Out);
+}
+
+/// Wrapper function around std::find to detect if an element exists
+/// in a container.
+template <typename R, typename E>
+bool is_contained(R &&Range, const E &Element) {
+  return std::find(adl_begin(Range), adl_end(Range), Element) != adl_end(Range);
+}
+
+/// Wrapper function around std::count to count the number of times an element
+/// \p Element occurs in the given range \p Range.
+template <typename R, typename E>
+auto count(R &&Range, const E &Element) ->
+    typename std::iterator_traits<decltype(adl_begin(Range))>::difference_type {
+  return std::count(adl_begin(Range), adl_end(Range), Element);
+}
+
+/// Wrapper function around std::count_if to count the number of times an
+/// element satisfying a given predicate occurs in a range.
+template <typename R, typename UnaryPredicate>
+auto count_if(R &&Range, UnaryPredicate P) ->
+    typename std::iterator_traits<decltype(adl_begin(Range))>::difference_type {
+  return std::count_if(adl_begin(Range), adl_end(Range), P);
+}
+
+/// Wrapper function around std::transform to apply a function to a range and
+/// store the result elsewhere.
+template <typename R, typename OutputIt, typename UnaryPredicate>
+OutputIt transform(R &&Range, OutputIt d_first, UnaryPredicate P) {
+  return std::transform(adl_begin(Range), adl_end(Range), d_first, P);
+}
+
+/// Provide wrappers to std::partition which take ranges instead of having to
+/// pass begin/end explicitly.
+template <typename R, typename UnaryPredicate>
+auto partition(R &&Range, UnaryPredicate P) -> decltype(adl_begin(Range)) {
+  return std::partition(adl_begin(Range), adl_end(Range), P);
+}
+
+/// Provide wrappers to std::lower_bound which take ranges instead of having to
+/// pass begin/end explicitly.
+template <typename R, typename ForwardIt>
+auto lower_bound(R &&Range, ForwardIt I) -> decltype(adl_begin(Range)) {
+  return std::lower_bound(adl_begin(Range), adl_end(Range), I);
+}
+
+/// Given a range of type R, iterate the entire range and return a
+/// SmallVector with elements of the vector.  This is useful, for example,
+/// when you want to iterate a range and then sort the results.
+template <unsigned Size, typename R>
+SmallVector<typename std::remove_const<detail::ValueOfRange<R>>::type, Size>
+to_vector(R &&Range) {
+  return {adl_begin(Range), adl_end(Range)};
+}
+
+/// Provide a container algorithm similar to C++ Library Fundamentals v2's
+/// `erase_if` which is equivalent to:
+///
+///   C.erase(remove_if(C, pred), C.end());
+///
+/// This version works for any container with an erase method call accepting
+/// two iterators.
+template <typename Container, typename UnaryPredicate>
+void erase_if(Container &C, UnaryPredicate P) {
+  C.erase(remove_if(C, P), C.end());
+}
+
+/// Get the size of a range. This is a wrapper function around std::distance
+/// which is only enabled when the operation is O(1).
+template <typename R>
+auto size(R &&Range, typename std::enable_if<
+                         std::is_same<typename std::iterator_traits<decltype(
+                                          Range.begin())>::iterator_category,
+                                      std::random_access_iterator_tag>::value,
+                         void>::type * = nullptr)
+    -> decltype(std::distance(Range.begin(), Range.end())) {
+  return std::distance(Range.begin(), Range.end());
+}
+
+//===----------------------------------------------------------------------===//
+//     Extra additions to <memory>
+//===----------------------------------------------------------------------===//
+
+// Implement make_unique according to N3656.
+
+/// Constructs a `new T()` with the given args and returns a
+///        `unique_ptr<T>` which owns the object.
+///
+/// Example:
+///
+///     auto p = make_unique<int>();
+///     auto p = make_unique<std::tuple<int, int>>(0, 1);
+template <class T, class... Args>
+typename std::enable_if<!std::is_array<T>::value, std::unique_ptr<T>>::type
+make_unique(Args &&... args) {
+  return std::unique_ptr<T>(new T(std::forward<Args>(args)...));
+}
+
+/// Constructs a `new T[n]` with the given args and returns a
+///        `unique_ptr<T[]>` which owns the object.
+///
+/// \param n size of the new array.
+///
+/// Example:
+///
+///     auto p = make_unique<int[]>(2); // value-initializes the array with 0's.
+template <class T>
+typename std::enable_if<std::is_array<T>::value && std::extent<T>::value == 0,
+                        std::unique_ptr<T>>::type
+make_unique(size_t n) {
+  return std::unique_ptr<T>(new typename std::remove_extent<T>::type[n]());
+}
+
+/// This function isn't used and is only here to provide better compile errors.
+template <class T, class... Args>
+typename std::enable_if<std::extent<T>::value != 0>::type
+make_unique(Args &&...) = delete;
+
+struct FreeDeleter {
+  void operator()(void* v) {
+    ::free(v);
+  }
+};
+
+template<typename First, typename Second>
+struct pair_hash {
+  size_t operator()(const std::pair<First, Second> &P) const {
+    return std::hash<First>()(P.first) * 31 + std::hash<Second>()(P.second);
+  }
+};
+
+/// A functor like C++14's std::less<void> in its absence.
+struct less {
+  template <typename A, typename B> bool operator()(A &&a, B &&b) const {
+    return std::forward<A>(a) < std::forward<B>(b);
+  }
+};
+
+/// A functor like C++14's std::equal<void> in its absence.
+struct equal {
+  template <typename A, typename B> bool operator()(A &&a, B &&b) const {
+    return std::forward<A>(a) == std::forward<B>(b);
+  }
+};
+
+/// Binary functor that adapts to any other binary functor after dereferencing
+/// operands.
+template <typename T> struct deref {
+  T func;
+
+  // Could be further improved to cope with non-derivable functors and
+  // non-binary functors (should be a variadic template member function
+  // operator()).
+  template <typename A, typename B>
+  auto operator()(A &lhs, B &rhs) const -> decltype(func(*lhs, *rhs)) {
+    assert(lhs);
+    assert(rhs);
+    return func(*lhs, *rhs);
+  }
+};
+
+namespace detail {
+
+template <typename R> class enumerator_iter;
+
+template <typename R> struct result_pair {
+  friend class enumerator_iter<R>;
+
+  result_pair() = default;
+  result_pair(std::size_t Index, IterOfRange<R> Iter)
+      : Index(Index), Iter(Iter) {}
+
+  result_pair<R> &operator=(const result_pair<R> &Other) {
+    Index = Other.Index;
+    Iter = Other.Iter;
+    return *this;
+  }
+
+  std::size_t index() const { return Index; }
+  const ValueOfRange<R> &value() const { return *Iter; }
+  ValueOfRange<R> &value() { return *Iter; }
+
+private:
+  std::size_t Index = std::numeric_limits<std::size_t>::max();
+  IterOfRange<R> Iter;
+};
+
+template <typename R>
+class enumerator_iter
+    : public iterator_facade_base<
+          enumerator_iter<R>, std::forward_iterator_tag, result_pair<R>,
+          typename std::iterator_traits<IterOfRange<R>>::difference_type,
+          typename std::iterator_traits<IterOfRange<R>>::pointer,
+          typename std::iterator_traits<IterOfRange<R>>::reference> {
+  using result_type = result_pair<R>;
+
+public:
+  explicit enumerator_iter(IterOfRange<R> EndIter)
+      : Result(std::numeric_limits<size_t>::max(), EndIter) {}
+
+  enumerator_iter(std::size_t Index, IterOfRange<R> Iter)
+      : Result(Index, Iter) {}
+
+  result_type &operator*() { return Result; }
+  const result_type &operator*() const { return Result; }
+
+  enumerator_iter<R> &operator++() {
+    assert(Result.Index != std::numeric_limits<size_t>::max());
+    ++Result.Iter;
+    ++Result.Index;
+    return *this;
+  }
+
+  bool operator==(const enumerator_iter<R> &RHS) const {
+    // Don't compare indices here, only iterators.  It's possible for an end
+    // iterator to have different indices depending on whether it was created
+    // by calling std::end() versus incrementing a valid iterator.
+    return Result.Iter == RHS.Result.Iter;
+  }
+
+  enumerator_iter<R> &operator=(const enumerator_iter<R> &Other) {
+    Result = Other.Result;
+    return *this;
+  }
+
+private:
+  result_type Result;
+};
+
+template <typename R> class enumerator {
+public:
+  explicit enumerator(R &&Range) : TheRange(std::forward<R>(Range)) {}
+
+  enumerator_iter<R> begin() {
+    return enumerator_iter<R>(0, std::begin(TheRange));
+  }
+
+  enumerator_iter<R> end() {
+    return enumerator_iter<R>(std::end(TheRange));
+  }
+
+private:
+  R TheRange;
+};
+
+} // end namespace detail
+
+/// Given an input range, returns a new range whose values are are pair (A,B)
+/// such that A is the 0-based index of the item in the sequence, and B is
+/// the value from the original sequence.  Example:
+///
+/// std::vector<char> Items = {'A', 'B', 'C', 'D'};
+/// for (auto X : enumerate(Items)) {
+///   printf("Item %d - %c\n", X.index(), X.value());
+/// }
+///
+/// Output:
+///   Item 0 - A
+///   Item 1 - B
+///   Item 2 - C
+///   Item 3 - D
+///
+template <typename R> detail::enumerator<R> enumerate(R &&TheRange) {
+  return detail::enumerator<R>(std::forward<R>(TheRange));
+}
+
+namespace detail {
+
+template <typename F, typename Tuple, std::size_t... I>
+auto apply_tuple_impl(F &&f, Tuple &&t, index_sequence<I...>)
+    -> decltype(std::forward<F>(f)(std::get<I>(std::forward<Tuple>(t))...)) {
+  return std::forward<F>(f)(std::get<I>(std::forward<Tuple>(t))...);
+}
+
+} // end namespace detail
+
+/// Given an input tuple (a1, a2, ..., an), pass the arguments of the
+/// tuple variadically to f as if by calling f(a1, a2, ..., an) and
+/// return the result.
+template <typename F, typename Tuple>
+auto apply_tuple(F &&f, Tuple &&t) -> decltype(detail::apply_tuple_impl(
+    std::forward<F>(f), std::forward<Tuple>(t),
+    build_index_impl<
+        std::tuple_size<typename std::decay<Tuple>::type>::value>{})) {
+  using Indices = build_index_impl<
+      std::tuple_size<typename std::decay<Tuple>::type>::value>;
+
+  return detail::apply_tuple_impl(std::forward<F>(f), std::forward<Tuple>(t),
+                                  Indices{});
+}
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_STLEXTRAS_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SafeThread.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SafeThread.h
new file mode 100644
index 0000000..ec4e2e1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SafeThread.h
@@ -0,0 +1,116 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_SAFETHREAD_H_
+#define WPIUTIL_WPI_SAFETHREAD_H_
+
+#include <atomic>
+#include <memory>
+#include <thread>
+#include <utility>
+
+#include "wpi/condition_variable.h"
+#include "wpi/mutex.h"
+
+namespace wpi {
+
+// Base class for SafeThreadOwner threads.
+class SafeThread {
+ public:
+  virtual ~SafeThread() = default;
+  virtual void Main() = 0;
+
+  mutable wpi::mutex m_mutex;
+  std::atomic_bool m_active{true};
+  wpi::condition_variable m_cond;
+};
+
+namespace detail {
+
+// Non-template proxy base class for common proxy code.
+class SafeThreadProxyBase {
+ public:
+  explicit SafeThreadProxyBase(std::shared_ptr<SafeThread> thr);
+  explicit operator bool() const { return m_thread != nullptr; }
+  std::unique_lock<wpi::mutex>& GetLock() { return m_lock; }
+
+ protected:
+  std::shared_ptr<SafeThread> m_thread;
+  std::unique_lock<wpi::mutex> m_lock;
+};
+
+// A proxy for SafeThread.
+// Also serves as a scoped lock on SafeThread::m_mutex.
+template <typename T>
+class SafeThreadProxy : public SafeThreadProxyBase {
+ public:
+  explicit SafeThreadProxy(std::shared_ptr<SafeThread> thr)
+      : SafeThreadProxyBase(std::move(thr)) {}
+  T& operator*() const { return *static_cast<T*>(m_thread.get()); }
+  T* operator->() const { return static_cast<T*>(m_thread.get()); }
+};
+
+// Non-template owner base class for common owner code.
+class SafeThreadOwnerBase {
+ public:
+  void Stop();
+  void Join();
+
+  SafeThreadOwnerBase() noexcept = default;
+  SafeThreadOwnerBase(const SafeThreadOwnerBase&) = delete;
+  SafeThreadOwnerBase& operator=(const SafeThreadOwnerBase&) = delete;
+  SafeThreadOwnerBase(SafeThreadOwnerBase&& other) noexcept
+      : SafeThreadOwnerBase() {
+    swap(*this, other);
+  }
+  SafeThreadOwnerBase& operator=(SafeThreadOwnerBase other) noexcept {
+    swap(*this, other);
+    return *this;
+  }
+  ~SafeThreadOwnerBase();
+
+  friend void swap(SafeThreadOwnerBase& lhs, SafeThreadOwnerBase& rhs) noexcept;
+
+  explicit operator bool() const;
+
+  std::thread::native_handle_type GetNativeThreadHandle();
+
+  void SetJoinAtExit(bool joinAtExit) { m_joinAtExit = joinAtExit; }
+
+ protected:
+  void Start(std::shared_ptr<SafeThread> thr);
+  std::shared_ptr<SafeThread> GetThread() const;
+
+ private:
+  mutable wpi::mutex m_mutex;
+  std::thread m_stdThread;
+  std::weak_ptr<SafeThread> m_thread;
+  std::atomic_bool m_joinAtExit{true};
+};
+
+void swap(SafeThreadOwnerBase& lhs, SafeThreadOwnerBase& rhs) noexcept;
+
+}  // namespace detail
+
+template <typename T>
+class SafeThreadOwner : public detail::SafeThreadOwnerBase {
+ public:
+  template <typename... Args>
+  void Start(Args&&... args) {
+    detail::SafeThreadOwnerBase::Start(
+        std::make_shared<T>(std::forward<Args>(args)...));
+  }
+
+  using Proxy = typename detail::SafeThreadProxy<T>;
+  Proxy GetThread() const {
+    return Proxy(detail::SafeThreadOwnerBase::GetThread());
+  }
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_SAFETHREAD_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Signal.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Signal.h
new file mode 100644
index 0000000..8ef89bd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Signal.h
@@ -0,0 +1,835 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+
+Sigslot, a signal-slot library
+
+https://github.com/palacaze/sigslot
+
+MIT License
+
+Copyright (c) 2017 Pierre-Antoine Lacaze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+ */
+#pragma once
+#include <atomic>
+#include <functional>
+#include <memory>
+#include <type_traits>
+#include <utility>
+
+#include "wpi/mutex.h"
+
+namespace wpi {
+
+namespace sig {
+
+namespace trait {
+
+/// represent a list of types
+template <typename...> struct typelist {};
+
+/**
+ * Pointers that can be converted to a weak pointer concept for tracking
+ * purpose must implement the to_weak() function in order to make use of
+ * ADL to convert that type and make it usable
+ */
+
+template<typename T>
+std::weak_ptr<T> to_weak(std::weak_ptr<T> w) {
+    return w;
+}
+
+template<typename T>
+std::weak_ptr<T> to_weak(std::shared_ptr<T> s) {
+    return s;
+}
+
+// tools
+namespace detail {
+
+template <class...>
+struct voider { using type = void; };
+
+// void_t from c++17
+template <class...T>
+using void_t = typename detail::voider<T...>::type;
+
+
+template <typename, typename, typename = void, typename = void>
+struct is_callable : std::false_type {};
+
+template <typename F, typename P, typename... T>
+struct is_callable<F, P, typelist<T...>,
+        void_t<decltype(((*std::declval<P>()).*std::declval<F>())(std::declval<T>()...))>>
+    : std::true_type {};
+
+template <typename F, typename... T>
+struct is_callable<F, typelist<T...>,
+        void_t<decltype(std::declval<F>()(std::declval<T>()...))>>
+    : std::true_type {};
+
+
+template <typename T, typename = void>
+struct is_weak_ptr : std::false_type {};
+
+template <typename T>
+struct is_weak_ptr<T, void_t<decltype(std::declval<T>().expired()),
+                             decltype(std::declval<T>().lock()),
+                             decltype(std::declval<T>().reset())>>
+    : std::true_type {};
+
+template <typename T, typename = void>
+struct is_weak_ptr_compatible : std::false_type {};
+
+template <typename T>
+struct is_weak_ptr_compatible<T, void_t<decltype(to_weak(std::declval<T>()))>>
+    : is_weak_ptr<decltype(to_weak(std::declval<T>()))> {};
+
+}  // namespace detail
+
+/// determine if a pointer is convertible into a "weak" pointer
+template <typename P>
+constexpr bool is_weak_ptr_compatible_v = detail::is_weak_ptr_compatible<std::decay_t<P>>::value;
+
+/// determine if a type T (Callable or Pmf) is callable with supplied arguments in L
+template <typename L, typename... T>
+constexpr bool is_callable_v = detail::is_callable<T..., L>::value;
+
+}  // namespace trait
+
+
+namespace detail {
+
+/* SlotState holds slot type independent state, to be used to interact with
+ * slots indirectly through connection and ScopedConnection objects.
+ */
+class SlotState {
+public:
+    constexpr SlotState() noexcept
+        : m_connected(true),
+          m_blocked(false) {}
+
+    virtual ~SlotState() = default;
+
+    bool connected() const noexcept { return m_connected; }
+    bool disconnect() noexcept { return m_connected.exchange(false); }
+
+    bool blocked() const noexcept { return m_blocked.load(); }
+    void block()   noexcept { m_blocked.store(true); }
+    void unblock() noexcept { m_blocked.store(false); }
+
+private:
+    std::atomic<bool> m_connected;
+    std::atomic<bool> m_blocked;
+};
+
+}  // namespace detail
+
+/**
+ * ConnectionBlocker is a RAII object that blocks a connection until destruction
+ */
+class ConnectionBlocker {
+public:
+    ConnectionBlocker() = default;
+    ~ConnectionBlocker() noexcept { release(); }
+
+    ConnectionBlocker(const ConnectionBlocker &) = delete;
+    ConnectionBlocker & operator=(const ConnectionBlocker &) = delete;
+
+    ConnectionBlocker(ConnectionBlocker && o) noexcept
+        : m_state{std::move(o.m_state)}
+    {}
+
+    ConnectionBlocker & operator=(ConnectionBlocker && o) noexcept {
+        release();
+        m_state.swap(o.m_state);
+        return *this;
+    }
+
+private:
+    friend class Connection;
+    ConnectionBlocker(std::weak_ptr<detail::SlotState> s) noexcept
+        : m_state{std::move(s)}
+    {
+        auto d = m_state.lock();
+        if (d) d->block();
+    }
+
+    void release() noexcept {
+        auto d = m_state.lock();
+        if (d) d->unblock();
+    }
+
+private:
+    std::weak_ptr<detail::SlotState> m_state;
+};
+
+
+/**
+ * A Connection object allows interaction with an ongoing slot connection
+ *
+ * It allows common actions such as connection blocking and disconnection.
+ * Note that Connection is not a RAII object, one does not need to hold one
+ * such object to keep the signal-slot connection alive.
+ */
+class Connection {
+public:
+    Connection() = default;
+    virtual ~Connection() = default;
+
+    Connection(const Connection &) noexcept = default;
+    Connection & operator=(const Connection &) noexcept = default;
+    Connection(Connection &&) noexcept = default;
+    Connection & operator=(Connection &&) noexcept = default;
+
+    bool valid() const noexcept {
+        return !m_state.expired();
+    }
+
+    bool connected() const noexcept {
+        const auto d = m_state.lock();
+        return d && d->connected();
+    }
+
+    bool disconnect() noexcept {
+        auto d = m_state.lock();
+        return d && d->disconnect();
+    }
+
+    bool blocked() const noexcept {
+        const auto d = m_state.lock();
+        return d && d->blocked();
+    }
+
+    void block() noexcept {
+        auto d = m_state.lock();
+        if(d)
+            d->block();
+    }
+
+    void unblock() noexcept {
+        auto d = m_state.lock();
+        if(d)
+            d->unblock();
+    }
+
+    ConnectionBlocker blocker() const noexcept {
+        return ConnectionBlocker{m_state};
+    }
+
+protected:
+    template <typename, typename...> friend class SignalBase;
+    Connection(std::weak_ptr<detail::SlotState> s) noexcept
+        : m_state{std::move(s)}
+    {}
+
+protected:
+    std::weak_ptr<detail::SlotState> m_state;
+};
+
+/**
+ * ScopedConnection is a RAII version of Connection
+ * It disconnects the slot from the signal upon destruction.
+ */
+class ScopedConnection : public Connection {
+public:
+    ScopedConnection() = default;
+    ~ScopedConnection() {
+        disconnect();
+    }
+
+    ScopedConnection(const Connection &c) noexcept : Connection(c) {}
+    ScopedConnection(Connection &&c) noexcept : Connection(std::move(c)) {}
+
+    ScopedConnection(const ScopedConnection &) noexcept = delete;
+    ScopedConnection & operator=(const ScopedConnection &) noexcept = delete;
+
+    ScopedConnection(ScopedConnection && o) noexcept
+        : Connection{std::move(o.m_state)}
+    {}
+
+    ScopedConnection & operator=(ScopedConnection && o) noexcept {
+        disconnect();
+        m_state.swap(o.m_state);
+        return *this;
+    }
+
+private:
+    template <typename, typename...> friend class SignalBase;
+    ScopedConnection(std::weak_ptr<detail::SlotState> s) noexcept
+        : Connection{std::move(s)}
+    {}
+};
+
+namespace detail {
+
+template <typename...>
+class SlotBase;
+
+template <typename... T>
+using SlotPtr = std::shared_ptr<SlotBase<T...>>;
+
+/* A base class for slot objects. This base type only depends on slot argument
+ * types, it will be used as an element in an intrusive singly-linked list of
+ * slots, hence the public next member.
+ */
+template <typename... Args>
+class SlotBase : public SlotState {
+public:
+    using base_types = trait::typelist<Args...>;
+
+    virtual ~SlotBase() noexcept = default;
+
+    // method effectively responsible for calling the "slot" function with
+    // supplied arguments whenever emission happens.
+    virtual void call_slot(Args...) = 0;
+
+    template <typename... U>
+    void operator()(U && ...u) {
+        if (SlotState::connected() && !SlotState::blocked())
+            call_slot(std::forward<U>(u)...);
+    }
+
+    SlotPtr<Args...> next;
+};
+
+template <typename, typename...> class Slot {};
+
+/*
+ * A slot object holds state information, and a callable to to be called
+ * whenever the function call operator of its SlotBase base class is called.
+ */
+template <typename Func, typename... Args>
+class Slot<Func, trait::typelist<Args...>> : public SlotBase<Args...> {
+public:
+    template <typename F>
+    constexpr Slot(F && f) : func{std::forward<F>(f)} {}
+
+    virtual void call_slot(Args ...args) override {
+        func(args...);
+    }
+
+private:
+    std::decay_t<Func> func;
+};
+
+/*
+ * Variation of slot that prepends a Connection object to the callable
+ */
+template <typename Func, typename... Args>
+class Slot<Func, trait::typelist<Connection&, Args...>> : public SlotBase<Args...> {
+public:
+    template <typename F>
+    constexpr Slot(F && f) : func{std::forward<F>(f)} {}
+
+    virtual void call_slot(Args ...args) override {
+        func(conn, args...);
+    }
+
+    Connection conn;
+
+private:
+    std::decay_t<Func> func;
+};
+
+/*
+ * A slot object holds state information, an object and a pointer over member
+ * function to be called whenever the function call operator of its SlotBase
+ * base class is called.
+ */
+template <typename Pmf, typename Ptr, typename... Args>
+class Slot<Pmf, Ptr, trait::typelist<Args...>> : public SlotBase<Args...> {
+public:
+    template <typename F, typename P>
+    constexpr Slot(F && f, P && p)
+        : pmf{std::forward<F>(f)},
+          ptr{std::forward<P>(p)} {}
+
+    virtual void call_slot(Args ...args) override {
+        ((*ptr).*pmf)(args...);
+    }
+
+private:
+    std::decay_t<Pmf> pmf;
+    std::decay_t<Ptr> ptr;
+};
+
+/*
+ * Variation of slot that prepends a Connection object to the callable
+ */
+template <typename Pmf, typename Ptr, typename... Args>
+class Slot<Pmf, Ptr, trait::typelist<Connection&, Args...>> : public SlotBase<Args...> {
+public:
+    template <typename F, typename P>
+    constexpr Slot(F && f, P && p)
+        : pmf{std::forward<F>(f)},
+          ptr{std::forward<P>(p)} {}
+
+    virtual void call_slot(Args ...args) override {
+        ((*ptr).*pmf)(conn, args...);
+    }
+
+    Connection conn;
+
+private:
+    std::decay_t<Pmf> pmf;
+    std::decay_t<Ptr> ptr;
+};
+
+template <typename, typename, typename...> class SlotTracked {};
+
+/*
+ * An implementation of a slot that tracks the life of a supplied object
+ * through a weak pointer in order to automatically disconnect the slot
+ * on said object destruction.
+ */
+template <typename Func, typename WeakPtr, typename... Args>
+class SlotTracked<Func, WeakPtr, trait::typelist<Args...>> : public SlotBase<Args...> {
+public:
+    template <typename F, typename P>
+    constexpr SlotTracked(F && f, P && p)
+        : func{std::forward<F>(f)},
+          ptr{std::forward<P>(p)}
+    {}
+
+    virtual void call_slot(Args ...args) override {
+        if (! SlotState::connected())
+            return;
+        if (ptr.expired())
+            SlotState::disconnect();
+        else
+            func(args...);
+    }
+
+private:
+    std::decay_t<Func> func;
+    std::decay_t<WeakPtr> ptr;
+};
+
+template <typename, typename, typename...> class SlotPmfTracked {};
+
+/*
+ * An implementation of a slot as a pointer over member function, that tracks
+ * the life of a supplied object through a weak pointer in order to automatically
+ * disconnect the slot on said object destruction.
+ */
+template <typename Pmf, typename WeakPtr, typename... Args>
+class SlotPmfTracked<Pmf, WeakPtr, trait::typelist<Args...>> : public SlotBase<Args...> {
+public:
+    template <typename F, typename P>
+    constexpr SlotPmfTracked(F && f, P && p)
+        : pmf{std::forward<F>(f)},
+          ptr{std::forward<P>(p)}
+    {}
+
+    virtual void call_slot(Args ...args) override {
+        if (! SlotState::connected())
+            return;
+        auto sp = ptr.lock();
+        if (!sp)
+            SlotState::disconnect();
+        else
+            ((*sp).*pmf)(args...);
+    }
+
+private:
+    std::decay_t<Pmf> pmf;
+    std::decay_t<WeakPtr> ptr;
+};
+
+
+// noop mutex for thread-unsafe use
+struct NullMutex {
+    NullMutex() = default;
+    NullMutex(const NullMutex &) = delete;
+    NullMutex operator=(const NullMutex &) = delete;
+    NullMutex(NullMutex &&) = delete;
+    NullMutex operator=(NullMutex &&) = delete;
+
+    bool try_lock() { return true; }
+    void lock() {}
+    void unlock() {}
+};
+
+}  // namespace detail
+
+
+/**
+ * SignalBase is an implementation of the observer pattern, through the use
+ * of an emitting object and slots that are connected to the signal and called
+ * with supplied arguments when a signal is emitted.
+ *
+ * wpi::SignalBase is the general implementation, whose locking policy must be
+ * set in order to decide thread safety guarantees. wpi::Signal and wpi::Signal_st
+ * are partial specializations for multi-threaded and single-threaded use.
+ *
+ * It does not allow slots to return a value.
+ *
+ * @tparam Lockable a lock type to decide the lock policy
+ * @tparam T... the argument types of the emitting and slots functions.
+ */
+template <typename Lockable, typename... T>
+class SignalBase {
+    using lock_type = std::unique_lock<Lockable>;
+    using SlotPtr = detail::SlotPtr<T...>;
+
+    struct CallSlots {
+        SlotPtr m_slots;
+        SignalBase& m_base;
+
+        CallSlots(SignalBase& base) : m_base(base) {}
+
+        template <typename... A>
+        void operator()(A && ... a) {
+            SlotPtr *prev = nullptr;
+            SlotPtr *curr = m_slots ? &m_slots : nullptr;
+
+            while (curr) {
+                // call non blocked, non connected slots
+                if ((*curr)->connected()) {
+                    if (!m_base.m_block && !(*curr)->blocked())
+                        (*curr)->operator()(a...);
+                    prev = curr;
+                    curr = (*curr)->next ? &((*curr)->next) : nullptr;
+                }
+                // remove slots marked as disconnected
+                else {
+                    if (prev) {
+                        (*prev)->next = (*curr)->next;
+                        curr = (*prev)->next ? &((*prev)->next) : nullptr;
+                    }
+                    else
+                        curr = (*curr)->next ? &((*curr)->next) : nullptr;
+                }
+            }
+        }
+    };
+
+public:
+    using arg_list = trait::typelist<T...>;
+    using ext_arg_list = trait::typelist<Connection&, T...>;
+
+    SignalBase() noexcept : m_block(false) {}
+    ~SignalBase() {
+        disconnect_all();
+    }
+
+    SignalBase(const SignalBase&) = delete;
+    SignalBase & operator=(const SignalBase&) = delete;
+
+    SignalBase(SignalBase && o)
+        : m_block{o.m_block.load()}
+    {
+        lock_type lock(o.m_mutex);
+        std::swap(m_func, o.m_func);
+    }
+
+    SignalBase & operator=(SignalBase && o) {
+        lock_type lock1(m_mutex, std::defer_lock);
+        lock_type lock2(o.m_mutex, std::defer_lock);
+        std::lock(lock1, lock2);
+
+        std::swap(m_func, o.m_func);
+        m_block.store(o.m_block.exchange(m_block.load()));
+        return *this;
+    }
+
+    /**
+     * Emit a signal
+     *
+     * Effect: All non blocked and connected slot functions will be called
+     *         with supplied arguments.
+     * Safety: With proper locking (see wpi::Signal), emission can happen from
+     *         multiple threads simultaneously. The guarantees only apply to the
+     *         signal object, it does not cover thread safety of potentially
+     *         shared state used in slot functions.
+     *
+     * @param a... arguments to emit
+     */
+    template <typename... A>
+    void operator()(A && ... a) {
+        lock_type lock(m_mutex);
+        if (!m_block && m_func) m_func(std::forward<A>(a)...);
+    }
+
+    /**
+     * Connect a callable of compatible arguments
+     *
+     * Effect: Creates and stores a new slot responsible for executing the
+     *         supplied callable for every subsequent signal emission.
+     * Safety: Thread-safety depends on locking policy.
+     *
+     * @param c a callable
+     * @return a Connection object that can be used to interact with the slot
+     */
+    template <typename Callable>
+    void connect(Callable && c) {
+        if (!m_func) {
+          m_func = std::forward<Callable>(c);
+        } else {
+          using slot_t = detail::Slot<Callable, arg_list>;
+          auto s = std::make_shared<slot_t>(std::forward<Callable>(c));
+          add_slot(s);
+        }
+    }
+
+    /**
+     * Connect a callable of compatible arguments, returning a Connection
+     *
+     * Effect: Creates and stores a new slot responsible for executing the
+     *         supplied callable for every subsequent signal emission.
+     * Safety: Thread-safety depends on locking policy.
+     *
+     * @param c a callable
+     * @return a Connection object that can be used to interact with the slot
+     */
+    template <typename Callable>
+    std::enable_if_t<trait::is_callable_v<arg_list, Callable>, Connection>
+    connect_connection(Callable && c) {
+        using slot_t = detail::Slot<Callable, arg_list>;
+        auto s = std::make_shared<slot_t>(std::forward<Callable>(c));
+        add_slot(s);
+        return Connection(s);
+    }
+
+    /**
+     * Connect a callable with an additional Connection argument
+     *
+     * The callable's first argument must be of type Connection. This overload
+     * the callable to manage it's own connection through this argument.
+     *
+     * @param c a callable
+     * @return a Connection object that can be used to interact with the slot
+     */
+    template <typename Callable>
+    std::enable_if_t<trait::is_callable_v<ext_arg_list, Callable>, Connection>
+    connect_extended(Callable && c) {
+        using slot_t = detail::Slot<Callable, ext_arg_list>;
+        auto s = std::make_shared<slot_t>(std::forward<Callable>(c));
+        s->conn = Connection(s);
+        add_slot(s);
+        return Connection(s);
+    }
+
+    /**
+     * Overload of connect for pointers over member functions
+     *
+     * @param pmf a pointer over member function
+     * @param ptr an object pointer
+     * @return a Connection object that can be used to interact with the slot
+     */
+    template <typename Pmf, typename Ptr>
+    std::enable_if_t<trait::is_callable_v<arg_list, Pmf, Ptr> &&
+                     !trait::is_weak_ptr_compatible_v<Ptr>, Connection>
+    connect(Pmf && pmf, Ptr && ptr) {
+        using slot_t = detail::Slot<Pmf, Ptr, arg_list>;
+        auto s = std::make_shared<slot_t>(std::forward<Pmf>(pmf), std::forward<Ptr>(ptr));
+        add_slot(s);
+        return Connection(s);
+    }
+
+    /**
+     * Overload  of connect for pointer over member functions and
+     *
+     * @param pmf a pointer over member function
+     * @param ptr an object pointer
+     * @return a Connection object that can be used to interact with the slot
+     */
+    template <typename Pmf, typename Ptr>
+    std::enable_if_t<trait::is_callable_v<ext_arg_list, Pmf, Ptr> &&
+                     !trait::is_weak_ptr_compatible_v<Ptr>, Connection>
+    connect_extended(Pmf && pmf, Ptr && ptr) {
+        using slot_t = detail::Slot<Pmf, Ptr, ext_arg_list>;
+        auto s = std::make_shared<slot_t>(std::forward<Pmf>(pmf), std::forward<Ptr>(ptr));
+        s->conn = Connection(s);
+        add_slot(s);
+        return Connection(s);
+    }
+
+    /**
+     * Overload of connect for lifetime object tracking and automatic disconnection
+     *
+     * Ptr must be convertible to an object following a loose form of weak pointer
+     * concept, by implementing the ADL-detected conversion function to_weak().
+     *
+     * This overload covers the case of a pointer over member function and a
+     * trackable pointer of that class.
+     *
+     * Note: only weak references are stored, a slot does not extend the lifetime
+     * of a suppied object.
+     *
+     * @param pmf a pointer over member function
+     * @param ptr a trackable object pointer
+     * @return a Connection object that can be used to interact with the slot
+     */
+    template <typename Pmf, typename Ptr>
+    std::enable_if_t<!trait::is_callable_v<arg_list, Pmf> &&
+                     trait::is_weak_ptr_compatible_v<Ptr>, Connection>
+    connect(Pmf && pmf, Ptr && ptr) {
+        using trait::to_weak;
+        auto w = to_weak(std::forward<Ptr>(ptr));
+        using slot_t = detail::SlotPmfTracked<Pmf, decltype(w), arg_list>;
+        auto s = std::make_shared<slot_t>(std::forward<Pmf>(pmf), w);
+        add_slot(s);
+        return Connection(s);
+    }
+
+    /**
+     * Overload of connect for lifetime object tracking and automatic disconnection
+     *
+     * Trackable must be convertible to an object following a loose form of weak
+     * pointer concept, by implementing the ADL-detected conversion function to_weak().
+     *
+     * This overload covers the case of a standalone callable and unrelated trackable
+     * object.
+     *
+     * Note: only weak references are stored, a slot does not extend the lifetime
+     * of a suppied object.
+     *
+     * @param c a callable
+     * @param ptr a trackable object pointer
+     * @return a Connection object that can be used to interact with the slot
+     */
+    template <typename Callable, typename Trackable>
+    std::enable_if_t<trait::is_callable_v<arg_list, Callable> &&
+                     trait::is_weak_ptr_compatible_v<Trackable>, Connection>
+    connect(Callable && c, Trackable && ptr) {
+        using trait::to_weak;
+        auto w = to_weak(std::forward<Trackable>(ptr));
+        using slot_t = detail::SlotTracked<Callable, decltype(w), arg_list>;
+        auto s = std::make_shared<slot_t>(std::forward<Callable>(c), w);
+        add_slot(s);
+        return Connection(s);
+    }
+
+    /**
+     * Creates a connection whose duration is tied to the return object
+     * Use the same semantics as connect
+     */
+    template <typename... CallArgs>
+    ScopedConnection connect_scoped(CallArgs && ...args) {
+        return connect_connection(std::forward<CallArgs>(args)...);
+    }
+
+    /**
+     * Disconnects all the slots
+     * Safety: Thread safety depends on locking policy
+     */
+    void disconnect_all() {
+        lock_type lock(m_mutex);
+        clear();
+    }
+
+    /**
+     * Blocks signal emission
+     * Safety: thread safe
+     */
+    void block() noexcept {
+        m_block.store(true);
+    }
+
+    /**
+     * Unblocks signal emission
+     * Safety: thread safe
+     */
+    void unblock() noexcept {
+        m_block.store(false);
+    }
+
+    /**
+     * Tests blocking state of signal emission
+     */
+    bool blocked() const noexcept {
+        return m_block.load();
+    }
+
+private:
+    template <typename S>
+    void add_slot(S &s) {
+        lock_type lock(m_mutex);
+        if (!m_func) {
+          // nothing stored
+          m_func = CallSlots(*this);
+          auto slots = m_func.template target<CallSlots>();
+          s->next = slots->m_slots;
+          slots->m_slots = s;
+        } else if (auto call_slots = m_func.template target<CallSlots>()) {
+          // already CallSlots
+          s->next = call_slots->m_slots;
+          call_slots->m_slots = s;
+        } else {
+          // was normal std::function, need to move it into a call slot
+          using slot_t = detail::Slot<std::function<void(T...)>, arg_list>;
+          auto s2 = std::make_shared<slot_t>(
+              std::forward<std::function<void(T...)>>(m_func));
+          m_func = CallSlots(*this);
+          auto slots = m_func.template target<CallSlots>();
+          s2->next = slots->m_slots;
+          s->next = s2;
+          slots->m_slots = s;
+        }
+    }
+
+    void clear() {
+        m_func = nullptr;
+    }
+
+private:
+    std::function<void(T...)> m_func;
+    Lockable m_mutex;
+    std::atomic<bool> m_block;
+};
+
+/**
+ * Specialization of SignalBase to be used in single threaded contexts.
+ * Slot connection, disconnection and signal emission are not thread-safe.
+ * This is significantly smaller than the thread-safe variant.
+ */
+template <typename... T>
+using Signal = SignalBase<detail::NullMutex, T...>;
+
+/**
+ * Specialization of SignalBase to be used in multi-threaded contexts.
+ * Slot connection, disconnection and signal emission are thread-safe.
+ *
+ * Beware of accidentally using recursive signal emission or cycles between
+ * two or more signals in your code. Locking std::mutex more than once is
+ * undefined behaviour, even if it "seems to work somehow". Use signal_r
+ * instead for that use case.
+ */
+template <typename... T>
+using Signal_mt = SignalBase<mutex, T...>;
+
+/**
+ * Specialization of SignalBase to be used in multi-threaded contexts, allowing
+ * for recursive signal emission and emission cycles.
+ * Slot connection, disconnection and signal emission are thread-safe.
+ */
+template <typename... T>
+using Signal_r = SignalBase<recursive_mutex, T...>;
+
+}  // namespace sig
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallPtrSet.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallPtrSet.h
new file mode 100644
index 0000000..8669527
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallPtrSet.h
@@ -0,0 +1,463 @@
+//===- llvm/ADT/SmallPtrSet.h - 'Normally small' pointer set ----*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the SmallPtrSet class.  See the doxygen comment for
+// SmallPtrSetImplBase for more details on the algorithm used.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SMALLPTRSET_H
+#define WPIUTIL_WPI_SMALLPTRSET_H
+
+#include "wpi/Compiler.h"
+#include "wpi/PointerLikeTypeTraits.h"
+#include "wpi/type_traits.h"
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <cstdlib>
+#include <cstring>
+#include <initializer_list>
+#include <iterator>
+#include <utility>
+
+namespace wpi {
+
+/// SmallPtrSetImplBase - This is the common code shared among all the
+/// SmallPtrSet<>'s, which is almost everything.  SmallPtrSet has two modes, one
+/// for small and one for large sets.
+///
+/// Small sets use an array of pointers allocated in the SmallPtrSet object,
+/// which is treated as a simple array of pointers.  When a pointer is added to
+/// the set, the array is scanned to see if the element already exists, if not
+/// the element is 'pushed back' onto the array.  If we run out of space in the
+/// array, we grow into the 'large set' case.  SmallSet should be used when the
+/// sets are often small.  In this case, no memory allocation is used, and only
+/// light-weight and cache-efficient scanning is used.
+///
+/// Large sets use a classic exponentially-probed hash table.  Empty buckets are
+/// represented with an illegal pointer value (-1) to allow null pointers to be
+/// inserted.  Tombstones are represented with another illegal pointer value
+/// (-2), to allow deletion.  The hash table is resized when the table is 3/4 or
+/// more.  When this happens, the table is doubled in size.
+///
+class SmallPtrSetImplBase {
+  friend class SmallPtrSetIteratorImpl;
+
+protected:
+  /// SmallArray - Points to a fixed size set of buckets, used in 'small mode'.
+  const void **SmallArray;
+  /// CurArray - This is the current set of buckets.  If equal to SmallArray,
+  /// then the set is in 'small mode'.
+  const void **CurArray;
+  /// CurArraySize - The allocated size of CurArray, always a power of two.
+  unsigned CurArraySize;
+
+  /// Number of elements in CurArray that contain a value or are a tombstone.
+  /// If small, all these elements are at the beginning of CurArray and the rest
+  /// is uninitialized.
+  unsigned NumNonEmpty;
+  /// Number of tombstones in CurArray.
+  unsigned NumTombstones;
+
+  // Helpers to copy and move construct a SmallPtrSet.
+  SmallPtrSetImplBase(const void **SmallStorage,
+                      const SmallPtrSetImplBase &that);
+  SmallPtrSetImplBase(const void **SmallStorage, unsigned SmallSize,
+                      SmallPtrSetImplBase &&that);
+
+  explicit SmallPtrSetImplBase(const void **SmallStorage, unsigned SmallSize)
+      : SmallArray(SmallStorage), CurArray(SmallStorage),
+        CurArraySize(SmallSize), NumNonEmpty(0), NumTombstones(0) {
+    assert(SmallSize && (SmallSize & (SmallSize-1)) == 0 &&
+           "Initial size must be a power of two!");
+  }
+
+  ~SmallPtrSetImplBase() {
+    if (!isSmall())
+      free(CurArray);
+  }
+
+public:
+  using size_type = unsigned;
+
+  SmallPtrSetImplBase &operator=(const SmallPtrSetImplBase &) = delete;
+
+  LLVM_NODISCARD bool empty() const { return size() == 0; }
+  size_type size() const { return NumNonEmpty - NumTombstones; }
+
+  void clear() {
+    // If the capacity of the array is huge, and the # elements used is small,
+    // shrink the array.
+    if (!isSmall()) {
+      if (size() * 4 < CurArraySize && CurArraySize > 32)
+        return shrink_and_clear();
+      // Fill the array with empty markers.
+      memset(CurArray, -1, CurArraySize * sizeof(void *));
+    }
+
+    NumNonEmpty = 0;
+    NumTombstones = 0;
+  }
+
+protected:
+  static void *getTombstoneMarker() { return reinterpret_cast<void*>(-2); }
+
+  static void *getEmptyMarker() {
+    // Note that -1 is chosen to make clear() efficiently implementable with
+    // memset and because it's not a valid pointer value.
+    return reinterpret_cast<void*>(-1);
+  }
+
+  const void **EndPointer() const {
+    return isSmall() ? CurArray + NumNonEmpty : CurArray + CurArraySize;
+  }
+
+  /// insert_imp - This returns true if the pointer was new to the set, false if
+  /// it was already in the set.  This is hidden from the client so that the
+  /// derived class can check that the right type of pointer is passed in.
+  std::pair<const void *const *, bool> insert_imp(const void *Ptr) {
+    if (isSmall()) {
+      // Check to see if it is already in the set.
+      const void **LastTombstone = nullptr;
+      for (const void **APtr = SmallArray, **E = SmallArray + NumNonEmpty;
+           APtr != E; ++APtr) {
+        const void *Value = *APtr;
+        if (Value == Ptr)
+          return std::make_pair(APtr, false);
+        if (Value == getTombstoneMarker())
+          LastTombstone = APtr;
+      }
+
+      // Did we find any tombstone marker?
+      if (LastTombstone != nullptr) {
+        *LastTombstone = Ptr;
+        --NumTombstones;
+        return std::make_pair(LastTombstone, true);
+      }
+
+      // Nope, there isn't.  If we stay small, just 'pushback' now.
+      if (NumNonEmpty < CurArraySize) {
+        SmallArray[NumNonEmpty++] = Ptr;
+        return std::make_pair(SmallArray + (NumNonEmpty - 1), true);
+      }
+      // Otherwise, hit the big set case, which will call grow.
+    }
+    return insert_imp_big(Ptr);
+  }
+
+  /// erase_imp - If the set contains the specified pointer, remove it and
+  /// return true, otherwise return false.  This is hidden from the client so
+  /// that the derived class can check that the right type of pointer is passed
+  /// in.
+  bool erase_imp(const void * Ptr) {
+    const void *const *P = find_imp(Ptr);
+    if (P == EndPointer())
+      return false;
+
+    const void **Loc = const_cast<const void **>(P);
+    assert(*Loc == Ptr && "broken find!");
+    *Loc = getTombstoneMarker();
+    NumTombstones++;
+    return true;
+  }
+
+  /// Returns the raw pointer needed to construct an iterator.  If element not
+  /// found, this will be EndPointer.  Otherwise, it will be a pointer to the
+  /// slot which stores Ptr;
+  const void *const * find_imp(const void * Ptr) const {
+    if (isSmall()) {
+      // Linear search for the item.
+      for (const void *const *APtr = SmallArray,
+                      *const *E = SmallArray + NumNonEmpty; APtr != E; ++APtr)
+        if (*APtr == Ptr)
+          return APtr;
+      return EndPointer();
+    }
+
+    // Big set case.
+    auto *Bucket = FindBucketFor(Ptr);
+    if (*Bucket == Ptr)
+      return Bucket;
+    return EndPointer();
+  }
+
+private:
+  bool isSmall() const { return CurArray == SmallArray; }
+
+  std::pair<const void *const *, bool> insert_imp_big(const void *Ptr);
+
+  const void * const *FindBucketFor(const void *Ptr) const;
+  void shrink_and_clear();
+
+  /// Grow - Allocate a larger backing store for the buckets and move it over.
+  void Grow(unsigned NewSize);
+
+protected:
+  /// swap - Swaps the elements of two sets.
+  /// Note: This method assumes that both sets have the same small size.
+  void swap(SmallPtrSetImplBase &RHS);
+
+  void CopyFrom(const SmallPtrSetImplBase &RHS);
+  void MoveFrom(unsigned SmallSize, SmallPtrSetImplBase &&RHS);
+
+private:
+  /// Code shared by MoveFrom() and move constructor.
+  void MoveHelper(unsigned SmallSize, SmallPtrSetImplBase &&RHS);
+  /// Code shared by CopyFrom() and copy constructor.
+  void CopyHelper(const SmallPtrSetImplBase &RHS);
+};
+
+/// SmallPtrSetIteratorImpl - This is the common base class shared between all
+/// instances of SmallPtrSetIterator.
+class SmallPtrSetIteratorImpl {
+protected:
+  const void *const *Bucket;
+  const void *const *End;
+
+public:
+  explicit SmallPtrSetIteratorImpl(const void *const *BP, const void*const *E)
+    : Bucket(BP), End(E) {
+    AdvanceIfNotValid();
+  }
+
+  bool operator==(const SmallPtrSetIteratorImpl &RHS) const {
+    return Bucket == RHS.Bucket;
+  }
+  bool operator!=(const SmallPtrSetIteratorImpl &RHS) const {
+    return Bucket != RHS.Bucket;
+  }
+
+protected:
+  /// AdvanceIfNotValid - If the current bucket isn't valid, advance to a bucket
+  /// that is.   This is guaranteed to stop because the end() bucket is marked
+  /// valid.
+  void AdvanceIfNotValid() {
+    assert(Bucket <= End);
+    while (Bucket != End &&
+           (*Bucket == SmallPtrSetImplBase::getEmptyMarker() ||
+            *Bucket == SmallPtrSetImplBase::getTombstoneMarker()))
+      ++Bucket;
+  }
+  void RetreatIfNotValid() {
+    assert(Bucket >= End);
+    while (Bucket != End &&
+           (Bucket[-1] == SmallPtrSetImplBase::getEmptyMarker() ||
+            Bucket[-1] == SmallPtrSetImplBase::getTombstoneMarker())) {
+      --Bucket;
+    }
+  }
+};
+
+/// SmallPtrSetIterator - This implements a const_iterator for SmallPtrSet.
+template <typename PtrTy>
+class SmallPtrSetIterator : public SmallPtrSetIteratorImpl {
+  using PtrTraits = PointerLikeTypeTraits<PtrTy>;
+
+public:
+  using value_type = PtrTy;
+  using reference = PtrTy;
+  using pointer = PtrTy;
+  using difference_type = std::ptrdiff_t;
+  using iterator_category = std::forward_iterator_tag;
+
+  explicit SmallPtrSetIterator(const void *const *BP, const void *const *E)
+      : SmallPtrSetIteratorImpl(BP, E) {}
+
+  // Most methods provided by baseclass.
+
+  const PtrTy operator*() const {
+    assert(Bucket < End);
+    return PtrTraits::getFromVoidPointer(const_cast<void*>(*Bucket));
+  }
+
+  inline SmallPtrSetIterator& operator++() {          // Preincrement
+    ++Bucket;
+    AdvanceIfNotValid();
+    return *this;
+  }
+
+  SmallPtrSetIterator operator++(int) {        // Postincrement
+    SmallPtrSetIterator tmp = *this;
+    ++*this;
+    return tmp;
+  }
+};
+
+/// RoundUpToPowerOfTwo - This is a helper template that rounds N up to the next
+/// power of two (which means N itself if N is already a power of two).
+template<unsigned N>
+struct RoundUpToPowerOfTwo;
+
+/// RoundUpToPowerOfTwoH - If N is not a power of two, increase it.  This is a
+/// helper template used to implement RoundUpToPowerOfTwo.
+template<unsigned N, bool isPowerTwo>
+struct RoundUpToPowerOfTwoH {
+  enum { Val = N };
+};
+template<unsigned N>
+struct RoundUpToPowerOfTwoH<N, false> {
+  enum {
+    // We could just use NextVal = N+1, but this converges faster.  N|(N-1) sets
+    // the right-most zero bits to one all at once, e.g. 0b0011000 -> 0b0011111.
+    Val = RoundUpToPowerOfTwo<(N|(N-1)) + 1>::Val
+  };
+};
+
+template<unsigned N>
+struct RoundUpToPowerOfTwo {
+  enum { Val = RoundUpToPowerOfTwoH<N, (N&(N-1)) == 0>::Val };
+};
+
+/// A templated base class for \c SmallPtrSet which provides the
+/// typesafe interface that is common across all small sizes.
+///
+/// This is particularly useful for passing around between interface boundaries
+/// to avoid encoding a particular small size in the interface boundary.
+template <typename PtrType>
+class SmallPtrSetImpl : public SmallPtrSetImplBase {
+  using ConstPtrType = typename add_const_past_pointer<PtrType>::type;
+  using PtrTraits = PointerLikeTypeTraits<PtrType>;
+  using ConstPtrTraits = PointerLikeTypeTraits<ConstPtrType>;
+
+protected:
+  // Constructors that forward to the base.
+  SmallPtrSetImpl(const void **SmallStorage, const SmallPtrSetImpl &that)
+      : SmallPtrSetImplBase(SmallStorage, that) {}
+  SmallPtrSetImpl(const void **SmallStorage, unsigned SmallSize,
+                  SmallPtrSetImpl &&that)
+      : SmallPtrSetImplBase(SmallStorage, SmallSize, std::move(that)) {}
+  explicit SmallPtrSetImpl(const void **SmallStorage, unsigned SmallSize)
+      : SmallPtrSetImplBase(SmallStorage, SmallSize) {}
+
+public:
+  using iterator = SmallPtrSetIterator<PtrType>;
+  using const_iterator = SmallPtrSetIterator<PtrType>;
+  using key_type = ConstPtrType;
+  using value_type = PtrType;
+
+  SmallPtrSetImpl(const SmallPtrSetImpl &) = delete;
+
+  /// Inserts Ptr if and only if there is no element in the container equal to
+  /// Ptr. The bool component of the returned pair is true if and only if the
+  /// insertion takes place, and the iterator component of the pair points to
+  /// the element equal to Ptr.
+  std::pair<iterator, bool> insert(PtrType Ptr) {
+    auto p = insert_imp(PtrTraits::getAsVoidPointer(Ptr));
+    return std::make_pair(makeIterator(p.first), p.second);
+  }
+
+  /// erase - If the set contains the specified pointer, remove it and return
+  /// true, otherwise return false.
+  bool erase(PtrType Ptr) {
+    return erase_imp(PtrTraits::getAsVoidPointer(Ptr));
+  }
+
+  /// count - Return 1 if the specified pointer is in the set, 0 otherwise.
+  size_type count(ConstPtrType Ptr) const { return find(Ptr) != end() ? 1 : 0; }
+  iterator find(ConstPtrType Ptr) const {
+    return makeIterator(find_imp(ConstPtrTraits::getAsVoidPointer(Ptr)));
+  }
+
+  template <typename IterT>
+  void insert(IterT I, IterT E) {
+    for (; I != E; ++I)
+      insert(*I);
+  }
+
+  void insert(std::initializer_list<PtrType> IL) {
+    insert(IL.begin(), IL.end());
+  }
+
+  iterator begin() const {
+    return makeIterator(CurArray);
+  }
+  iterator end() const { return makeIterator(EndPointer()); }
+
+private:
+  /// Create an iterator that dereferences to same place as the given pointer.
+  iterator makeIterator(const void *const *P) const {
+    return iterator(P, EndPointer());
+  }
+};
+
+/// SmallPtrSet - This class implements a set which is optimized for holding
+/// SmallSize or less elements.  This internally rounds up SmallSize to the next
+/// power of two if it is not already a power of two.  See the comments above
+/// SmallPtrSetImplBase for details of the algorithm.
+template<class PtrType, unsigned SmallSize>
+class SmallPtrSet : public SmallPtrSetImpl<PtrType> {
+  // In small mode SmallPtrSet uses linear search for the elements, so it is
+  // not a good idea to choose this value too high. You may consider using a
+  // DenseSet<> instead if you expect many elements in the set.
+  static_assert(SmallSize <= 32, "SmallSize should be small");
+
+  using BaseT = SmallPtrSetImpl<PtrType>;
+
+  // Make sure that SmallSize is a power of two, round up if not.
+  enum { SmallSizePowTwo = RoundUpToPowerOfTwo<SmallSize>::Val };
+  /// SmallStorage - Fixed size storage used in 'small mode'.
+  const void *SmallStorage[SmallSizePowTwo];
+
+public:
+  SmallPtrSet() : BaseT(SmallStorage, SmallSizePowTwo) {}
+  SmallPtrSet(const SmallPtrSet &that) : BaseT(SmallStorage, that) {}
+  SmallPtrSet(SmallPtrSet &&that)
+      : BaseT(SmallStorage, SmallSizePowTwo, std::move(that)) {}
+
+  template<typename It>
+  SmallPtrSet(It I, It E) : BaseT(SmallStorage, SmallSizePowTwo) {
+    this->insert(I, E);
+  }
+
+  SmallPtrSet(std::initializer_list<PtrType> IL)
+      : BaseT(SmallStorage, SmallSizePowTwo) {
+    this->insert(IL.begin(), IL.end());
+  }
+
+  SmallPtrSet<PtrType, SmallSize> &
+  operator=(const SmallPtrSet<PtrType, SmallSize> &RHS) {
+    if (&RHS != this)
+      this->CopyFrom(RHS);
+    return *this;
+  }
+
+  SmallPtrSet<PtrType, SmallSize> &
+  operator=(SmallPtrSet<PtrType, SmallSize> &&RHS) {
+    if (&RHS != this)
+      this->MoveFrom(SmallSizePowTwo, std::move(RHS));
+    return *this;
+  }
+
+  SmallPtrSet<PtrType, SmallSize> &
+  operator=(std::initializer_list<PtrType> IL) {
+    this->clear();
+    this->insert(IL.begin(), IL.end());
+    return *this;
+  }
+
+  /// swap - Swaps the elements of two sets.
+  void swap(SmallPtrSet<PtrType, SmallSize> &RHS) {
+    SmallPtrSetImplBase::swap(RHS);
+  }
+};
+
+} // end namespace wpi
+
+namespace std {
+
+  /// Implement std::swap in terms of SmallPtrSet swap.
+  template<class T, unsigned N>
+  inline void swap(wpi::SmallPtrSet<T, N> &LHS, wpi::SmallPtrSet<T, N> &RHS) {
+    LHS.swap(RHS);
+  }
+
+} // end namespace std
+
+#endif // LLVM_ADT_SMALLPTRSET_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallSet.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallSet.h
new file mode 100644
index 0000000..87fd287
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallSet.h
@@ -0,0 +1,142 @@
+//===- llvm/ADT/SmallSet.h - 'Normally small' sets --------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the SmallSet class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SMALLSET_H
+#define WPIUTIL_WPI_SMALLSET_H
+
+#include "wpi/optional.h"
+#include "wpi/SmallPtrSet.h"
+#include "wpi/SmallVector.h"
+#include "wpi/Compiler.h"
+#include <cstddef>
+#include <functional>
+#include <set>
+#include <utility>
+
+namespace wpi {
+
+/// SmallSet - This maintains a set of unique values, optimizing for the case
+/// when the set is small (less than N).  In this case, the set can be
+/// maintained with no mallocs.  If the set gets large, we expand to using an
+/// std::set to maintain reasonable lookup times.
+///
+/// Note that this set does not provide a way to iterate over members in the
+/// set.
+template <typename T, unsigned N, typename C = std::less<T>>
+class SmallSet {
+  /// Use a SmallVector to hold the elements here (even though it will never
+  /// reach its 'large' stage) to avoid calling the default ctors of elements
+  /// we will never use.
+  SmallVector<T, N> Vector;
+  std::set<T, C> Set;
+
+  using VIterator = typename SmallVector<T, N>::const_iterator;
+  using mutable_iterator = typename SmallVector<T, N>::iterator;
+
+  // In small mode SmallPtrSet uses linear search for the elements, so it is
+  // not a good idea to choose this value too high. You may consider using a
+  // DenseSet<> instead if you expect many elements in the set.
+  static_assert(N <= 32, "N should be small");
+
+public:
+  using size_type = size_t;
+
+  SmallSet() = default;
+
+  LLVM_NODISCARD bool empty() const {
+    return Vector.empty() && Set.empty();
+  }
+
+  size_type size() const {
+    return isSmall() ? Vector.size() : Set.size();
+  }
+
+  /// count - Return 1 if the element is in the set, 0 otherwise.
+  size_type count(const T &V) const {
+    if (isSmall()) {
+      // Since the collection is small, just do a linear search.
+      return vfind(V) == Vector.end() ? 0 : 1;
+    } else {
+      return Set.count(V);
+    }
+  }
+
+  /// insert - Insert an element into the set if it isn't already there.
+  /// Returns true if the element is inserted (it was not in the set before).
+  /// The first value of the returned pair is unused and provided for
+  /// partial compatibility with the standard library self-associative container
+  /// concept.
+  // FIXME: Add iterators that abstract over the small and large form, and then
+  // return those here.
+  std::pair<nullopt_t, bool> insert(const T &V) {
+    if (!isSmall())
+      return std::make_pair(nullopt, Set.insert(V).second);
+
+    VIterator I = vfind(V);
+    if (I != Vector.end())    // Don't reinsert if it already exists.
+      return std::make_pair(nullopt, false);
+    if (Vector.size() < N) {
+      Vector.push_back(V);
+      return std::make_pair(nullopt, true);
+    }
+
+    // Otherwise, grow from vector to set.
+    while (!Vector.empty()) {
+      Set.insert(Vector.back());
+      Vector.pop_back();
+    }
+    Set.insert(V);
+    return std::make_pair(nullopt, true);
+  }
+
+  template <typename IterT>
+  void insert(IterT I, IterT E) {
+    for (; I != E; ++I)
+      insert(*I);
+  }
+
+  bool erase(const T &V) {
+    if (!isSmall())
+      return Set.erase(V);
+    for (mutable_iterator I = Vector.begin(), E = Vector.end(); I != E; ++I)
+      if (*I == V) {
+        Vector.erase(I);
+        return true;
+      }
+    return false;
+  }
+
+  void clear() {
+    Vector.clear();
+    Set.clear();
+  }
+
+private:
+  bool isSmall() const { return Set.empty(); }
+
+  VIterator vfind(const T &V) const {
+    for (VIterator I = Vector.begin(), E = Vector.end(); I != E; ++I)
+      if (*I == V)
+        return I;
+    return Vector.end();
+  }
+};
+
+/// If this set is of pointer values, transparently switch over to using
+/// SmallPtrSet for performance.
+template <typename PointeeType, unsigned N>
+class SmallSet<PointeeType*, N> : public SmallPtrSet<PointeeType*, N> {};
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_SMALLSET_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallString.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallString.h
new file mode 100644
index 0000000..32969b1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallString.h
@@ -0,0 +1,297 @@
+//===- llvm/ADT/SmallString.h - 'Normally small' strings --------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the SmallString class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SMALLSTRING_H
+#define WPIUTIL_WPI_SMALLSTRING_H
+
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include <cstddef>
+
+namespace wpi {
+
+/// SmallString - A SmallString is just a SmallVector with methods and accessors
+/// that make it work better as a string (e.g. operator+ etc).
+template<unsigned InternalLen>
+class SmallString : public SmallVector<char, InternalLen> {
+public:
+  /// Default ctor - Initialize to empty.
+  SmallString() = default;
+
+  /// Initialize from a StringRef.
+  SmallString(StringRef S) : SmallVector<char, InternalLen>(S.begin(), S.end()) {}
+
+  /// Initialize with a range.
+  template<typename ItTy>
+  SmallString(ItTy S, ItTy E) : SmallVector<char, InternalLen>(S, E) {}
+
+  // Note that in order to add new overloads for append & assign, we have to
+  // duplicate the inherited versions so as not to inadvertently hide them.
+
+  /// @}
+  /// @name String Assignment
+  /// @{
+
+  /// Assign from a repeated element.
+  void assign(size_t NumElts, char Elt) {
+    this->SmallVectorImpl<char>::assign(NumElts, Elt);
+  }
+
+  /// Assign from an iterator pair.
+  template<typename in_iter>
+  void assign(in_iter S, in_iter E) {
+    this->clear();
+    SmallVectorImpl<char>::append(S, E);
+  }
+
+  /// Assign from a StringRef.
+  void assign(StringRef RHS) {
+    this->clear();
+    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
+  }
+
+  /// Assign from a SmallVector.
+  void assign(const SmallVectorImpl<char> &RHS) {
+    this->clear();
+    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
+  }
+
+  /// @}
+  /// @name String Concatenation
+  /// @{
+
+  /// Append from an iterator pair.
+  template<typename in_iter>
+  void append(in_iter S, in_iter E) {
+    SmallVectorImpl<char>::append(S, E);
+  }
+
+  void append(size_t NumInputs, char Elt) {
+    SmallVectorImpl<char>::append(NumInputs, Elt);
+  }
+
+  /// Append from a StringRef.
+  void append(StringRef RHS) {
+    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
+  }
+
+  /// Append from a SmallVector.
+  void append(const SmallVectorImpl<char> &RHS) {
+    SmallVectorImpl<char>::append(RHS.begin(), RHS.end());
+  }
+
+  /// @}
+  /// @name String Comparison
+  /// @{
+
+  /// Check for string equality.  This is more efficient than compare() when
+  /// the relative ordering of inequal strings isn't needed.
+  bool equals(StringRef RHS) const {
+    return str().equals(RHS);
+  }
+
+  /// Check for string equality, ignoring case.
+  bool equals_lower(StringRef RHS) const {
+    return str().equals_lower(RHS);
+  }
+
+  /// Compare two strings; the result is -1, 0, or 1 if this string is
+  /// lexicographically less than, equal to, or greater than the \p RHS.
+  int compare(StringRef RHS) const {
+    return str().compare(RHS);
+  }
+
+  /// compare_lower - Compare two strings, ignoring case.
+  int compare_lower(StringRef RHS) const {
+    return str().compare_lower(RHS);
+  }
+
+  /// compare_numeric - Compare two strings, treating sequences of digits as
+  /// numbers.
+  int compare_numeric(StringRef RHS) const {
+    return str().compare_numeric(RHS);
+  }
+
+  /// @}
+  /// @name String Predicates
+  /// @{
+
+  /// startswith - Check if this string starts with the given \p Prefix.
+  bool startswith(StringRef Prefix) const {
+    return str().startswith(Prefix);
+  }
+
+  /// endswith - Check if this string ends with the given \p Suffix.
+  bool endswith(StringRef Suffix) const {
+    return str().endswith(Suffix);
+  }
+
+  /// @}
+  /// @name String Searching
+  /// @{
+
+  /// find - Search for the first character \p C in the string.
+  ///
+  /// \return - The index of the first occurrence of \p C, or npos if not
+  /// found.
+  size_t find(char C, size_t From = 0) const {
+    return str().find(C, From);
+  }
+
+  /// Search for the first string \p Str in the string.
+  ///
+  /// \returns The index of the first occurrence of \p Str, or npos if not
+  /// found.
+  size_t find(StringRef Str, size_t From = 0) const {
+    return str().find(Str, From);
+  }
+
+  /// Search for the last character \p C in the string.
+  ///
+  /// \returns The index of the last occurrence of \p C, or npos if not
+  /// found.
+  size_t rfind(char C, size_t From = StringRef::npos) const {
+    return str().rfind(C, From);
+  }
+
+  /// Search for the last string \p Str in the string.
+  ///
+  /// \returns The index of the last occurrence of \p Str, or npos if not
+  /// found.
+  size_t rfind(StringRef Str) const {
+    return str().rfind(Str);
+  }
+
+  /// Find the first character in the string that is \p C, or npos if not
+  /// found. Same as find.
+  size_t find_first_of(char C, size_t From = 0) const {
+    return str().find_first_of(C, From);
+  }
+
+  /// Find the first character in the string that is in \p Chars, or npos if
+  /// not found.
+  ///
+  /// Complexity: O(size() + Chars.size())
+  size_t find_first_of(StringRef Chars, size_t From = 0) const {
+    return str().find_first_of(Chars, From);
+  }
+
+  /// Find the first character in the string that is not \p C or npos if not
+  /// found.
+  size_t find_first_not_of(char C, size_t From = 0) const {
+    return str().find_first_not_of(C, From);
+  }
+
+  /// Find the first character in the string that is not in the string
+  /// \p Chars, or npos if not found.
+  ///
+  /// Complexity: O(size() + Chars.size())
+  size_t find_first_not_of(StringRef Chars, size_t From = 0) const {
+    return str().find_first_not_of(Chars, From);
+  }
+
+  /// Find the last character in the string that is \p C, or npos if not
+  /// found.
+  size_t find_last_of(char C, size_t From = StringRef::npos) const {
+    return str().find_last_of(C, From);
+  }
+
+  /// Find the last character in the string that is in \p C, or npos if not
+  /// found.
+  ///
+  /// Complexity: O(size() + Chars.size())
+  size_t find_last_of(
+      StringRef Chars, size_t From = StringRef::npos) const {
+    return str().find_last_of(Chars, From);
+  }
+
+  /// @}
+  /// @name Helpful Algorithms
+  /// @{
+
+  /// Return the number of occurrences of \p C in the string.
+  size_t count(char C) const {
+    return str().count(C);
+  }
+
+  /// Return the number of non-overlapped occurrences of \p Str in the
+  /// string.
+  size_t count(StringRef Str) const {
+    return str().count(Str);
+  }
+
+  /// @}
+  /// @name Substring Operations
+  /// @{
+
+  /// Return a reference to the substring from [Start, Start + N).
+  ///
+  /// \param Start The index of the starting character in the substring; if
+  /// the index is npos or greater than the length of the string then the
+  /// empty substring will be returned.
+  ///
+  /// \param N The number of characters to included in the substring. If \p N
+  /// exceeds the number of characters remaining in the string, the string
+  /// suffix (starting with \p Start) will be returned.
+  StringRef substr(size_t Start, size_t N = StringRef::npos) const {
+    return str().substr(Start, N);
+  }
+
+  /// Return a reference to the substring from [Start, End).
+  ///
+  /// \param Start The index of the starting character in the substring; if
+  /// the index is npos or greater than the length of the string then the
+  /// empty substring will be returned.
+  ///
+  /// \param End The index following the last character to include in the
+  /// substring. If this is npos, or less than \p Start, or exceeds the
+  /// number of characters remaining in the string, the string suffix
+  /// (starting with \p Start) will be returned.
+  StringRef slice(size_t Start, size_t End) const {
+    return str().slice(Start, End);
+  }
+
+  // Extra methods.
+
+  /// Explicit conversion to StringRef.
+  StringRef str() const { return StringRef(this->begin(), this->size()); }
+
+  // TODO: Make this const, if it's safe...
+  const char* c_str() {
+    this->push_back(0);
+    this->pop_back();
+    return this->data();
+  }
+
+  /// Implicit conversion to StringRef.
+  operator StringRef() const { return str(); }
+
+  // Extra operators.
+  const SmallString &operator=(StringRef RHS) {
+    this->clear();
+    return *this += RHS;
+  }
+
+  SmallString &operator+=(StringRef RHS) {
+    this->append(RHS.begin(), RHS.end());
+    return *this;
+  }
+  SmallString &operator+=(char C) {
+    this->push_back(C);
+    return *this;
+  }
+};
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_SMALLSTRING_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallVector.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallVector.h
new file mode 100644
index 0000000..3c5ad39
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SmallVector.h
@@ -0,0 +1,964 @@
+//===- llvm/ADT/SmallVector.h - 'Normally small' vectors --------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the SmallVector class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_SMALLVECTOR_H
+#define WPIUTIL_WPI_SMALLVECTOR_H
+
+// This file uses std::memcpy() to copy std::pair<unsigned int, unsigned int>.
+// That type is POD, but the standard doesn't guarantee that. GCC doesn't treat
+// the type as POD so it throws a warning. We want to consider this a warning
+// instead of an error.
+#if __GNUC__ >= 8
+#pragma GCC diagnostic warning "-Wclass-memaccess"
+#endif
+
+#include "wpi/iterator_range.h"
+#include "wpi/AlignOf.h"
+#include "wpi/Compiler.h"
+#include "wpi/MathExtras.h"
+#include "wpi/memory.h"
+#include "wpi/type_traits.h"
+#include <algorithm>
+#include <cassert>
+#include <cstddef>
+#include <cstdlib>
+#include <cstring>
+#include <initializer_list>
+#include <iterator>
+#include <memory>
+#include <new>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+/// This is all the non-templated stuff common to all SmallVectors.
+class SmallVectorBase {
+protected:
+  void *BeginX, *EndX, *CapacityX;
+
+protected:
+  SmallVectorBase(void *FirstEl, size_t Size)
+    : BeginX(FirstEl), EndX(FirstEl), CapacityX((char*)FirstEl+Size) {}
+
+  /// This is an implementation of the grow() method which only works
+  /// on POD-like data types and is out of line to reduce code duplication.
+  void grow_pod(void *FirstEl, size_t MinSizeInBytes, size_t TSize);
+
+public:
+  /// This returns size()*sizeof(T).
+  size_t size_in_bytes() const {
+    return size_t((char*)EndX - (char*)BeginX);
+  }
+
+  /// capacity_in_bytes - This returns capacity()*sizeof(T).
+  size_t capacity_in_bytes() const {
+    return size_t((char*)CapacityX - (char*)BeginX);
+  }
+
+  LLVM_NODISCARD bool empty() const { return BeginX == EndX; }
+};
+
+/// This is the part of SmallVectorTemplateBase which does not depend on whether
+/// the type T is a POD. The extra dummy template argument is used by ArrayRef
+/// to avoid unnecessarily requiring T to be complete.
+template <typename T, typename = void>
+class SmallVectorTemplateCommon : public SmallVectorBase {
+private:
+  template <typename, unsigned> friend struct SmallVectorStorage;
+
+  // Allocate raw space for N elements of type T.  If T has a ctor or dtor, we
+  // don't want it to be automatically run, so we need to represent the space as
+  // something else.  Use an array of char of sufficient alignment.
+  using U = AlignedCharArrayUnion<T>;
+  U FirstEl;
+  // Space after 'FirstEl' is clobbered, do not add any instance vars after it.
+
+protected:
+  SmallVectorTemplateCommon(size_t Size) : SmallVectorBase(&FirstEl, Size) {}
+
+  void grow_pod(size_t MinSizeInBytes, size_t TSize) {
+    SmallVectorBase::grow_pod(&FirstEl, MinSizeInBytes, TSize);
+  }
+
+  /// Return true if this is a smallvector which has not had dynamic
+  /// memory allocated for it.
+  bool isSmall() const {
+    return BeginX == static_cast<const void*>(&FirstEl);
+  }
+
+  /// Put this vector in a state of being small.
+  void resetToSmall() {
+    BeginX = EndX = CapacityX = &FirstEl;
+  }
+
+  void setEnd(T *P) { this->EndX = P; }
+
+public:
+  using size_type = size_t;
+  using difference_type = ptrdiff_t;
+  using value_type = T;
+  using iterator = T *;
+  using const_iterator = const T *;
+
+  using const_reverse_iterator = std::reverse_iterator<const_iterator>;
+  using reverse_iterator = std::reverse_iterator<iterator>;
+
+  using reference = T &;
+  using const_reference = const T &;
+  using pointer = T *;
+  using const_pointer = const T *;
+
+  // forward iterator creation methods.
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  iterator begin() { return (iterator)this->BeginX; }
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  const_iterator begin() const { return (const_iterator)this->BeginX; }
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  iterator end() { return (iterator)this->EndX; }
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  const_iterator end() const { return (const_iterator)this->EndX; }
+
+protected:
+  iterator capacity_ptr() { return (iterator)this->CapacityX; }
+  const_iterator capacity_ptr() const { return (const_iterator)this->CapacityX;}
+
+public:
+  // reverse iterator creation methods.
+  reverse_iterator rbegin()            { return reverse_iterator(end()); }
+  const_reverse_iterator rbegin() const{ return const_reverse_iterator(end()); }
+  reverse_iterator rend()              { return reverse_iterator(begin()); }
+  const_reverse_iterator rend() const { return const_reverse_iterator(begin());}
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  size_type size() const { return end()-begin(); }
+  size_type max_size() const { return size_type(-1) / sizeof(T); }
+
+  /// Return the total number of elements in the currently allocated buffer.
+  size_t capacity() const { return capacity_ptr() - begin(); }
+
+  /// Return a pointer to the vector's buffer, even if empty().
+  pointer data() { return pointer(begin()); }
+  /// Return a pointer to the vector's buffer, even if empty().
+  const_pointer data() const { return const_pointer(begin()); }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  reference operator[](size_type idx) {
+    assert(idx < size());
+    return begin()[idx];
+  }
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  const_reference operator[](size_type idx) const {
+    assert(idx < size());
+    return begin()[idx];
+  }
+
+  reference front() {
+    assert(!empty());
+    return begin()[0];
+  }
+  const_reference front() const {
+    assert(!empty());
+    return begin()[0];
+  }
+
+  reference back() {
+    assert(!empty());
+    return end()[-1];
+  }
+  const_reference back() const {
+    assert(!empty());
+    return end()[-1];
+  }
+};
+
+/// SmallVectorTemplateBase<isPodLike = false> - This is where we put method
+/// implementations that are designed to work with non-POD-like T's.
+template <typename T, bool isPodLike>
+class SmallVectorTemplateBase : public SmallVectorTemplateCommon<T> {
+protected:
+  SmallVectorTemplateBase(size_t Size) : SmallVectorTemplateCommon<T>(Size) {}
+
+  static void destroy_range(T *S, T *E) {
+    while (S != E) {
+      --E;
+      E->~T();
+    }
+  }
+
+  /// Move the range [I, E) into the uninitialized memory starting with "Dest",
+  /// constructing elements as needed.
+  template<typename It1, typename It2>
+  static void uninitialized_move(It1 I, It1 E, It2 Dest) {
+    std::uninitialized_copy(std::make_move_iterator(I),
+                            std::make_move_iterator(E), Dest);
+  }
+
+  /// Copy the range [I, E) onto the uninitialized memory starting with "Dest",
+  /// constructing elements as needed.
+  template<typename It1, typename It2>
+  static void uninitialized_copy(It1 I, It1 E, It2 Dest) {
+    std::uninitialized_copy(I, E, Dest);
+  }
+
+  /// Grow the allocated memory (without initializing new elements), doubling
+  /// the size of the allocated memory. Guarantees space for at least one more
+  /// element, or MinSize more elements if specified.
+  void grow(size_t MinSize = 0);
+
+public:
+  void push_back(const T &Elt) {
+    if (LLVM_UNLIKELY(this->EndX >= this->CapacityX))
+      this->grow();
+    ::new ((void*) this->end()) T(Elt);
+    this->setEnd(this->end()+1);
+  }
+
+  void push_back(T &&Elt) {
+    if (LLVM_UNLIKELY(this->EndX >= this->CapacityX))
+      this->grow();
+    ::new ((void*) this->end()) T(::std::move(Elt));
+    this->setEnd(this->end()+1);
+  }
+
+  void pop_back() {
+    this->setEnd(this->end()-1);
+    this->end()->~T();
+  }
+};
+
+// Define this out-of-line to dissuade the C++ compiler from inlining it.
+template <typename T, bool isPodLike>
+void SmallVectorTemplateBase<T, isPodLike>::grow(size_t MinSize) {
+  size_t CurCapacity = this->capacity();
+  size_t CurSize = this->size();
+  // Always grow, even from zero.
+  size_t NewCapacity = size_t(NextPowerOf2(CurCapacity+2));
+  if (NewCapacity < MinSize)
+    NewCapacity = MinSize;
+  T *NewElts = static_cast<T*>(CheckedMalloc(NewCapacity*sizeof(T)));
+
+  // Move the elements over.
+  this->uninitialized_move(this->begin(), this->end(), NewElts);
+
+  // Destroy the original elements.
+  destroy_range(this->begin(), this->end());
+
+  // If this wasn't grown from the inline copy, deallocate the old space.
+  if (!this->isSmall())
+    free(this->begin());
+
+  this->setEnd(NewElts+CurSize);
+  this->BeginX = NewElts;
+  this->CapacityX = this->begin()+NewCapacity;
+}
+
+
+/// SmallVectorTemplateBase<isPodLike = true> - This is where we put method
+/// implementations that are designed to work with POD-like T's.
+template <typename T>
+class SmallVectorTemplateBase<T, true> : public SmallVectorTemplateCommon<T> {
+protected:
+  SmallVectorTemplateBase(size_t Size) : SmallVectorTemplateCommon<T>(Size) {}
+
+  // No need to do a destroy loop for POD's.
+  static void destroy_range(T *, T *) {}
+
+  /// Move the range [I, E) onto the uninitialized memory
+  /// starting with "Dest", constructing elements into it as needed.
+  template<typename It1, typename It2>
+  static void uninitialized_move(It1 I, It1 E, It2 Dest) {
+    // Just do a copy.
+    uninitialized_copy(I, E, Dest);
+  }
+
+  /// Copy the range [I, E) onto the uninitialized memory
+  /// starting with "Dest", constructing elements into it as needed.
+  template<typename It1, typename It2>
+  static void uninitialized_copy(It1 I, It1 E, It2 Dest) {
+    // Arbitrary iterator types; just use the basic implementation.
+    std::uninitialized_copy(I, E, Dest);
+  }
+
+  /// Copy the range [I, E) onto the uninitialized memory
+  /// starting with "Dest", constructing elements into it as needed.
+  template <typename T1, typename T2>
+  static void uninitialized_copy(
+      T1 *I, T1 *E, T2 *Dest,
+      typename std::enable_if<std::is_same<typename std::remove_const<T1>::type,
+                                           T2>::value>::type * = nullptr) {
+    // Use memcpy for PODs iterated by pointers (which includes SmallVector
+    // iterators): std::uninitialized_copy optimizes to memmove, but we can
+    // use memcpy here. Note that I and E are iterators and thus might be
+    // invalid for memcpy if they are equal.
+    if (I != E)
+      memcpy(Dest, I, (E - I) * sizeof(T));
+  }
+
+  /// Double the size of the allocated memory, guaranteeing space for at
+  /// least one more element or MinSize if specified.
+  void grow(size_t MinSize = 0) {
+    this->grow_pod(MinSize*sizeof(T), sizeof(T));
+  }
+
+public:
+  void push_back(const T &Elt) {
+    if (LLVM_UNLIKELY(this->EndX >= this->CapacityX))
+      this->grow();
+    memcpy(this->end(), &Elt, sizeof(T));
+    this->setEnd(this->end()+1);
+  }
+
+  void pop_back() {
+    this->setEnd(this->end()-1);
+  }
+};
+
+/// This class consists of common code factored out of the SmallVector class to
+/// reduce code duplication based on the SmallVector 'N' template parameter.
+template <typename T>
+class SmallVectorImpl : public SmallVectorTemplateBase<T, isPodLike<T>::value> {
+  using SuperClass = SmallVectorTemplateBase<T, isPodLike<T>::value>;
+
+public:
+  using iterator = typename SuperClass::iterator;
+  using const_iterator = typename SuperClass::const_iterator;
+  using size_type = typename SuperClass::size_type;
+
+protected:
+  // Default ctor - Initialize to empty.
+  explicit SmallVectorImpl(unsigned N)
+    : SmallVectorTemplateBase<T, isPodLike<T>::value>(N*sizeof(T)) {
+  }
+
+public:
+  SmallVectorImpl(const SmallVectorImpl &) = delete;
+
+  ~SmallVectorImpl() {
+    // Subclass has already destructed this vector's elements.
+    // If this wasn't grown from the inline copy, deallocate the old space.
+    if (!this->isSmall())
+      free(this->begin());
+  }
+
+  void clear() {
+    this->destroy_range(this->begin(), this->end());
+    this->EndX = this->BeginX;
+  }
+
+  void resize(size_type N) {
+    if (N < this->size()) {
+      this->destroy_range(this->begin()+N, this->end());
+      this->setEnd(this->begin()+N);
+    } else if (N > this->size()) {
+      if (this->capacity() < N)
+        this->grow(N);
+      for (auto I = this->end(), E = this->begin() + N; I != E; ++I)
+        new (&*I) T();
+      this->setEnd(this->begin()+N);
+    }
+  }
+
+  void resize(size_type N, const T &NV) {
+    if (N < this->size()) {
+      this->destroy_range(this->begin()+N, this->end());
+      this->setEnd(this->begin()+N);
+    } else if (N > this->size()) {
+      if (this->capacity() < N)
+        this->grow(N);
+      std::uninitialized_fill(this->end(), this->begin()+N, NV);
+      this->setEnd(this->begin()+N);
+    }
+  }
+
+  void reserve(size_type N) {
+    if (this->capacity() < N)
+      this->grow(N);
+  }
+
+  LLVM_NODISCARD T pop_back_val() {
+    T Result = ::std::move(this->back());
+    this->pop_back();
+    return Result;
+  }
+
+  void swap(SmallVectorImpl &RHS);
+
+  /// Add the specified range to the end of the SmallVector.
+  template <typename in_iter,
+            typename = typename std::enable_if<std::is_convertible<
+                typename std::iterator_traits<in_iter>::iterator_category,
+                std::input_iterator_tag>::value>::type>
+  void append(in_iter in_start, in_iter in_end) {
+    size_type NumInputs = std::distance(in_start, in_end);
+    // Grow allocated space if needed.
+    if (NumInputs > size_type(this->capacity_ptr()-this->end()))
+      this->grow(this->size()+NumInputs);
+
+    // Copy the new elements over.
+    this->uninitialized_copy(in_start, in_end, this->end());
+    this->setEnd(this->end() + NumInputs);
+  }
+
+  /// Add the specified range to the end of the SmallVector.
+  void append(size_type NumInputs, const T &Elt) {
+    // Grow allocated space if needed.
+    if (NumInputs > size_type(this->capacity_ptr()-this->end()))
+      this->grow(this->size()+NumInputs);
+
+    // Copy the new elements over.
+    std::uninitialized_fill_n(this->end(), NumInputs, Elt);
+    this->setEnd(this->end() + NumInputs);
+  }
+
+  void append(std::initializer_list<T> IL) {
+    append(IL.begin(), IL.end());
+  }
+
+  // FIXME: Consider assigning over existing elements, rather than clearing &
+  // re-initializing them - for all assign(...) variants.
+
+  void assign(size_type NumElts, const T &Elt) {
+    clear();
+    if (this->capacity() < NumElts)
+      this->grow(NumElts);
+    this->setEnd(this->begin()+NumElts);
+    std::uninitialized_fill(this->begin(), this->end(), Elt);
+  }
+
+  template <typename in_iter,
+            typename = typename std::enable_if<std::is_convertible<
+                typename std::iterator_traits<in_iter>::iterator_category,
+                std::input_iterator_tag>::value>::type>
+  void assign(in_iter in_start, in_iter in_end) {
+    clear();
+    append(in_start, in_end);
+  }
+
+  void assign(std::initializer_list<T> IL) {
+    clear();
+    append(IL);
+  }
+
+  iterator erase(const_iterator CI) {
+    // Just cast away constness because this is a non-const member function.
+    iterator I = const_cast<iterator>(CI);
+
+    assert(I >= this->begin() && "Iterator to erase is out of bounds.");
+    assert(I < this->end() && "Erasing at past-the-end iterator.");
+
+    iterator N = I;
+    // Shift all elts down one.
+    std::move(I+1, this->end(), I);
+    // Drop the last elt.
+    this->pop_back();
+    return(N);
+  }
+
+  iterator erase(const_iterator CS, const_iterator CE) {
+    // Just cast away constness because this is a non-const member function.
+    iterator S = const_cast<iterator>(CS);
+    iterator E = const_cast<iterator>(CE);
+
+    assert(S >= this->begin() && "Range to erase is out of bounds.");
+    assert(S <= E && "Trying to erase invalid range.");
+    assert(E <= this->end() && "Trying to erase past the end.");
+
+    iterator N = S;
+    // Shift all elts down.
+    iterator I = std::move(E, this->end(), S);
+    // Drop the last elts.
+    this->destroy_range(I, this->end());
+    this->setEnd(I);
+    return(N);
+  }
+
+  iterator insert(iterator I, T &&Elt) {
+    if (I == this->end()) {  // Important special case for empty vector.
+      this->push_back(::std::move(Elt));
+      return this->end()-1;
+    }
+
+    assert(I >= this->begin() && "Insertion iterator is out of bounds.");
+    assert(I <= this->end() && "Inserting past the end of the vector.");
+
+    if (this->EndX >= this->CapacityX) {
+      size_t EltNo = I-this->begin();
+      this->grow();
+      I = this->begin()+EltNo;
+    }
+
+    ::new ((void*) this->end()) T(::std::move(this->back()));
+    // Push everything else over.
+    std::move_backward(I, this->end()-1, this->end());
+    this->setEnd(this->end()+1);
+
+    // If we just moved the element we're inserting, be sure to update
+    // the reference.
+    T *EltPtr = &Elt;
+    if (I <= EltPtr && EltPtr < this->EndX)
+      ++EltPtr;
+
+    *I = ::std::move(*EltPtr);
+    return I;
+  }
+
+  iterator insert(iterator I, const T &Elt) {
+    if (I == this->end()) {  // Important special case for empty vector.
+      this->push_back(Elt);
+      return this->end()-1;
+    }
+
+    assert(I >= this->begin() && "Insertion iterator is out of bounds.");
+    assert(I <= this->end() && "Inserting past the end of the vector.");
+
+    if (this->EndX >= this->CapacityX) {
+      size_t EltNo = I-this->begin();
+      this->grow();
+      I = this->begin()+EltNo;
+    }
+    ::new ((void*) this->end()) T(std::move(this->back()));
+    // Push everything else over.
+    std::move_backward(I, this->end()-1, this->end());
+    this->setEnd(this->end()+1);
+
+    // If we just moved the element we're inserting, be sure to update
+    // the reference.
+    const T *EltPtr = &Elt;
+    if (I <= EltPtr && EltPtr < this->EndX)
+      ++EltPtr;
+
+    *I = *EltPtr;
+    return I;
+  }
+
+  iterator insert(iterator I, size_type NumToInsert, const T &Elt) {
+    // Convert iterator to elt# to avoid invalidating iterator when we reserve()
+    size_t InsertElt = I - this->begin();
+
+    if (I == this->end()) {  // Important special case for empty vector.
+      append(NumToInsert, Elt);
+      return this->begin()+InsertElt;
+    }
+
+    assert(I >= this->begin() && "Insertion iterator is out of bounds.");
+    assert(I <= this->end() && "Inserting past the end of the vector.");
+
+    // Ensure there is enough space.
+    reserve(this->size() + NumToInsert);
+
+    // Uninvalidate the iterator.
+    I = this->begin()+InsertElt;
+
+    // If there are more elements between the insertion point and the end of the
+    // range than there are being inserted, we can use a simple approach to
+    // insertion.  Since we already reserved space, we know that this won't
+    // reallocate the vector.
+    if (size_t(this->end()-I) >= NumToInsert) {
+      T *OldEnd = this->end();
+      append(std::move_iterator<iterator>(this->end() - NumToInsert),
+             std::move_iterator<iterator>(this->end()));
+
+      // Copy the existing elements that get replaced.
+      std::move_backward(I, OldEnd-NumToInsert, OldEnd);
+
+      std::fill_n(I, NumToInsert, Elt);
+      return I;
+    }
+
+    // Otherwise, we're inserting more elements than exist already, and we're
+    // not inserting at the end.
+
+    // Move over the elements that we're about to overwrite.
+    T *OldEnd = this->end();
+    this->setEnd(this->end() + NumToInsert);
+    size_t NumOverwritten = OldEnd-I;
+    this->uninitialized_move(I, OldEnd, this->end()-NumOverwritten);
+
+    // Replace the overwritten part.
+    std::fill_n(I, NumOverwritten, Elt);
+
+    // Insert the non-overwritten middle part.
+    std::uninitialized_fill_n(OldEnd, NumToInsert-NumOverwritten, Elt);
+    return I;
+  }
+
+  template <typename ItTy,
+            typename = typename std::enable_if<std::is_convertible<
+                typename std::iterator_traits<ItTy>::iterator_category,
+                std::input_iterator_tag>::value>::type>
+  iterator insert(iterator I, ItTy From, ItTy To) {
+    // Convert iterator to elt# to avoid invalidating iterator when we reserve()
+    size_t InsertElt = I - this->begin();
+
+    if (I == this->end()) {  // Important special case for empty vector.
+      append(From, To);
+      return this->begin()+InsertElt;
+    }
+
+    assert(I >= this->begin() && "Insertion iterator is out of bounds.");
+    assert(I <= this->end() && "Inserting past the end of the vector.");
+
+    size_t NumToInsert = std::distance(From, To);
+
+    // Ensure there is enough space.
+    reserve(this->size() + NumToInsert);
+
+    // Uninvalidate the iterator.
+    I = this->begin()+InsertElt;
+
+    // If there are more elements between the insertion point and the end of the
+    // range than there are being inserted, we can use a simple approach to
+    // insertion.  Since we already reserved space, we know that this won't
+    // reallocate the vector.
+    if (size_t(this->end()-I) >= NumToInsert) {
+      T *OldEnd = this->end();
+      append(std::move_iterator<iterator>(this->end() - NumToInsert),
+             std::move_iterator<iterator>(this->end()));
+
+      // Copy the existing elements that get replaced.
+      std::move_backward(I, OldEnd-NumToInsert, OldEnd);
+
+      std::copy(From, To, I);
+      return I;
+    }
+
+    // Otherwise, we're inserting more elements than exist already, and we're
+    // not inserting at the end.
+
+    // Move over the elements that we're about to overwrite.
+    T *OldEnd = this->end();
+    this->setEnd(this->end() + NumToInsert);
+    size_t NumOverwritten = OldEnd-I;
+    this->uninitialized_move(I, OldEnd, this->end()-NumOverwritten);
+
+    // Replace the overwritten part.
+    for (T *J = I; NumOverwritten > 0; --NumOverwritten) {
+      *J = *From;
+      ++J; ++From;
+    }
+
+    // Insert the non-overwritten middle part.
+    this->uninitialized_copy(From, To, OldEnd);
+    return I;
+  }
+
+  void insert(iterator I, std::initializer_list<T> IL) {
+    insert(I, IL.begin(), IL.end());
+  }
+
+  template <typename... ArgTypes> void emplace_back(ArgTypes &&... Args) {
+    if (LLVM_UNLIKELY(this->EndX >= this->CapacityX))
+      this->grow();
+    ::new ((void *)this->end()) T(std::forward<ArgTypes>(Args)...);
+    this->setEnd(this->end() + 1);
+  }
+
+  SmallVectorImpl &operator=(const SmallVectorImpl &RHS);
+
+  SmallVectorImpl &operator=(SmallVectorImpl &&RHS);
+
+  bool operator==(const SmallVectorImpl &RHS) const {
+    if (this->size() != RHS.size()) return false;
+    return std::equal(this->begin(), this->end(), RHS.begin());
+  }
+  bool operator!=(const SmallVectorImpl &RHS) const {
+    return !(*this == RHS);
+  }
+
+  bool operator<(const SmallVectorImpl &RHS) const {
+    return std::lexicographical_compare(this->begin(), this->end(),
+                                        RHS.begin(), RHS.end());
+  }
+
+  /// Set the array size to \p N, which the current array must have enough
+  /// capacity for.
+  ///
+  /// This does not construct or destroy any elements in the vector.
+  ///
+  /// Clients can use this in conjunction with capacity() to write past the end
+  /// of the buffer when they know that more elements are available, and only
+  /// update the size later. This avoids the cost of value initializing elements
+  /// which will only be overwritten.
+  void set_size(size_type N) {
+    assert(N <= this->capacity());
+    this->setEnd(this->begin() + N);
+  }
+};
+
+template <typename T>
+void SmallVectorImpl<T>::swap(SmallVectorImpl<T> &RHS) {
+  if (this == &RHS) return;
+
+  // We can only avoid copying elements if neither vector is small.
+  if (!this->isSmall() && !RHS.isSmall()) {
+    std::swap(this->BeginX, RHS.BeginX);
+    std::swap(this->EndX, RHS.EndX);
+    std::swap(this->CapacityX, RHS.CapacityX);
+    return;
+  }
+  if (RHS.size() > this->capacity())
+    this->grow(RHS.size());
+  if (this->size() > RHS.capacity())
+    RHS.grow(this->size());
+
+  // Swap the shared elements.
+  size_t NumShared = this->size();
+  if (NumShared > RHS.size()) NumShared = RHS.size();
+  for (size_type i = 0; i != NumShared; ++i)
+    std::swap((*this)[i], RHS[i]);
+
+  // Copy over the extra elts.
+  if (this->size() > RHS.size()) {
+    size_t EltDiff = this->size() - RHS.size();
+    this->uninitialized_copy(this->begin()+NumShared, this->end(), RHS.end());
+    RHS.setEnd(RHS.end()+EltDiff);
+    this->destroy_range(this->begin()+NumShared, this->end());
+    this->setEnd(this->begin()+NumShared);
+  } else if (RHS.size() > this->size()) {
+    size_t EltDiff = RHS.size() - this->size();
+    this->uninitialized_copy(RHS.begin()+NumShared, RHS.end(), this->end());
+    this->setEnd(this->end() + EltDiff);
+    this->destroy_range(RHS.begin()+NumShared, RHS.end());
+    RHS.setEnd(RHS.begin()+NumShared);
+  }
+}
+
+template <typename T>
+SmallVectorImpl<T> &SmallVectorImpl<T>::
+  operator=(const SmallVectorImpl<T> &RHS) {
+  // Avoid self-assignment.
+  if (this == &RHS) return *this;
+
+  // If we already have sufficient space, assign the common elements, then
+  // destroy any excess.
+  size_t RHSSize = RHS.size();
+  size_t CurSize = this->size();
+  if (CurSize >= RHSSize) {
+    // Assign common elements.
+    iterator NewEnd;
+    if (RHSSize)
+      NewEnd = std::copy(RHS.begin(), RHS.begin()+RHSSize, this->begin());
+    else
+      NewEnd = this->begin();
+
+    // Destroy excess elements.
+    this->destroy_range(NewEnd, this->end());
+
+    // Trim.
+    this->setEnd(NewEnd);
+    return *this;
+  }
+
+  // If we have to grow to have enough elements, destroy the current elements.
+  // This allows us to avoid copying them during the grow.
+  // FIXME: don't do this if they're efficiently moveable.
+  if (this->capacity() < RHSSize) {
+    // Destroy current elements.
+    this->destroy_range(this->begin(), this->end());
+    this->setEnd(this->begin());
+    CurSize = 0;
+    this->grow(RHSSize);
+  } else if (CurSize) {
+    // Otherwise, use assignment for the already-constructed elements.
+    std::copy(RHS.begin(), RHS.begin()+CurSize, this->begin());
+  }
+
+  // Copy construct the new elements in place.
+  this->uninitialized_copy(RHS.begin()+CurSize, RHS.end(),
+                           this->begin()+CurSize);
+
+  // Set end.
+  this->setEnd(this->begin()+RHSSize);
+  return *this;
+}
+
+template <typename T>
+SmallVectorImpl<T> &SmallVectorImpl<T>::operator=(SmallVectorImpl<T> &&RHS) {
+  // Avoid self-assignment.
+  if (this == &RHS) return *this;
+
+  // If the RHS isn't small, clear this vector and then steal its buffer.
+  if (!RHS.isSmall()) {
+    this->destroy_range(this->begin(), this->end());
+    if (!this->isSmall()) free(this->begin());
+    this->BeginX = RHS.BeginX;
+    this->EndX = RHS.EndX;
+    this->CapacityX = RHS.CapacityX;
+    RHS.resetToSmall();
+    return *this;
+  }
+
+  // If we already have sufficient space, assign the common elements, then
+  // destroy any excess.
+  size_t RHSSize = RHS.size();
+  size_t CurSize = this->size();
+  if (CurSize >= RHSSize) {
+    // Assign common elements.
+    iterator NewEnd = this->begin();
+    if (RHSSize)
+      NewEnd = std::move(RHS.begin(), RHS.end(), NewEnd);
+
+    // Destroy excess elements and trim the bounds.
+    this->destroy_range(NewEnd, this->end());
+    this->setEnd(NewEnd);
+
+    // Clear the RHS.
+    RHS.clear();
+
+    return *this;
+  }
+
+  // If we have to grow to have enough elements, destroy the current elements.
+  // This allows us to avoid copying them during the grow.
+  // FIXME: this may not actually make any sense if we can efficiently move
+  // elements.
+  if (this->capacity() < RHSSize) {
+    // Destroy current elements.
+    this->destroy_range(this->begin(), this->end());
+    this->setEnd(this->begin());
+    CurSize = 0;
+    this->grow(RHSSize);
+  } else if (CurSize) {
+    // Otherwise, use assignment for the already-constructed elements.
+    std::move(RHS.begin(), RHS.begin()+CurSize, this->begin());
+  }
+
+  // Move-construct the new elements in place.
+  this->uninitialized_move(RHS.begin()+CurSize, RHS.end(),
+                           this->begin()+CurSize);
+
+  // Set end.
+  this->setEnd(this->begin()+RHSSize);
+
+  RHS.clear();
+  return *this;
+}
+
+/// Storage for the SmallVector elements which aren't contained in
+/// SmallVectorTemplateCommon. There are 'N-1' elements here. The remaining '1'
+/// element is in the base class. This is specialized for the N=1 and N=0 cases
+/// to avoid allocating unnecessary storage.
+template <typename T, unsigned N>
+struct SmallVectorStorage {
+  typename SmallVectorTemplateCommon<T>::U InlineElts[N - 1];
+};
+template <typename T> struct SmallVectorStorage<T, 1> {};
+template <typename T> struct SmallVectorStorage<T, 0> {};
+
+/// This is a 'vector' (really, a variable-sized array), optimized
+/// for the case when the array is small.  It contains some number of elements
+/// in-place, which allows it to avoid heap allocation when the actual number of
+/// elements is below that threshold.  This allows normal "small" cases to be
+/// fast without losing generality for large inputs.
+///
+/// Note that this does not attempt to be exception safe.
+///
+template <typename T, unsigned N>
+class SmallVector : public SmallVectorImpl<T> {
+  /// Inline space for elements which aren't stored in the base class.
+  SmallVectorStorage<T, N> Storage;
+
+public:
+  SmallVector() : SmallVectorImpl<T>(N) {}
+
+  ~SmallVector() {
+    // Destroy the constructed elements in the vector.
+    this->destroy_range(this->begin(), this->end());
+  }
+
+  explicit SmallVector(size_t Size, const T &Value = T())
+    : SmallVectorImpl<T>(N) {
+    this->assign(Size, Value);
+  }
+
+  template <typename ItTy,
+            typename = typename std::enable_if<std::is_convertible<
+                typename std::iterator_traits<ItTy>::iterator_category,
+                std::input_iterator_tag>::value>::type>
+  SmallVector(ItTy S, ItTy E) : SmallVectorImpl<T>(N) {
+    this->append(S, E);
+  }
+
+  template <typename RangeTy>
+  explicit SmallVector(const iterator_range<RangeTy> &R)
+      : SmallVectorImpl<T>(N) {
+    this->append(R.begin(), R.end());
+  }
+
+  SmallVector(std::initializer_list<T> IL) : SmallVectorImpl<T>(N) {
+    this->assign(IL);
+  }
+
+  SmallVector(const SmallVector &RHS) : SmallVectorImpl<T>(N) {
+    if (!RHS.empty())
+      SmallVectorImpl<T>::operator=(RHS);
+  }
+
+  const SmallVector &operator=(const SmallVector &RHS) {
+    SmallVectorImpl<T>::operator=(RHS);
+    return *this;
+  }
+
+  SmallVector(SmallVector &&RHS) : SmallVectorImpl<T>(N) {
+    if (!RHS.empty())
+      SmallVectorImpl<T>::operator=(::std::move(RHS));
+  }
+
+  SmallVector(SmallVectorImpl<T> &&RHS) : SmallVectorImpl<T>(N) {
+    if (!RHS.empty())
+      SmallVectorImpl<T>::operator=(::std::move(RHS));
+  }
+
+  const SmallVector &operator=(SmallVector &&RHS) {
+    SmallVectorImpl<T>::operator=(::std::move(RHS));
+    return *this;
+  }
+
+  const SmallVector &operator=(SmallVectorImpl<T> &&RHS) {
+    SmallVectorImpl<T>::operator=(::std::move(RHS));
+    return *this;
+  }
+
+  const SmallVector &operator=(std::initializer_list<T> IL) {
+    this->assign(IL);
+    return *this;
+  }
+};
+
+template <typename T, unsigned N>
+inline size_t capacity_in_bytes(const SmallVector<T, N> &X) {
+  return X.capacity_in_bytes();
+}
+
+} // end namespace wpi
+
+namespace std {
+
+  /// Implement std::swap in terms of SmallVector swap.
+  template<typename T>
+  inline void
+  swap(wpi::SmallVectorImpl<T> &LHS, wpi::SmallVectorImpl<T> &RHS) {
+    LHS.swap(RHS);
+  }
+
+  /// Implement std::swap in terms of SmallVector swap.
+  template<typename T, unsigned N>
+  inline void
+  swap(wpi::SmallVector<T, N> &LHS, wpi::SmallVector<T, N> &RHS) {
+    LHS.swap(RHS);
+  }
+
+} // end namespace std
+
+#endif // LLVM_ADT_SMALLVECTOR_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SocketError.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SocketError.h
new file mode 100644
index 0000000..d5f3ff0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/SocketError.h
@@ -0,0 +1,25 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_SOCKETERROR_H_
+#define WPIUTIL_WPI_SOCKETERROR_H_
+
+#include <string>
+
+namespace wpi {
+
+int SocketErrno();
+
+std::string SocketStrerror(int code);
+
+static inline std::string SocketStrerror() {
+  return SocketStrerror(SocketErrno());
+}
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_SOCKETERROR_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringExtras.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringExtras.h
new file mode 100644
index 0000000..10d6aff
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringExtras.h
@@ -0,0 +1,380 @@
+//===- llvm/ADT/StringExtras.h - Useful string functions --------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file contains some functions that are useful when dealing with strings.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_STRINGEXTRAS_H
+#define WPIUTIL_WPI_STRINGEXTRAS_H
+
+#include "wpi/ArrayRef.h"
+#include "wpi/SmallString.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <cstdlib>
+#include <cstring>
+#include <iterator>
+#include <string>
+#include <utility>
+
+namespace wpi {
+
+template<typename T> class SmallVectorImpl;
+class raw_ostream;
+
+/// hexdigit - Return the hexadecimal character for the
+/// given number \p X (which should be less than 16).
+inline char hexdigit(unsigned X, bool LowerCase = false) {
+  const char HexChar = LowerCase ? 'a' : 'A';
+  return X < 10 ? '0' + X : HexChar + X - 10;
+}
+
+/// Construct a string ref from a boolean.
+inline StringRef toStringRef(bool B) { return StringRef(B ? "true" : "false"); }
+
+/// Construct a string ref from an array ref of unsigned chars.
+inline StringRef toStringRef(ArrayRef<uint8_t> Input) {
+  return StringRef(reinterpret_cast<const char *>(Input.begin()), Input.size());
+}
+
+/// Construct a string ref from an array ref of unsigned chars.
+inline ArrayRef<uint8_t> arrayRefFromStringRef(StringRef Input) {
+  return {Input.bytes_begin(), Input.bytes_end()};
+}
+
+/// Interpret the given character \p C as a hexadecimal digit and return its
+/// value.
+///
+/// If \p C is not a valid hex digit, -1U is returned.
+inline unsigned hexDigitValue(char C) {
+  if (C >= '0' && C <= '9') return C-'0';
+  if (C >= 'a' && C <= 'f') return C-'a'+10U;
+  if (C >= 'A' && C <= 'F') return C-'A'+10U;
+  return -1U;
+}
+
+/// Checks if character \p C is one of the 10 decimal digits.
+inline bool isDigit(char C) { return C >= '0' && C <= '9'; }
+
+/// Checks if character \p C is a hexadecimal numeric character.
+inline bool isHexDigit(char C) { return hexDigitValue(C) != -1U; }
+
+/// Checks if character \p C is a valid letter as classified by "C" locale.
+inline bool isAlpha(char C) {
+  return ('a' <= C && C <= 'z') || ('A' <= C && C <= 'Z');
+}
+
+/// Checks whether character \p C is either a decimal digit or an uppercase or
+/// lowercase letter as classified by "C" locale.
+inline bool isAlnum(char C) { return isAlpha(C) || isDigit(C); }
+
+/// Returns the corresponding lowercase character if \p x is uppercase.
+inline char toLower(char x) {
+  if (x >= 'A' && x <= 'Z')
+    return x - 'A' + 'a';
+  return x;
+}
+
+/// Returns the corresponding uppercase character if \p x is lowercase.
+inline char toUpper(char x) {
+  if (x >= 'a' && x <= 'z')
+    return x - 'a' + 'A';
+  return x;
+}
+
+inline std::string utohexstr(uint64_t X, bool LowerCase = false) {
+  char Buffer[17];
+  char *BufPtr = std::end(Buffer);
+
+  if (X == 0) *--BufPtr = '0';
+
+  while (X) {
+    unsigned char Mod = static_cast<unsigned char>(X) & 15;
+    *--BufPtr = hexdigit(Mod, LowerCase);
+    X >>= 4;
+  }
+
+  return std::string(BufPtr, std::end(Buffer));
+}
+
+/// Convert buffer \p Input to its hexadecimal representation.
+/// The returned string is double the size of \p Input.
+inline std::string toHex(StringRef Input) {
+  static const char *const LUT = "0123456789ABCDEF";
+  size_t Length = Input.size();
+
+  std::string Output;
+  Output.reserve(2 * Length);
+  for (size_t i = 0; i < Length; ++i) {
+    const unsigned char c = Input[i];
+    Output.push_back(LUT[c >> 4]);
+    Output.push_back(LUT[c & 15]);
+  }
+  return Output;
+}
+
+inline std::string toHex(ArrayRef<uint8_t> Input) {
+  return toHex(toStringRef(Input));
+}
+
+inline uint8_t hexFromNibbles(char MSB, char LSB) {
+  unsigned U1 = hexDigitValue(MSB);
+  unsigned U2 = hexDigitValue(LSB);
+  assert(U1 != -1U && U2 != -1U);
+
+  return static_cast<uint8_t>((U1 << 4) | U2);
+}
+
+/// Convert hexadecimal string \p Input to its binary representation.
+/// The return string is half the size of \p Input.
+inline std::string fromHex(StringRef Input) {
+  if (Input.empty())
+    return std::string();
+
+  std::string Output;
+  Output.reserve((Input.size() + 1) / 2);
+  if (Input.size() % 2 == 1) {
+    Output.push_back(hexFromNibbles('0', Input.front()));
+    Input = Input.drop_front();
+  }
+
+  assert(Input.size() % 2 == 0);
+  while (!Input.empty()) {
+    uint8_t Hex = hexFromNibbles(Input[0], Input[1]);
+    Output.push_back(Hex);
+    Input = Input.drop_front(2);
+  }
+  return Output;
+}
+
+/// Convert the string \p S to an integer of the specified type using
+/// the radix \p Base.  If \p Base is 0, auto-detects the radix.
+/// Returns true if the number was successfully converted, false otherwise.
+template <typename N> bool to_integer(StringRef S, N &Num, unsigned Base = 0) {
+  return !S.getAsInteger(Base, Num);
+}
+
+namespace detail {
+template <typename N>
+inline bool to_float(const Twine &T, N &Num, N (*StrTo)(const char *, char **)) {
+  SmallString<32> Storage;
+  StringRef S = T.toNullTerminatedStringRef(Storage);
+  char *End;
+  N Temp = StrTo(S.data(), &End);
+  if (*End != '\0')
+    return false;
+  Num = Temp;
+  return true;
+}
+}
+
+inline bool to_float(const Twine &T, float &Num) {
+  return detail::to_float(T, Num, strtof);
+}
+
+inline bool to_float(const Twine &T, double &Num) {
+  return detail::to_float(T, Num, strtod);
+}
+
+inline bool to_float(const Twine &T, long double &Num) {
+  return detail::to_float(T, Num, strtold);
+}
+
+inline std::string utostr(uint64_t X, bool isNeg = false) {
+  char Buffer[21];
+  char *BufPtr = std::end(Buffer);
+
+  if (X == 0) *--BufPtr = '0';  // Handle special case...
+
+  while (X) {
+    *--BufPtr = '0' + char(X % 10);
+    X /= 10;
+  }
+
+  if (isNeg) *--BufPtr = '-';   // Add negative sign...
+  return std::string(BufPtr, std::end(Buffer));
+}
+
+inline std::string itostr(int64_t X) {
+  if (X < 0)
+    return utostr(static_cast<uint64_t>(-X), true);
+  else
+    return utostr(static_cast<uint64_t>(X));
+}
+
+/// StrInStrNoCase - Portable version of strcasestr.  Locates the first
+/// occurrence of string 's1' in string 's2', ignoring case.  Returns
+/// the offset of s2 in s1 or npos if s2 cannot be found.
+StringRef::size_type StrInStrNoCase(StringRef s1, StringRef s2);
+
+/// getToken - This function extracts one token from source, ignoring any
+/// leading characters that appear in the Delimiters string, and ending the
+/// token at any of the characters that appear in the Delimiters string.  If
+/// there are no tokens in the source string, an empty string is returned.
+/// The function returns a pair containing the extracted token and the
+/// remaining tail string.
+std::pair<StringRef, StringRef> getToken(StringRef Source,
+                                         StringRef Delimiters = " \t\n\v\f\r");
+
+/// SplitString - Split up the specified string according to the specified
+/// delimiters, appending the result fragments to the output list.
+void SplitString(StringRef Source,
+                 SmallVectorImpl<StringRef> &OutFragments,
+                 StringRef Delimiters = " \t\n\v\f\r");
+
+/// HashString - Hash function for strings.
+///
+/// This is the Bernstein hash function.
+//
+// FIXME: Investigate whether a modified bernstein hash function performs
+// better: http://eternallyconfuzzled.com/tuts/algorithms/jsw_tut_hashing.aspx
+//   X*33+c -> X*33^c
+static inline unsigned HashString(StringRef Str, unsigned Result = 0) {
+  for (StringRef::size_type i = 0, e = Str.size(); i != e; ++i)
+    Result = Result * 33 + (unsigned char)Str[i];
+  return Result;
+}
+
+/// Returns the English suffix for an ordinal integer (-st, -nd, -rd, -th).
+inline StringRef getOrdinalSuffix(unsigned Val) {
+  // It is critically important that we do this perfectly for
+  // user-written sequences with over 100 elements.
+  switch (Val % 100) {
+  case 11:
+  case 12:
+  case 13:
+    return "th";
+  default:
+    switch (Val % 10) {
+      case 1: return "st";
+      case 2: return "nd";
+      case 3: return "rd";
+      default: return "th";
+    }
+  }
+}
+
+/// PrintEscapedString - Print each character of the specified string, escaping
+/// it if it is not printable or if it is an escape char.
+void PrintEscapedString(StringRef Name, raw_ostream &Out);
+
+/// printLowerCase - Print each character as lowercase if it is uppercase.
+void printLowerCase(StringRef String, raw_ostream &Out);
+
+namespace detail {
+
+template <typename IteratorT>
+inline std::string join_impl(IteratorT Begin, IteratorT End,
+                             StringRef Separator, std::input_iterator_tag) {
+  std::string S;
+  if (Begin == End)
+    return S;
+
+  S += (*Begin);
+  while (++Begin != End) {
+    S += Separator;
+    S += (*Begin);
+  }
+  return S;
+}
+
+template <typename IteratorT>
+inline std::string join_impl(IteratorT Begin, IteratorT End,
+                             StringRef Separator, std::forward_iterator_tag) {
+  std::string S;
+  if (Begin == End)
+    return S;
+
+  size_t Len = (std::distance(Begin, End) - 1) * Separator.size();
+  for (IteratorT I = Begin; I != End; ++I)
+    Len += (*Begin).size();
+  S.reserve(Len);
+  S += (*Begin);
+  while (++Begin != End) {
+    S += Separator;
+    S += (*Begin);
+  }
+  return S;
+}
+
+template <typename Sep>
+inline void join_items_impl(std::string &Result, Sep Separator) {}
+
+template <typename Sep, typename Arg>
+inline void join_items_impl(std::string &Result, Sep Separator,
+                            const Arg &Item) {
+  Result += Item;
+}
+
+template <typename Sep, typename Arg1, typename... Args>
+inline void join_items_impl(std::string &Result, Sep Separator, const Arg1 &A1,
+                            Args &&... Items) {
+  Result += A1;
+  Result += Separator;
+  join_items_impl(Result, Separator, std::forward<Args>(Items)...);
+}
+
+inline size_t join_one_item_size(char C) { return 1; }
+inline size_t join_one_item_size(const char *S) { return S ? ::strlen(S) : 0; }
+
+template <typename T> inline size_t join_one_item_size(const T &Str) {
+  return Str.size();
+}
+
+inline size_t join_items_size() { return 0; }
+
+template <typename A1> inline size_t join_items_size(const A1 &A) {
+  return join_one_item_size(A);
+}
+template <typename A1, typename... Args>
+inline size_t join_items_size(const A1 &A, Args &&... Items) {
+  return join_one_item_size(A) + join_items_size(std::forward<Args>(Items)...);
+}
+
+} // end namespace detail
+
+/// Joins the strings in the range [Begin, End), adding Separator between
+/// the elements.
+template <typename IteratorT>
+inline std::string join(IteratorT Begin, IteratorT End, StringRef Separator) {
+  using tag = typename std::iterator_traits<IteratorT>::iterator_category;
+  return detail::join_impl(Begin, End, Separator, tag());
+}
+
+/// Joins the strings in the range [R.begin(), R.end()), adding Separator
+/// between the elements.
+template <typename Range>
+inline std::string join(Range &&R, StringRef Separator) {
+  return join(R.begin(), R.end(), Separator);
+}
+
+/// Joins the strings in the parameter pack \p Items, adding \p Separator
+/// between the elements.  All arguments must be implicitly convertible to
+/// std::string, or there should be an overload of std::string::operator+=()
+/// that accepts the argument explicitly.
+template <typename Sep, typename... Args>
+inline std::string join_items(Sep Separator, Args &&... Items) {
+  std::string Result;
+  if (sizeof...(Items) == 0)
+    return Result;
+
+  size_t NS = detail::join_one_item_size(Separator);
+  size_t NI = detail::join_items_size(std::forward<Args>(Items)...);
+  Result.reserve(NI + (sizeof...(Items) - 1) * NS + 1);
+  detail::join_items_impl(Result, Separator, std::forward<Args>(Items)...);
+  return Result;
+}
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_STRINGEXTRAS_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringMap.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringMap.h
new file mode 100644
index 0000000..80110dc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringMap.h
@@ -0,0 +1,638 @@
+//===- StringMap.h - String Hash table map interface ------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file defines the StringMap class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_STRINGMAP_H
+#define WPIUTIL_WPI_STRINGMAP_H
+
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include "wpi/iterator.h"
+#include "wpi/iterator_range.h"
+#include "wpi/PointerLikeTypeTraits.h"
+#include "wpi/deprecated.h"
+#include "wpi/memory.h"
+#include <algorithm>
+#include <cassert>
+#include <cstdint>
+#include <cstdlib>
+#include <cstring>
+#include <initializer_list>
+#include <iterator>
+#include <utility>
+
+namespace wpi {
+
+template<typename ValueTy> class StringMapConstIterator;
+template<typename ValueTy> class StringMapIterator;
+template<typename ValueTy> class StringMapKeyIterator;
+template<typename ValueTy> class StringMapEntry;
+
+/// StringMapEntryBase - Shared base class of StringMapEntry instances.
+class StringMapEntryBase {
+  size_t StrLen;
+
+public:
+  explicit StringMapEntryBase(size_t Len) : StrLen(Len) {}
+
+  size_t getKeyLength() const { return StrLen; }
+};
+
+/// StringMapImpl - This is the base class of StringMap that is shared among
+/// all of its instantiations.
+class StringMapImpl {
+protected:
+  // Array of NumBuckets pointers to entries, null pointers are holes.
+  // TheTable[NumBuckets] contains a sentinel value for easy iteration. Followed
+  // by an array of the actual hash values as unsigned integers.
+  StringMapEntryBase **TheTable = nullptr;
+  unsigned NumBuckets = 0;
+  unsigned NumItems = 0;
+  unsigned NumTombstones = 0;
+  unsigned ItemSize;
+
+protected:
+  explicit StringMapImpl(unsigned itemSize)
+      : ItemSize(itemSize) {}
+  StringMapImpl(StringMapImpl &&RHS)
+      : TheTable(RHS.TheTable), NumBuckets(RHS.NumBuckets),
+        NumItems(RHS.NumItems), NumTombstones(RHS.NumTombstones),
+        ItemSize(RHS.ItemSize) {
+    RHS.TheTable = nullptr;
+    RHS.NumBuckets = 0;
+    RHS.NumItems = 0;
+    RHS.NumTombstones = 0;
+  }
+
+  StringMapImpl(unsigned InitSize, unsigned ItemSize);
+  unsigned RehashTable(unsigned BucketNo = 0);
+
+  /// LookupBucketFor - Look up the bucket that the specified string should end
+  /// up in.  If it already exists as a key in the map, the Item pointer for the
+  /// specified bucket will be non-null.  Otherwise, it will be null.  In either
+  /// case, the FullHashValue field of the bucket will be set to the hash value
+  /// of the string.
+  unsigned LookupBucketFor(StringRef Key);
+
+  /// FindKey - Look up the bucket that contains the specified key. If it exists
+  /// in the map, return the bucket number of the key.  Otherwise return -1.
+  /// This does not modify the map.
+  int FindKey(StringRef Key) const;
+
+  /// RemoveKey - Remove the specified StringMapEntry from the table, but do not
+  /// delete it.  This aborts if the value isn't in the table.
+  void RemoveKey(StringMapEntryBase *V);
+
+  /// RemoveKey - Remove the StringMapEntry for the specified key from the
+  /// table, returning it.  If the key is not in the table, this returns null.
+  StringMapEntryBase *RemoveKey(StringRef Key);
+
+  /// Allocate the table with the specified number of buckets and otherwise
+  /// setup the map as empty.
+  void init(unsigned Size);
+
+public:
+  static StringMapEntryBase *getTombstoneVal() {
+    uintptr_t Val = static_cast<uintptr_t>(-1);
+    Val <<= PointerLikeTypeTraits<StringMapEntryBase *>::NumLowBitsAvailable;
+    return reinterpret_cast<StringMapEntryBase *>(Val);
+  }
+
+  unsigned getNumBuckets() const { return NumBuckets; }
+  unsigned getNumItems() const { return NumItems; }
+
+  bool empty() const { return NumItems == 0; }
+  unsigned size() const { return NumItems; }
+
+  void swap(StringMapImpl &Other) {
+    std::swap(TheTable, Other.TheTable);
+    std::swap(NumBuckets, Other.NumBuckets);
+    std::swap(NumItems, Other.NumItems);
+    std::swap(NumTombstones, Other.NumTombstones);
+  }
+};
+
+/// StringMapEntry - This is used to represent one value that is inserted into
+/// a StringMap.  It contains the Value itself and the key: the string length
+/// and data.
+template<typename ValueTy>
+class StringMapEntry : public StringMapEntryBase {
+public:
+  ValueTy second;
+
+  explicit StringMapEntry(size_t strLen)
+    : StringMapEntryBase(strLen), second() {}
+  template <typename... InitTy>
+  StringMapEntry(size_t strLen, InitTy &&... InitVals)
+      : StringMapEntryBase(strLen), second(std::forward<InitTy>(InitVals)...) {}
+  StringMapEntry(StringMapEntry &E) = delete;
+
+  StringRef getKey() const {
+    return StringRef(getKeyData(), getKeyLength());
+  }
+
+  const ValueTy &getValue() const { return second; }
+  ValueTy &getValue() { return second; }
+
+  void setValue(const ValueTy &V) { second = V; }
+
+  /// getKeyData - Return the start of the string data that is the key for this
+  /// value.  The string data is always stored immediately after the
+  /// StringMapEntry object.
+  const char *getKeyData() const {return reinterpret_cast<const char*>(this+1);}
+
+  StringRef first() const { return StringRef(getKeyData(), getKeyLength()); }
+
+  /// Create a StringMapEntry for the specified key construct the value using
+  /// \p InitiVals.
+  template <typename... InitTy>
+  static StringMapEntry *Create(StringRef Key, InitTy &&... InitVals) {
+    size_t KeyLength = Key.size();
+
+    // Allocate a new item with space for the string at the end and a null
+    // terminator.
+    size_t AllocSize = sizeof(StringMapEntry) + KeyLength + 1;
+
+    StringMapEntry *NewItem =
+      static_cast<StringMapEntry*>(CheckedMalloc(AllocSize));
+
+    // Construct the value.
+    new (NewItem) StringMapEntry(KeyLength, std::forward<InitTy>(InitVals)...);
+
+    // Copy the string information.
+    char *StrBuffer = const_cast<char*>(NewItem->getKeyData());
+    if (KeyLength > 0)
+      memcpy(StrBuffer, Key.data(), KeyLength);
+    StrBuffer[KeyLength] = 0;  // Null terminate for convenience of clients.
+    return NewItem;
+  }
+
+  static StringMapEntry *Create(StringRef Key) {
+    return Create(Key, ValueTy());
+  }
+
+  /// GetStringMapEntryFromKeyData - Given key data that is known to be embedded
+  /// into a StringMapEntry, return the StringMapEntry itself.
+  static StringMapEntry &GetStringMapEntryFromKeyData(const char *KeyData) {
+    char *Ptr = const_cast<char*>(KeyData) - sizeof(StringMapEntry<ValueTy>);
+    return *reinterpret_cast<StringMapEntry*>(Ptr);
+  }
+
+  /// Destroy - Destroy this StringMapEntry, releasing memory back to the
+  /// specified allocator.
+  void Destroy() {
+    // Free memory referenced by the item.
+    this->~StringMapEntry();
+    std::free(static_cast<void *>(this));
+  }
+};
+
+
+/// StringMap - This is an unconventional map that is specialized for handling
+/// keys that are "strings", which are basically ranges of bytes. This does some
+/// funky memory allocation and hashing things to make it extremely efficient,
+/// storing the string data *after* the value in the map.
+template<typename ValueTy>
+class StringMap : public StringMapImpl {
+public:
+  using MapEntryTy = StringMapEntry<ValueTy>;
+
+  StringMap() : StringMapImpl(static_cast<unsigned>(sizeof(MapEntryTy))) {}
+
+  explicit StringMap(unsigned InitialSize)
+    : StringMapImpl(InitialSize, static_cast<unsigned>(sizeof(MapEntryTy))) {}
+
+  StringMap(std::initializer_list<std::pair<StringRef, ValueTy>> List)
+      : StringMapImpl(List.size(), static_cast<unsigned>(sizeof(MapEntryTy))) {
+    for (const auto &P : List) {
+      insert(P);
+    }
+  }
+
+  StringMap(StringMap &&RHS)
+      : StringMapImpl(std::move(RHS)) {}
+
+  StringMap(const StringMap &RHS) :
+    StringMapImpl(static_cast<unsigned>(sizeof(MapEntryTy))) {
+    if (RHS.empty())
+      return;
+
+    // Allocate TheTable of the same size as RHS's TheTable, and set the
+    // sentinel appropriately (and NumBuckets).
+    init(RHS.NumBuckets);
+    unsigned *HashTable = (unsigned *)(TheTable + NumBuckets + 1),
+             *RHSHashTable = (unsigned *)(RHS.TheTable + NumBuckets + 1);
+
+    NumItems = RHS.NumItems;
+    NumTombstones = RHS.NumTombstones;
+    for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
+      StringMapEntryBase *Bucket = RHS.TheTable[I];
+      if (!Bucket || Bucket == getTombstoneVal()) {
+        TheTable[I] = Bucket;
+        continue;
+      }
+
+      TheTable[I] = MapEntryTy::Create(
+          static_cast<MapEntryTy *>(Bucket)->getKey(),
+          static_cast<MapEntryTy *>(Bucket)->getValue());
+      HashTable[I] = RHSHashTable[I];
+    }
+
+    // Note that here we've copied everything from the RHS into this object,
+    // tombstones included. We could, instead, have re-probed for each key to
+    // instantiate this new object without any tombstone buckets. The
+    // assumption here is that items are rarely deleted from most StringMaps,
+    // and so tombstones are rare, so the cost of re-probing for all inputs is
+    // not worthwhile.
+  }
+
+  StringMap &operator=(StringMap RHS) {
+    StringMapImpl::swap(RHS);
+    return *this;
+  }
+
+  ~StringMap() {
+    // Delete all the elements in the map, but don't reset the elements
+    // to default values.  This is a copy of clear(), but avoids unnecessary
+    // work not required in the destructor.
+    if (!empty()) {
+      for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
+        StringMapEntryBase *Bucket = TheTable[I];
+        if (Bucket && Bucket != getTombstoneVal()) {
+          static_cast<MapEntryTy*>(Bucket)->Destroy();
+        }
+      }
+    }
+    free(TheTable);
+  }
+
+  using key_type = const char*;
+  using mapped_type = ValueTy;
+  using value_type = StringMapEntry<ValueTy>;
+  using size_type = size_t;
+
+  using const_iterator = StringMapConstIterator<ValueTy>;
+  using iterator = StringMapIterator<ValueTy>;
+
+  iterator begin() {
+    return iterator(TheTable, NumBuckets == 0);
+  }
+  iterator end() {
+    return iterator(TheTable+NumBuckets, true);
+  }
+  const_iterator begin() const {
+    return const_iterator(TheTable, NumBuckets == 0);
+  }
+  const_iterator end() const {
+    return const_iterator(TheTable+NumBuckets, true);
+  }
+
+  iterator_range<StringMapKeyIterator<ValueTy>> keys() const {
+    return make_range(StringMapKeyIterator<ValueTy>(begin()),
+                      StringMapKeyIterator<ValueTy>(end()));
+  }
+
+  iterator find(StringRef Key) {
+    int Bucket = FindKey(Key);
+    if (Bucket == -1) return end();
+    return iterator(TheTable+Bucket, true);
+  }
+
+  const_iterator find(StringRef Key) const {
+    int Bucket = FindKey(Key);
+    if (Bucket == -1) return end();
+    return const_iterator(TheTable+Bucket, true);
+  }
+
+  /// lookup - Return the entry for the specified key, or a default
+  /// constructed value if no such entry exists.
+  ValueTy lookup(StringRef Key) const {
+    const_iterator it = find(Key);
+    if (it != end())
+      return it->second;
+    return ValueTy();
+  }
+
+  /// Lookup the ValueTy for the \p Key, or create a default constructed value
+  /// if the key is not in the map.
+  ValueTy &operator[](StringRef Key) { return try_emplace(Key).first->second; }
+
+  /// count - Return 1 if the element is in the map, 0 otherwise.
+  size_type count(StringRef Key) const {
+    return find(Key) == end() ? 0 : 1;
+  }
+
+  /// insert - Insert the specified key/value pair into the map.  If the key
+  /// already exists in the map, return false and ignore the request, otherwise
+  /// insert it and return true.
+  bool insert(MapEntryTy *KeyValue) {
+    unsigned BucketNo = LookupBucketFor(KeyValue->getKey());
+    StringMapEntryBase *&Bucket = TheTable[BucketNo];
+    if (Bucket && Bucket != getTombstoneVal())
+      return false;  // Already exists in map.
+
+    if (Bucket == getTombstoneVal())
+      --NumTombstones;
+    Bucket = KeyValue;
+    ++NumItems;
+    assert(NumItems + NumTombstones <= NumBuckets);
+
+    RehashTable();
+    return true;
+  }
+
+  /// insert - Inserts the specified key/value pair into the map if the key
+  /// isn't already in the map. The bool component of the returned pair is true
+  /// if and only if the insertion takes place, and the iterator component of
+  /// the pair points to the element with key equivalent to the key of the pair.
+  std::pair<iterator, bool> insert(std::pair<StringRef, ValueTy> KV) {
+    return try_emplace(KV.first, std::move(KV.second));
+  }
+
+  template <typename... ArgsTy>
+  WPI_DEPRECATED("use try_emplace instead")
+  std::pair<iterator, bool> emplace_second(StringRef Key, ArgsTy &&... Args) {
+    return try_emplace(Key, std::forward<ArgsTy>(Args)...);
+  }
+
+  /// Emplace a new element for the specified key into the map if the key isn't
+  /// already in the map. The bool component of the returned pair is true
+  /// if and only if the insertion takes place, and the iterator component of
+  /// the pair points to the element with key equivalent to the key of the pair.
+  template <typename... ArgsTy>
+  std::pair<iterator, bool> try_emplace(StringRef Key, ArgsTy &&... Args) {
+    unsigned BucketNo = LookupBucketFor(Key);
+    StringMapEntryBase *&Bucket = TheTable[BucketNo];
+    if (Bucket && Bucket != getTombstoneVal())
+      return std::make_pair(iterator(TheTable + BucketNo, false),
+                            false); // Already exists in map.
+
+    if (Bucket == getTombstoneVal())
+      --NumTombstones;
+    Bucket = MapEntryTy::Create(Key, std::forward<ArgsTy>(Args)...);
+    ++NumItems;
+    assert(NumItems + NumTombstones <= NumBuckets);
+
+    BucketNo = RehashTable(BucketNo);
+    return std::make_pair(iterator(TheTable + BucketNo, false), true);
+  }
+
+  // clear - Empties out the StringMap
+  void clear() {
+    if (empty()) return;
+
+    // Zap all values, resetting the keys back to non-present (not tombstone),
+    // which is safe because we're removing all elements.
+    for (unsigned I = 0, E = NumBuckets; I != E; ++I) {
+      StringMapEntryBase *&Bucket = TheTable[I];
+      if (Bucket && Bucket != getTombstoneVal()) {
+        static_cast<MapEntryTy*>(Bucket)->Destroy();
+      }
+      Bucket = nullptr;
+    }
+
+    NumItems = 0;
+    NumTombstones = 0;
+  }
+
+  /// remove - Remove the specified key/value pair from the map, but do not
+  /// erase it.  This aborts if the key is not in the map.
+  void remove(MapEntryTy *KeyValue) {
+    RemoveKey(KeyValue);
+  }
+
+  void erase(iterator I) {
+    MapEntryTy &V = *I;
+    remove(&V);
+    V.Destroy();
+  }
+
+  bool erase(StringRef Key) {
+    iterator I = find(Key);
+    if (I == end()) return false;
+    erase(I);
+    return true;
+  }
+};
+
+template <typename DerivedTy, typename ValueTy>
+class StringMapIterBase
+    : public iterator_facade_base<DerivedTy, std::forward_iterator_tag,
+                                  ValueTy> {
+protected:
+  StringMapEntryBase **Ptr = nullptr;
+
+public:
+  StringMapIterBase() = default;
+
+  explicit StringMapIterBase(StringMapEntryBase **Bucket,
+                             bool NoAdvance = false)
+      : Ptr(Bucket) {
+    if (!NoAdvance) AdvancePastEmptyBuckets();
+  }
+
+  DerivedTy &operator=(const DerivedTy &Other) {
+    Ptr = Other.Ptr;
+    return static_cast<DerivedTy &>(*this);
+  }
+
+  bool operator==(const DerivedTy &RHS) const { return Ptr == RHS.Ptr; }
+
+  DerivedTy &operator++() { // Preincrement
+    ++Ptr;
+    AdvancePastEmptyBuckets();
+    return static_cast<DerivedTy &>(*this);
+  }
+
+  DerivedTy operator++(int) { // Post-increment
+    DerivedTy Tmp(Ptr);
+    ++*this;
+    return Tmp;
+  }
+
+  DerivedTy &operator--() { // Predecrement
+    --Ptr;
+    ReversePastEmptyBuckets();
+    return static_cast<DerivedTy &>(*this);
+  }
+
+  DerivedTy operator--(int) { // Post-decrement
+    DerivedTy Tmp(Ptr);
+    --*this;
+    return Tmp;
+  }
+
+private:
+  void AdvancePastEmptyBuckets() {
+    while (*Ptr == nullptr || *Ptr == StringMapImpl::getTombstoneVal())
+      ++Ptr;
+  }
+  void ReversePastEmptyBuckets() {
+    while (*Ptr == nullptr || *Ptr == StringMapImpl::getTombstoneVal())
+      --Ptr;
+  }
+};
+
+template <typename ValueTy>
+class StringMapConstIterator
+    : public StringMapIterBase<StringMapConstIterator<ValueTy>,
+                               const StringMapEntry<ValueTy>> {
+  using base = StringMapIterBase<StringMapConstIterator<ValueTy>,
+                                 const StringMapEntry<ValueTy>>;
+
+public:
+  using value_type = const StringMapEntry<ValueTy>;
+
+  StringMapConstIterator() = default;
+  explicit StringMapConstIterator(StringMapEntryBase **Bucket,
+                                  bool NoAdvance = false)
+      : base(Bucket, NoAdvance) {}
+
+  value_type &operator*() const {
+    return *static_cast<value_type *>(*this->Ptr);
+  }
+};
+
+template <typename ValueTy>
+class StringMapIterator : public StringMapIterBase<StringMapIterator<ValueTy>,
+                                                   StringMapEntry<ValueTy>> {
+  using base =
+      StringMapIterBase<StringMapIterator<ValueTy>, StringMapEntry<ValueTy>>;
+
+public:
+  using value_type = StringMapEntry<ValueTy>;
+
+  StringMapIterator() = default;
+  explicit StringMapIterator(StringMapEntryBase **Bucket,
+                             bool NoAdvance = false)
+      : base(Bucket, NoAdvance) {}
+
+  value_type &operator*() const {
+    return *static_cast<value_type *>(*this->Ptr);
+  }
+
+  operator StringMapConstIterator<ValueTy>() const {
+    return StringMapConstIterator<ValueTy>(this->Ptr, true);
+  }
+};
+
+template <typename ValueTy>
+class StringMapKeyIterator
+    : public iterator_adaptor_base<StringMapKeyIterator<ValueTy>,
+                                   StringMapConstIterator<ValueTy>,
+                                   std::forward_iterator_tag, StringRef> {
+  using base = iterator_adaptor_base<StringMapKeyIterator<ValueTy>,
+                                     StringMapConstIterator<ValueTy>,
+                                     std::forward_iterator_tag, StringRef>;
+
+public:
+  StringMapKeyIterator() = default;
+  explicit StringMapKeyIterator(StringMapConstIterator<ValueTy> Iter)
+      : base(std::move(Iter)) {}
+
+  StringRef &operator*() {
+    Key = this->wrapped()->getKey();
+    return Key;
+  }
+
+private:
+  StringRef Key;
+};
+
+template <typename ValueTy>
+bool operator==(const StringMap<ValueTy>& lhs, const StringMap<ValueTy>& rhs) {
+  // same instance?
+  if (&lhs == &rhs) return true;
+
+  // first check that sizes are identical
+  if (lhs.size() != rhs.size()) return false;
+
+  // copy into vectors and sort by key
+  SmallVector<StringMapConstIterator<ValueTy>, 16> lhs_items;
+  lhs_items.reserve(lhs.size());
+  for (auto i = lhs.begin(), end = lhs.end(); i != end; ++i)
+    lhs_items.push_back(i);
+  std::sort(lhs_items.begin(), lhs_items.end(),
+            [](const StringMapConstIterator<ValueTy>& a,
+               const StringMapConstIterator<ValueTy>& b) {
+              return a->getKey() < b->getKey();
+            });
+
+  SmallVector<StringMapConstIterator<ValueTy>, 16> rhs_items;
+  rhs_items.reserve(rhs.size());
+  for (auto i = rhs.begin(), end = rhs.end(); i != end; ++i)
+    rhs_items.push_back(i);
+  std::sort(rhs_items.begin(), rhs_items.end(),
+            [](const StringMapConstIterator<ValueTy>& a,
+               const StringMapConstIterator<ValueTy>& b) {
+              return a->getKey() < b->getKey();
+            });
+
+  // compare vector keys and values
+  for (auto a = lhs_items.begin(), b = rhs_items.begin(),
+            aend = lhs_items.end(), bend = rhs_items.end();
+       a != aend && b != bend; ++a, ++b) {
+    if ((*a)->first() != (*b)->first() || (*a)->second != (*b)->second)
+      return false;
+  }
+  return true;
+}
+
+template <typename ValueTy>
+inline bool operator!=(const StringMap<ValueTy>& lhs,
+                       const StringMap<ValueTy>& rhs) {
+  return !(lhs == rhs);
+}
+
+template <typename ValueTy>
+bool operator<(const StringMap<ValueTy>& lhs, const StringMap<ValueTy>& rhs) {
+  // same instance?
+  if (&lhs == &rhs) return false;
+
+  // copy into vectors and sort by key
+  SmallVector<StringRef, 16> lhs_keys;
+  lhs_keys.reserve(lhs.size());
+  for (auto i = lhs.begin(), end = lhs.end(); i != end; ++i)
+    lhs_keys.push_back(i->getKey());
+  std::sort(lhs_keys.begin(), lhs_keys.end());
+
+  SmallVector<StringRef, 16> rhs_keys;
+  rhs_keys.reserve(rhs.size());
+  for (auto i = rhs.begin(), end = rhs.end(); i != end; ++i)
+    rhs_keys.push_back(i->getKey());
+  std::sort(rhs_keys.begin(), rhs_keys.end());
+
+  // use std::vector comparison
+  return lhs_keys < rhs_keys;
+}
+
+template <typename ValueTy>
+inline bool operator<=(const StringMap<ValueTy>& lhs,
+                       const StringMap<ValueTy>& rhs) {
+  return !(rhs < lhs);
+}
+
+template <typename ValueTy>
+inline bool operator>(const StringMap<ValueTy>& lhs,
+                      const StringMap<ValueTy>& rhs) {
+  return !(lhs <= rhs);
+}
+
+template <typename ValueTy>
+inline bool operator>=(const StringMap<ValueTy>& lhs,
+                       const StringMap<ValueTy>& rhs) {
+  return !(lhs < rhs);
+}
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_STRINGMAP_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringRef.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringRef.h
new file mode 100644
index 0000000..5c8729d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/StringRef.h
@@ -0,0 +1,935 @@
+//===- StringRef.h - Constant String Reference Wrapper ----------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_STRINGREF_H
+#define WPIUTIL_WPI_STRINGREF_H
+
+#include "wpi/STLExtras.h"
+#include "wpi/iterator_range.h"
+#include "wpi/Compiler.h"
+#include <algorithm>
+#include <cassert>
+#include <cstddef>
+#include <cstring>
+#include <iosfwd>
+#include <limits>
+#include <string>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+  class hash_code;
+  template <typename T> class SmallVectorImpl;
+  class StringRef;
+
+  /// Helper functions for StringRef::getAsInteger.
+  bool getAsUnsignedInteger(StringRef Str, unsigned Radix,
+                            unsigned long long &Result) noexcept;
+
+  bool getAsSignedInteger(StringRef Str, unsigned Radix, long long &Result) noexcept;
+
+  bool consumeUnsignedInteger(StringRef &Str, unsigned Radix,
+                              unsigned long long &Result) noexcept;
+  bool consumeSignedInteger(StringRef &Str, unsigned Radix, long long &Result) noexcept;
+
+  /// StringRef - Represent a constant reference to a string, i.e. a character
+  /// array and a length, which need not be null terminated.
+  ///
+  /// This class does not own the string data, it is expected to be used in
+  /// situations where the character data resides in some other buffer, whose
+  /// lifetime extends past that of the StringRef. For this reason, it is not in
+  /// general safe to store a StringRef.
+  class StringRef {
+  public:
+    static const size_t npos = ~size_t(0);
+
+    using iterator = const char *;
+    using const_iterator = const char *;
+    using size_type = size_t;
+
+  private:
+    /// The start of the string, in an external buffer.
+    const char *Data = nullptr;
+
+    /// The length of the string.
+    size_t Length = 0;
+
+    // Workaround memcmp issue with null pointers (undefined behavior)
+    // by providing a specialized version
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    static int compareMemory(const char *Lhs, const char *Rhs, size_t Length) noexcept {
+      if (Length == 0) { return 0; }
+      return ::memcmp(Lhs,Rhs,Length);
+    }
+
+  public:
+    /// @name Constructors
+    /// @{
+
+    /// Construct an empty string ref.
+    /*implicit*/ StringRef() = default;
+
+    /// Disable conversion from nullptr.  This prevents things like
+    /// if (S == nullptr)
+    StringRef(std::nullptr_t) = delete;
+
+    /// Construct a string ref from a cstring.
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    /*implicit*/ StringRef(const char *Str)
+        : Data(Str), Length(Str ? ::strlen(Str) : 0) {}
+
+    /// Construct a string ref from a pointer and length.
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    /*implicit*/ constexpr StringRef(const char *data, size_t length)
+        : Data(data), Length(length) {}
+
+    /// Construct a string ref from an std::string.
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    /*implicit*/ StringRef(const std::string &Str)
+      : Data(Str.data()), Length(Str.length()) {}
+
+    static StringRef withNullAsEmpty(const char *data) {
+      return StringRef(data ? data : "");
+    }
+
+    /// @}
+    /// @name Iterators
+    /// @{
+
+    iterator begin() const noexcept { return Data; }
+
+    iterator end() const noexcept { return Data + Length; }
+
+    const unsigned char *bytes_begin() const noexcept {
+      return reinterpret_cast<const unsigned char *>(begin());
+    }
+    const unsigned char *bytes_end() const noexcept {
+      return reinterpret_cast<const unsigned char *>(end());
+    }
+    iterator_range<const unsigned char *> bytes() const noexcept {
+      return make_range(bytes_begin(), bytes_end());
+    }
+
+    /// @}
+    /// @name String Operations
+    /// @{
+
+    /// data - Get a pointer to the start of the string (which may not be null
+    /// terminated).
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    const char *data() const noexcept { return Data; }
+
+    /// empty - Check if the string is empty.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool empty() const noexcept { return size() == 0; }
+
+    /// size - Get the string size.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    size_t size() const noexcept { return Length; }
+
+    /// front - Get the first character in the string.
+    LLVM_NODISCARD
+    char front() const noexcept {
+      assert(!empty());
+      return Data[0];
+    }
+
+    /// back - Get the last character in the string.
+    LLVM_NODISCARD
+    char back() const noexcept {
+      assert(!empty());
+      return Data[Length-1];
+    }
+
+    // copy - Allocate copy in Allocator and return StringRef to it.
+    template <typename Allocator>
+    LLVM_NODISCARD StringRef copy(Allocator &A) const {
+      // Don't request a length 0 copy from the allocator.
+      if (empty())
+        return StringRef();
+      char *S = A.template Allocate<char>(Length);
+      std::copy(begin(), end(), S);
+      return StringRef(S, Length);
+    }
+
+    /// equals - Check for string equality, this is more efficient than
+    /// compare() when the relative ordering of inequal strings isn't needed.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool equals(StringRef RHS) const noexcept {
+      return (Length == RHS.Length &&
+              compareMemory(Data, RHS.Data, RHS.Length) == 0);
+    }
+
+    /// equals_lower - Check for string equality, ignoring case.
+    LLVM_NODISCARD
+    bool equals_lower(StringRef RHS) const noexcept {
+      return Length == RHS.Length && compare_lower(RHS) == 0;
+    }
+
+    /// compare - Compare two strings; the result is -1, 0, or 1 if this string
+    /// is lexicographically less than, equal to, or greater than the \p RHS.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    int compare(StringRef RHS) const noexcept {
+      // Check the prefix for a mismatch.
+      if (int Res = compareMemory(Data, RHS.Data, std::min(Length, RHS.Length)))
+        return Res < 0 ? -1 : 1;
+
+      // Otherwise the prefixes match, so we only need to check the lengths.
+      if (Length == RHS.Length)
+        return 0;
+      return Length < RHS.Length ? -1 : 1;
+    }
+
+    /// compare_lower - Compare two strings, ignoring case.
+    LLVM_NODISCARD
+    int compare_lower(StringRef RHS) const noexcept;
+
+    /// compare_numeric - Compare two strings, treating sequences of digits as
+    /// numbers.
+    LLVM_NODISCARD
+    int compare_numeric(StringRef RHS) const noexcept;
+
+    /// str - Get the contents as an std::string.
+    LLVM_NODISCARD
+    std::string str() const {
+      if (!Data) return std::string();
+      return std::string(Data, Length);
+    }
+
+    /// @}
+    /// @name Operator Overloads
+    /// @{
+
+    LLVM_NODISCARD
+    char operator[](size_t Index) const noexcept {
+      assert(Index < Length && "Invalid index!");
+      return Data[Index];
+    }
+
+    /// Disallow accidental assignment from a temporary std::string.
+    ///
+    /// The declaration here is extra complicated so that `stringRef = {}`
+    /// and `stringRef = "abc"` continue to select the move assignment operator.
+    template <typename T>
+    typename std::enable_if<std::is_same<T, std::string>::value,
+                            StringRef>::type &
+    operator=(T &&Str) = delete;
+
+    /// @}
+    /// @name Type Conversions
+    /// @{
+
+    operator std::string() const {
+      return str();
+    }
+
+    /// @}
+    /// @name String Predicates
+    /// @{
+
+    /// Check if this string starts with the given \p Prefix.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool startswith(StringRef Prefix) const noexcept {
+      return Length >= Prefix.Length &&
+             compareMemory(Data, Prefix.Data, Prefix.Length) == 0;
+    }
+
+    /// Check if this string starts with the given \p Prefix, ignoring case.
+    LLVM_NODISCARD
+    bool startswith_lower(StringRef Prefix) const noexcept;
+
+    /// Check if this string ends with the given \p Suffix.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool endswith(StringRef Suffix) const noexcept {
+      return Length >= Suffix.Length &&
+        compareMemory(end() - Suffix.Length, Suffix.Data, Suffix.Length) == 0;
+    }
+
+    /// Check if this string ends with the given \p Suffix, ignoring case.
+    LLVM_NODISCARD
+    bool endswith_lower(StringRef Suffix) const noexcept;
+
+    /// @}
+    /// @name String Searching
+    /// @{
+
+    /// Search for the first character \p C in the string.
+    ///
+    /// \returns The index of the first occurrence of \p C, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    size_t find(char C, size_t From = 0) const noexcept {
+      size_t FindBegin = std::min(From, Length);
+      if (FindBegin < Length) { // Avoid calling memchr with nullptr.
+        // Just forward to memchr, which is faster than a hand-rolled loop.
+        if (const void *P = ::memchr(Data + FindBegin, C, Length - FindBegin))
+          return static_cast<const char *>(P) - Data;
+      }
+      return npos;
+    }
+
+    /// Search for the first character \p C in the string, ignoring case.
+    ///
+    /// \returns The index of the first occurrence of \p C, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t find_lower(char C, size_t From = 0) const noexcept;
+
+    /// Search for the first character satisfying the predicate \p F
+    ///
+    /// \returns The index of the first character satisfying \p F starting from
+    /// \p From, or npos if not found.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    size_t find_if(function_ref<bool(char)> F, size_t From = 0) const noexcept {
+      StringRef S = drop_front(From);
+      while (!S.empty()) {
+        if (F(S.front()))
+          return size() - S.size();
+        S = S.drop_front();
+      }
+      return npos;
+    }
+
+    /// Search for the first character not satisfying the predicate \p F
+    ///
+    /// \returns The index of the first character not satisfying \p F starting
+    /// from \p From, or npos if not found.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    size_t find_if_not(function_ref<bool(char)> F, size_t From = 0) const noexcept {
+      return find_if([F](char c) { return !F(c); }, From);
+    }
+
+    /// Search for the first string \p Str in the string.
+    ///
+    /// \returns The index of the first occurrence of \p Str, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t find(StringRef Str, size_t From = 0) const noexcept;
+
+    /// Search for the first string \p Str in the string, ignoring case.
+    ///
+    /// \returns The index of the first occurrence of \p Str, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t find_lower(StringRef Str, size_t From = 0) const noexcept;
+
+    /// Search for the last character \p C in the string.
+    ///
+    /// \returns The index of the last occurrence of \p C, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t rfind(char C, size_t From = npos) const noexcept {
+      From = std::min(From, Length);
+      size_t i = From;
+      while (i != 0) {
+        --i;
+        if (Data[i] == C)
+          return i;
+      }
+      return npos;
+    }
+
+    /// Search for the last character \p C in the string, ignoring case.
+    ///
+    /// \returns The index of the last occurrence of \p C, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t rfind_lower(char C, size_t From = npos) const noexcept;
+
+    /// Search for the last string \p Str in the string.
+    ///
+    /// \returns The index of the last occurrence of \p Str, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t rfind(StringRef Str) const noexcept;
+
+    /// Search for the last string \p Str in the string, ignoring case.
+    ///
+    /// \returns The index of the last occurrence of \p Str, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t rfind_lower(StringRef Str) const noexcept;
+
+    /// Find the first character in the string that is \p C, or npos if not
+    /// found. Same as find.
+    LLVM_NODISCARD
+    size_t find_first_of(char C, size_t From = 0) const noexcept {
+      return find(C, From);
+    }
+
+    /// Find the first character in the string that is in \p Chars, or npos if
+    /// not found.
+    ///
+    /// Complexity: O(size() + Chars.size())
+    LLVM_NODISCARD
+    size_t find_first_of(StringRef Chars, size_t From = 0) const noexcept;
+
+    /// Find the first character in the string that is not \p C or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t find_first_not_of(char C, size_t From = 0) const noexcept;
+
+    /// Find the first character in the string that is not in the string
+    /// \p Chars, or npos if not found.
+    ///
+    /// Complexity: O(size() + Chars.size())
+    LLVM_NODISCARD
+    size_t find_first_not_of(StringRef Chars, size_t From = 0) const noexcept;
+
+    /// Find the last character in the string that is \p C, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t find_last_of(char C, size_t From = npos) const noexcept {
+      return rfind(C, From);
+    }
+
+    /// Find the last character in the string that is in \p C, or npos if not
+    /// found.
+    ///
+    /// Complexity: O(size() + Chars.size())
+    LLVM_NODISCARD
+    size_t find_last_of(StringRef Chars, size_t From = npos) const noexcept;
+
+    /// Find the last character in the string that is not \p C, or npos if not
+    /// found.
+    LLVM_NODISCARD
+    size_t find_last_not_of(char C, size_t From = npos) const noexcept;
+
+    /// Find the last character in the string that is not in \p Chars, or
+    /// npos if not found.
+    ///
+    /// Complexity: O(size() + Chars.size())
+    LLVM_NODISCARD
+    size_t find_last_not_of(StringRef Chars, size_t From = npos) const noexcept;
+
+    /// Return true if the given string is a substring of *this, and false
+    /// otherwise.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool contains(StringRef Other) const noexcept { return find(Other) != npos; }
+
+    /// Return true if the given character is contained in *this, and false
+    /// otherwise.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool contains(char C) const noexcept { return find_first_of(C) != npos; }
+
+    /// Return true if the given string is a substring of *this, and false
+    /// otherwise.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool contains_lower(StringRef Other) const noexcept {
+      return find_lower(Other) != npos;
+    }
+
+    /// Return true if the given character is contained in *this, and false
+    /// otherwise.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool contains_lower(char C) const noexcept { return find_lower(C) != npos; }
+
+    /// @}
+    /// @name Helpful Algorithms
+    /// @{
+
+    /// Return the number of occurrences of \p C in the string.
+    LLVM_NODISCARD
+    size_t count(char C) const noexcept {
+      size_t Count = 0;
+      for (size_t i = 0, e = Length; i != e; ++i)
+        if (Data[i] == C)
+          ++Count;
+      return Count;
+    }
+
+    /// Return the number of non-overlapped occurrences of \p Str in
+    /// the string.
+    size_t count(StringRef Str) const noexcept;
+
+    /// Parse the current string as an integer of the specified radix.  If
+    /// \p Radix is specified as zero, this does radix autosensing using
+    /// extended C rules: 0 is octal, 0x is hex, 0b is binary.
+    ///
+    /// If the string is invalid or if only a subset of the string is valid,
+    /// this returns true to signify the error.  The string is considered
+    /// erroneous if empty or if it overflows T.
+    template <typename T>
+    typename std::enable_if<std::numeric_limits<T>::is_signed, bool>::type
+    getAsInteger(unsigned Radix, T &Result) const noexcept {
+      long long LLVal;
+      if (getAsSignedInteger(*this, Radix, LLVal) ||
+            static_cast<T>(LLVal) != LLVal)
+        return true;
+      Result = LLVal;
+      return false;
+    }
+
+    template <typename T>
+    typename std::enable_if<!std::numeric_limits<T>::is_signed, bool>::type
+    getAsInteger(unsigned Radix, T &Result) const noexcept {
+      unsigned long long ULLVal;
+      // The additional cast to unsigned long long is required to avoid the
+      // Visual C++ warning C4805: '!=' : unsafe mix of type 'bool' and type
+      // 'unsigned __int64' when instantiating getAsInteger with T = bool.
+      if (getAsUnsignedInteger(*this, Radix, ULLVal) ||
+          static_cast<unsigned long long>(static_cast<T>(ULLVal)) != ULLVal)
+        return true;
+      Result = ULLVal;
+      return false;
+    }
+
+    /// Parse the current string as an integer of the specified radix.  If
+    /// \p Radix is specified as zero, this does radix autosensing using
+    /// extended C rules: 0 is octal, 0x is hex, 0b is binary.
+    ///
+    /// If the string does not begin with a number of the specified radix,
+    /// this returns true to signify the error. The string is considered
+    /// erroneous if empty or if it overflows T.
+    /// The portion of the string representing the discovered numeric value
+    /// is removed from the beginning of the string.
+    template <typename T>
+    typename std::enable_if<std::numeric_limits<T>::is_signed, bool>::type
+    consumeInteger(unsigned Radix, T &Result) noexcept {
+      long long LLVal;
+      if (consumeSignedInteger(*this, Radix, LLVal) ||
+          static_cast<long long>(static_cast<T>(LLVal)) != LLVal)
+        return true;
+      Result = LLVal;
+      return false;
+    }
+
+    template <typename T>
+    typename std::enable_if<!std::numeric_limits<T>::is_signed, bool>::type
+    consumeInteger(unsigned Radix, T &Result) noexcept {
+      unsigned long long ULLVal;
+      if (consumeUnsignedInteger(*this, Radix, ULLVal) ||
+          static_cast<unsigned long long>(static_cast<T>(ULLVal)) != ULLVal)
+        return true;
+      Result = ULLVal;
+      return false;
+    }
+
+    /// @}
+    /// @name String Operations
+    /// @{
+
+    // Convert the given ASCII string to lowercase.
+    LLVM_NODISCARD
+    std::string lower() const;
+
+    /// Convert the given ASCII string to uppercase.
+    LLVM_NODISCARD
+    std::string upper() const;
+
+    /// @}
+    /// @name Substring Operations
+    /// @{
+
+    /// Return a reference to the substring from [Start, Start + N).
+    ///
+    /// \param Start The index of the starting character in the substring; if
+    /// the index is npos or greater than the length of the string then the
+    /// empty substring will be returned.
+    ///
+    /// \param N The number of characters to included in the substring. If N
+    /// exceeds the number of characters remaining in the string, the string
+    /// suffix (starting with \p Start) will be returned.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef substr(size_t Start, size_t N = npos) const noexcept {
+      Start = std::min(Start, Length);
+      return StringRef(Data + Start, std::min(N, Length - Start));
+    }
+
+    /// Return a StringRef equal to 'this' but with only the first \p N
+    /// elements remaining.  If \p N is greater than the length of the
+    /// string, the entire string is returned.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef take_front(size_t N = 1) const noexcept {
+      if (N >= size())
+        return *this;
+      return drop_back(size() - N);
+    }
+
+    /// Return a StringRef equal to 'this' but with only the last \p N
+    /// elements remaining.  If \p N is greater than the length of the
+    /// string, the entire string is returned.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef take_back(size_t N = 1) const noexcept {
+      if (N >= size())
+        return *this;
+      return drop_front(size() - N);
+    }
+
+    /// Return the longest prefix of 'this' such that every character
+    /// in the prefix satisfies the given predicate.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef take_while(function_ref<bool(char)> F) const noexcept {
+      return substr(0, find_if_not(F));
+    }
+
+    /// Return the longest prefix of 'this' such that no character in
+    /// the prefix satisfies the given predicate.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef take_until(function_ref<bool(char)> F) const noexcept {
+      return substr(0, find_if(F));
+    }
+
+    /// Return a StringRef equal to 'this' but with the first \p N elements
+    /// dropped.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef drop_front(size_t N = 1) const noexcept {
+      assert(size() >= N && "Dropping more elements than exist");
+      return substr(N);
+    }
+
+    /// Return a StringRef equal to 'this' but with the last \p N elements
+    /// dropped.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef drop_back(size_t N = 1) const noexcept {
+      assert(size() >= N && "Dropping more elements than exist");
+      return substr(0, size()-N);
+    }
+
+    /// Return a StringRef equal to 'this', but with all characters satisfying
+    /// the given predicate dropped from the beginning of the string.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef drop_while(function_ref<bool(char)> F) const noexcept {
+      return substr(find_if_not(F));
+    }
+
+    /// Return a StringRef equal to 'this', but with all characters not
+    /// satisfying the given predicate dropped from the beginning of the string.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef drop_until(function_ref<bool(char)> F) const noexcept {
+      return substr(find_if(F));
+    }
+
+    /// Returns true if this StringRef has the given prefix and removes that
+    /// prefix.
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool consume_front(StringRef Prefix) noexcept {
+      if (!startswith(Prefix))
+        return false;
+
+      *this = drop_front(Prefix.size());
+      return true;
+    }
+
+    /// Returns true if this StringRef has the given suffix and removes that
+    /// suffix.
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    bool consume_back(StringRef Suffix) noexcept {
+      if (!endswith(Suffix))
+        return false;
+
+      *this = drop_back(Suffix.size());
+      return true;
+    }
+
+    /// Return a reference to the substring from [Start, End).
+    ///
+    /// \param Start The index of the starting character in the substring; if
+    /// the index is npos or greater than the length of the string then the
+    /// empty substring will be returned.
+    ///
+    /// \param End The index following the last character to include in the
+    /// substring. If this is npos or exceeds the number of characters
+    /// remaining in the string, the string suffix (starting with \p Start)
+    /// will be returned. If this is less than \p Start, an empty string will
+    /// be returned.
+    LLVM_NODISCARD
+    LLVM_ATTRIBUTE_ALWAYS_INLINE
+    StringRef slice(size_t Start, size_t End) const noexcept {
+      Start = std::min(Start, Length);
+      End = std::min(std::max(Start, End), Length);
+      return StringRef(Data + Start, End - Start);
+    }
+
+    /// Split into two substrings around the first occurrence of a separator
+    /// character.
+    ///
+    /// If \p Separator is in the string, then the result is a pair (LHS, RHS)
+    /// such that (*this == LHS + Separator + RHS) is true and RHS is
+    /// maximal. If \p Separator is not in the string, then the result is a
+    /// pair (LHS, RHS) where (*this == LHS) and (RHS == "").
+    ///
+    /// \param Separator The character to split on.
+    /// \returns The split substrings.
+    LLVM_NODISCARD
+    std::pair<StringRef, StringRef> split(char Separator) const {
+      size_t Idx = find(Separator);
+      if (Idx == npos)
+        return std::make_pair(*this, StringRef());
+      return std::make_pair(slice(0, Idx), slice(Idx+1, npos));
+    }
+
+    /// Split into two substrings around the first occurrence of a separator
+    /// string.
+    ///
+    /// If \p Separator is in the string, then the result is a pair (LHS, RHS)
+    /// such that (*this == LHS + Separator + RHS) is true and RHS is
+    /// maximal. If \p Separator is not in the string, then the result is a
+    /// pair (LHS, RHS) where (*this == LHS) and (RHS == "").
+    ///
+    /// \param Separator - The string to split on.
+    /// \return - The split substrings.
+    LLVM_NODISCARD
+    std::pair<StringRef, StringRef> split(StringRef Separator) const {
+      size_t Idx = find(Separator);
+      if (Idx == npos)
+        return std::make_pair(*this, StringRef());
+      return std::make_pair(slice(0, Idx), slice(Idx + Separator.size(), npos));
+    }
+
+    /// Split into substrings around the occurrences of a separator string.
+    ///
+    /// Each substring is stored in \p A. If \p MaxSplit is >= 0, at most
+    /// \p MaxSplit splits are done and consequently <= \p MaxSplit + 1
+    /// elements are added to A.
+    /// If \p KeepEmpty is false, empty strings are not added to \p A. They
+    /// still count when considering \p MaxSplit
+    /// An useful invariant is that
+    /// Separator.join(A) == *this if MaxSplit == -1 and KeepEmpty == true
+    ///
+    /// \param A - Where to put the substrings.
+    /// \param Separator - The string to split on.
+    /// \param MaxSplit - The maximum number of times the string is split.
+    /// \param KeepEmpty - True if empty substring should be added.
+    void split(SmallVectorImpl<StringRef> &A,
+               StringRef Separator, int MaxSplit = -1,
+               bool KeepEmpty = true) const;
+
+    /// Split into substrings around the occurrences of a separator character.
+    ///
+    /// Each substring is stored in \p A. If \p MaxSplit is >= 0, at most
+    /// \p MaxSplit splits are done and consequently <= \p MaxSplit + 1
+    /// elements are added to A.
+    /// If \p KeepEmpty is false, empty strings are not added to \p A. They
+    /// still count when considering \p MaxSplit
+    /// An useful invariant is that
+    /// Separator.join(A) == *this if MaxSplit == -1 and KeepEmpty == true
+    ///
+    /// \param A - Where to put the substrings.
+    /// \param Separator - The string to split on.
+    /// \param MaxSplit - The maximum number of times the string is split.
+    /// \param KeepEmpty - True if empty substring should be added.
+    void split(SmallVectorImpl<StringRef> &A, char Separator, int MaxSplit = -1,
+               bool KeepEmpty = true) const;
+
+    /// Split into two substrings around the last occurrence of a separator
+    /// character.
+    ///
+    /// If \p Separator is in the string, then the result is a pair (LHS, RHS)
+    /// such that (*this == LHS + Separator + RHS) is true and RHS is
+    /// minimal. If \p Separator is not in the string, then the result is a
+    /// pair (LHS, RHS) where (*this == LHS) and (RHS == "").
+    ///
+    /// \param Separator - The character to split on.
+    /// \return - The split substrings.
+    LLVM_NODISCARD
+    std::pair<StringRef, StringRef> rsplit(char Separator) const {
+      size_t Idx = rfind(Separator);
+      if (Idx == npos)
+        return std::make_pair(*this, StringRef());
+      return std::make_pair(slice(0, Idx), slice(Idx+1, npos));
+    }
+
+    /// Return string with consecutive \p Char characters starting from the
+    /// the left removed.
+    LLVM_NODISCARD
+    StringRef ltrim(char Char) const noexcept {
+      return drop_front(std::min(Length, find_first_not_of(Char)));
+    }
+
+    /// Return string with consecutive characters in \p Chars starting from
+    /// the left removed.
+    LLVM_NODISCARD
+    StringRef ltrim(StringRef Chars = " \t\n\v\f\r") const noexcept {
+      return drop_front(std::min(Length, find_first_not_of(Chars)));
+    }
+
+    /// Return string with consecutive \p Char characters starting from the
+    /// right removed.
+    LLVM_NODISCARD
+    StringRef rtrim(char Char) const noexcept {
+      return drop_back(size() - std::min(Length, find_last_not_of(Char) + 1));
+    }
+
+    /// Return string with consecutive characters in \p Chars starting from
+    /// the right removed.
+    LLVM_NODISCARD
+    StringRef rtrim(StringRef Chars = " \t\n\v\f\r") const noexcept {
+      return drop_back(size() - std::min(Length, find_last_not_of(Chars) + 1));
+    }
+
+    /// Return string with consecutive \p Char characters starting from the
+    /// left and right removed.
+    LLVM_NODISCARD
+    StringRef trim(char Char) const noexcept {
+      return ltrim(Char).rtrim(Char);
+    }
+
+    /// Return string with consecutive characters in \p Chars starting from
+    /// the left and right removed.
+    LLVM_NODISCARD
+    StringRef trim(StringRef Chars = " \t\n\v\f\r") const noexcept {
+      return ltrim(Chars).rtrim(Chars);
+    }
+
+    /// @}
+  };
+
+  /// A wrapper around a string literal that serves as a proxy for constructing
+  /// global tables of StringRefs with the length computed at compile time.
+  /// In order to avoid the invocation of a global constructor, StringLiteral
+  /// should *only* be used in a constexpr context, as such:
+  ///
+  /// constexpr StringLiteral S("test");
+  ///
+  class StringLiteral : public StringRef {
+  private:
+    constexpr StringLiteral(const char *Str, size_t N) : StringRef(Str, N) {
+    }
+
+  public:
+    template <size_t N>
+    constexpr StringLiteral(const char (&Str)[N])
+#if defined(__clang__) && __has_attribute(enable_if)
+#pragma clang diagnostic push
+#pragma clang diagnostic ignored "-Wgcc-compat"
+        __attribute((enable_if(__builtin_strlen(Str) == N - 1,
+                               "invalid string literal")))
+#pragma clang diagnostic pop
+#endif
+        : StringRef(Str, N - 1) {
+    }
+
+    // Explicit construction for strings like "foo\0bar".
+    template <size_t N>
+    static constexpr StringLiteral withInnerNUL(const char (&Str)[N]) {
+      return StringLiteral(Str, N - 1);
+    }
+  };
+
+  /// @name StringRef Comparison Operators
+  /// @{
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  bool operator==(StringRef LHS, StringRef RHS) noexcept {
+    return LHS.equals(RHS);
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  bool operator!=(StringRef LHS, StringRef RHS) noexcept {
+    return !(LHS == RHS);
+  }
+
+  inline bool operator<(StringRef LHS, StringRef RHS) noexcept {
+    return LHS.compare(RHS) == -1;
+  }
+
+  inline bool operator<=(StringRef LHS, StringRef RHS) noexcept {
+    return LHS.compare(RHS) != 1;
+  }
+
+  inline bool operator>(StringRef LHS, StringRef RHS) noexcept {
+    return LHS.compare(RHS) == 1;
+  }
+
+  inline bool operator>=(StringRef LHS, StringRef RHS) noexcept {
+    return LHS.compare(RHS) != -1;
+  }
+
+  inline bool operator==(StringRef LHS, const char *RHS) noexcept {
+    return LHS.equals(StringRef(RHS));
+  }
+
+  inline bool operator!=(StringRef LHS, const char *RHS) noexcept {
+    return !(LHS == StringRef(RHS));
+  }
+
+  inline bool operator<(StringRef LHS, const char *RHS) noexcept {
+    return LHS.compare(StringRef(RHS)) == -1;
+  }
+
+  inline bool operator<=(StringRef LHS, const char *RHS) noexcept {
+    return LHS.compare(StringRef(RHS)) != 1;
+  }
+
+  inline bool operator>(StringRef LHS, const char *RHS) noexcept {
+    return LHS.compare(StringRef(RHS)) == 1;
+  }
+
+  inline bool operator>=(StringRef LHS, const char *RHS) noexcept {
+    return LHS.compare(StringRef(RHS)) != -1;
+  }
+
+  inline bool operator==(const char *LHS, StringRef RHS) noexcept {
+    return StringRef(LHS).equals(RHS);
+  }
+
+  inline bool operator!=(const char *LHS, StringRef RHS) noexcept {
+    return !(StringRef(LHS) == RHS);
+  }
+
+  inline bool operator<(const char *LHS, StringRef RHS) noexcept {
+    return StringRef(LHS).compare(RHS) == -1;
+  }
+
+  inline bool operator<=(const char *LHS, StringRef RHS) noexcept {
+    return StringRef(LHS).compare(RHS) != 1;
+  }
+
+  inline bool operator>(const char *LHS, StringRef RHS) noexcept {
+    return StringRef(LHS).compare(RHS) == 1;
+  }
+
+  inline bool operator>=(const char *LHS, StringRef RHS) noexcept {
+    return StringRef(LHS).compare(RHS) != -1;
+  }
+
+  inline std::string &operator+=(std::string &buffer, StringRef string) {
+    return buffer.append(string.data(), string.size());
+  }
+
+  std::ostream &operator<<(std::ostream &os, StringRef string);
+
+  /// @}
+
+  /// Compute a hash_code for a StringRef.
+  LLVM_NODISCARD
+  hash_code hash_value(StringRef S);
+
+  // StringRefs can be treated like a POD type.
+  template <typename T> struct isPodLike;
+  template <> struct isPodLike<StringRef> { static const bool value = true; };
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_STRINGREF_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPAcceptor.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPAcceptor.h
new file mode 100644
index 0000000..da82a8a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPAcceptor.h
@@ -0,0 +1,57 @@
+/*
+   TCPAcceptor.h
+
+   TCPAcceptor class interface. TCPAcceptor provides methods to passively
+   establish TCP/IP connections with clients.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
+*/
+
+#ifndef WPIUTIL_WPI_TCPACCEPTOR_H_
+#define WPIUTIL_WPI_TCPACCEPTOR_H_
+
+#include <atomic>
+#include <memory>
+#include <string>
+
+#include "wpi/NetworkAcceptor.h"
+#include "wpi/TCPStream.h"
+
+namespace wpi {
+
+class Logger;
+
+class TCPAcceptor : public NetworkAcceptor {
+  int m_lsd;
+  int m_port;
+  std::string m_address;
+  bool m_listening;
+  std::atomic_bool m_shutdown;
+  Logger& m_logger;
+
+ public:
+  TCPAcceptor(int port, const char* address, Logger& logger);
+  ~TCPAcceptor();
+
+  int start() override;
+  void shutdown() override;
+  std::unique_ptr<NetworkStream> accept() override;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_TCPACCEPTOR_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPConnector.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPConnector.h
new file mode 100644
index 0000000..a05342b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPConnector.h
@@ -0,0 +1,49 @@
+/*
+   TCPConnector.h
+
+   TCPConnector class interface. TCPConnector provides methods to actively
+   establish TCP/IP connections with a server.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License
+*/
+
+#ifndef WPIUTIL_WPI_TCPCONNECTOR_H_
+#define WPIUTIL_WPI_TCPCONNECTOR_H_
+
+#include <memory>
+#include <utility>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/NetworkStream.h"
+
+namespace wpi {
+
+class Logger;
+
+class TCPConnector {
+ public:
+  static std::unique_ptr<NetworkStream> connect(const char* server, int port,
+                                                Logger& logger,
+                                                int timeout = 0);
+  static std::unique_ptr<NetworkStream> connect_parallel(
+      ArrayRef<std::pair<const char*, int>> servers, Logger& logger,
+      int timeout = 0);
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_TCPCONNECTOR_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPStream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPStream.h
new file mode 100644
index 0000000..6a38ffb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/TCPStream.h
@@ -0,0 +1,71 @@
+/*
+   TCPStream.h
+
+   TCPStream class interface. TCPStream provides methods to trasnfer
+   data between peers over a TCP/IP connection.
+
+   ------------------------------------------
+
+   Copyright (c) 2013 [Vic Hargrave - http://vichargrave.com]
+
+   Licensed under the Apache License, Version 2.0 (the "License");
+   you may not use this file except in compliance with the License.
+   You may obtain a copy of the License at
+
+       http://www.apache.org/licenses/LICENSE-2.0
+
+   Unless required by applicable law or agreed to in writing, software
+   distributed under the License is distributed on an "AS IS" BASIS,
+   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+   See the License for the specific language governing permissions and
+   limitations under the License.
+*/
+
+#ifndef WPIUTIL_WPI_TCPSTREAM_H_
+#define WPIUTIL_WPI_TCPSTREAM_H_
+
+#include <cstddef>
+#include <string>
+
+#include "wpi/NetworkStream.h"
+
+struct sockaddr_in;
+
+namespace wpi {
+
+class TCPStream : public NetworkStream {
+  int m_sd;
+  std::string m_peerIP;
+  int m_peerPort;
+  bool m_blocking;
+
+ public:
+  friend class TCPAcceptor;
+  friend class TCPConnector;
+
+  ~TCPStream();
+
+  size_t send(const char* buffer, size_t len, Error* err) override;
+  size_t receive(char* buffer, size_t len, Error* err,
+                 int timeout = 0) override;
+  void close() override;
+
+  StringRef getPeerIP() const override;
+  int getPeerPort() const override;
+  void setNoDelay() override;
+  bool setBlocking(bool enabled) override;
+  int getNativeHandle() const override;
+
+  TCPStream(const TCPStream& stream) = delete;
+  TCPStream& operator=(const TCPStream&) = delete;
+
+ private:
+  bool WaitForReadEvent(int timeout);
+
+  TCPStream(int sd, sockaddr_in* address);
+  TCPStream() = delete;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_TCPSTREAM_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Twine.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Twine.h
new file mode 100644
index 0000000..bbf3a0f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/Twine.h
@@ -0,0 +1,533 @@
+//===- Twine.h - Fast Temporary String Concatenation ------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_TWINE_H
+#define WPIUTIL_WPI_TWINE_H
+
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include <cassert>
+#include <cstdint>
+#include <string>
+
+namespace wpi {
+
+  class raw_ostream;
+
+  /// Twine - A lightweight data structure for efficiently representing the
+  /// concatenation of temporary values as strings.
+  ///
+  /// A Twine is a kind of rope, it represents a concatenated string using a
+  /// binary-tree, where the string is the preorder of the nodes. Since the
+  /// Twine can be efficiently rendered into a buffer when its result is used,
+  /// it avoids the cost of generating temporary values for intermediate string
+  /// results -- particularly in cases when the Twine result is never
+  /// required. By explicitly tracking the type of leaf nodes, we can also avoid
+  /// the creation of temporary strings for conversions operations (such as
+  /// appending an integer to a string).
+  ///
+  /// A Twine is not intended for use directly and should not be stored, its
+  /// implementation relies on the ability to store pointers to temporary stack
+  /// objects which may be deallocated at the end of a statement. Twines should
+  /// only be used accepted as const references in arguments, when an API wishes
+  /// to accept possibly-concatenated strings.
+  ///
+  /// Twines support a special 'null' value, which always concatenates to form
+  /// itself, and renders as an empty string. This can be returned from APIs to
+  /// effectively nullify any concatenations performed on the result.
+  ///
+  /// \b Implementation
+  ///
+  /// Given the nature of a Twine, it is not possible for the Twine's
+  /// concatenation method to construct interior nodes; the result must be
+  /// represented inside the returned value. For this reason a Twine object
+  /// actually holds two values, the left- and right-hand sides of a
+  /// concatenation. We also have nullary Twine objects, which are effectively
+  /// sentinel values that represent empty strings.
+  ///
+  /// Thus, a Twine can effectively have zero, one, or two children. The \see
+  /// isNullary(), \see isUnary(), and \see isBinary() predicates exist for
+  /// testing the number of children.
+  ///
+  /// We maintain a number of invariants on Twine objects (FIXME: Why):
+  ///  - Nullary twines are always represented with their Kind on the left-hand
+  ///    side, and the Empty kind on the right-hand side.
+  ///  - Unary twines are always represented with the value on the left-hand
+  ///    side, and the Empty kind on the right-hand side.
+  ///  - If a Twine has another Twine as a child, that child should always be
+  ///    binary (otherwise it could have been folded into the parent).
+  ///
+  /// These invariants are check by \see isValid().
+  ///
+  /// \b Efficiency Considerations
+  ///
+  /// The Twine is designed to yield efficient and small code for common
+  /// situations. For this reason, the concat() method is inlined so that
+  /// concatenations of leaf nodes can be optimized into stores directly into a
+  /// single stack allocated object.
+  ///
+  /// In practice, not all compilers can be trusted to optimize concat() fully,
+  /// so we provide two additional methods (and accompanying operator+
+  /// overloads) to guarantee that particularly important cases (cstring plus
+  /// StringRef) codegen as desired.
+  class Twine {
+    /// NodeKind - Represent the type of an argument.
+    enum NodeKind : unsigned char {
+      /// An empty string; the result of concatenating anything with it is also
+      /// empty.
+      NullKind,
+
+      /// The empty string.
+      EmptyKind,
+
+      /// A pointer to a Twine instance.
+      TwineKind,
+
+      /// A pointer to a C string instance.
+      CStringKind,
+
+      /// A pointer to an std::string instance.
+      StdStringKind,
+
+      /// A pointer to a StringRef instance.
+      StringRefKind,
+
+      /// A pointer to a SmallString instance.
+      SmallStringKind,
+
+      /// A char value, to render as a character.
+      CharKind,
+
+      /// An unsigned int value, to render as an unsigned decimal integer.
+      DecUIKind,
+
+      /// An int value, to render as a signed decimal integer.
+      DecIKind,
+
+      /// A pointer to an unsigned long value, to render as an unsigned decimal
+      /// integer.
+      DecULKind,
+
+      /// A pointer to a long value, to render as a signed decimal integer.
+      DecLKind,
+
+      /// A pointer to an unsigned long long value, to render as an unsigned
+      /// decimal integer.
+      DecULLKind,
+
+      /// A pointer to a long long value, to render as a signed decimal integer.
+      DecLLKind,
+
+      /// A pointer to a uint64_t value, to render as an unsigned hexadecimal
+      /// integer.
+      UHexKind
+    };
+
+    union Child
+    {
+      const Twine *twine;
+      const char *cString;
+      const std::string *stdString;
+      const StringRef *stringRef;
+      const SmallVectorImpl<char> *smallString;
+      char character;
+      unsigned int decUI;
+      int decI;
+      const unsigned long *decUL;
+      const long *decL;
+      const unsigned long long *decULL;
+      const long long *decLL;
+      const uint64_t *uHex;
+    };
+
+    /// LHS - The prefix in the concatenation, which may be uninitialized for
+    /// Null or Empty kinds.
+    Child LHS;
+
+    /// RHS - The suffix in the concatenation, which may be uninitialized for
+    /// Null or Empty kinds.
+    Child RHS;
+
+    /// LHSKind - The NodeKind of the left hand side, \see getLHSKind().
+    NodeKind LHSKind = EmptyKind;
+
+    /// RHSKind - The NodeKind of the right hand side, \see getRHSKind().
+    NodeKind RHSKind = EmptyKind;
+
+    /// Construct a nullary twine; the kind must be NullKind or EmptyKind.
+    explicit Twine(NodeKind Kind) : LHSKind(Kind) {
+      assert(isNullary() && "Invalid kind!");
+    }
+
+    /// Construct a binary twine.
+    explicit Twine(const Twine &LHS, const Twine &RHS)
+        : LHSKind(TwineKind), RHSKind(TwineKind) {
+      this->LHS.twine = &LHS;
+      this->RHS.twine = &RHS;
+      assert(isValid() && "Invalid twine!");
+    }
+
+    /// Construct a twine from explicit values.
+    explicit Twine(Child LHS, NodeKind LHSKind, Child RHS, NodeKind RHSKind)
+        : LHS(LHS), RHS(RHS), LHSKind(LHSKind), RHSKind(RHSKind) {
+      assert(isValid() && "Invalid twine!");
+    }
+
+    /// Check for the empty twine.
+    bool isEmpty() const {
+      return getLHSKind() == EmptyKind;
+    }
+
+    /// Check if this is a nullary twine (null or empty).
+    bool isNullary() const {
+      return isNull() || isEmpty();
+    }
+
+    /// Check if this is a unary twine.
+    bool isUnary() const {
+      return getRHSKind() == EmptyKind && !isNullary();
+    }
+
+    /// Check if this is a binary twine.
+    bool isBinary() const {
+      return getLHSKind() != NullKind && getRHSKind() != EmptyKind;
+    }
+
+    /// Check if this is a valid twine (satisfying the invariants on
+    /// order and number of arguments).
+    bool isValid() const {
+      // Nullary twines always have Empty on the RHS.
+      if (isNullary() && getRHSKind() != EmptyKind)
+        return false;
+
+      // Null should never appear on the RHS.
+      if (getRHSKind() == NullKind)
+        return false;
+
+      // The RHS cannot be non-empty if the LHS is empty.
+      if (getRHSKind() != EmptyKind && getLHSKind() == EmptyKind)
+        return false;
+#if 0 // causes spurious warnings
+      // A twine child should always be binary.
+      if (getLHSKind() == TwineKind &&
+          !LHS.twine->isBinary())
+        return false;
+      if (getRHSKind() == TwineKind &&
+          !RHS.twine->isBinary())
+        return false;
+#endif
+      return true;
+    }
+
+    /// Get the NodeKind of the left-hand side.
+    NodeKind getLHSKind() const { return LHSKind; }
+
+    /// Get the NodeKind of the right-hand side.
+    NodeKind getRHSKind() const { return RHSKind; }
+
+    /// Print one child from a twine.
+    void printOneChild(raw_ostream &OS, Child Ptr, NodeKind Kind) const;
+
+    /// Print the representation of one child from a twine.
+    void printOneChildRepr(raw_ostream &OS, Child Ptr,
+                           NodeKind Kind) const;
+
+  public:
+    /// @name Constructors
+    /// @{
+
+    /// Construct from an empty string.
+    /*implicit*/ Twine() {
+      assert(isValid() && "Invalid twine!");
+    }
+
+    Twine(const Twine &) = default;
+
+    /// Construct from a C string.
+    ///
+    /// We take care here to optimize "" into the empty twine -- this will be
+    /// optimized out for string constants. This allows Twine arguments have
+    /// default "" values, without introducing unnecessary string constants.
+    /*implicit*/ Twine(const char *Str) {
+      if (Str[0] != '\0') {
+        LHS.cString = Str;
+        LHSKind = CStringKind;
+      } else
+        LHSKind = EmptyKind;
+
+      assert(isValid() && "Invalid twine!");
+    }
+
+    /// Construct from an std::string.
+    /*implicit*/ Twine(const std::string &Str) : LHSKind(StdStringKind) {
+      LHS.stdString = &Str;
+      assert(isValid() && "Invalid twine!");
+    }
+
+    /// Construct from a StringRef.
+    /*implicit*/ Twine(const StringRef &Str) : LHSKind(StringRefKind) {
+      LHS.stringRef = &Str;
+      assert(isValid() && "Invalid twine!");
+    }
+
+    /// Construct from a SmallString.
+    /*implicit*/ Twine(const SmallVectorImpl<char> &Str)
+        : LHSKind(SmallStringKind) {
+      LHS.smallString = &Str;
+      assert(isValid() && "Invalid twine!");
+    }
+
+    /// Construct from a char.
+    explicit Twine(char Val) : LHSKind(CharKind) {
+      LHS.character = Val;
+    }
+
+    /// Construct from a signed char.
+    explicit Twine(signed char Val) : LHSKind(CharKind) {
+      LHS.character = static_cast<char>(Val);
+    }
+
+    /// Construct from an unsigned char.
+    explicit Twine(unsigned char Val) : LHSKind(CharKind) {
+      LHS.character = static_cast<char>(Val);
+    }
+
+    /// Construct a twine to print \p Val as an unsigned decimal integer.
+    explicit Twine(unsigned Val) : LHSKind(DecUIKind) {
+      LHS.decUI = Val;
+    }
+
+    /// Construct a twine to print \p Val as a signed decimal integer.
+    explicit Twine(int Val) : LHSKind(DecIKind) {
+      LHS.decI = Val;
+    }
+
+    /// Construct a twine to print \p Val as an unsigned decimal integer.
+    explicit Twine(const unsigned long &Val) : LHSKind(DecULKind) {
+      LHS.decUL = &Val;
+    }
+
+    /// Construct a twine to print \p Val as a signed decimal integer.
+    explicit Twine(const long &Val) : LHSKind(DecLKind) {
+      LHS.decL = &Val;
+    }
+
+    /// Construct a twine to print \p Val as an unsigned decimal integer.
+    explicit Twine(const unsigned long long &Val) : LHSKind(DecULLKind) {
+      LHS.decULL = &Val;
+    }
+
+    /// Construct a twine to print \p Val as a signed decimal integer.
+    explicit Twine(const long long &Val) : LHSKind(DecLLKind) {
+      LHS.decLL = &Val;
+    }
+
+    // FIXME: Unfortunately, to make sure this is as efficient as possible we
+    // need extra binary constructors from particular types. We can't rely on
+    // the compiler to be smart enough to fold operator+()/concat() down to the
+    // right thing. Yet.
+
+    /// Construct as the concatenation of a C string and a StringRef.
+    /*implicit*/ Twine(const char *LHS, const StringRef &RHS)
+        : LHSKind(CStringKind), RHSKind(StringRefKind) {
+      this->LHS.cString = LHS;
+      this->RHS.stringRef = &RHS;
+      assert(isValid() && "Invalid twine!");
+    }
+
+    /// Construct as the concatenation of a StringRef and a C string.
+    /*implicit*/ Twine(const StringRef &LHS, const char *RHS)
+        : LHSKind(StringRefKind), RHSKind(CStringKind) {
+      this->LHS.stringRef = &LHS;
+      this->RHS.cString = RHS;
+      assert(isValid() && "Invalid twine!");
+    }
+
+    /// Since the intended use of twines is as temporary objects, assignments
+    /// when concatenating might cause undefined behavior or stack corruptions
+    Twine &operator=(const Twine &) = delete;
+
+    /// Create a 'null' string, which is an empty string that always
+    /// concatenates to form another empty string.
+    static Twine createNull() {
+      return Twine(NullKind);
+    }
+
+    /// @}
+    /// @name Numeric Conversions
+    /// @{
+
+    // Construct a twine to print \p Val as an unsigned hexadecimal integer.
+    static Twine utohexstr(const uint64_t &Val) {
+      Child LHS, RHS;
+      LHS.uHex = &Val;
+      RHS.twine = nullptr;
+      return Twine(LHS, UHexKind, RHS, EmptyKind);
+    }
+
+    /// @}
+    /// @name Predicate Operations
+    /// @{
+
+    /// Check for the null twine.
+    bool isNull() const {
+      return getLHSKind() == NullKind;
+    }
+
+    /// Check if this twine is trivially empty; a false return value does not
+    /// necessarily mean the twine is empty.
+    bool isTriviallyEmpty() const {
+      return isNullary();
+    }
+
+    /// Return true if this twine can be dynamically accessed as a single
+    /// StringRef value with getSingleStringRef().
+    bool isSingleStringRef() const {
+      if (getRHSKind() != EmptyKind) return false;
+
+      switch (getLHSKind()) {
+      case EmptyKind:
+      case CStringKind:
+      case StdStringKind:
+      case StringRefKind:
+      case SmallStringKind:
+      case CharKind:
+        return true;
+      default:
+        return false;
+      }
+    }
+
+    /// @}
+    /// @name String Operations
+    /// @{
+
+    Twine concat(const Twine &Suffix) const;
+
+    /// @}
+    /// @name Output & Conversion.
+    /// @{
+
+    /// Return the twine contents as a std::string.
+    std::string str() const;
+
+    /// Append the concatenated string into the given SmallString or SmallVector.
+    void toVector(SmallVectorImpl<char> &Out) const;
+
+    /// This returns the twine as a single StringRef.  This method is only valid
+    /// if isSingleStringRef() is true.
+    StringRef getSingleStringRef() const {
+      assert(isSingleStringRef() &&"This cannot be had as a single stringref!");
+      switch (getLHSKind()) {
+      default:
+        // unreachable("Out of sync with isSingleStringRef");
+        return StringRef();
+      case EmptyKind:      return StringRef();
+      case CStringKind:    return StringRef(LHS.cString);
+      case StdStringKind:  return StringRef(*LHS.stdString);
+      case StringRefKind:  return *LHS.stringRef;
+      case SmallStringKind:
+        return StringRef(LHS.smallString->data(), LHS.smallString->size());
+      case CharKind:       return StringRef(&LHS.character, 1);
+      }
+    }
+
+    /// This returns the twine as a single StringRef if it can be
+    /// represented as such. Otherwise the twine is written into the given
+    /// SmallVector and a StringRef to the SmallVector's data is returned.
+    StringRef toStringRef(SmallVectorImpl<char> &Out) const {
+      if (isSingleStringRef())
+        return getSingleStringRef();
+      toVector(Out);
+      return StringRef(Out.data(), Out.size());
+    }
+
+    /// This returns the twine as a single null terminated StringRef if it
+    /// can be represented as such. Otherwise the twine is written into the
+    /// given SmallVector and a StringRef to the SmallVector's data is returned.
+    ///
+    /// The returned StringRef's size does not include the null terminator.
+    StringRef toNullTerminatedStringRef(SmallVectorImpl<char> &Out) const;
+
+    /// Write the concatenated string represented by this twine to the
+    /// stream \p OS.
+    void print(raw_ostream &OS) const;
+
+    /// Dump the concatenated string represented by this twine to stderr.
+    void dump() const;
+
+    /// Write the representation of this twine to the stream \p OS.
+    void printRepr(raw_ostream &OS) const;
+
+    /// Dump the representation of this twine to stderr.
+    void dumpRepr() const;
+
+    /// @}
+  };
+
+  /// @name Twine Inline Implementations
+  /// @{
+
+  inline Twine Twine::concat(const Twine &Suffix) const {
+    // Concatenation with null is null.
+    if (isNull() || Suffix.isNull())
+      return Twine(NullKind);
+
+    // Concatenation with empty yields the other side.
+    if (isEmpty())
+      return Suffix;
+    if (Suffix.isEmpty())
+      return *this;
+
+    // Otherwise we need to create a new node, taking care to fold in unary
+    // twines.
+    Child NewLHS, NewRHS;
+    NewLHS.twine = this;
+    NewRHS.twine = &Suffix;
+    NodeKind NewLHSKind = TwineKind, NewRHSKind = TwineKind;
+    if (isUnary()) {
+      NewLHS = LHS;
+      NewLHSKind = getLHSKind();
+    }
+    if (Suffix.isUnary()) {
+      NewRHS = Suffix.LHS;
+      NewRHSKind = Suffix.getLHSKind();
+    }
+
+    return Twine(NewLHS, NewLHSKind, NewRHS, NewRHSKind);
+  }
+
+  inline Twine operator+(const Twine &LHS, const Twine &RHS) {
+    return LHS.concat(RHS);
+  }
+
+  /// Additional overload to guarantee simplified codegen; this is equivalent to
+  /// concat().
+
+  inline Twine operator+(const char *LHS, const StringRef &RHS) {
+    return Twine(LHS, RHS);
+  }
+
+  /// Additional overload to guarantee simplified codegen; this is equivalent to
+  /// concat().
+
+  inline Twine operator+(const StringRef &LHS, const char *RHS) {
+    return Twine(LHS, RHS);
+  }
+
+  inline raw_ostream &operator<<(raw_ostream &OS, const Twine &RHS) {
+    RHS.print(OS);
+    return OS;
+  }
+
+  /// @}
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_TWINE_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UDPClient.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UDPClient.h
new file mode 100644
index 0000000..635eca8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UDPClient.h
@@ -0,0 +1,53 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UDPCLIENT_H_
+#define WPIUTIL_WPI_UDPCLIENT_H_
+
+#include <string>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+#include "wpi/mutex.h"
+
+namespace wpi {
+
+class Logger;
+
+class UDPClient {
+  int m_lsd;
+  int m_port;
+  std::string m_address;
+  Logger& m_logger;
+
+ public:
+  explicit UDPClient(Logger& logger);
+  UDPClient(const Twine& address, Logger& logger);
+  UDPClient(const UDPClient& other) = delete;
+  UDPClient(UDPClient&& other);
+  ~UDPClient();
+
+  UDPClient& operator=(const UDPClient& other) = delete;
+  UDPClient& operator=(UDPClient&& other);
+
+  int start();
+  int start(int port);
+  void shutdown();
+  // The passed in address MUST be a resolved IP address.
+  int send(ArrayRef<uint8_t> data, const Twine& server, int port);
+  int send(StringRef data, const Twine& server, int port);
+  int receive(uint8_t* data_received, int receive_len);
+  int receive(uint8_t* data_received, int receive_len,
+              SmallVectorImpl<char>* addr_received, int* port_received);
+  int set_timeout(double timeout);
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UDPCLIENT_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UidVector.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UidVector.h
new file mode 100644
index 0000000..ead1246
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UidVector.h
@@ -0,0 +1,149 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UIDVECTOR_H_
+#define WPIUTIL_WPI_UIDVECTOR_H_
+
+#include <iterator>
+#include <utility>
+#include <vector>
+
+namespace wpi {
+
+namespace impl {
+template <typename It>
+class UidVectorIterator {
+ public:
+  using iterator_type = std::forward_iterator_tag;
+  using value_type = typename It::value_type;
+  using difference_type = typename It::difference_type;
+  using reference = typename It::reference;
+  using pointer = typename It::pointer;
+
+  UidVectorIterator() = default;
+  explicit UidVectorIterator(It it, It end) : m_it(it), m_end(end) {
+    // advance to first non-empty element
+    while (m_it != m_end && !*m_it) ++m_it;
+  }
+
+  reference operator*() const noexcept { return *m_it; }
+  pointer operator->() const noexcept { return m_it.operator->(); }
+
+  UidVectorIterator& operator++() noexcept {
+    // advance past empty elements
+    do {
+      ++m_it;
+    } while (m_it != m_end && !*m_it);
+    return *this;
+  }
+
+  UidVectorIterator operator++(int)noexcept {
+    UidVectorIterator it = *this;
+    ++it;
+    return it;
+  }
+
+  bool operator==(const UidVectorIterator& oth) const noexcept {
+    return m_it == oth.m_it;
+  }
+
+  bool operator!=(const UidVectorIterator& oth) const noexcept {
+    return m_it != oth.m_it;
+  }
+
+ private:
+  It m_it;
+  It m_end;
+};
+}  // namespace impl
+
+// Vector which provides an integrated freelist for removal and reuse of
+// individual elements.
+// @tparam T element type; must be default-constructible and evaluate in
+//           boolean context to false when "empty"
+// @tparam reuse_threshold how many free elements to store up before starting
+//                         to recycle them
+template <typename T, typename std::vector<T>::size_type reuse_threshold>
+class UidVector {
+ public:
+  using value_type = T;
+  using pointer = T*;
+  using const_pointer = const T*;
+  using reference = T&;
+  using const_reference = const T&;
+  using size_type = typename std::vector<T>::size_type;
+  using difference_type = typename std::vector<T>::difference_type;
+  using iterator = impl::UidVectorIterator<typename std::vector<T>::iterator>;
+  using const_iterator =
+      impl::UidVectorIterator<typename std::vector<T>::const_iterator>;
+
+  bool empty() const { return m_active_count == 0; }
+  size_type size() const { return m_vector.size(); }
+  T& operator[](size_type i) { return m_vector[i]; }
+  const T& operator[](size_type i) const { return m_vector[i]; }
+
+  // Add a new T to the vector.  If there are elements on the freelist,
+  // reuses the last one; otherwise adds to the end of the vector.
+  // Returns the resulting element index.
+  template <class... Args>
+  size_type emplace_back(Args&&... args) {
+    size_type uid;
+    if (m_free.size() < reuse_threshold) {
+      uid = m_vector.size();
+      m_vector.emplace_back(std::forward<Args>(args)...);
+    } else {
+      uid = m_free.front();
+      m_free.erase(m_free.begin());
+      m_vector[uid] = T(std::forward<Args>(args)...);
+    }
+    ++m_active_count;
+    return uid;
+  }
+
+  // Removes the identified element by replacing it with a default-constructed
+  // one.  The element is added to the freelist for later reuse.
+  void erase(size_type uid) {
+    if (uid >= m_vector.size() || !m_vector[uid]) return;
+    m_free.push_back(uid);
+    m_vector[uid] = T();
+    --m_active_count;
+  }
+
+  // Removes all elements.
+  void clear() {
+    m_vector.clear();
+    m_free.clear();
+    m_active_count = 0;
+  }
+
+  // Iterator access
+  iterator begin() noexcept {
+    return iterator(m_vector.begin(), m_vector.end());
+  }
+  const_iterator begin() const noexcept {
+    return const_iterator(m_vector.begin(), m_vector.end());
+  }
+  const_iterator cbegin() const noexcept {
+    return const_iterator(m_vector.begin(), m_vector.end());
+  }
+  iterator end() noexcept { return iterator(m_vector.end(), m_vector.end()); }
+  const_iterator end() const noexcept {
+    return const_iterator(m_vector.end(), m_vector.end());
+  }
+  const_iterator cend() const noexcept {
+    return const_iterator(m_vector.end(), m_vector.end());
+  }
+
+ private:
+  std::vector<T> m_vector;
+  std::vector<size_type> m_free;
+  size_type m_active_count{0};
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UIDVECTOR_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UrlParser.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UrlParser.h
new file mode 100644
index 0000000..e3da269
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/UrlParser.h
@@ -0,0 +1,96 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_URLPARSER_H_
+#define WPIUTIL_WPI_URLPARSER_H_
+
+#include "wpi/StringRef.h"
+#include "wpi/http_parser.h"
+
+namespace wpi {
+
+/**
+ * Parses a URL into its constiuent components.
+ * `schema://userinfo@host:port/the/path?query#fragment`
+ */
+class UrlParser {
+ public:
+  /**
+   * Parse a URL.
+   * @param in input
+   * @param isConnect
+   */
+  UrlParser(StringRef in, bool isConnect) {
+    m_data = in;
+    http_parser_url_init(&m_url);
+    m_error = http_parser_parse_url(in.data(), in.size(), isConnect, &m_url);
+  }
+
+  /**
+   * Determine if the URL is valid (e.g. the parse was successful).
+   */
+  bool IsValid() const { return !m_error; }
+
+  bool HasSchema() const { return (m_url.field_set & (1 << UF_SCHEMA)) != 0; }
+
+  bool HasHost() const { return (m_url.field_set & (1 << UF_HOST)) != 0; }
+
+  bool HasPort() const { return (m_url.field_set & (1 << UF_PORT)) != 0; }
+
+  bool HasPath() const { return (m_url.field_set & (1 << UF_PATH)) != 0; }
+
+  bool HasQuery() const { return (m_url.field_set & (1 << UF_QUERY)) != 0; }
+
+  bool HasFragment() const {
+    return (m_url.field_set & (1 << UF_FRAGMENT)) != 0;
+  }
+
+  bool HasUserInfo() const {
+    return (m_url.field_set & (1 << UF_USERINFO)) != 0;
+  }
+
+  StringRef GetSchema() const {
+    return m_data.substr(m_url.field_data[UF_SCHEMA].off,
+                         m_url.field_data[UF_SCHEMA].len);
+  }
+
+  StringRef GetHost() const {
+    return m_data.substr(m_url.field_data[UF_HOST].off,
+                         m_url.field_data[UF_HOST].len);
+  }
+
+  unsigned int GetPort() const { return m_url.port; }
+
+  StringRef GetPath() const {
+    return m_data.substr(m_url.field_data[UF_PATH].off,
+                         m_url.field_data[UF_PATH].len);
+  }
+
+  StringRef GetQuery() const {
+    return m_data.substr(m_url.field_data[UF_QUERY].off,
+                         m_url.field_data[UF_QUERY].len);
+  }
+
+  StringRef GetFragment() const {
+    return m_data.substr(m_url.field_data[UF_FRAGMENT].off,
+                         m_url.field_data[UF_FRAGMENT].len);
+  }
+
+  StringRef GetUserInfo() const {
+    return m_data.substr(m_url.field_data[UF_USERINFO].off,
+                         m_url.field_data[UF_USERINFO].len);
+  }
+
+ private:
+  bool m_error;
+  StringRef m_data;
+  http_parser_url m_url;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_URLPARSER_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WebSocket.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WebSocket.h
new file mode 100644
index 0000000..418c134
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WebSocket.h
@@ -0,0 +1,378 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_WEBSOCKET_H_
+#define WPIUTIL_WPI_WEBSOCKET_H_
+
+#include <stdint.h>
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <utility>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/Signal.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+#include "wpi/uv/Buffer.h"
+#include "wpi/uv/Error.h"
+#include "wpi/uv/Timer.h"
+
+namespace wpi {
+
+namespace uv {
+class Stream;
+}  // namespace uv
+
+/**
+ * RFC 6455 compliant WebSocket client and server implementation.
+ */
+class WebSocket : public std::enable_shared_from_this<WebSocket> {
+  struct private_init {};
+
+  static constexpr uint8_t kOpCont = 0x00;
+  static constexpr uint8_t kOpText = 0x01;
+  static constexpr uint8_t kOpBinary = 0x02;
+  static constexpr uint8_t kOpClose = 0x08;
+  static constexpr uint8_t kOpPing = 0x09;
+  static constexpr uint8_t kOpPong = 0x0A;
+  static constexpr uint8_t kOpMask = 0x0F;
+  static constexpr uint8_t kFlagFin = 0x80;
+  static constexpr uint8_t kFlagMasking = 0x80;
+  static constexpr uint8_t kLenMask = 0x7f;
+
+ public:
+  WebSocket(uv::Stream& stream, bool server, const private_init&);
+  WebSocket(const WebSocket&) = delete;
+  WebSocket(WebSocket&&) = delete;
+  WebSocket& operator=(const WebSocket&) = delete;
+  WebSocket& operator=(WebSocket&&) = delete;
+  ~WebSocket();
+
+  /**
+   * Connection states.
+   */
+  enum State {
+    /** The connection is not yet open. */
+    CONNECTING = 0,
+    /** The connection is open and ready to communicate. */
+    OPEN,
+    /** The connection is in the process of closing. */
+    CLOSING,
+    /** The connection failed. */
+    FAILED,
+    /** The connection is closed. */
+    CLOSED
+  };
+
+  /**
+   * Client connection options.
+   */
+  struct ClientOptions {
+    ClientOptions() : handshakeTimeout{uv::Timer::Time::max()} {}
+
+    /** Timeout for the handshake request. */
+    uv::Timer::Time handshakeTimeout;
+
+    /** Additional headers to include in handshake. */
+    ArrayRef<std::pair<StringRef, StringRef>> extraHeaders;
+  };
+
+  /**
+   * Starts a client connection by performing the initial client handshake.
+   * An open event is emitted when the handshake completes.
+   * This sets the stream user data to the websocket.
+   * @param stream Connection stream
+   * @param uri The Request-URI to send
+   * @param host The host or host:port to send
+   * @param protocols The list of subprotocols
+   * @param options Handshake options
+   */
+  static std::shared_ptr<WebSocket> CreateClient(
+      uv::Stream& stream, const Twine& uri, const Twine& host,
+      ArrayRef<StringRef> protocols = ArrayRef<StringRef>{},
+      const ClientOptions& options = ClientOptions{});
+
+  /**
+   * Starts a server connection by performing the initial server side handshake.
+   * This should be called after the HTTP headers have been received.
+   * An open event is emitted when the handshake completes.
+   * This sets the stream user data to the websocket.
+   * @param stream Connection stream
+   * @param key The value of the Sec-WebSocket-Key header field in the client
+   *            request
+   * @param version The value of the Sec-WebSocket-Version header field in the
+   *                client request
+   * @param protocol The subprotocol to send to the client (in the
+   *                 Sec-WebSocket-Protocol header field).
+   */
+  static std::shared_ptr<WebSocket> CreateServer(
+      uv::Stream& stream, StringRef key, StringRef version,
+      StringRef protocol = StringRef{});
+
+  /**
+   * Get connection state.
+   */
+  State GetState() const { return m_state; }
+
+  /**
+   * Return if the connection is open.  Messages can only be sent on open
+   * connections.
+   */
+  bool IsOpen() const { return m_state == OPEN; }
+
+  /**
+   * Get the underlying stream.
+   */
+  uv::Stream& GetStream() const { return m_stream; }
+
+  /**
+   * Get the selected sub-protocol.  Only valid in or after the open() event.
+   */
+  StringRef GetProtocol() const { return m_protocol; }
+
+  /**
+   * Set the maximum message size.  Default is 128 KB.  If configured to combine
+   * fragments this maximum applies to the entire message (all combined
+   * fragments).
+   * @param size Maximum message size in bytes
+   */
+  void SetMaxMessageSize(size_t size) { m_maxMessageSize = size; }
+
+  /**
+   * Set whether or not fragmented frames should be combined.  Default is to
+   * combine.  If fragmented frames are combined, the text and binary callbacks
+   * will always have the second parameter (fin) set to true.
+   * @param combine True if fragmented frames should be combined.
+   */
+  void SetCombineFragments(bool combine) { m_combineFragments = combine; }
+
+  /**
+   * Initiate a closing handshake.
+   * @param code A numeric status code (defaults to 1005, no status code)
+   * @param reason A human-readable string explaining why the connection is
+   *               closing (optional).
+   */
+  void Close(uint16_t code = 1005, const Twine& reason = Twine{});
+
+  /**
+   * Send a text message.
+   * @param data UTF-8 encoded data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendText(
+      ArrayRef<uv::Buffer> data,
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+    Send(kFlagFin | kOpText, data, callback);
+  }
+
+  /**
+   * Send a binary message.
+   * @param data Data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendBinary(
+      ArrayRef<uv::Buffer> data,
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+    Send(kFlagFin | kOpBinary, data, callback);
+  }
+
+  /**
+   * Send a text message fragment.  This must be followed by one or more
+   * SendFragment() calls, where the last one has fin=True, to complete the
+   * message.
+   * @param data UTF-8 encoded data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendTextFragment(
+      ArrayRef<uv::Buffer> data,
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+    Send(kOpText, data, callback);
+  }
+
+  /**
+   * Send a text message fragment.  This must be followed by one or more
+   * SendFragment() calls, where the last one has fin=True, to complete the
+   * message.
+   * @param data Data to send
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendBinaryFragment(
+      ArrayRef<uv::Buffer> data,
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+    Send(kOpBinary, data, callback);
+  }
+
+  /**
+   * Send a continuation frame.  This is used to send additional parts of a
+   * message started with SendTextFragment() or SendBinaryFragment().
+   * @param data Data to send
+   * @param fin Set to true if this is the final fragment of the message
+   * @param callback Callback which is invoked when the write completes.
+   */
+  void SendFragment(
+      ArrayRef<uv::Buffer> data, bool fin,
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+    Send(kOpCont | (fin ? kFlagFin : 0), data, callback);
+  }
+
+  /**
+   * Send a ping frame with no data.
+   * @param callback Optional callback which is invoked when the ping frame
+   *                 write completes.
+   */
+  void SendPing(std::function<void(uv::Error)> callback = nullptr) {
+    SendPing(ArrayRef<uv::Buffer>{}, [callback](auto bufs, uv::Error err) {
+      if (callback) callback(err);
+    });
+  }
+
+  /**
+   * Send a ping frame.
+   * @param data Data to send in the ping frame
+   * @param callback Callback which is invoked when the ping frame
+   *                 write completes.
+   */
+  void SendPing(
+      ArrayRef<uv::Buffer> data,
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+    Send(kFlagFin | kOpPing, data, callback);
+  }
+
+  /**
+   * Send a pong frame with no data.
+   * @param callback Optional callback which is invoked when the pong frame
+   *                 write completes.
+   */
+  void SendPong(std::function<void(uv::Error)> callback = nullptr) {
+    SendPong(ArrayRef<uv::Buffer>{}, [callback](auto bufs, uv::Error err) {
+      if (callback) callback(err);
+    });
+  }
+
+  /**
+   * Send a pong frame.
+   * @param data Data to send in the pong frame
+   * @param callback Callback which is invoked when the pong frame
+   *                 write completes.
+   */
+  void SendPong(
+      ArrayRef<uv::Buffer> data,
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback) {
+    Send(kFlagFin | kOpPong, data, callback);
+  }
+
+  /**
+   * Fail the connection.
+   */
+  void Fail(uint16_t code = 1002, const Twine& reason = "protocol error");
+
+  /**
+   * Forcibly close the connection.
+   */
+  void Terminate(uint16_t code = 1006, const Twine& reason = "terminated");
+
+  /**
+   * Gets user-defined data.
+   * @return User-defined data if any, nullptr otherwise.
+   */
+  template <typename T = void>
+  std::shared_ptr<T> GetData() const {
+    return std::static_pointer_cast<T>(m_data);
+  }
+
+  /**
+   * Sets user-defined data.
+   * @param data User-defined arbitrary data.
+   */
+  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
+
+  /**
+   * Open event.  Emitted when the connection is open and ready to communicate.
+   * The parameter is the selected subprotocol.
+   */
+  sig::Signal<StringRef> open;
+
+  /**
+   * Close event.  Emitted when the connection is closed.  The first parameter
+   * is a numeric value indicating the status code explaining why the connection
+   * has been closed.  The second parameter is a human-readable string
+   * explaining the reason why the connection has been closed.
+   */
+  sig::Signal<uint16_t, StringRef> closed;
+
+  /**
+   * Text message event.  Emitted when a text message is received.
+   * The first parameter is the data, the second parameter is true if the
+   * data is the last fragment of the message.
+   */
+  sig::Signal<StringRef, bool> text;
+
+  /**
+   * Binary message event.  Emitted when a binary message is received.
+   * The first parameter is the data, the second parameter is true if the
+   * data is the last fragment of the message.
+   */
+  sig::Signal<ArrayRef<uint8_t>, bool> binary;
+
+  /**
+   * Ping event.  Emitted when a ping message is received.
+   */
+  sig::Signal<ArrayRef<uint8_t>> ping;
+
+  /**
+   * Pong event.  Emitted when a pong message is received.
+   */
+  sig::Signal<ArrayRef<uint8_t>> pong;
+
+ private:
+  // user data
+  std::shared_ptr<void> m_data;
+
+  // constructor parameters
+  uv::Stream& m_stream;
+  bool m_server;
+
+  // subprotocol, set via constructor (server) or handshake (client)
+  std::string m_protocol;
+
+  // user-settable configuration
+  size_t m_maxMessageSize = 128 * 1024;
+  bool m_combineFragments = true;
+
+  // operating state
+  State m_state = CONNECTING;
+
+  // incoming message buffers/state
+  SmallVector<uint8_t, 14> m_header;
+  size_t m_headerSize = 0;
+  SmallVector<uint8_t, 1024> m_payload;
+  size_t m_frameStart = 0;
+  uint64_t m_frameSize = UINT64_MAX;
+  uint8_t m_fragmentOpcode = 0;
+
+  // temporary data used only during client handshake
+  class ClientHandshakeData;
+  std::unique_ptr<ClientHandshakeData> m_clientHandshake;
+
+  void StartClient(const Twine& uri, const Twine& host,
+                   ArrayRef<StringRef> protocols, const ClientOptions& options);
+  void StartServer(StringRef key, StringRef version, StringRef protocol);
+  void SendClose(uint16_t code, const Twine& reason);
+  void SetClosed(uint16_t code, const Twine& reason, bool failed = false);
+  void Shutdown();
+  void HandleIncoming(uv::Buffer& buf, size_t size);
+  void Send(
+      uint8_t opcode, ArrayRef<uv::Buffer> data,
+      std::function<void(MutableArrayRef<uv::Buffer>, uv::Error)> callback);
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_WEBSOCKET_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WebSocketServer.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WebSocketServer.h
new file mode 100644
index 0000000..c324c99
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WebSocketServer.h
@@ -0,0 +1,149 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_WEBSOCKETSERVER_H_
+#define WPIUTIL_WPI_WEBSOCKETSERVER_H_
+
+#include <functional>
+#include <memory>
+#include <string>
+#include <utility>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/HttpParser.h"
+#include "wpi/Signal.h"
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include "wpi/WebSocket.h"
+
+namespace wpi {
+
+namespace uv {
+class Stream;
+}  // namespace uv
+
+/**
+ * WebSocket HTTP server helper.  Handles websocket-specific headers.  User
+ * must provide the HttpParser.
+ */
+class WebSocketServerHelper {
+ public:
+  /**
+   * Constructor.
+   * @param req HttpParser for request
+   */
+  explicit WebSocketServerHelper(HttpParser& req);
+
+  /**
+   * Get whether or not this was a websocket upgrade.
+   * Only valid during and after the upgrade event.
+   */
+  bool IsWebsocket() const { return m_websocket; }
+
+  /**
+   * Try to find a match to the list of sub-protocols provided by the client.
+   * The list is priority ordered, so the first match wins.
+   * Only valid during and after the upgrade event.
+   * @param protocols Acceptable protocols
+   * @return Pair; first item is true if a match was made, false if not.
+   *         Second item is the matched protocol if a match was made, otherwise
+   *         is empty.
+   */
+  std::pair<bool, StringRef> MatchProtocol(ArrayRef<StringRef> protocols);
+
+  /**
+   * Accept the upgrade.  Disconnect other readers (such as the HttpParser
+   * reader) before calling this.  See also WebSocket::CreateServer().
+   * @param stream Connection stream
+   * @param protocol The subprotocol to send to the client
+   */
+  std::shared_ptr<WebSocket> Accept(uv::Stream& stream,
+                                    StringRef protocol = StringRef{}) {
+    return WebSocket::CreateServer(stream, m_key, m_version, protocol);
+  }
+
+  bool IsUpgrade() const { return m_gotHost && m_websocket; }
+
+  /**
+   * Upgrade event.  Call Accept() to accept the upgrade.
+   */
+  sig::Signal<> upgrade;
+
+ private:
+  bool m_gotHost = false;
+  bool m_websocket = false;
+  SmallVector<std::string, 2> m_protocols;
+  SmallString<64> m_key;
+  SmallString<16> m_version;
+};
+
+/**
+ * Dedicated WebSocket server.
+ */
+class WebSocketServer : public std::enable_shared_from_this<WebSocketServer> {
+  struct private_init {};
+
+ public:
+  /**
+   * Server options.
+   */
+  struct ServerOptions {
+    /**
+     * Checker for URL.  Return true if URL should be accepted.  By default all
+     * URLs are accepted.
+     */
+    std::function<bool(StringRef)> checkUrl;
+
+    /**
+     * Checker for Host header.  Return true if Host should be accepted.  By
+     * default all hosts are accepted.
+     */
+    std::function<bool(StringRef)> checkHost;
+  };
+
+  /**
+   * Private constructor.
+   */
+  WebSocketServer(uv::Stream& stream, ArrayRef<StringRef> protocols,
+                  const ServerOptions& options, const private_init&);
+
+  /**
+   * Starts a dedicated WebSocket server on the provided connection.  The
+   * connection should be an accepted client stream.
+   * This also sets the stream user data to the socket server.
+   * A connected event is emitted when the connection is opened.
+   * @param stream Connection stream
+   * @param protocols Acceptable subprotocols
+   * @param options Handshake options
+   */
+  static std::shared_ptr<WebSocketServer> Create(
+      uv::Stream& stream, ArrayRef<StringRef> protocols = ArrayRef<StringRef>{},
+      const ServerOptions& options = ServerOptions{});
+
+  /**
+   * Connected event.  First parameter is the URL, second is the websocket.
+   */
+  sig::Signal<StringRef, WebSocket&> connected;
+
+ private:
+  uv::Stream& m_stream;
+  HttpParser m_req{HttpParser::kRequest};
+  WebSocketServerHelper m_helper;
+  SmallVector<std::string, 2> m_protocols;
+  ServerOptions m_options;
+  bool m_aborted = false;
+  sig::ScopedConnection m_dataConn;
+  sig::ScopedConnection m_errorConn;
+  sig::ScopedConnection m_endConn;
+
+  void Abort(uint16_t code, StringRef reason);
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_WEBSOCKETSERVER_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WindowsError.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WindowsError.h
new file mode 100644
index 0000000..565e2b7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WindowsError.h
@@ -0,0 +1,19 @@
+//===-- WindowsError.h - Support for mapping windows errors to posix-------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_WINDOWSERROR_H
+#define WPIUTIL_WPI_WINDOWSERROR_H
+
+#include <system_error>
+
+namespace wpi {
+std::error_code mapWindowsError(unsigned EV);
+}
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WorkerThread.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WorkerThread.h
new file mode 100644
index 0000000..9a04f1a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/WorkerThread.h
@@ -0,0 +1,276 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_WORKERTHREAD_H_
+#define WPIUTIL_WPI_WORKERTHREAD_H_
+
+#include <functional>
+#include <memory>
+#include <tuple>
+#include <utility>
+#include <vector>
+
+#include "wpi/STLExtras.h"
+#include "wpi/SafeThread.h"
+#include "wpi/future.h"
+#include "wpi/uv/Async.h"
+
+namespace wpi {
+
+namespace detail {
+
+template <typename R>
+struct WorkerThreadAsync {
+  using AfterWorkFunction = std::function<void(R)>;
+
+  ~WorkerThreadAsync() { UnsetLoop(); }
+
+  void SetLoop(uv::Loop& loop) {
+    auto async = uv::Async<AfterWorkFunction, R>::Create(loop);
+    async->wakeup.connect(
+        [](AfterWorkFunction func, R result) { func(result); });
+    m_async = async;
+  }
+
+  void UnsetLoop() {
+    if (auto async = m_async.lock()) {
+      async->Close();
+      m_async.reset();
+    }
+  }
+
+  std::weak_ptr<uv::Async<AfterWorkFunction, R>> m_async;
+};
+
+template <>
+struct WorkerThreadAsync<void> {
+  using AfterWorkFunction = std::function<void()>;
+
+  ~WorkerThreadAsync() { RemoveLoop(); }
+
+  void SetLoop(uv::Loop& loop) {
+    auto async = uv::Async<AfterWorkFunction>::Create(loop);
+    async->wakeup.connect([](AfterWorkFunction func) { func(); });
+    m_async = async;
+  }
+
+  void RemoveLoop() {
+    if (auto async = m_async.lock()) {
+      async->Close();
+      m_async.reset();
+    }
+  }
+
+  std::weak_ptr<uv::Async<AfterWorkFunction>> m_async;
+};
+
+template <typename R, typename... T>
+struct WorkerThreadRequest {
+  using WorkFunction = std::function<R(T...)>;
+  using AfterWorkFunction = typename WorkerThreadAsync<R>::AfterWorkFunction;
+
+  WorkerThreadRequest() = default;
+  WorkerThreadRequest(uint64_t promiseId_, WorkFunction work_,
+                      std::tuple<T...> params_)
+      : promiseId(promiseId_),
+        work(std::move(work_)),
+        params(std::move(params_)) {}
+  WorkerThreadRequest(WorkFunction work_, AfterWorkFunction afterWork_,
+                      std::tuple<T...> params_)
+      : promiseId(0),
+        work(std::move(work_)),
+        afterWork(std::move(afterWork_)),
+        params(std::move(params_)) {}
+
+  uint64_t promiseId;
+  WorkFunction work;
+  AfterWorkFunction afterWork;
+  std::tuple<T...> params;
+};
+
+template <typename R, typename... T>
+class WorkerThreadThread : public SafeThread {
+ public:
+  using Request = WorkerThreadRequest<R, T...>;
+
+  void Main() override;
+
+  std::vector<Request> m_requests;
+  PromiseFactory<R> m_promises;
+  detail::WorkerThreadAsync<R> m_async;
+};
+
+template <typename R, typename... T>
+void RunWorkerThreadRequest(WorkerThreadThread<R, T...>& thr,
+                            WorkerThreadRequest<R, T...>& req) {
+  R result = apply_tuple(req.work, std::move(req.params));
+  if (req.afterWork) {
+    if (auto async = thr.m_async.m_async.lock())
+      async->Send(std::move(req.afterWork), std::move(result));
+  } else {
+    thr.m_promises.SetValue(req.promiseId, std::move(result));
+  }
+}
+
+template <typename... T>
+void RunWorkerThreadRequest(WorkerThreadThread<void, T...>& thr,
+                            WorkerThreadRequest<void, T...>& req) {
+  apply_tuple(req.work, req.params);
+  if (req.afterWork) {
+    if (auto async = thr.m_async.m_async.lock())
+      async->Send(std::move(req.afterWork));
+  } else {
+    thr.m_promises.SetValue(req.promiseId);
+  }
+}
+
+template <typename R, typename... T>
+void WorkerThreadThread<R, T...>::Main() {
+  std::vector<Request> requests;
+  while (m_active) {
+    std::unique_lock<wpi::mutex> lock(m_mutex);
+    m_cond.wait(lock, [&] { return !m_active || !m_requests.empty(); });
+    if (!m_active) break;
+
+    // don't want to hold the lock while executing the callbacks
+    requests.swap(m_requests);
+    lock.unlock();
+
+    for (auto&& req : requests) {
+      if (!m_active) break;  // requests may be long-running
+      RunWorkerThreadRequest(*this, req);
+    }
+    requests.clear();
+    m_promises.Notify();
+  }
+}
+
+}  // namespace detail
+
+template <typename T>
+class WorkerThread;
+
+template <typename R, typename... T>
+class WorkerThread<R(T...)> final {
+  using Thread = detail::WorkerThreadThread<R, T...>;
+
+ public:
+  using WorkFunction = std::function<R(T...)>;
+  using AfterWorkFunction =
+      typename detail::WorkerThreadAsync<R>::AfterWorkFunction;
+
+  WorkerThread() { m_owner.Start(); }
+
+  /**
+   * Set the loop.  This must be called from the loop thread.
+   * Subsequent calls to QueueWorkThen will run afterWork on the provided
+   * loop (via an async handle).
+   *
+   * @param loop the loop to use for running afterWork routines
+   */
+  void SetLoop(uv::Loop& loop) {
+    if (auto thr = m_owner.GetThread()) thr->m_async.SetLoop(loop);
+  }
+
+  /**
+   * Set the loop.  This must be called from the loop thread.
+   * Subsequent calls to QueueWorkThen will run afterWork on the provided
+   * loop (via an async handle).
+   *
+   * @param loop the loop to use for running afterWork routines
+   */
+  void SetLoop(std::shared_ptr<uv::Loop> loop) { SetLoop(*loop); }
+
+  /**
+   * Unset the loop.  This must be called from the loop thread.
+   * Subsequent calls to QueueWorkThen will no longer run afterWork.
+   */
+  void UnsetLoop() {
+    if (auto thr = m_owner.GetThread()) thr->m_async.UnsetLoop();
+  }
+
+  /**
+   * Get the handle used by QueueWorkThen() to run afterWork.
+   * This handle is set by SetLoop().
+   * Calling Close() on this handle is the same as calling UnsetLoop().
+   *
+   * @return The handle (if nullptr, no handle is set)
+   */
+  std::shared_ptr<uv::Handle> GetHandle() const {
+    if (auto thr = m_owner.GetThread())
+      return thr->m_async.m_async.lock();
+    else
+      return nullptr;
+  }
+
+  /**
+   * Wakeup the worker thread, call the work function, and return a future for
+   * the result.
+   *
+   * It’s safe to call this function from any thread.
+   * The work function will be called on the worker thread.
+   *
+   * The future will return a default-constructed result if this class is
+   * destroyed while waiting for a result.
+   *
+   * @param work Work function (called on worker thread)
+   */
+  template <typename... U>
+  future<R> QueueWork(WorkFunction work, U&&... u) {
+    if (auto thr = m_owner.GetThread()) {
+      // create the future
+      uint64_t req = thr->m_promises.CreateRequest();
+
+      // add the parameters to the input queue
+      thr->m_requests.emplace_back(
+          req, std::move(work), std::forward_as_tuple(std::forward<U>(u)...));
+
+      // signal the thread
+      thr->m_cond.notify_one();
+
+      // return future
+      return thr->m_promises.CreateFuture(req);
+    }
+
+    // XXX: is this the right thing to do?
+    return future<R>();
+  }
+
+  /**
+   * Wakeup the worker thread, call the work function, and call the afterWork
+   * function with the result on the loop set by SetLoop().
+   *
+   * It’s safe to call this function from any thread.
+   * The work function will be called on the worker thread, and the afterWork
+   * function will be called on the loop thread.
+   *
+   * SetLoop() must be called prior to calling this function for afterWork to
+   * be called.
+   *
+   * @param work Work function (called on worker thread)
+   * @param afterWork After work function (called on loop thread)
+   */
+  template <typename... U>
+  void QueueWorkThen(WorkFunction work, AfterWorkFunction afterWork, U&&... u) {
+    if (auto thr = m_owner.GetThread()) {
+      // add the parameters to the input queue
+      thr->m_requests.emplace_back(
+          std::move(work), std::move(afterWork),
+          std::forward_as_tuple(std::forward<U>(u)...));
+
+      // signal the thread
+      thr->m_cond.notify_one();
+    }
+  }
+
+ private:
+  SafeThreadOwner<Thread> m_owner;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_WORKERTHREAD_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/condition_variable.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/condition_variable.h
new file mode 100644
index 0000000..1599e19
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/condition_variable.h
@@ -0,0 +1,22 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <condition_variable>
+
+#include "wpi/priority_mutex.h"
+
+namespace wpi {
+
+#if defined(__linux__) && defined(WPI_HAVE_PRIORITY_MUTEX)
+using condition_variable = ::std::condition_variable_any;
+#else
+using condition_variable = ::std::condition_variable;
+#endif
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/deprecated.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/deprecated.h
new file mode 100644
index 0000000..51f2163
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/deprecated.h
@@ -0,0 +1,33 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_DEPRECATED_H_
+#define WPIUTIL_WPI_DEPRECATED_H_
+
+// [[deprecated(msg)]] is a C++14 feature not supported by MSVC or GCC < 4.9.
+// We provide an equivalent warning implementation for those compilers here.
+#ifndef WPI_DEPRECATED
+#if defined(_MSC_VER)
+#define WPI_DEPRECATED(msg) __declspec(deprecated(msg))
+#elif defined(__GNUC__)
+#if __GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ > 8)
+#if __cplusplus > 201103L
+#define WPI_DEPRECATED(msg) [[deprecated(msg)]]
+#else
+#define WPI_DEPRECATED(msg) [[gnu::deprecated(msg)]]
+#endif
+#else
+#define WPI_DEPRECATED(msg) __attribute__((deprecated(msg)))
+#endif
+#elif __cplusplus > 201103L
+#define WPI_DEPRECATED(msg) [[deprecated(msg)]]
+#else
+#define WPI_DEPRECATED(msg) /*nothing*/
+#endif
+#endif
+
+#endif  // WPIUTIL_WPI_DEPRECATED_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/future.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/future.h
new file mode 100644
index 0000000..04e7e45
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/future.h
@@ -0,0 +1,907 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_FUTURE_H_
+#define WPIUTIL_WPI_FUTURE_H_
+
+#include <stdint.h>
+
+#include <algorithm>
+#include <atomic>
+#include <chrono>
+#include <functional>
+#include <type_traits>
+#include <utility>
+#include <vector>
+
+#include "wpi/condition_variable.h"
+#include "wpi/mutex.h"
+
+namespace wpi {
+
+template <typename T>
+class PromiseFactory;
+
+template <typename T>
+class future;
+
+template <typename T>
+class promise;
+template <>
+class promise<void>;
+
+namespace detail {
+
+class PromiseFactoryBase {
+ public:
+  ~PromiseFactoryBase();
+
+  bool IsActive() const { return m_active; }
+
+  wpi::mutex& GetResultMutex() { return m_resultMutex; }
+
+  void Notify() { m_resultCv.notify_all(); }
+
+  // must be called with locked lock == ResultMutex
+  void Wait(std::unique_lock<wpi::mutex>& lock) { m_resultCv.wait(lock); }
+
+  // returns false if timeout reached
+  template <class Clock, class Duration>
+  bool WaitUntil(std::unique_lock<wpi::mutex>& lock,
+                 const std::chrono::time_point<Clock, Duration>& timeout_time) {
+    return m_resultCv.wait_until(lock, timeout_time) ==
+           std::cv_status::no_timeout;
+  }
+
+  void IgnoreResult(uint64_t request);
+
+  uint64_t CreateRequest();
+
+  // returns true if request was pending
+  // must be called with ResultMutex held
+  bool EraseRequest(uint64_t request);
+
+  // same as doing CreateRequest() followed by EraseRequest()
+  // must be called with ResultMutex held
+  uint64_t CreateErasedRequest() { return ++m_uid; }
+
+ private:
+  wpi::mutex m_resultMutex;
+  std::atomic_bool m_active{true};
+  wpi::condition_variable m_resultCv;
+
+  uint64_t m_uid = 0;
+  std::vector<uint64_t> m_requests;
+};
+
+template <typename To, typename From>
+struct FutureThen {
+  template <typename F>
+  static future<To> Create(PromiseFactory<From>& fromFactory, uint64_t request,
+                           PromiseFactory<To>& factory, F&& func);
+};
+
+template <typename From>
+struct FutureThen<void, From> {
+  template <typename F>
+  static future<void> Create(PromiseFactory<From>& fromFactory,
+                             uint64_t request, PromiseFactory<void>& factory,
+                             F&& func);
+};
+
+template <typename To>
+struct FutureThen<To, void> {
+  template <typename F>
+  static future<To> Create(PromiseFactory<void>& fromFactory, uint64_t request,
+                           PromiseFactory<To>& factory, F&& func);
+};
+
+template <>
+struct FutureThen<void, void> {
+  template <typename F>
+  static future<void> Create(PromiseFactory<void>& fromFactory,
+                             uint64_t request, PromiseFactory<void>& factory,
+                             F&& func);
+};
+
+}  // namespace detail
+
+/**
+ * A promise factory for lightweight futures.
+ *
+ * The lifetime of the factory must be ensured to be longer than any futures
+ * it creates.
+ *
+ * Use CreateRequest() to create the future request id, and then CreateFuture()
+ * and CreatePromise() to create future and promise objects.  A promise should
+ * only be created once for any given request id.
+ *
+ * @tparam T the "return" type of the promise/future
+ */
+template <typename T>
+class PromiseFactory final : public detail::PromiseFactoryBase {
+  friend class future<T>;
+
+ public:
+  using detail::PromiseFactoryBase::Notify;
+  using ThenFunction = std::function<void(uint64_t, T)>;
+
+  /**
+   * Creates a future.
+   *
+   * @param request the request id returned by CreateRequest()
+   * @return the future
+   */
+  future<T> CreateFuture(uint64_t request);
+
+  /**
+   * Creates a future and makes it immediately ready.
+   *
+   * @return the future
+   */
+  future<T> MakeReadyFuture(T&& value);
+
+  /**
+   * Creates a promise.
+   *
+   * @param request the request id returned by CreateRequest()
+   * @return the promise
+   */
+  promise<T> CreatePromise(uint64_t request);
+
+  /**
+   * Sets a value directly for a future without creating a promise object.
+   * Identical to `CreatePromise(request).set_value(value)`.
+   *
+   * @param request request id, as returned by CreateRequest()
+   * @param value lvalue
+   */
+  void SetValue(uint64_t request, const T& value);
+
+  /**
+   * Sets a value directly for a future without creating a promise object.
+   * Identical to `CreatePromise(request).set_value(value)`.
+   *
+   * @param request request id, as returned by CreateRequest()
+   * @param value rvalue
+   */
+  void SetValue(uint64_t request, T&& value);
+
+  void SetThen(uint64_t request, uint64_t outRequest, ThenFunction func);
+
+  bool IsReady(uint64_t request) noexcept;
+  T GetResult(uint64_t request);
+  void WaitResult(uint64_t request);
+  template <class Clock, class Duration>
+  bool WaitResultUntil(
+      uint64_t request,
+      const std::chrono::time_point<Clock, Duration>& timeout_time);
+
+  static PromiseFactory& GetInstance();
+
+ private:
+  struct Then {
+    Then(uint64_t request_, uint64_t outRequest_, ThenFunction func_)
+        : request(request_), outRequest(outRequest_), func(std::move(func_)) {}
+    uint64_t request;
+    uint64_t outRequest;
+    ThenFunction func;
+  };
+
+  std::vector<Then> m_thens;
+  std::vector<std::pair<uint64_t, T>> m_results;
+};
+
+/**
+ * Explicit specialization for PromiseFactory<void>.
+ */
+template <>
+class PromiseFactory<void> final : public detail::PromiseFactoryBase {
+  friend class future<void>;
+
+ public:
+  using detail::PromiseFactoryBase::Notify;
+  using ThenFunction = std::function<void(uint64_t)>;
+
+  /**
+   * Creates a future.
+   *
+   * @param request the request id returned by CreateRequest()
+   * @return std::pair of the future and the request id
+   */
+  future<void> CreateFuture(uint64_t request);
+
+  /**
+   * Creates a future and makes it immediately ready.
+   *
+   * @return the future
+   */
+  future<void> MakeReadyFuture();
+
+  /**
+   * Creates a promise.
+   *
+   * @param request the request id returned by CreateRequest()
+   * @return the promise
+   */
+  promise<void> CreatePromise(uint64_t request);
+
+  /**
+   * Sets a value directly for a future without creating a promise object.
+   * Identical to `promise(factory, request).set_value()`.
+   *
+   * @param request request id, as returned by CreateRequest()
+   */
+  void SetValue(uint64_t request);
+
+  void SetThen(uint64_t request, uint64_t outRequest, ThenFunction func);
+
+  bool IsReady(uint64_t request) noexcept;
+  void GetResult(uint64_t request);
+  void WaitResult(uint64_t request);
+  template <class Clock, class Duration>
+  bool WaitResultUntil(
+      uint64_t request,
+      const std::chrono::time_point<Clock, Duration>& timeout_time);
+
+  static PromiseFactory& GetInstance();
+
+ private:
+  struct Then {
+    Then(uint64_t request_, uint64_t outRequest_, ThenFunction func_)
+        : request(request_), outRequest(outRequest_), func(std::move(func_)) {}
+    uint64_t request;
+    uint64_t outRequest;
+    ThenFunction func;
+  };
+
+  std::vector<Then> m_thens;
+  std::vector<uint64_t> m_results;
+};
+
+/**
+ * A lightweight version of std::future.
+ *
+ * Use either promise::get_future() or PromiseFactory::CreateFuture() to create.
+ *
+ * @tparam T the "return" type
+ */
+template <typename T>
+class future final {
+  friend class PromiseFactory<T>;
+  friend class promise<T>;
+
+ public:
+  /**
+   * Constructs an empty (invalid) future.
+   */
+  future() noexcept = default;
+
+  future(future&& oth) noexcept {
+    this->m_request = oth.m_request;
+    this->m_promises = oth.m_promises;
+    oth.m_request = 0;
+    oth.m_promises = nullptr;
+  }
+  future(const future&) = delete;
+
+  template <typename R>
+  future(future<R>&& oth) noexcept
+      : future(oth.then([](R&& val) -> T { return val; })) {}
+
+  /**
+   * Ignores the result of the future if it has not been retrieved.
+   */
+  ~future() {
+    if (m_promises) m_promises->IgnoreResult(m_request);
+  }
+
+  future& operator=(future&& oth) noexcept {
+    this->m_request = oth.m_request;
+    this->m_promises = oth.m_promises;
+    oth.m_request = 0;
+    oth.m_promises = nullptr;
+    return *this;
+  }
+  future& operator=(const future&) = delete;
+
+  /**
+   * Gets the value.  Calls wait() if the value is not yet available.
+   * Can only be called once.  The future will be marked invalid after the call.
+   *
+   * @return The value provided by the corresponding promise.set_value().
+   */
+  T get() {
+    if (m_promises)
+      return m_promises->GetResult(m_request);
+    else
+      return T();
+  }
+
+  template <typename R, typename F>
+  future<R> then(PromiseFactory<R>& factory, F&& func) {
+    if (m_promises) {
+      auto promises = m_promises;
+      m_promises = nullptr;
+      return detail::FutureThen<R, T>::Create(*promises, m_request, factory,
+                                              func);
+    } else {
+      return future<R>();
+    }
+  }
+
+  template <typename F, typename R = typename std::result_of<F && (T &&)>::type>
+  future<R> then(F&& func) {
+    return then(PromiseFactory<R>::GetInstance(), std::forward<F>(func));
+  }
+
+  bool is_ready() const noexcept {
+    return m_promises && m_promises->IsReady(m_request);
+  }
+
+  /**
+   * Checks if the future is valid.
+   * A default-constructed future or one where get() has been called is invalid.
+   *
+   * @return True if valid
+   */
+  bool valid() const noexcept { return m_promises; }
+
+  /**
+   * Waits for the promise to provide a value.
+   * Does not return until the value is available or the promise is destroyed
+   * (in which case a default-constructed value is "returned").
+   * If the value has already been provided, returns immediately.
+   */
+  void wait() const {
+    if (m_promises) m_promises->WaitResult(m_request);
+  }
+
+  /**
+   * Waits for the promise to provide a value, or the specified time has been
+   * reached.
+   *
+   * @return True if the promise provided a value, false if timed out.
+   */
+  template <class Clock, class Duration>
+  bool wait_until(
+      const std::chrono::time_point<Clock, Duration>& timeout_time) const {
+    return m_promises && m_promises->WaitResultUntil(m_request, timeout_time);
+  }
+
+  /**
+   * Waits for the promise to provide a value, or the specified amount of time
+   * has elapsed.
+   *
+   * @return True if the promise provided a value, false if timed out.
+   */
+  template <class Rep, class Period>
+  bool wait_for(
+      const std::chrono::duration<Rep, Period>& timeout_duration) const {
+    return wait_until(std::chrono::steady_clock::now() + timeout_duration);
+  }
+
+ private:
+  future(PromiseFactory<T>* promises, uint64_t request) noexcept
+      : m_request(request), m_promises(promises) {}
+
+  uint64_t m_request = 0;
+  PromiseFactory<T>* m_promises = nullptr;
+};
+
+/**
+ * Explicit specialization for future<void>.
+ */
+template <>
+class future<void> final {
+  friend class PromiseFactory<void>;
+  friend class promise<void>;
+
+ public:
+  /**
+   * Constructs an empty (invalid) future.
+   */
+  future() noexcept = default;
+
+  future(future&& oth) noexcept {
+    m_request = oth.m_request;
+    m_promises = oth.m_promises;
+    oth.m_request = 0;
+    oth.m_promises = nullptr;
+  }
+  future(const future&) = delete;
+
+  /**
+   * Ignores the result of the future if it has not been retrieved.
+   */
+  ~future() {
+    if (m_promises) m_promises->IgnoreResult(m_request);
+  }
+
+  future& operator=(future&& oth) noexcept {
+    m_request = oth.m_request;
+    m_promises = oth.m_promises;
+    oth.m_request = 0;
+    oth.m_promises = nullptr;
+    return *this;
+  }
+  future& operator=(const future&) = delete;
+
+  /**
+   * Gets the value.  Calls wait() if the value is not yet available.
+   * Can only be called once.  The future will be marked invalid after the call.
+   */
+  void get() {
+    if (m_promises) m_promises->GetResult(m_request);
+  }
+
+  template <typename R, typename F>
+  future<R> then(PromiseFactory<R>& factory, F&& func) {
+    if (m_promises) {
+      auto promises = m_promises;
+      m_promises = nullptr;
+      return detail::FutureThen<R, void>::Create(*promises, m_request, factory,
+                                                 func);
+    } else {
+      return future<R>();
+    }
+  }
+
+  template <typename F, typename R = typename std::result_of<F && ()>::type>
+  future<R> then(F&& func) {
+    return then(PromiseFactory<R>::GetInstance(), std::forward<F>(func));
+  }
+
+  bool is_ready() const noexcept {
+    return m_promises && m_promises->IsReady(m_request);
+  }
+
+  /**
+   * Checks if the future is valid.
+   * A default-constructed future or one where get() has been called is invalid.
+   *
+   * @return True if valid
+   */
+  bool valid() const noexcept { return m_promises; }
+
+  /**
+   * Waits for the promise to provide a value.
+   * Does not return until the value is available or the promise is destroyed
+   * If the value has already been provided, returns immediately.
+   */
+  void wait() const {
+    if (m_promises) m_promises->WaitResult(m_request);
+  }
+
+  /**
+   * Waits for the promise to provide a value, or the specified time has been
+   * reached.
+   *
+   * @return True if the promise provided a value, false if timed out.
+   */
+  template <class Clock, class Duration>
+  bool wait_until(
+      const std::chrono::time_point<Clock, Duration>& timeout_time) const {
+    return m_promises && m_promises->WaitResultUntil(m_request, timeout_time);
+  }
+
+  /**
+   * Waits for the promise to provide a value, or the specified amount of time
+   * has elapsed.
+   *
+   * @return True if the promise provided a value, false if timed out.
+   */
+  template <class Rep, class Period>
+  bool wait_for(
+      const std::chrono::duration<Rep, Period>& timeout_duration) const {
+    return wait_until(std::chrono::steady_clock::now() + timeout_duration);
+  }
+
+ private:
+  future(PromiseFactory<void>* promises, uint64_t request) noexcept
+      : m_request(request), m_promises(promises) {}
+
+  uint64_t m_request = 0;
+  PromiseFactory<void>* m_promises = nullptr;
+};
+
+/**
+ * A lightweight version of std::promise.
+ *
+ * Use PromiseFactory::CreatePromise() to create.
+ *
+ * @tparam T the "return" type
+ */
+template <typename T>
+class promise final {
+  friend class PromiseFactory<T>;
+
+ public:
+  /**
+   * Constructs an empty promise.
+   */
+  promise() : m_promises(&PromiseFactory<T>::GetInstance()) {
+    m_request = m_promises->CreateRequest();
+  }
+
+  promise(promise&& oth) noexcept
+      : m_request(oth.m_request), m_promises(oth.m_promises) {
+    oth.m_request = 0;
+    oth.m_promises = nullptr;
+  }
+
+  promise(const promise&) = delete;
+
+  /**
+   * Sets the promised value to a default-constructed T if not already set.
+   */
+  ~promise() {
+    if (m_promises) m_promises->SetValue(m_request, T());
+  }
+
+  promise& operator=(promise&& oth) noexcept {
+    m_request = oth.m_request;
+    m_promises = oth.m_promises;
+    oth.m_request = 0;
+    oth.m_promises = nullptr;
+    return *this;
+  }
+
+  promise& operator=(const promise&) = delete;
+
+  /**
+   * Swaps this promise with another one.
+   */
+  void swap(promise& oth) noexcept {
+    std::swap(m_request, oth.m_request);
+    std::swap(m_promises, oth.m_promises);
+  }
+
+  /**
+   * Gets a future for this promise.
+   *
+   * @return The future
+   */
+  future<T> get_future() noexcept { return future<T>(m_promises, m_request); }
+
+  /**
+   * Sets the promised value.
+   * Only effective once (subsequent calls will be ignored).
+   *
+   * @param value The value to provide to the waiting future
+   */
+  void set_value(const T& value) {
+    if (m_promises) m_promises->SetValue(m_request, value);
+    m_promises = nullptr;
+  }
+
+  /**
+   * Sets the promised value.
+   * Only effective once (subsequent calls will be ignored).
+   *
+   * @param value The value to provide to the waiting future
+   */
+  void set_value(T&& value) {
+    if (m_promises) m_promises->SetValue(m_request, std::move(value));
+    m_promises = nullptr;
+  }
+
+ private:
+  promise(PromiseFactory<T>* promises, uint64_t request) noexcept
+      : m_request(request), m_promises(promises) {}
+
+  uint64_t m_request = 0;
+  PromiseFactory<T>* m_promises = nullptr;
+};
+
+/**
+ * Explicit specialization for promise<void>.
+ */
+template <>
+class promise<void> final {
+  friend class PromiseFactory<void>;
+
+ public:
+  /**
+   * Constructs an empty promise.
+   */
+  promise() : m_promises(&PromiseFactory<void>::GetInstance()) {
+    m_request = m_promises->CreateRequest();
+  }
+
+  promise(promise&& oth) noexcept
+      : m_request(oth.m_request), m_promises(oth.m_promises) {
+    oth.m_request = 0;
+    oth.m_promises = nullptr;
+  }
+
+  promise(const promise&) = delete;
+
+  /**
+   * Sets the promised value if not already set.
+   */
+  ~promise() {
+    if (m_promises) m_promises->SetValue(m_request);
+  }
+
+  promise& operator=(promise&& oth) noexcept {
+    m_request = oth.m_request;
+    m_promises = oth.m_promises;
+    oth.m_request = 0;
+    oth.m_promises = nullptr;
+    return *this;
+  }
+
+  promise& operator=(const promise&) = delete;
+
+  /**
+   * Swaps this promise with another one.
+   */
+  void swap(promise& oth) noexcept {
+    std::swap(m_request, oth.m_request);
+    std::swap(m_promises, oth.m_promises);
+  }
+
+  /**
+   * Gets a future for this promise.
+   *
+   * @return The future
+   */
+  future<void> get_future() noexcept {
+    return future<void>(m_promises, m_request);
+  }
+
+  /**
+   * Sets the promised value.
+   * Only effective once (subsequent calls will be ignored).
+   */
+  void set_value() {
+    if (m_promises) m_promises->SetValue(m_request);
+    m_promises = nullptr;
+  }
+
+ private:
+  promise(PromiseFactory<void>* promises, uint64_t request) noexcept
+      : m_request(request), m_promises(promises) {}
+
+  uint64_t m_request = 0;
+  PromiseFactory<void>* m_promises = nullptr;
+};
+
+/**
+ * Constructs a valid future with the value set.
+ */
+template <typename T>
+inline future<T> make_ready_future(T&& value) {
+  return PromiseFactory<T>::GetInstance().MakeReadyFuture(
+      std::forward<T>(value));
+}
+
+/**
+ * Constructs a valid future with the value set.
+ */
+inline future<void> make_ready_future() {
+  return PromiseFactory<void>::GetInstance().MakeReadyFuture();
+}
+
+template <typename T>
+inline future<T> PromiseFactory<T>::CreateFuture(uint64_t request) {
+  return future<T>{this, request};
+}
+
+template <typename T>
+future<T> PromiseFactory<T>::MakeReadyFuture(T&& value) {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  uint64_t req = CreateErasedRequest();
+  m_results.emplace_back(std::piecewise_construct, std::forward_as_tuple(req),
+                         std::forward_as_tuple(std::move(value)));
+  return future<T>{this, req};
+}
+
+template <typename T>
+inline promise<T> PromiseFactory<T>::CreatePromise(uint64_t request) {
+  return promise<T>{this, request};
+}
+
+template <typename T>
+void PromiseFactory<T>::SetValue(uint64_t request, const T& value) {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  if (!EraseRequest(request)) return;
+  auto it = std::find_if(m_thens.begin(), m_thens.end(),
+                         [=](const auto& x) { return x.request == request; });
+  if (it != m_thens.end()) {
+    uint64_t outRequest = it->outRequest;
+    ThenFunction func = std::move(it->func);
+    m_thens.erase(it);
+    lock.unlock();
+    return func(outRequest, value);
+  }
+  m_results.emplace_back(std::piecewise_construct,
+                         std::forward_as_tuple(request),
+                         std::forward_as_tuple(value));
+  Notify();
+}
+
+template <typename T>
+void PromiseFactory<T>::SetValue(uint64_t request, T&& value) {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  if (!EraseRequest(request)) return;
+  auto it = std::find_if(m_thens.begin(), m_thens.end(),
+                         [=](const auto& x) { return x.request == request; });
+  if (it != m_thens.end()) {
+    uint64_t outRequest = it->outRequest;
+    ThenFunction func = std::move(it->func);
+    m_thens.erase(it);
+    lock.unlock();
+    return func(outRequest, std::move(value));
+  }
+  m_results.emplace_back(std::piecewise_construct,
+                         std::forward_as_tuple(request),
+                         std::forward_as_tuple(std::move(value)));
+  Notify();
+}
+
+template <typename T>
+void PromiseFactory<T>::SetThen(uint64_t request, uint64_t outRequest,
+                                ThenFunction func) {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  auto it = std::find_if(m_results.begin(), m_results.end(),
+                         [=](const auto& r) { return r.first == request; });
+  if (it != m_results.end()) {
+    auto val = std::move(it->second);
+    m_results.erase(it);
+    lock.unlock();
+    return func(outRequest, std::move(val));
+  }
+  m_thens.emplace_back(request, outRequest, func);
+}
+
+template <typename T>
+bool PromiseFactory<T>::IsReady(uint64_t request) noexcept {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  auto it = std::find_if(m_results.begin(), m_results.end(),
+                         [=](const auto& r) { return r.first == request; });
+  return it != m_results.end();
+}
+
+template <typename T>
+T PromiseFactory<T>::GetResult(uint64_t request) {
+  // wait for response
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  while (IsActive()) {
+    // Did we get a response to *our* request?
+    auto it = std::find_if(m_results.begin(), m_results.end(),
+                           [=](const auto& r) { return r.first == request; });
+    if (it != m_results.end()) {
+      // Yes, remove it from the vector and we're done.
+      auto rv = std::move(it->second);
+      m_results.erase(it);
+      return rv;
+    }
+    // No, keep waiting for a response
+    Wait(lock);
+  }
+  return T();
+}
+
+template <typename T>
+void PromiseFactory<T>::WaitResult(uint64_t request) {
+  // wait for response
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  while (IsActive()) {
+    // Did we get a response to *our* request?
+    auto it = std::find_if(m_results.begin(), m_results.end(),
+                           [=](const auto& r) { return r.first == request; });
+    if (it != m_results.end()) return;
+    // No, keep waiting for a response
+    Wait(lock);
+  }
+}
+
+template <typename T>
+template <class Clock, class Duration>
+bool PromiseFactory<T>::WaitResultUntil(
+    uint64_t request,
+    const std::chrono::time_point<Clock, Duration>& timeout_time) {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  bool timeout = false;
+  while (IsActive()) {
+    // Did we get a response to *our* request?
+    auto it = std::find_if(m_results.begin(), m_results.end(),
+                           [=](const auto& r) { return r.first == request; });
+    if (it != m_results.end()) return true;
+    if (timeout) break;
+    // No, keep waiting for a response
+    if (!WaitUntil(lock, timeout_time)) timeout = true;
+  }
+  return false;
+}
+
+template <typename T>
+PromiseFactory<T>& PromiseFactory<T>::GetInstance() {
+  static PromiseFactory inst;
+  return inst;
+}
+
+inline future<void> PromiseFactory<void>::CreateFuture(uint64_t request) {
+  return future<void>{this, request};
+}
+
+inline promise<void> PromiseFactory<void>::CreatePromise(uint64_t request) {
+  return promise<void>{this, request};
+}
+
+template <class Clock, class Duration>
+bool PromiseFactory<void>::WaitResultUntil(
+    uint64_t request,
+    const std::chrono::time_point<Clock, Duration>& timeout_time) {
+  std::unique_lock<wpi::mutex> lock(GetResultMutex());
+  bool timeout = false;
+  while (IsActive()) {
+    // Did we get a response to *our* request?
+    auto it = std::find_if(m_results.begin(), m_results.end(),
+                           [=](const auto& r) { return r == request; });
+    if (it != m_results.end()) return true;
+    if (timeout) break;
+    // No, keep waiting for a response
+    if (!WaitUntil(lock, timeout_time)) timeout = true;
+  }
+  return false;
+}
+
+template <typename To, typename From>
+template <typename F>
+future<To> detail::FutureThen<To, From>::Create(
+    PromiseFactory<From>& fromFactory, uint64_t request,
+    PromiseFactory<To>& factory, F&& func) {
+  uint64_t req = factory.CreateRequest();
+  fromFactory.SetThen(request, req, [&factory, func](uint64_t r, From value) {
+    factory.SetValue(r, func(std::move(value)));
+  });
+  return factory.CreateFuture(req);
+}
+
+template <typename From>
+template <typename F>
+future<void> detail::FutureThen<void, From>::Create(
+    PromiseFactory<From>& fromFactory, uint64_t request,
+    PromiseFactory<void>& factory, F&& func) {
+  uint64_t req = factory.CreateRequest();
+  fromFactory.SetThen(request, req, [&factory, func](uint64_t r, From value) {
+    func(std::move(value));
+    factory.SetValue(r);
+  });
+  return factory.CreateFuture(req);
+}
+
+template <typename To>
+template <typename F>
+future<To> detail::FutureThen<To, void>::Create(
+    PromiseFactory<void>& fromFactory, uint64_t request,
+    PromiseFactory<To>& factory, F&& func) {
+  uint64_t req = factory.CreateRequest();
+  fromFactory.SetThen(request, req, [&factory, func](uint64_t r) {
+    factory.SetValue(r, func());
+  });
+  return factory.CreateFuture(req);
+}
+
+template <typename F>
+future<void> detail::FutureThen<void, void>::Create(
+    PromiseFactory<void>& fromFactory, uint64_t request,
+    PromiseFactory<void>& factory, F&& func) {
+  uint64_t req = factory.CreateRequest();
+  fromFactory.SetThen(request, req, [&factory, func](uint64_t r) {
+    func();
+    factory.SetValue(r);
+  });
+  return factory.CreateFuture(req);
+}
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_FUTURE_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/hostname.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/hostname.h
new file mode 100644
index 0000000..b2f9f0c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/hostname.h
@@ -0,0 +1,23 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_HOSTNAME_H_
+#define WPIUTIL_WPI_HOSTNAME_H_
+
+#include <string>
+
+#include "wpi/StringRef.h"
+
+namespace wpi {
+template <typename T>
+class SmallVectorImpl;
+
+std::string GetHostname();
+StringRef GetHostname(SmallVectorImpl<char>& name);
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_HOSTNAME_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/http_parser.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/http_parser.h
new file mode 100644
index 0000000..f4bf9fd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/http_parser.h
@@ -0,0 +1,421 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+#ifndef wpi_http_parser_h
+#define wpi_http_parser_h
+
+/* Also update SONAME in the Makefile whenever you change these. */
+#define HTTP_PARSER_VERSION_MAJOR 2
+#define HTTP_PARSER_VERSION_MINOR 8
+#define HTTP_PARSER_VERSION_PATCH 1
+
+#include <stddef.h>
+#include <stdint.h>
+
+/* Compile with -DHTTP_PARSER_STRICT=0 to make less checks, but run
+ * faster
+ */
+#ifndef HTTP_PARSER_STRICT
+# define HTTP_PARSER_STRICT 1
+#endif
+
+/* Maximium header size allowed. If the macro is not defined
+ * before including this header then the default is used. To
+ * change the maximum header size, define the macro in the build
+ * environment (e.g. -DHTTP_MAX_HEADER_SIZE=<value>). To remove
+ * the effective limit on the size of the header, define the macro
+ * to a very large number (e.g. -DHTTP_MAX_HEADER_SIZE=0x7fffffff)
+ */
+#ifndef HTTP_MAX_HEADER_SIZE
+# define HTTP_MAX_HEADER_SIZE (80*1024)
+#endif
+
+namespace wpi {
+
+struct http_parser;
+struct http_parser_settings;
+
+
+/* Callbacks should return non-zero to indicate an error. The parser will
+ * then halt execution.
+ *
+ * The one exception is on_headers_complete. In a HTTP_RESPONSE parser
+ * returning '1' from on_headers_complete will tell the parser that it
+ * should not expect a body. This is used when receiving a response to a
+ * HEAD request which may contain 'Content-Length' or 'Transfer-Encoding:
+ * chunked' headers that indicate the presence of a body.
+ *
+ * Returning `2` from on_headers_complete will tell parser that it should not
+ * expect neither a body nor any futher responses on this connection. This is
+ * useful for handling responses to a CONNECT request which may not contain
+ * `Upgrade` or `Connection: upgrade` headers.
+ *
+ * http_data_cb does not return data chunks. It will be called arbitrarily
+ * many times for each string. E.G. you might get 10 callbacks for "on_url"
+ * each providing just a few characters more data.
+ */
+typedef int (*http_data_cb) (http_parser*, const char *at, size_t length);
+typedef int (*http_cb) (http_parser*);
+
+
+/* Status Codes */
+#define HTTP_STATUS_MAP(XX)                                                 \
+  XX(100, CONTINUE,                        Continue)                        \
+  XX(101, SWITCHING_PROTOCOLS,             Switching Protocols)             \
+  XX(102, PROCESSING,                      Processing)                      \
+  XX(200, OK,                              OK)                              \
+  XX(201, CREATED,                         Created)                         \
+  XX(202, ACCEPTED,                        Accepted)                        \
+  XX(203, NON_AUTHORITATIVE_INFORMATION,   Non-Authoritative Information)   \
+  XX(204, NO_CONTENT,                      No Content)                      \
+  XX(205, RESET_CONTENT,                   Reset Content)                   \
+  XX(206, PARTIAL_CONTENT,                 Partial Content)                 \
+  XX(207, MULTI_STATUS,                    Multi-Status)                    \
+  XX(208, ALREADY_REPORTED,                Already Reported)                \
+  XX(226, IM_USED,                         IM Used)                         \
+  XX(300, MULTIPLE_CHOICES,                Multiple Choices)                \
+  XX(301, MOVED_PERMANENTLY,               Moved Permanently)               \
+  XX(302, FOUND,                           Found)                           \
+  XX(303, SEE_OTHER,                       See Other)                       \
+  XX(304, NOT_MODIFIED,                    Not Modified)                    \
+  XX(305, USE_PROXY,                       Use Proxy)                       \
+  XX(307, TEMPORARY_REDIRECT,              Temporary Redirect)              \
+  XX(308, PERMANENT_REDIRECT,              Permanent Redirect)              \
+  XX(400, BAD_REQUEST,                     Bad Request)                     \
+  XX(401, UNAUTHORIZED,                    Unauthorized)                    \
+  XX(402, PAYMENT_REQUIRED,                Payment Required)                \
+  XX(403, FORBIDDEN,                       Forbidden)                       \
+  XX(404, NOT_FOUND,                       Not Found)                       \
+  XX(405, METHOD_NOT_ALLOWED,              Method Not Allowed)              \
+  XX(406, NOT_ACCEPTABLE,                  Not Acceptable)                  \
+  XX(407, PROXY_AUTHENTICATION_REQUIRED,   Proxy Authentication Required)   \
+  XX(408, REQUEST_TIMEOUT,                 Request Timeout)                 \
+  XX(409, CONFLICT,                        Conflict)                        \
+  XX(410, GONE,                            Gone)                            \
+  XX(411, LENGTH_REQUIRED,                 Length Required)                 \
+  XX(412, PRECONDITION_FAILED,             Precondition Failed)             \
+  XX(413, PAYLOAD_TOO_LARGE,               Payload Too Large)               \
+  XX(414, URI_TOO_LONG,                    URI Too Long)                    \
+  XX(415, UNSUPPORTED_MEDIA_TYPE,          Unsupported Media Type)          \
+  XX(416, RANGE_NOT_SATISFIABLE,           Range Not Satisfiable)           \
+  XX(417, EXPECTATION_FAILED,              Expectation Failed)              \
+  XX(421, MISDIRECTED_REQUEST,             Misdirected Request)             \
+  XX(422, UNPROCESSABLE_ENTITY,            Unprocessable Entity)            \
+  XX(423, LOCKED,                          Locked)                          \
+  XX(424, FAILED_DEPENDENCY,               Failed Dependency)               \
+  XX(426, UPGRADE_REQUIRED,                Upgrade Required)                \
+  XX(428, PRECONDITION_REQUIRED,           Precondition Required)           \
+  XX(429, TOO_MANY_REQUESTS,               Too Many Requests)               \
+  XX(431, REQUEST_HEADER_FIELDS_TOO_LARGE, Request Header Fields Too Large) \
+  XX(451, UNAVAILABLE_FOR_LEGAL_REASONS,   Unavailable For Legal Reasons)   \
+  XX(500, INTERNAL_SERVER_ERROR,           Internal Server Error)           \
+  XX(501, NOT_IMPLEMENTED,                 Not Implemented)                 \
+  XX(502, BAD_GATEWAY,                     Bad Gateway)                     \
+  XX(503, SERVICE_UNAVAILABLE,             Service Unavailable)             \
+  XX(504, GATEWAY_TIMEOUT,                 Gateway Timeout)                 \
+  XX(505, HTTP_VERSION_NOT_SUPPORTED,      HTTP Version Not Supported)      \
+  XX(506, VARIANT_ALSO_NEGOTIATES,         Variant Also Negotiates)         \
+  XX(507, INSUFFICIENT_STORAGE,            Insufficient Storage)            \
+  XX(508, LOOP_DETECTED,                   Loop Detected)                   \
+  XX(510, NOT_EXTENDED,                    Not Extended)                    \
+  XX(511, NETWORK_AUTHENTICATION_REQUIRED, Network Authentication Required) \
+
+enum http_status
+  {
+#define XX(num, name, string) HTTP_STATUS_##name = num,
+  HTTP_STATUS_MAP(XX)
+#undef XX
+  };
+
+
+/* Request Methods */
+#define HTTP_METHOD_MAP(XX)         \
+  XX(0,  DELETE,      DELETE)       \
+  XX(1,  GET,         GET)          \
+  XX(2,  HEAD,        HEAD)         \
+  XX(3,  POST,        POST)         \
+  XX(4,  PUT,         PUT)          \
+  /* pathological */                \
+  XX(5,  CONNECT,     CONNECT)      \
+  XX(6,  OPTIONS,     OPTIONS)      \
+  XX(7,  TRACE,       TRACE)        \
+  /* WebDAV */                      \
+  XX(8,  COPY,        COPY)         \
+  XX(9,  LOCK,        LOCK)         \
+  XX(10, MKCOL,       MKCOL)        \
+  XX(11, MOVE,        MOVE)         \
+  XX(12, PROPFIND,    PROPFIND)     \
+  XX(13, PROPPATCH,   PROPPATCH)    \
+  XX(14, SEARCH,      SEARCH)       \
+  XX(15, UNLOCK,      UNLOCK)       \
+  XX(16, BIND,        BIND)         \
+  XX(17, REBIND,      REBIND)       \
+  XX(18, UNBIND,      UNBIND)       \
+  XX(19, ACL,         ACL)          \
+  /* subversion */                  \
+  XX(20, REPORT,      REPORT)       \
+  XX(21, MKACTIVITY,  MKACTIVITY)   \
+  XX(22, CHECKOUT,    CHECKOUT)     \
+  XX(23, MERGE,       MERGE)        \
+  /* upnp */                        \
+  XX(24, MSEARCH,     M-SEARCH)     \
+  XX(25, NOTIFY,      NOTIFY)       \
+  XX(26, SUBSCRIBE,   SUBSCRIBE)    \
+  XX(27, UNSUBSCRIBE, UNSUBSCRIBE)  \
+  /* RFC-5789 */                    \
+  XX(28, PATCH,       PATCH)        \
+  XX(29, PURGE,       PURGE)        \
+  /* CalDAV */                      \
+  XX(30, MKCALENDAR,  MKCALENDAR)   \
+  /* RFC-2068, section 19.6.1.2 */  \
+  XX(31, LINK,        LINK)         \
+  XX(32, UNLINK,      UNLINK)       \
+  /* icecast */                     \
+  XX(33, SOURCE,      SOURCE)       \
+
+enum http_method
+  {
+#define XX(num, name, string) HTTP_##name = num,
+  HTTP_METHOD_MAP(XX)
+#undef XX
+  };
+
+
+enum http_parser_type { HTTP_REQUEST, HTTP_RESPONSE, HTTP_BOTH };
+
+
+/* Flag values for http_parser.flags field */
+enum flags
+  { F_CHUNKED               = 1 << 0
+  , F_CONNECTION_KEEP_ALIVE = 1 << 1
+  , F_CONNECTION_CLOSE      = 1 << 2
+  , F_CONNECTION_UPGRADE    = 1 << 3
+  , F_TRAILING              = 1 << 4
+  , F_UPGRADE               = 1 << 5
+  , F_SKIPBODY              = 1 << 6
+  , F_CONTENTLENGTH         = 1 << 7
+  };
+
+
+/* Map for errno-related constants
+ *
+ * The provided argument should be a macro that takes 2 arguments.
+ */
+#define HTTP_ERRNO_MAP(XX)                                           \
+  /* No error */                                                     \
+  XX(OK, "success")                                                  \
+                                                                     \
+  /* Callback-related errors */                                      \
+  XX(CB_message_begin, "the on_message_begin callback failed")       \
+  XX(CB_url, "the on_url callback failed")                           \
+  XX(CB_header_field, "the on_header_field callback failed")         \
+  XX(CB_header_value, "the on_header_value callback failed")         \
+  XX(CB_headers_complete, "the on_headers_complete callback failed") \
+  XX(CB_body, "the on_body callback failed")                         \
+  XX(CB_message_complete, "the on_message_complete callback failed") \
+  XX(CB_status, "the on_status callback failed")                     \
+  XX(CB_chunk_header, "the on_chunk_header callback failed")         \
+  XX(CB_chunk_complete, "the on_chunk_complete callback failed")     \
+                                                                     \
+  /* Parsing-related errors */                                       \
+  XX(INVALID_EOF_STATE, "stream ended at an unexpected time")        \
+  XX(HEADER_OVERFLOW,                                                \
+     "too many header bytes seen; overflow detected")                \
+  XX(CLOSED_CONNECTION,                                              \
+     "data received after completed connection: close message")      \
+  XX(INVALID_VERSION, "invalid HTTP version")                        \
+  XX(INVALID_STATUS, "invalid HTTP status code")                     \
+  XX(INVALID_METHOD, "invalid HTTP method")                          \
+  XX(INVALID_URL, "invalid URL")                                     \
+  XX(INVALID_HOST, "invalid host")                                   \
+  XX(INVALID_PORT, "invalid port")                                   \
+  XX(INVALID_PATH, "invalid path")                                   \
+  XX(INVALID_QUERY_STRING, "invalid query string")                   \
+  XX(INVALID_FRAGMENT, "invalid fragment")                           \
+  XX(LF_EXPECTED, "LF character expected")                           \
+  XX(INVALID_HEADER_TOKEN, "invalid character in header")            \
+  XX(INVALID_CONTENT_LENGTH,                                         \
+     "invalid character in content-length header")                   \
+  XX(UNEXPECTED_CONTENT_LENGTH,                                      \
+     "unexpected content-length header")                             \
+  XX(INVALID_CHUNK_SIZE,                                             \
+     "invalid character in chunk size header")                       \
+  XX(INVALID_CONSTANT, "invalid constant string")                    \
+  XX(INVALID_INTERNAL_STATE, "encountered unexpected internal state")\
+  XX(STRICT, "strict mode assertion failed")                         \
+  XX(PAUSED, "parser is paused")                                     \
+  XX(UNKNOWN, "an unknown error occurred")
+
+
+/* Define HPE_* values for each errno value above */
+#define HTTP_ERRNO_GEN(n, s) HPE_##n,
+enum http_errno {
+  HTTP_ERRNO_MAP(HTTP_ERRNO_GEN)
+};
+#undef HTTP_ERRNO_GEN
+
+
+/* Get an http_errno value from an http_parser */
+#define HTTP_PARSER_ERRNO(p)            ((::wpi::http_errno) (p)->http_errno)
+
+
+struct http_parser {
+  /** PRIVATE **/
+  unsigned int type : 2;         /* enum http_parser_type */
+  unsigned int flags : 8;        /* F_* values from 'flags' enum; semi-public */
+  unsigned int state : 7;        /* enum state from http_parser.c */
+  unsigned int header_state : 7; /* enum header_state from http_parser.c */
+  unsigned int index : 7;        /* index into current matcher */
+  unsigned int lenient_http_headers : 1;
+
+  uint32_t nread;          /* # bytes read in various scenarios */
+  uint64_t content_length; /* # bytes in body (0 if no Content-Length header) */
+
+  /** READ-ONLY **/
+  unsigned short http_major;
+  unsigned short http_minor;
+  unsigned int status_code : 16; /* responses only */
+  unsigned int method : 8;       /* requests only */
+  unsigned int http_errno : 7;
+
+  /* 1 = Upgrade header was present and the parser has exited because of that.
+   * 0 = No upgrade header present.
+   * Should be checked when http_parser_execute() returns in addition to
+   * error checking.
+   */
+  unsigned int upgrade : 1;
+
+  /** PUBLIC **/
+  void *data; /* A pointer to get hook to the "connection" or "socket" object */
+};
+
+
+struct http_parser_settings {
+  http_cb      on_message_begin;
+  http_data_cb on_url;
+  http_data_cb on_status;
+  http_data_cb on_header_field;
+  http_data_cb on_header_value;
+  http_cb      on_headers_complete;
+  http_data_cb on_body;
+  http_cb      on_message_complete;
+  /* When on_chunk_header is called, the current chunk length is stored
+   * in parser->content_length.
+   */
+  http_cb      on_chunk_header;
+  http_cb      on_chunk_complete;
+};
+
+
+enum http_parser_url_fields
+  { UF_SCHEMA           = 0
+  , UF_HOST             = 1
+  , UF_PORT             = 2
+  , UF_PATH             = 3
+  , UF_QUERY            = 4
+  , UF_FRAGMENT         = 5
+  , UF_USERINFO         = 6
+  , UF_MAX              = 7
+  };
+
+
+/* Result structure for http_parser_parse_url().
+ *
+ * Callers should index into field_data[] with UF_* values iff field_set
+ * has the relevant (1 << UF_*) bit set. As a courtesy to clients (and
+ * because we probably have padding left over), we convert any port to
+ * a uint16_t.
+ */
+struct http_parser_url {
+  uint16_t field_set;           /* Bitmask of (1 << UF_*) values */
+  uint16_t port;                /* Converted UF_PORT string */
+
+  struct {
+    uint16_t off;               /* Offset into buffer in which field starts */
+    uint16_t len;               /* Length of run in buffer */
+  } field_data[UF_MAX];
+};
+
+
+/* Returns the library version. Bits 16-23 contain the major version number,
+ * bits 8-15 the minor version number and bits 0-7 the patch level.
+ * Usage example:
+ *
+ *   unsigned long version = http_parser_version();
+ *   unsigned major = (version >> 16) & 255;
+ *   unsigned minor = (version >> 8) & 255;
+ *   unsigned patch = version & 255;
+ *   printf("http_parser v%u.%u.%u\n", major, minor, patch);
+ */
+unsigned long http_parser_version(void);
+
+void http_parser_init(http_parser *parser, enum http_parser_type type);
+
+
+/* Initialize http_parser_settings members to 0
+ */
+void http_parser_settings_init(http_parser_settings *settings);
+
+
+/* Executes the parser. Returns number of parsed bytes. Sets
+ * `parser->http_errno` on error. */
+size_t http_parser_execute(http_parser *parser,
+                           const http_parser_settings *settings,
+                           const char *data,
+                           size_t len);
+
+
+/* If http_should_keep_alive() in the on_headers_complete or
+ * on_message_complete callback returns 0, then this should be
+ * the last message on the connection.
+ * If you are the server, respond with the "Connection: close" header.
+ * If you are the client, close the connection.
+ */
+int http_should_keep_alive(const http_parser *parser);
+
+/* Returns a string version of the HTTP method. */
+const char *http_method_str(enum http_method m);
+
+/* Returns a string version of the HTTP status code. */
+const char *http_status_str(enum http_status s);
+
+/* Return a string name of the given error */
+const char *http_errno_name(enum http_errno err);
+
+/* Return a string description of the given error */
+const char *http_errno_description(enum http_errno err);
+
+/* Initialize all http_parser_url members to 0 */
+void http_parser_url_init(struct http_parser_url *u);
+
+/* Parse a URL; return nonzero on failure */
+int http_parser_parse_url(const char *buf, size_t buflen,
+                          int is_connect,
+                          struct http_parser_url *u);
+
+/* Pause or un-pause the parser; a nonzero value pauses */
+void http_parser_pause(http_parser *parser, int paused);
+
+/* Checks if this is the final chunk of the body. */
+int http_body_is_final(const http_parser *parser);
+
+}  // namespace wpi
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/iterator.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/iterator.h
new file mode 100644
index 0000000..2bae588
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/iterator.h
@@ -0,0 +1,339 @@
+//===- iterator.h - Utilities for using and defining iterators --*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ITERATOR_H
+#define WPIUTIL_WPI_ITERATOR_H
+
+#include "wpi/iterator_range.h"
+#include <algorithm>
+#include <cstddef>
+#include <iterator>
+#include <type_traits>
+#include <utility>
+
+namespace wpi {
+
+/// CRTP base class which implements the entire standard iterator facade
+/// in terms of a minimal subset of the interface.
+///
+/// Use this when it is reasonable to implement most of the iterator
+/// functionality in terms of a core subset. If you need special behavior or
+/// there are performance implications for this, you may want to override the
+/// relevant members instead.
+///
+/// Note, one abstraction that this does *not* provide is implementing
+/// subtraction in terms of addition by negating the difference. Negation isn't
+/// always information preserving, and I can see very reasonable iterator
+/// designs where this doesn't work well. It doesn't really force much added
+/// boilerplate anyways.
+///
+/// Another abstraction that this doesn't provide is implementing increment in
+/// terms of addition of one. These aren't equivalent for all iterator
+/// categories, and respecting that adds a lot of complexity for little gain.
+///
+/// Classes wishing to use `iterator_facade_base` should implement the following
+/// methods:
+///
+/// Forward Iterators:
+///   (All of the following methods)
+///   - DerivedT &operator=(const DerivedT &R);
+///   - bool operator==(const DerivedT &R) const;
+///   - const T &operator*() const;
+///   - T &operator*();
+///   - DerivedT &operator++();
+///
+/// Bidirectional Iterators:
+///   (All methods of forward iterators, plus the following)
+///   - DerivedT &operator--();
+///
+/// Random-access Iterators:
+///   (All methods of bidirectional iterators excluding the following)
+///   - DerivedT &operator++();
+///   - DerivedT &operator--();
+///   (and plus the following)
+///   - bool operator<(const DerivedT &RHS) const;
+///   - DifferenceTypeT operator-(const DerivedT &R) const;
+///   - DerivedT &operator+=(DifferenceTypeT N);
+///   - DerivedT &operator-=(DifferenceTypeT N);
+///
+template <typename DerivedT, typename IteratorCategoryT, typename T,
+          typename DifferenceTypeT = std::ptrdiff_t, typename PointerT = T *,
+          typename ReferenceT = T &>
+class iterator_facade_base
+    : public std::iterator<IteratorCategoryT, T, DifferenceTypeT, PointerT,
+                           ReferenceT> {
+protected:
+  enum {
+    IsRandomAccess = std::is_base_of<std::random_access_iterator_tag,
+                                     IteratorCategoryT>::value,
+    IsBidirectional = std::is_base_of<std::bidirectional_iterator_tag,
+                                      IteratorCategoryT>::value,
+  };
+
+  /// A proxy object for computing a reference via indirecting a copy of an
+  /// iterator. This is used in APIs which need to produce a reference via
+  /// indirection but for which the iterator object might be a temporary. The
+  /// proxy preserves the iterator internally and exposes the indirected
+  /// reference via a conversion operator.
+  class ReferenceProxy {
+    friend iterator_facade_base;
+
+    DerivedT I;
+
+    ReferenceProxy(DerivedT I) : I(std::move(I)) {}
+
+  public:
+    operator ReferenceT() const { return *I; }
+  };
+
+public:
+  DerivedT operator+(DifferenceTypeT n) const {
+    static_assert(std::is_base_of<iterator_facade_base, DerivedT>::value,
+                  "Must pass the derived type to this template!");
+    static_assert(
+        IsRandomAccess,
+        "The '+' operator is only defined for random access iterators.");
+    DerivedT tmp = *static_cast<const DerivedT *>(this);
+    tmp += n;
+    return tmp;
+  }
+  friend DerivedT operator+(DifferenceTypeT n, const DerivedT &i) {
+    static_assert(
+        IsRandomAccess,
+        "The '+' operator is only defined for random access iterators.");
+    return i + n;
+  }
+  DerivedT operator-(DifferenceTypeT n) const {
+    static_assert(
+        IsRandomAccess,
+        "The '-' operator is only defined for random access iterators.");
+    DerivedT tmp = *static_cast<const DerivedT *>(this);
+    tmp -= n;
+    return tmp;
+  }
+
+  DerivedT &operator++() {
+    static_assert(std::is_base_of<iterator_facade_base, DerivedT>::value,
+                  "Must pass the derived type to this template!");
+    return static_cast<DerivedT *>(this)->operator+=(1);
+  }
+  DerivedT operator++(int) {
+    DerivedT tmp = *static_cast<DerivedT *>(this);
+    ++*static_cast<DerivedT *>(this);
+    return tmp;
+  }
+  DerivedT &operator--() {
+    static_assert(
+        IsBidirectional,
+        "The decrement operator is only defined for bidirectional iterators.");
+    return static_cast<DerivedT *>(this)->operator-=(1);
+  }
+  DerivedT operator--(int) {
+    static_assert(
+        IsBidirectional,
+        "The decrement operator is only defined for bidirectional iterators.");
+    DerivedT tmp = *static_cast<DerivedT *>(this);
+    --*static_cast<DerivedT *>(this);
+    return tmp;
+  }
+
+  bool operator!=(const DerivedT &RHS) const {
+    return !static_cast<const DerivedT *>(this)->operator==(RHS);
+  }
+
+  bool operator>(const DerivedT &RHS) const {
+    static_assert(
+        IsRandomAccess,
+        "Relational operators are only defined for random access iterators.");
+    return !static_cast<const DerivedT *>(this)->operator<(RHS) &&
+           !static_cast<const DerivedT *>(this)->operator==(RHS);
+  }
+  bool operator<=(const DerivedT &RHS) const {
+    static_assert(
+        IsRandomAccess,
+        "Relational operators are only defined for random access iterators.");
+    return !static_cast<const DerivedT *>(this)->operator>(RHS);
+  }
+  bool operator>=(const DerivedT &RHS) const {
+    static_assert(
+        IsRandomAccess,
+        "Relational operators are only defined for random access iterators.");
+    return !static_cast<const DerivedT *>(this)->operator<(RHS);
+  }
+
+  PointerT operator->() { return &static_cast<DerivedT *>(this)->operator*(); }
+  PointerT operator->() const {
+    return &static_cast<const DerivedT *>(this)->operator*();
+  }
+  ReferenceProxy operator[](DifferenceTypeT n) {
+    static_assert(IsRandomAccess,
+                  "Subscripting is only defined for random access iterators.");
+    return ReferenceProxy(static_cast<DerivedT *>(this)->operator+(n));
+  }
+  ReferenceProxy operator[](DifferenceTypeT n) const {
+    static_assert(IsRandomAccess,
+                  "Subscripting is only defined for random access iterators.");
+    return ReferenceProxy(static_cast<const DerivedT *>(this)->operator+(n));
+  }
+};
+
+/// CRTP base class for adapting an iterator to a different type.
+///
+/// This class can be used through CRTP to adapt one iterator into another.
+/// Typically this is done through providing in the derived class a custom \c
+/// operator* implementation. Other methods can be overridden as well.
+template <
+    typename DerivedT, typename WrappedIteratorT,
+    typename IteratorCategoryT =
+        typename std::iterator_traits<WrappedIteratorT>::iterator_category,
+    typename T = typename std::iterator_traits<WrappedIteratorT>::value_type,
+    typename DifferenceTypeT =
+        typename std::iterator_traits<WrappedIteratorT>::difference_type,
+    typename PointerT = typename std::conditional<
+        std::is_same<T, typename std::iterator_traits<
+                            WrappedIteratorT>::value_type>::value,
+        typename std::iterator_traits<WrappedIteratorT>::pointer, T *>::type,
+    typename ReferenceT = typename std::conditional<
+        std::is_same<T, typename std::iterator_traits<
+                            WrappedIteratorT>::value_type>::value,
+        typename std::iterator_traits<WrappedIteratorT>::reference, T &>::type,
+    // Don't provide these, they are mostly to act as aliases below.
+    typename WrappedTraitsT = std::iterator_traits<WrappedIteratorT>>
+class iterator_adaptor_base
+    : public iterator_facade_base<DerivedT, IteratorCategoryT, T,
+                                  DifferenceTypeT, PointerT, ReferenceT> {
+  using BaseT = typename iterator_adaptor_base::iterator_facade_base;
+
+protected:
+  WrappedIteratorT I;
+
+  iterator_adaptor_base() = default;
+
+  explicit iterator_adaptor_base(WrappedIteratorT u) : I(std::move(u)) {
+    static_assert(std::is_base_of<iterator_adaptor_base, DerivedT>::value,
+                  "Must pass the derived type to this template!");
+  }
+
+  const WrappedIteratorT &wrapped() const { return I; }
+
+public:
+  using difference_type = DifferenceTypeT;
+
+  DerivedT &operator+=(difference_type n) {
+    static_assert(
+        BaseT::IsRandomAccess,
+        "The '+=' operator is only defined for random access iterators.");
+    I += n;
+    return *static_cast<DerivedT *>(this);
+  }
+  DerivedT &operator-=(difference_type n) {
+    static_assert(
+        BaseT::IsRandomAccess,
+        "The '-=' operator is only defined for random access iterators.");
+    I -= n;
+    return *static_cast<DerivedT *>(this);
+  }
+  using BaseT::operator-;
+  difference_type operator-(const DerivedT &RHS) const {
+    static_assert(
+        BaseT::IsRandomAccess,
+        "The '-' operator is only defined for random access iterators.");
+    return I - RHS.I;
+  }
+
+  // We have to explicitly provide ++ and -- rather than letting the facade
+  // forward to += because WrappedIteratorT might not support +=.
+  using BaseT::operator++;
+  DerivedT &operator++() {
+    ++I;
+    return *static_cast<DerivedT *>(this);
+  }
+  using BaseT::operator--;
+  DerivedT &operator--() {
+    static_assert(
+        BaseT::IsBidirectional,
+        "The decrement operator is only defined for bidirectional iterators.");
+    --I;
+    return *static_cast<DerivedT *>(this);
+  }
+
+  bool operator==(const DerivedT &RHS) const { return I == RHS.I; }
+  bool operator<(const DerivedT &RHS) const {
+    static_assert(
+        BaseT::IsRandomAccess,
+        "Relational operators are only defined for random access iterators.");
+    return I < RHS.I;
+  }
+
+  ReferenceT operator*() const { return *I; }
+};
+
+/// An iterator type that allows iterating over the pointees via some
+/// other iterator.
+///
+/// The typical usage of this is to expose a type that iterates over Ts, but
+/// which is implemented with some iterator over T*s:
+///
+/// \code
+///   using iterator = pointee_iterator<SmallVectorImpl<T *>::iterator>;
+/// \endcode
+template <typename WrappedIteratorT,
+          typename T = typename std::remove_reference<
+              decltype(**std::declval<WrappedIteratorT>())>::type>
+struct pointee_iterator
+    : iterator_adaptor_base<
+          pointee_iterator<WrappedIteratorT>, WrappedIteratorT,
+          typename std::iterator_traits<WrappedIteratorT>::iterator_category,
+          T> {
+  pointee_iterator() = default;
+  template <typename U>
+  pointee_iterator(U &&u)
+      : pointee_iterator::iterator_adaptor_base(std::forward<U &&>(u)) {}
+
+  T &operator*() const { return **this->I; }
+};
+
+template <typename RangeT, typename WrappedIteratorT =
+                               decltype(std::begin(std::declval<RangeT>()))>
+iterator_range<pointee_iterator<WrappedIteratorT>>
+make_pointee_range(RangeT &&Range) {
+  using PointeeIteratorT = pointee_iterator<WrappedIteratorT>;
+  return make_range(PointeeIteratorT(std::begin(std::forward<RangeT>(Range))),
+                    PointeeIteratorT(std::end(std::forward<RangeT>(Range))));
+}
+
+template <typename WrappedIteratorT,
+          typename T = decltype(&*std::declval<WrappedIteratorT>())>
+class pointer_iterator
+    : public iterator_adaptor_base<pointer_iterator<WrappedIteratorT>,
+                                   WrappedIteratorT, T> {
+  mutable T Ptr;
+
+public:
+  pointer_iterator() = default;
+
+  explicit pointer_iterator(WrappedIteratorT u)
+      : pointer_iterator::iterator_adaptor_base(std::move(u)) {}
+
+  T &operator*() { return Ptr = &*this->I; }
+  const T &operator*() const { return Ptr = &*this->I; }
+};
+
+template <typename RangeT, typename WrappedIteratorT =
+                               decltype(std::begin(std::declval<RangeT>()))>
+iterator_range<pointer_iterator<WrappedIteratorT>>
+make_pointer_range(RangeT &&Range) {
+  using PointerIteratorT = pointer_iterator<WrappedIteratorT>;
+  return make_range(PointerIteratorT(std::begin(std::forward<RangeT>(Range))),
+                    PointerIteratorT(std::end(std::forward<RangeT>(Range))));
+}
+
+} // end namespace wpi
+
+#endif // LLVM_ADT_ITERATOR_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/iterator_range.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/iterator_range.h
new file mode 100644
index 0000000..e43c1f7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/iterator_range.h
@@ -0,0 +1,68 @@
+//===- iterator_range.h - A range adaptor for iterators ---------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+/// \file
+/// This provides a very simple, boring adaptor for a begin and end iterator
+/// into a range type. This should be used to build range views that work well
+/// with range based for loops and range based constructors.
+///
+/// Note that code here follows more standards-based coding conventions as it
+/// is mirroring proposed interfaces for standardization.
+///
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_ITERATOR_RANGE_H
+#define WPIUTIL_WPI_ITERATOR_RANGE_H
+
+#include <iterator>
+#include <utility>
+
+namespace wpi {
+
+/// A range adaptor for a pair of iterators.
+///
+/// This just wraps two iterators into a range-compatible interface. Nothing
+/// fancy at all.
+template <typename IteratorT>
+class iterator_range {
+  IteratorT begin_iterator, end_iterator;
+
+public:
+  //TODO: Add SFINAE to test that the Container's iterators match the range's
+  //      iterators.
+  template <typename Container>
+  iterator_range(Container &&c)
+  //TODO: Consider ADL/non-member begin/end calls.
+      : begin_iterator(c.begin()), end_iterator(c.end()) {}
+  iterator_range(IteratorT begin_iterator, IteratorT end_iterator)
+      : begin_iterator(std::move(begin_iterator)),
+        end_iterator(std::move(end_iterator)) {}
+
+  IteratorT begin() const { return begin_iterator; }
+  IteratorT end() const { return end_iterator; }
+};
+
+/// Convenience function for iterating over sub-ranges.
+///
+/// This provides a bit of syntactic sugar to make using sub-ranges
+/// in for loops a bit easier. Analogous to std::make_pair().
+template <class T> iterator_range<T> make_range(T x, T y) {
+  return iterator_range<T>(std::move(x), std::move(y));
+}
+
+template <typename T> iterator_range<T> make_range(std::pair<T, T> p) {
+  return iterator_range<T>(std::move(p.first), std::move(p.second));
+}
+
+template<typename T>
+iterator_range<decltype(begin(std::declval<T>()))> drop_begin(T &&t, int n) {
+  return make_range(std::next(begin(t), n), end(t));
+}
+}
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/jni_util.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/jni_util.h
new file mode 100644
index 0000000..7cb6c65
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/jni_util.h
@@ -0,0 +1,658 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_JNI_UTIL_H_
+#define WPIUTIL_WPI_JNI_UTIL_H_
+
+#include <jni.h>
+
+#include <queue>
+#include <string>
+#include <type_traits>
+#include <utility>
+#include <vector>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/ConvertUTF.h"
+#include "wpi/SafeThread.h"
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include "wpi/deprecated.h"
+#include "wpi/mutex.h"
+#include "wpi/raw_ostream.h"
+
+/** WPILib C++ utilities (wpiutil) namespace */
+namespace wpi {
+
+/** Java Native Interface (JNI) utility functions */
+namespace java {
+
+// Gets a Java stack trace.  Also provides the last function
+// in the stack trace not starting with excludeFuncPrefix (useful for e.g.
+// finding the first user call to a series of library functions).
+std::string GetJavaStackTrace(JNIEnv* env, std::string* func = nullptr,
+                              StringRef excludeFuncPrefix = StringRef());
+
+// Shim for backwards compatibility
+template <const char* excludeFuncPrefix>
+WPI_DEPRECATED("use StringRef function instead")
+std::string GetJavaStackTrace(JNIEnv* env, std::string* func) {
+  return GetJavaStackTrace(
+      env, func,
+      excludeFuncPrefix == nullptr ? StringRef() : excludeFuncPrefix);
+}
+
+// Finds a class and keep it as a global reference.
+// Use with caution, as the destructor does NOT call DeleteGlobalRef due
+// to potential shutdown issues with doing so.
+class JClass {
+ public:
+  JClass() = default;
+
+  JClass(JNIEnv* env, const char* name) {
+    jclass local = env->FindClass(name);
+    if (!local) return;
+    m_cls = static_cast<jclass>(env->NewGlobalRef(local));
+    env->DeleteLocalRef(local);
+  }
+
+  void free(JNIEnv* env) {
+    if (m_cls) env->DeleteGlobalRef(m_cls);
+    m_cls = nullptr;
+  }
+
+  explicit operator bool() const { return m_cls; }
+
+  operator jclass() const { return m_cls; }
+
+ protected:
+  jclass m_cls = nullptr;
+};
+
+struct JClassInit {
+  const char* name;
+  JClass* cls;
+};
+
+template <typename T>
+class JGlobal {
+ public:
+  JGlobal() = default;
+
+  JGlobal(JNIEnv* env, T obj) {
+    m_cls = static_cast<T>(env->NewGlobalRef(obj));
+  }
+
+  void free(JNIEnv* env) {
+    if (m_cls) env->DeleteGlobalRef(m_cls);
+    m_cls = nullptr;
+  }
+
+  explicit operator bool() const { return m_cls; }
+
+  operator T() const { return m_cls; }
+
+ protected:
+  T m_cls = nullptr;
+};
+
+// Container class for cleaning up Java local references.
+// The destructor calls DeleteLocalRef.
+template <typename T>
+class JLocal {
+ public:
+  JLocal(JNIEnv* env, T obj) : m_env(env), m_obj(obj) {}
+  JLocal(const JLocal&) = delete;
+  JLocal(JLocal&& oth) : m_env(oth.m_env), m_obj(oth.m_obj) {
+    oth.m_obj = nullptr;
+  }
+  JLocal& operator=(const JLocal&) = delete;
+  JLocal& operator=(JLocal&& oth) {
+    m_env = oth.m_env;
+    m_obj = oth.m_obj;
+    oth.m_obj = nullptr;
+    return *this;
+  }
+  ~JLocal() {
+    if (m_obj) m_env->DeleteLocalRef(m_obj);
+  }
+  operator T() { return m_obj; }
+  T obj() { return m_obj; }
+
+ private:
+  JNIEnv* m_env;
+  T m_obj;
+};
+
+//
+// Conversions from Java objects to C++
+//
+
+// Java string (jstring) reference.  The string is provided as UTF8.
+// This is not actually a reference, as it makes a copy of the string
+// characters, but it's named this way for consistency.
+class JStringRef {
+ public:
+  JStringRef(JNIEnv* env, jstring str) {
+    if (str) {
+      jsize size = env->GetStringLength(str);
+      const jchar* chars = env->GetStringCritical(str, nullptr);
+      if (chars) {
+        convertUTF16ToUTF8String(makeArrayRef(chars, size), m_str);
+        env->ReleaseStringCritical(str, chars);
+      }
+    } else {
+      errs() << "JStringRef was passed a null pointer at \n"
+             << GetJavaStackTrace(env);
+    }
+    // Ensure str is null-terminated.
+    m_str.push_back('\0');
+    m_str.pop_back();
+  }
+
+  operator StringRef() const { return m_str; }
+  StringRef str() const { return m_str; }
+  const char* c_str() const { return m_str.data(); }
+  size_t size() const { return m_str.size(); }
+
+ private:
+  SmallString<128> m_str;
+};
+
+// Details for J*ArrayRef and CriticalJ*ArrayRef
+namespace detail {
+
+template <typename C, typename T>
+class JArrayRefInner {};
+
+// Specialization of JArrayRefBase to provide StringRef conversion.
+template <typename C>
+class JArrayRefInner<C, jbyte> {
+ public:
+  operator StringRef() const { return str(); }
+
+  StringRef str() const {
+    auto arr = static_cast<const C*>(this)->array();
+    if (arr.empty()) return StringRef{};
+    return StringRef{reinterpret_cast<const char*>(arr.data()), arr.size()};
+  }
+};
+
+// Base class for J*ArrayRef and CriticalJ*ArrayRef
+template <typename T>
+class JArrayRefBase : public JArrayRefInner<JArrayRefBase<T>, T> {
+ public:
+  explicit operator bool() const { return this->m_elements != nullptr; }
+
+  operator ArrayRef<T>() const { return array(); }
+
+  ArrayRef<T> array() const {
+    if (!this->m_elements) return ArrayRef<T>{};
+    return ArrayRef<T>{this->m_elements, this->m_size};
+  }
+
+  JArrayRefBase(const JArrayRefBase&) = delete;
+  JArrayRefBase& operator=(const JArrayRefBase&) = delete;
+
+  JArrayRefBase(JArrayRefBase&& oth)
+      : m_env(oth.m_env),
+        m_jarr(oth.m_jarr),
+        m_size(oth.m_size),
+        m_elements(oth.m_elements) {
+    oth.m_jarr = nullptr;
+    oth.m_elements = nullptr;
+  }
+
+  JArrayRefBase& operator=(JArrayRefBase&& oth) {
+    this->m_env = oth.m_env;
+    this->m_jarr = oth.m_jarr;
+    this->m_size = oth.m_size;
+    this->m_elements = oth.m_elements;
+    oth.m_jarr = nullptr;
+    oth.m_elements = nullptr;
+    return *this;
+  }
+
+ protected:
+  JArrayRefBase(JNIEnv* env, T* elements, size_t size) {
+    this->m_env = env;
+    this->m_jarr = nullptr;
+    this->m_size = size;
+    this->m_elements = elements;
+  }
+
+  JArrayRefBase(JNIEnv* env, jarray jarr, size_t size) {
+    this->m_env = env;
+    this->m_jarr = jarr;
+    this->m_size = size;
+    this->m_elements = nullptr;
+  }
+
+  JArrayRefBase(JNIEnv* env, jarray jarr)
+      : JArrayRefBase(env, jarr, jarr ? env->GetArrayLength(jarr) : 0) {}
+
+  JNIEnv* m_env;
+  jarray m_jarr = nullptr;
+  size_t m_size;
+  T* m_elements;
+};
+
+}  // namespace detail
+
+// Java array / DirectBuffer reference.
+
+#define WPI_JNI_JARRAYREF(T, F)                                                \
+  class J##F##ArrayRef : public detail::JArrayRefBase<T> {                     \
+   public:                                                                     \
+    J##F##ArrayRef(JNIEnv* env, jobject bb, int len)                           \
+        : detail::JArrayRefBase<T>(                                            \
+              env,                                                             \
+              static_cast<T*>(bb ? env->GetDirectBufferAddress(bb) : nullptr), \
+              len) {                                                           \
+      if (!bb)                                                                 \
+        errs() << "JArrayRef was passed a null pointer at \n"                  \
+               << GetJavaStackTrace(env);                                      \
+    }                                                                          \
+    J##F##ArrayRef(JNIEnv* env, T##Array jarr, int len)                        \
+        : detail::JArrayRefBase<T>(env, jarr, len) {                           \
+      if (jarr)                                                                \
+        m_elements = env->Get##F##ArrayElements(jarr, nullptr);                \
+      else                                                                     \
+        errs() << "JArrayRef was passed a null pointer at \n"                  \
+               << GetJavaStackTrace(env);                                      \
+    }                                                                          \
+    J##F##ArrayRef(JNIEnv* env, T##Array jarr)                                 \
+        : detail::JArrayRefBase<T>(env, jarr) {                                \
+      if (jarr)                                                                \
+        m_elements = env->Get##F##ArrayElements(jarr, nullptr);                \
+      else                                                                     \
+        errs() << "JArrayRef was passed a null pointer at \n"                  \
+               << GetJavaStackTrace(env);                                      \
+    }                                                                          \
+    ~J##F##ArrayRef() {                                                        \
+      if (m_jarr && m_elements)                                                \
+        m_env->Release##F##ArrayElements(static_cast<T##Array>(m_jarr),        \
+                                         m_elements, JNI_ABORT);               \
+    }                                                                          \
+  };                                                                           \
+                                                                               \
+  class CriticalJ##F##ArrayRef : public detail::JArrayRefBase<T> {             \
+   public:                                                                     \
+    CriticalJ##F##ArrayRef(JNIEnv* env, T##Array jarr, int len)                \
+        : detail::JArrayRefBase<T>(env, jarr, len) {                           \
+      if (jarr)                                                                \
+        m_elements =                                                           \
+            static_cast<T*>(env->GetPrimitiveArrayCritical(jarr, nullptr));    \
+      else                                                                     \
+        errs() << "JArrayRef was passed a null pointer at \n"                  \
+               << GetJavaStackTrace(env);                                      \
+    }                                                                          \
+    CriticalJ##F##ArrayRef(JNIEnv* env, T##Array jarr)                         \
+        : detail::JArrayRefBase<T>(env, jarr) {                                \
+      if (jarr)                                                                \
+        m_elements =                                                           \
+            static_cast<T*>(env->GetPrimitiveArrayCritical(jarr, nullptr));    \
+      else                                                                     \
+        errs() << "JArrayRef was passed a null pointer at \n"                  \
+               << GetJavaStackTrace(env);                                      \
+    }                                                                          \
+    ~CriticalJ##F##ArrayRef() {                                                \
+      if (m_jarr && m_elements)                                                \
+        m_env->ReleasePrimitiveArrayCritical(m_jarr, m_elements, JNI_ABORT);   \
+    }                                                                          \
+  };
+
+WPI_JNI_JARRAYREF(jboolean, Boolean)
+WPI_JNI_JARRAYREF(jbyte, Byte)
+WPI_JNI_JARRAYREF(jshort, Short)
+WPI_JNI_JARRAYREF(jint, Int)
+WPI_JNI_JARRAYREF(jlong, Long)
+WPI_JNI_JARRAYREF(jfloat, Float)
+WPI_JNI_JARRAYREF(jdouble, Double)
+
+#undef WPI_JNI_JARRAYREF
+
+//
+// Conversions from C++ to Java objects
+//
+
+// Convert a UTF8 string into a jstring.
+inline jstring MakeJString(JNIEnv* env, StringRef str) {
+  SmallVector<UTF16, 128> chars;
+  convertUTF8ToUTF16String(str, chars);
+  return env->NewString(chars.begin(), chars.size());
+}
+
+// details for MakeJIntArray
+namespace detail {
+
+// Slow path (get primitive array and set individual elements).  This
+// is used if the input type is not an integer of the same size (note
+// signed/unsigned is ignored).
+template <typename T,
+          bool = (std::is_integral<T>::value && sizeof(jint) == sizeof(T))>
+struct ConvertIntArray {
+  static jintArray ToJava(JNIEnv* env, ArrayRef<T> arr) {
+    jintArray jarr = env->NewIntArray(arr.size());
+    if (!jarr) return nullptr;
+    jint* elements =
+        static_cast<jint*>(env->GetPrimitiveArrayCritical(jarr, nullptr));
+    if (!elements) return nullptr;
+    for (size_t i = 0; i < arr.size(); ++i)
+      elements[i] = static_cast<jint>(arr[i]);
+    env->ReleasePrimitiveArrayCritical(jarr, elements, 0);
+    return jarr;
+  }
+};
+
+// Fast path (use SetIntArrayRegion)
+template <typename T>
+struct ConvertIntArray<T, true> {
+  static jintArray ToJava(JNIEnv* env, ArrayRef<T> arr) {
+    jintArray jarr = env->NewIntArray(arr.size());
+    if (!jarr) return nullptr;
+    env->SetIntArrayRegion(jarr, 0, arr.size(),
+                           reinterpret_cast<const jint*>(arr.data()));
+    return jarr;
+  }
+};
+
+}  // namespace detail
+
+// Convert an ArrayRef to a jintArray.
+template <typename T>
+inline jintArray MakeJIntArray(JNIEnv* env, ArrayRef<T> arr) {
+  return detail::ConvertIntArray<T>::ToJava(env, arr);
+}
+
+// Convert a SmallVector to a jintArray.  This is required in addition to
+// ArrayRef because template resolution occurs prior to implicit conversions.
+template <typename T>
+inline jintArray MakeJIntArray(JNIEnv* env, const SmallVectorImpl<T>& arr) {
+  return detail::ConvertIntArray<T>::ToJava(env, arr);
+}
+
+// Convert a std::vector to a jintArray.  This is required in addition to
+// ArrayRef because template resolution occurs prior to implicit conversions.
+template <typename T>
+inline jintArray MakeJIntArray(JNIEnv* env, const std::vector<T>& arr) {
+  return detail::ConvertIntArray<T>::ToJava(env, arr);
+}
+
+// Convert a StringRef into a jbyteArray.
+inline jbyteArray MakeJByteArray(JNIEnv* env, StringRef str) {
+  jbyteArray jarr = env->NewByteArray(str.size());
+  if (!jarr) return nullptr;
+  env->SetByteArrayRegion(jarr, 0, str.size(),
+                          reinterpret_cast<const jbyte*>(str.data()));
+  return jarr;
+}
+
+// Convert an array of integers into a jbooleanArray.
+inline jbooleanArray MakeJBooleanArray(JNIEnv* env, ArrayRef<int> arr) {
+  jbooleanArray jarr = env->NewBooleanArray(arr.size());
+  if (!jarr) return nullptr;
+  jboolean* elements =
+      static_cast<jboolean*>(env->GetPrimitiveArrayCritical(jarr, nullptr));
+  if (!elements) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i)
+    elements[i] = arr[i] ? JNI_TRUE : JNI_FALSE;
+  env->ReleasePrimitiveArrayCritical(jarr, elements, 0);
+  return jarr;
+}
+
+// Convert an array of booleans into a jbooleanArray.
+inline jbooleanArray MakeJBooleanArray(JNIEnv* env, ArrayRef<bool> arr) {
+  jbooleanArray jarr = env->NewBooleanArray(arr.size());
+  if (!jarr) return nullptr;
+  jboolean* elements =
+      static_cast<jboolean*>(env->GetPrimitiveArrayCritical(jarr, nullptr));
+  if (!elements) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i)
+    elements[i] = arr[i] ? JNI_TRUE : JNI_FALSE;
+  env->ReleasePrimitiveArrayCritical(jarr, elements, 0);
+  return jarr;
+}
+
+  // Other MakeJ*Array conversions.
+
+#define WPI_JNI_MAKEJARRAY(T, F)                                  \
+  inline T##Array MakeJ##F##Array(JNIEnv* env, ArrayRef<T> arr) { \
+    T##Array jarr = env->New##F##Array(arr.size());               \
+    if (!jarr) return nullptr;                                    \
+    env->Set##F##ArrayRegion(jarr, 0, arr.size(), arr.data());    \
+    return jarr;                                                  \
+  }
+
+WPI_JNI_MAKEJARRAY(jboolean, Boolean)
+WPI_JNI_MAKEJARRAY(jbyte, Byte)
+WPI_JNI_MAKEJARRAY(jshort, Short)
+WPI_JNI_MAKEJARRAY(jlong, Long)
+WPI_JNI_MAKEJARRAY(jfloat, Float)
+WPI_JNI_MAKEJARRAY(jdouble, Double)
+
+#undef WPI_JNI_MAKEJARRAY
+
+// Convert an array of std::string into a jarray of jstring.
+inline jobjectArray MakeJStringArray(JNIEnv* env, ArrayRef<std::string> arr) {
+  static JClass stringCls{env, "java/lang/String"};
+  if (!stringCls) return nullptr;
+  jobjectArray jarr = env->NewObjectArray(arr.size(), stringCls, nullptr);
+  if (!jarr) return nullptr;
+  for (size_t i = 0; i < arr.size(); ++i) {
+    JLocal<jstring> elem{env, MakeJString(env, arr[i])};
+    env->SetObjectArrayElement(jarr, i, elem.obj());
+  }
+  return jarr;
+}
+
+// Generic callback thread implementation.
+//
+// JNI's AttachCurrentThread() creates a Java Thread object on every
+// invocation, which is both time inefficient and causes issues with Eclipse
+// (which tries to keep a thread list up-to-date and thus gets swamped).
+//
+// Instead, this class attaches just once.  When a hardware notification
+// occurs, a condition variable wakes up this thread and this thread actually
+// makes the call into Java.
+//
+// The template parameter T is the message being passed to the callback, but
+// also needs to provide the following functions:
+//  static JavaVM* GetJVM();
+//  static const char* GetName();
+//  void CallJava(JNIEnv *env, jobject func, jmethodID mid);
+template <typename T>
+class JCallbackThread : public SafeThread {
+ public:
+  void Main();
+
+  std::queue<T> m_queue;
+  jobject m_func = nullptr;
+  jmethodID m_mid;
+};
+
+template <typename T>
+class JCallbackManager : public SafeThreadOwner<JCallbackThread<T>> {
+ public:
+  JCallbackManager() { this->SetJoinAtExit(false); }
+  void SetFunc(JNIEnv* env, jobject func, jmethodID mid);
+
+  template <typename... Args>
+  void Send(Args&&... args);
+};
+
+template <typename T>
+void JCallbackManager<T>::SetFunc(JNIEnv* env, jobject func, jmethodID mid) {
+  auto thr = this->GetThread();
+  if (!thr) return;
+  // free global reference
+  if (thr->m_func) env->DeleteGlobalRef(thr->m_func);
+  // create global reference
+  thr->m_func = env->NewGlobalRef(func);
+  thr->m_mid = mid;
+}
+
+template <typename T>
+template <typename... Args>
+void JCallbackManager<T>::Send(Args&&... args) {
+  auto thr = this->GetThread();
+  if (!thr) return;
+  thr->m_queue.emplace(std::forward<Args>(args)...);
+  thr->m_cond.notify_one();
+}
+
+template <typename T>
+void JCallbackThread<T>::Main() {
+  JNIEnv* env;
+  JavaVMAttachArgs args;
+  args.version = JNI_VERSION_1_2;
+  args.name = const_cast<char*>(T::GetName());
+  args.group = nullptr;
+  jint rs = T::GetJVM()->AttachCurrentThreadAsDaemon(
+      reinterpret_cast<void**>(&env), &args);
+  if (rs != JNI_OK) return;
+
+  std::unique_lock<wpi::mutex> lock(m_mutex);
+  while (m_active) {
+    m_cond.wait(lock, [&] { return !(m_active && m_queue.empty()); });
+    if (!m_active) break;
+    while (!m_queue.empty()) {
+      if (!m_active) break;
+      auto item = std::move(m_queue.front());
+      m_queue.pop();
+      auto func = m_func;
+      auto mid = m_mid;
+      lock.unlock();  // don't hold mutex during callback execution
+      item.CallJava(env, func, mid);
+      if (env->ExceptionCheck()) {
+        env->ExceptionDescribe();
+        env->ExceptionClear();
+      }
+      lock.lock();
+    }
+  }
+
+  JavaVM* jvm = T::GetJVM();
+  if (jvm) jvm->DetachCurrentThread();
+}
+
+template <typename T>
+class JSingletonCallbackManager : public JCallbackManager<T> {
+ public:
+  static JSingletonCallbackManager<T>& GetInstance() {
+    static JSingletonCallbackManager<T> instance;
+    return instance;
+  }
+};
+
+inline std::string GetJavaStackTrace(JNIEnv* env, std::string* func,
+                                     StringRef excludeFuncPrefix) {
+  // create a throwable
+  static JClass throwableCls(env, "java/lang/Throwable");
+  if (!throwableCls) return "";
+  static jmethodID constructorId = nullptr;
+  if (!constructorId)
+    constructorId = env->GetMethodID(throwableCls, "<init>", "()V");
+  JLocal<jobject> throwable(env, env->NewObject(throwableCls, constructorId));
+
+  // retrieve information from the exception.
+  // get method id
+  // getStackTrace returns an array of StackTraceElement
+  static jmethodID getStackTraceId = nullptr;
+  if (!getStackTraceId)
+    getStackTraceId = env->GetMethodID(throwableCls, "getStackTrace",
+                                       "()[Ljava/lang/StackTraceElement;");
+
+  // call getStackTrace
+  JLocal<jobjectArray> stackTrace(
+      env, static_cast<jobjectArray>(
+               env->CallObjectMethod(throwable, getStackTraceId)));
+
+  if (!stackTrace) return "";
+
+  // get length of the array
+  jsize stackTraceLength = env->GetArrayLength(stackTrace);
+
+  // get toString methodId of StackTraceElement class
+  static JClass stackTraceElementCls(env, "java/lang/StackTraceElement");
+  if (!stackTraceElementCls) return "";
+  static jmethodID toStringId = nullptr;
+  if (!toStringId)
+    toStringId = env->GetMethodID(stackTraceElementCls, "toString",
+                                  "()Ljava/lang/String;");
+
+  bool haveLoc = false;
+  std::string buf;
+  raw_string_ostream oss(buf);
+  for (jsize i = 0; i < stackTraceLength; i++) {
+    // add the result of toString method of each element in the result
+    JLocal<jobject> curStackTraceElement(
+        env, env->GetObjectArrayElement(stackTrace, i));
+
+    // call to string on the object
+    JLocal<jstring> stackElementString(
+        env, static_cast<jstring>(
+                 env->CallObjectMethod(curStackTraceElement, toStringId)));
+
+    if (!stackElementString) return "";
+
+    // add a line to res
+    JStringRef elem(env, stackElementString);
+    oss << elem << '\n';
+
+    if (func) {
+      // func is caller of immediate caller (if there was one)
+      // or, if we see it, the first user function
+      if (i == 1) {
+        *func = elem.str();
+      } else if (i > 1 && !haveLoc && !excludeFuncPrefix.empty() &&
+                 !elem.str().startswith(excludeFuncPrefix)) {
+        *func = elem.str();
+        haveLoc = true;
+      }
+    }
+  }
+
+  return oss.str();
+}
+
+// Finds an exception class and keep it as a global reference.
+// Similar to JClass, but provides Throw methods.
+// Use with caution, as the destructor does NOT call DeleteGlobalRef due
+// to potential shutdown issues with doing so.
+class JException : public JClass {
+ public:
+  JException() = default;
+  JException(JNIEnv* env, const char* name) : JClass(env, name) {
+    if (m_cls)
+      m_constructor =
+          env->GetMethodID(m_cls, "<init>", "(Ljava/lang/String;)V");
+  }
+
+  void Throw(JNIEnv* env, jstring msg) {
+    jobject exception = env->NewObject(m_cls, m_constructor, msg);
+    env->Throw(static_cast<jthrowable>(exception));
+  }
+
+  void Throw(JNIEnv* env, StringRef msg) { Throw(env, MakeJString(env, msg)); }
+
+  explicit operator bool() const { return m_constructor; }
+
+ private:
+  jmethodID m_constructor = nullptr;
+};
+
+struct JExceptionInit {
+  const char* name;
+  JException* cls;
+};
+
+}  // namespace java
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_JNI_UTIL_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/json.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/json.h
new file mode 100644
index 0000000..a3aa776
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/json.h
@@ -0,0 +1,8185 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++
+|  |  |__   |  |  | | | |  version 3.1.2
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2018 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#ifndef WPIUTIL_JSON_H
+#define WPIUTIL_JSON_H
+
+#define NLOHMANN_JSON_VERSION_MAJOR 3
+#define NLOHMANN_JSON_VERSION_MINOR 1
+#define NLOHMANN_JSON_VERSION_PATCH 2
+
+
+#include <algorithm> // all_of, copy, find, for_each, generate_n, min, reverse, remove, fill, none_of, transform
+#include <array> // array
+#include <cassert> // assert
+#include <ciso646> // and, not, or
+#include <cstddef> // nullptr_t, ptrdiff_t, size_t
+#include <cstdint> // uint8_t, uint16_t, uint32_t, uint64_t
+#include <exception> // exception
+#include <functional> // function, hash, less
+#include <initializer_list> // initializer_list
+#include <iterator>
+#include <limits> // numeric_limits
+#include <memory> // allocator, shared_ptr, make_shared, addressof
+#include <stdexcept> // runtime_error
+#include <string> // string, char_traits, stoi, to_string
+#include <tuple> // tuple, get, make_tuple
+#include <type_traits>
+#include <utility>
+#include <vector> // vector
+
+#include "wpi/ArrayRef.h"
+#include "wpi/StringMap.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+
+namespace wpi
+{
+
+class raw_istream;
+class raw_ostream;
+
+class JsonTest;
+
+/*!
+@brief default JSONSerializer template argument
+
+This serializer ignores the template arguments and uses ADL
+([argument-dependent lookup](http://en.cppreference.com/w/cpp/language/adl))
+for serialization.
+*/
+template<typename = void, typename = void>
+struct adl_serializer;
+
+/*!
+@brief JSON Pointer
+
+A JSON pointer defines a string syntax for identifying a specific value
+within a JSON document. It can be used with functions `at` and
+`operator[]`. Furthermore, JSON pointers are the base for JSON patches.
+
+@sa [RFC 6901](https://tools.ietf.org/html/rfc6901)
+
+@since version 2.0.0
+*/
+class json_pointer;
+
+/*!
+@brief default JSON class
+
+This type is the default specialization of the @ref json class which
+uses the standard template types.
+
+@since version 1.0.0
+*/
+class json;
+}
+
+// exclude unsupported compilers
+#if defined(__clang__)
+    #if (__clang_major__ * 10000 + __clang_minor__ * 100 + __clang_patchlevel__) < 30400
+        #error "unsupported Clang version - see https://github.com/nlohmann/json#supported-compilers"
+    #endif
+#elif defined(__GNUC__) && !(defined(__ICC) || defined(__INTEL_COMPILER))
+    #if (__GNUC__ * 10000 + __GNUC_MINOR__ * 100 + __GNUC_PATCHLEVEL__) < 40900
+        #error "unsupported GCC version - see https://github.com/nlohmann/json#supported-compilers"
+    #endif
+#endif
+
+// disable float-equal warnings on GCC/clang
+#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
+    #pragma GCC diagnostic push
+    #pragma GCC diagnostic ignored "-Wfloat-equal"
+#endif
+
+// disable documentation warnings on clang
+#if defined(__clang__)
+    #pragma GCC diagnostic push
+    #pragma GCC diagnostic ignored "-Wdocumentation"
+#endif
+
+// allow to disable exceptions
+#if (defined(__cpp_exceptions) || defined(__EXCEPTIONS) || defined(_CPPUNWIND)) && !defined(JSON_NOEXCEPTION)
+    #define JSON_THROW(exception) throw exception
+    #define JSON_TRY try
+    #define JSON_CATCH(exception) catch(exception)
+#else
+    #define JSON_THROW(exception) std::abort()
+    #define JSON_TRY if(true)
+    #define JSON_CATCH(exception) if(false)
+#endif
+
+// override exception macros
+#if defined(JSON_THROW_USER)
+    #undef JSON_THROW
+    #define JSON_THROW JSON_THROW_USER
+#endif
+#if defined(JSON_TRY_USER)
+    #undef JSON_TRY
+    #define JSON_TRY JSON_TRY_USER
+#endif
+#if defined(JSON_CATCH_USER)
+    #undef JSON_CATCH
+    #define JSON_CATCH JSON_CATCH_USER
+#endif
+
+// manual branch prediction
+#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
+    #define JSON_LIKELY(x)      __builtin_expect(!!(x), 1)
+    #define JSON_UNLIKELY(x)    __builtin_expect(!!(x), 0)
+#else
+    #define JSON_LIKELY(x)      x
+    #define JSON_UNLIKELY(x)    x
+#endif
+
+// C++ language standard detection
+#if (defined(__cplusplus) && __cplusplus >= 201703L) || (defined(_HAS_CXX17) && _HAS_CXX17 == 1) // fix for issue #464
+    #define JSON_HAS_CPP_17
+    #define JSON_HAS_CPP_14
+#elif (defined(__cplusplus) && __cplusplus >= 201402L) || (defined(_HAS_CXX14) && _HAS_CXX14 == 1)
+    #define JSON_HAS_CPP_14
+#endif
+
+/*!
+@brief Helper to determine whether there's a key_type for T.
+
+This helper is used to tell associative containers apart from other containers
+such as sequence containers. For instance, `std::map` passes the test as it
+contains a `mapped_type`, whereas `std::vector` fails the test.
+
+@sa http://stackoverflow.com/a/7728728/266378
+@since version 1.0.0, overworked in version 2.0.6
+*/
+#define NLOHMANN_JSON_HAS_HELPER(type)                                        \
+    template<typename T> struct has_##type {                                  \
+    private:                                                                  \
+        template<typename U, typename = typename U::type>                     \
+        static int detect(U &&);                                              \
+        static void detect(...);                                              \
+    public:                                                                   \
+        static constexpr bool value =                                         \
+                std::is_integral<decltype(detect(std::declval<T>()))>::value; \
+    }
+
+namespace wpi
+{
+/*!
+@brief detail namespace with internal helper functions
+
+This namespace collects functions that should not be exposed,
+implementations of some @ref json methods, and meta-programming helpers.
+
+@since version 2.1.0
+*/
+namespace detail
+{
+/////////////
+// helpers //
+/////////////
+
+template<typename> struct is_json : std::false_type {};
+
+template<> struct is_json<json> : std::true_type {};
+
+// alias templates to reduce boilerplate
+template<bool B, typename T = void>
+using enable_if_t = typename std::enable_if<B, T>::type;
+
+template<typename T>
+using uncvref_t = typename std::remove_cv<typename std::remove_reference<T>::type>::type;
+
+// implementation of C++14 index_sequence and affiliates
+// source: https://stackoverflow.com/a/32223343
+template<std::size_t... Ints>
+struct index_sequence
+{
+    using type = index_sequence;
+    using value_type = std::size_t;
+    static constexpr std::size_t size() noexcept
+    {
+        return sizeof...(Ints);
+    }
+};
+
+template<class Sequence1, class Sequence2>
+struct merge_and_renumber;
+
+template<std::size_t... I1, std::size_t... I2>
+struct merge_and_renumber<index_sequence<I1...>, index_sequence<I2...>>
+        : index_sequence < I1..., (sizeof...(I1) + I2)... > {};
+
+template<std::size_t N>
+struct make_index_sequence
+    : merge_and_renumber < typename make_index_sequence < N / 2 >::type,
+      typename make_index_sequence < N - N / 2 >::type > {};
+
+template<> struct make_index_sequence<0> : index_sequence<> {};
+template<> struct make_index_sequence<1> : index_sequence<0> {};
+
+template<typename... Ts>
+using index_sequence_for = make_index_sequence<sizeof...(Ts)>;
+
+/*
+Implementation of two C++17 constructs: conjunction, negation. This is needed
+to avoid evaluating all the traits in a condition
+
+For example: not std::is_same<void, T>::value and has_value_type<T>::value
+will not compile when T = void (on MSVC at least). Whereas
+conjunction<negation<std::is_same<void, T>>, has_value_type<T>>::value will
+stop evaluating if negation<...>::value == false
+
+Please note that those constructs must be used with caution, since symbols can
+become very long quickly (which can slow down compilation and cause MSVC
+internal compiler errors). Only use it when you have to (see example ahead).
+*/
+template<class...> struct conjunction : std::true_type {};
+template<class B1> struct conjunction<B1> : B1 {};
+template<class B1, class... Bn>
+struct conjunction<B1, Bn...> : std::conditional<bool(B1::value), conjunction<Bn...>, B1>::type {};
+
+template<class B> struct negation : std::integral_constant<bool, not B::value> {};
+
+// dispatch utility (taken from ranges-v3)
+template<unsigned N> struct priority_tag : priority_tag < N - 1 > {};
+template<> struct priority_tag<0> {};
+
+////////////////////////
+// has_/is_ functions //
+////////////////////////
+
+// source: https://stackoverflow.com/a/37193089/4116453
+
+template <typename T, typename = void>
+struct is_complete_type : std::false_type {};
+
+template <typename T>
+struct is_complete_type<T, decltype(void(sizeof(T)))> : std::true_type {};
+
+NLOHMANN_JSON_HAS_HELPER(mapped_type);
+NLOHMANN_JSON_HAS_HELPER(key_type);
+NLOHMANN_JSON_HAS_HELPER(value_type);
+NLOHMANN_JSON_HAS_HELPER(iterator);
+
+template<bool B, class RealType, class CompatibleObjectType>
+struct is_compatible_object_type_impl : std::false_type {};
+
+template<class RealType, class CompatibleObjectType>
+struct is_compatible_object_type_impl<true, RealType, CompatibleObjectType>
+{
+    static constexpr auto value =
+        std::is_constructible<StringRef, typename CompatibleObjectType::key_type>::value and
+        std::is_constructible<typename RealType::mapped_type, typename CompatibleObjectType::mapped_type>::value;
+};
+
+template<class BasicJsonType, class CompatibleObjectType>
+struct is_compatible_object_type
+{
+    static auto constexpr value = is_compatible_object_type_impl <
+                                  conjunction<negation<std::is_same<void, CompatibleObjectType>>,
+                                  has_mapped_type<CompatibleObjectType>,
+                                  has_key_type<CompatibleObjectType>>::value,
+                                  typename BasicJsonType::object_t, CompatibleObjectType >::value;
+};
+
+template<typename BasicJsonType, typename T>
+struct is_json_nested_type
+{
+    static auto constexpr value = std::is_same<T, typename BasicJsonType::iterator>::value or
+                                  std::is_same<T, typename BasicJsonType::const_iterator>::value or
+                                  std::is_same<T, typename BasicJsonType::reverse_iterator>::value or
+                                  std::is_same<T, typename BasicJsonType::const_reverse_iterator>::value;
+};
+
+template<class BasicJsonType, class CompatibleArrayType>
+struct is_compatible_array_type
+{
+    static auto constexpr value =
+        conjunction<negation<std::is_same<void, CompatibleArrayType>>,
+        negation<is_compatible_object_type<
+        BasicJsonType, CompatibleArrayType>>,
+        negation<std::is_constructible<StringRef,
+        CompatibleArrayType>>,
+        negation<is_json_nested_type<BasicJsonType, CompatibleArrayType>>,
+        has_value_type<CompatibleArrayType>,
+        has_iterator<CompatibleArrayType>>::value;
+};
+
+template<bool, typename, typename>
+struct is_compatible_integer_type_impl : std::false_type {};
+
+template<typename RealIntegerType, typename CompatibleNumberIntegerType>
+struct is_compatible_integer_type_impl<true, RealIntegerType, CompatibleNumberIntegerType>
+{
+    // is there an assert somewhere on overflows?
+    using RealLimits = std::numeric_limits<RealIntegerType>;
+    using CompatibleLimits = std::numeric_limits<CompatibleNumberIntegerType>;
+
+    static constexpr auto value =
+        std::is_constructible<RealIntegerType, CompatibleNumberIntegerType>::value and
+        CompatibleLimits::is_integer and
+        RealLimits::is_signed == CompatibleLimits::is_signed;
+};
+
+template<typename RealIntegerType, typename CompatibleNumberIntegerType>
+struct is_compatible_integer_type
+{
+    static constexpr auto value =
+        is_compatible_integer_type_impl <
+        std::is_integral<CompatibleNumberIntegerType>::value and
+        not std::is_same<bool, CompatibleNumberIntegerType>::value,
+        RealIntegerType, CompatibleNumberIntegerType > ::value;
+};
+
+// trait checking if JSONSerializer<T>::from_json(json const&, udt&) exists
+template<typename BasicJsonType, typename T>
+struct has_from_json
+{
+  private:
+    // also check the return type of from_json
+    template<typename U, typename = enable_if_t<std::is_same<void, decltype(uncvref_t<U>::from_json(
+                 std::declval<BasicJsonType>(), std::declval<T&>()))>::value>>
+    static int detect(U&&);
+    static void detect(...);
+
+  public:
+    static constexpr bool value = std::is_integral<decltype(
+                                      detect(std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
+};
+
+// This trait checks if JSONSerializer<T>::from_json(json const&) exists
+// this overload is used for non-default-constructible user-defined-types
+template<typename BasicJsonType, typename T>
+struct has_non_default_from_json
+{
+  private:
+    template <
+        typename U,
+        typename = enable_if_t<std::is_same<
+                                   T, decltype(uncvref_t<U>::from_json(std::declval<BasicJsonType>()))>::value >>
+    static int detect(U&&);
+    static void detect(...);
+
+  public:
+    static constexpr bool value = std::is_integral<decltype(detect(
+                                      std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
+};
+
+// This trait checks if BasicJsonType::json_serializer<T>::to_json exists
+template<typename BasicJsonType, typename T>
+struct has_to_json
+{
+  private:
+    template<typename U, typename = decltype(uncvref_t<U>::to_json(
+                 std::declval<BasicJsonType&>(), std::declval<T>()))>
+    static int detect(U&&);
+    static void detect(...);
+
+  public:
+    static constexpr bool value = std::is_integral<decltype(detect(
+                                      std::declval<typename BasicJsonType::template json_serializer<T, void>>()))>::value;
+};
+
+template <typename BasicJsonType, typename CompatibleCompleteType>
+struct is_compatible_complete_type
+{
+    static constexpr bool value =
+        not std::is_base_of<std::istream, CompatibleCompleteType>::value and
+        not is_json<CompatibleCompleteType>::value and
+        not is_json_nested_type<BasicJsonType, CompatibleCompleteType>::value and
+        has_to_json<BasicJsonType, CompatibleCompleteType>::value;
+};
+
+template <typename BasicJsonType, typename CompatibleType>
+struct is_compatible_type
+    : conjunction<is_complete_type<CompatibleType>,
+      is_compatible_complete_type<BasicJsonType, CompatibleType>>
+{
+};
+
+// taken from ranges-v3
+template<typename T>
+struct static_const
+{
+    static constexpr T value{};
+};
+
+template<typename T>
+constexpr T static_const<T>::value;
+
+////////////////
+// exceptions //
+////////////////
+
+/*!
+@brief general exception of the @ref json class
+
+This class is an extension of `std::exception` objects with a member @a id for
+exception ids. It is used as the base class for all exceptions thrown by the
+@ref json class. This class can hence be used as "wildcard" to catch
+exceptions.
+
+Subclasses:
+- @ref parse_error for exceptions indicating a parse error
+- @ref invalid_iterator for exceptions indicating errors with iterators
+- @ref type_error for exceptions indicating executing a member function with
+                  a wrong type
+- @ref out_of_range for exceptions indicating access out of the defined range
+- @ref other_error for exceptions indicating other library errors
+
+@internal
+@note To have nothrow-copy-constructible exceptions, we internally use
+      `std::runtime_error` which can cope with arbitrary-length error messages.
+      Intermediate strings are built with static functions and then passed to
+      the actual constructor.
+@endinternal
+
+@liveexample{The following code shows how arbitrary library exceptions can be
+caught.,exception}
+
+@since version 3.0.0
+*/
+class exception : public std::exception
+{
+  public:
+    /// returns the explanatory string
+    const char* what() const noexcept override
+    {
+        return m.what();
+    }
+
+    /// the id of the exception
+    const int id;
+
+  protected:
+    exception(int id_, const Twine& what_arg);
+
+  private:
+    /// an exception object as storage for error messages
+    std::runtime_error m;
+};
+
+/*!
+@brief exception indicating a parse error
+
+This exception is thrown by the library when a parse error occurs. Parse errors
+can occur during the deserialization of JSON text, CBOR, MessagePack, as well
+as when using JSON Patch.
+
+Member @a byte holds the byte index of the last read character in the input
+file.
+
+Exceptions have ids 1xx.
+
+name / id                      | example message | description
+------------------------------ | --------------- | -------------------------
+json.exception.parse_error.101 | parse error at 2: unexpected end of input; expected string literal | This error indicates a syntax error while deserializing a JSON text. The error message describes that an unexpected token (character) was encountered, and the member @a byte indicates the error position.
+json.exception.parse_error.102 | parse error at 14: missing or wrong low surrogate | JSON uses the `\uxxxx` format to describe Unicode characters. Code points above above 0xFFFF are split into two `\uxxxx` entries ("surrogate pairs"). This error indicates that the surrogate pair is incomplete or contains an invalid code point.
+json.exception.parse_error.103 | parse error: code points above 0x10FFFF are invalid | Unicode supports code points up to 0x10FFFF. Code points above 0x10FFFF are invalid.
+json.exception.parse_error.104 | parse error: JSON patch must be an array of objects | [RFC 6902](https://tools.ietf.org/html/rfc6902) requires a JSON Patch document to be a JSON document that represents an array of objects.
+json.exception.parse_error.105 | parse error: operation must have string member 'op' | An operation of a JSON Patch document must contain exactly one "op" member, whose value indicates the operation to perform. Its value must be one of "add", "remove", "replace", "move", "copy", or "test"; other values are errors.
+json.exception.parse_error.106 | parse error: array index '01' must not begin with '0' | An array index in a JSON Pointer ([RFC 6901](https://tools.ietf.org/html/rfc6901)) may be `0` or any number without a leading `0`.
+json.exception.parse_error.107 | parse error: JSON pointer must be empty or begin with '/' - was: 'foo' | A JSON Pointer must be a Unicode string containing a sequence of zero or more reference tokens, each prefixed by a `/` character.
+json.exception.parse_error.108 | parse error: escape character '~' must be followed with '0' or '1' | In a JSON Pointer, only `~0` and `~1` are valid escape sequences.
+json.exception.parse_error.109 | parse error: array index 'one' is not a number | A JSON Pointer array index must be a number.
+json.exception.parse_error.110 | parse error at 1: cannot read 2 bytes from vector | When parsing CBOR or MessagePack, the byte vector ends before the complete value has been read.
+json.exception.parse_error.112 | parse error at 1: error reading CBOR; last byte: 0xF8 | Not all types of CBOR or MessagePack are supported. This exception occurs if an unsupported byte was read.
+json.exception.parse_error.113 | parse error at 2: expected a CBOR string; last byte: 0x98 | While parsing a map key, a value that is not a string has been read.
+
+@note For an input with n bytes, 1 is the index of the first character and n+1
+      is the index of the terminating null byte or the end of file. This also
+      holds true when reading a byte vector (CBOR or MessagePack).
+
+@liveexample{The following code shows how a `parse_error` exception can be
+caught.,parse_error}
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref invalid_iterator for exceptions indicating errors with iterators
+@sa @ref type_error for exceptions indicating executing a member function with
+                    a wrong type
+@sa @ref out_of_range for exceptions indicating access out of the defined range
+@sa @ref other_error for exceptions indicating other library errors
+
+@since version 3.0.0
+*/
+class parse_error : public exception
+{
+  public:
+    /*!
+    @brief create a parse error exception
+    @param[in] id_       the id of the exception
+    @param[in] byte_     the byte index where the error occurred (or 0 if the
+                         position cannot be determined)
+    @param[in] what_arg  the explanatory string
+    @return parse_error object
+    */
+    static parse_error create(int id_, std::size_t byte_, const Twine& what_arg);
+
+    /*!
+    @brief byte index of the parse error
+
+    The byte index of the last read character in the input file.
+
+    @note For an input with n bytes, 1 is the index of the first character and
+          n+1 is the index of the terminating null byte or the end of file.
+          This also holds true when reading a byte vector (CBOR or MessagePack).
+    */
+    const std::size_t byte;
+
+  private:
+    parse_error(int id_, std::size_t byte_, const Twine& what_arg)
+        : exception(id_, what_arg), byte(byte_) {}
+};
+
+/*!
+@brief exception indicating errors with iterators
+
+This exception is thrown if iterators passed to a library function do not match
+the expected semantics.
+
+Exceptions have ids 2xx.
+
+name / id                           | example message | description
+----------------------------------- | --------------- | -------------------------
+json.exception.invalid_iterator.201 | iterators are not compatible | The iterators passed to constructor @ref json(InputIT first, InputIT last) are not compatible, meaning they do not belong to the same container. Therefore, the range (@a first, @a last) is invalid.
+json.exception.invalid_iterator.202 | iterator does not fit current value | In an erase or insert function, the passed iterator @a pos does not belong to the JSON value for which the function was called. It hence does not define a valid position for the deletion/insertion.
+json.exception.invalid_iterator.203 | iterators do not fit current value | Either iterator passed to function @ref erase(IteratorType first, IteratorType last) does not belong to the JSON value from which values shall be erased. It hence does not define a valid range to delete values from.
+json.exception.invalid_iterator.204 | iterators out of range | When an iterator range for a primitive type (number, boolean, or string) is passed to a constructor or an erase function, this range has to be exactly (@ref begin(), @ref end()), because this is the only way the single stored value is expressed. All other ranges are invalid.
+json.exception.invalid_iterator.205 | iterator out of range | When an iterator for a primitive type (number, boolean, or string) is passed to an erase function, the iterator has to be the @ref begin() iterator, because it is the only way to address the stored value. All other iterators are invalid.
+json.exception.invalid_iterator.206 | cannot construct with iterators from null | The iterators passed to constructor @ref json(InputIT first, InputIT last) belong to a JSON null value and hence to not define a valid range.
+json.exception.invalid_iterator.207 | cannot use key() for non-object iterators | The key() member function can only be used on iterators belonging to a JSON object, because other types do not have a concept of a key.
+json.exception.invalid_iterator.208 | cannot use operator[] for object iterators | The operator[] to specify a concrete offset cannot be used on iterators belonging to a JSON object, because JSON objects are unordered.
+json.exception.invalid_iterator.209 | cannot use offsets with object iterators | The offset operators (+, -, +=, -=) cannot be used on iterators belonging to a JSON object, because JSON objects are unordered.
+json.exception.invalid_iterator.210 | iterators do not fit | The iterator range passed to the insert function are not compatible, meaning they do not belong to the same container. Therefore, the range (@a first, @a last) is invalid.
+json.exception.invalid_iterator.211 | passed iterators may not belong to container | The iterator range passed to the insert function must not be a subrange of the container to insert to.
+json.exception.invalid_iterator.212 | cannot compare iterators of different containers | When two iterators are compared, they must belong to the same container.
+json.exception.invalid_iterator.213 | cannot compare order of object iterators | The order of object iterators cannot be compared, because JSON objects are unordered.
+json.exception.invalid_iterator.214 | cannot get value | Cannot get value for iterator: Either the iterator belongs to a null value or it is an iterator to a primitive type (number, boolean, or string), but the iterator is different to @ref begin().
+
+@liveexample{The following code shows how an `invalid_iterator` exception can be
+caught.,invalid_iterator}
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref parse_error for exceptions indicating a parse error
+@sa @ref type_error for exceptions indicating executing a member function with
+                    a wrong type
+@sa @ref out_of_range for exceptions indicating access out of the defined range
+@sa @ref other_error for exceptions indicating other library errors
+
+@since version 3.0.0
+*/
+class invalid_iterator : public exception
+{
+  public:
+    static invalid_iterator create(int id_, const Twine& what_arg);
+
+  private:
+    invalid_iterator(int id_, const Twine& what_arg)
+        : exception(id_, what_arg) {}
+};
+
+/*!
+@brief exception indicating executing a member function with a wrong type
+
+This exception is thrown in case of a type error; that is, a library function is
+executed on a JSON value whose type does not match the expected semantics.
+
+Exceptions have ids 3xx.
+
+name / id                     | example message | description
+----------------------------- | --------------- | -------------------------
+json.exception.type_error.301 | cannot create object from initializer list | To create an object from an initializer list, the initializer list must consist only of a list of pairs whose first element is a string. When this constraint is violated, an array is created instead.
+json.exception.type_error.302 | type must be object, but is array | During implicit or explicit value conversion, the JSON type must be compatible to the target type. For instance, a JSON string can only be converted into string types, but not into numbers or boolean types.
+json.exception.type_error.303 | incompatible ReferenceType for get_ref, actual type is object | To retrieve a reference to a value stored in a @ref json object with @ref get_ref, the type of the reference must match the value type. For instance, for a JSON array, the @a ReferenceType must be @ref array_t&.
+json.exception.type_error.304 | cannot use at() with string | The @ref at() member functions can only be executed for certain JSON types.
+json.exception.type_error.305 | cannot use operator[] with string | The @ref operator[] member functions can only be executed for certain JSON types.
+json.exception.type_error.306 | cannot use value() with string | The @ref value() member functions can only be executed for certain JSON types.
+json.exception.type_error.307 | cannot use erase() with string | The @ref erase() member functions can only be executed for certain JSON types.
+json.exception.type_error.308 | cannot use push_back() with string | The @ref push_back() and @ref operator+= member functions can only be executed for certain JSON types.
+json.exception.type_error.309 | cannot use insert() with | The @ref insert() member functions can only be executed for certain JSON types.
+json.exception.type_error.310 | cannot use swap() with number | The @ref swap() member functions can only be executed for certain JSON types.
+json.exception.type_error.311 | cannot use emplace_back() with string | The @ref emplace_back() member function can only be executed for certain JSON types.
+json.exception.type_error.312 | cannot use update() with string | The @ref update() member functions can only be executed for certain JSON types.
+json.exception.type_error.313 | invalid value to unflatten | The @ref unflatten function converts an object whose keys are JSON Pointers back into an arbitrary nested JSON value. The JSON Pointers must not overlap, because then the resulting value would not be well defined.
+json.exception.type_error.314 | only objects can be unflattened | The @ref unflatten function only works for an object whose keys are JSON Pointers.
+json.exception.type_error.315 | values in object must be primitive | The @ref unflatten function only works for an object whose keys are JSON Pointers and whose values are primitive.
+json.exception.type_error.316 | invalid UTF-8 byte at index 10: 0x7E | The @ref dump function only works with UTF-8 encoded strings; that is, if you assign a `std::string` to a JSON value, make sure it is UTF-8 encoded. |
+
+@liveexample{The following code shows how a `type_error` exception can be
+caught.,type_error}
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref parse_error for exceptions indicating a parse error
+@sa @ref invalid_iterator for exceptions indicating errors with iterators
+@sa @ref out_of_range for exceptions indicating access out of the defined range
+@sa @ref other_error for exceptions indicating other library errors
+
+@since version 3.0.0
+*/
+class type_error : public exception
+{
+  public:
+    static type_error create(int id_, const Twine& what_arg);
+
+  private:
+    type_error(int id_, const Twine& what_arg) : exception(id_, what_arg) {}
+};
+
+/*!
+@brief exception indicating access out of the defined range
+
+This exception is thrown in case a library function is called on an input
+parameter that exceeds the expected range, for instance in case of array
+indices or nonexisting object keys.
+
+Exceptions have ids 4xx.
+
+name / id                       | example message | description
+------------------------------- | --------------- | -------------------------
+json.exception.out_of_range.401 | array index 3 is out of range | The provided array index @a i is larger than @a size-1.
+json.exception.out_of_range.402 | array index '-' (3) is out of range | The special array index `-` in a JSON Pointer never describes a valid element of the array, but the index past the end. That is, it can only be used to add elements at this position, but not to read it.
+json.exception.out_of_range.403 | key 'foo' not found | The provided key was not found in the JSON object.
+json.exception.out_of_range.404 | unresolved reference token 'foo' | A reference token in a JSON Pointer could not be resolved.
+json.exception.out_of_range.405 | JSON pointer has no parent | The JSON Patch operations 'remove' and 'add' can not be applied to the root element of the JSON value.
+json.exception.out_of_range.406 | number overflow parsing '10E1000' | A parsed number could not be stored as without changing it to NaN or INF.
+json.exception.out_of_range.407 | number overflow serializing '9223372036854775808' | UBJSON only supports integers numbers up to 9223372036854775807. |
+json.exception.out_of_range.408 | excessive array size: 8658170730974374167 | The size (following `#`) of an UBJSON array or object exceeds the maximal capacity. |
+
+@liveexample{The following code shows how an `out_of_range` exception can be
+caught.,out_of_range}
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref parse_error for exceptions indicating a parse error
+@sa @ref invalid_iterator for exceptions indicating errors with iterators
+@sa @ref type_error for exceptions indicating executing a member function with
+                    a wrong type
+@sa @ref other_error for exceptions indicating other library errors
+
+@since version 3.0.0
+*/
+class out_of_range : public exception
+{
+  public:
+    static out_of_range create(int id_, const Twine& what_arg);
+
+  private:
+    out_of_range(int id_, const Twine& what_arg) : exception(id_, what_arg) {}
+};
+
+/*!
+@brief exception indicating other library errors
+
+This exception is thrown in case of errors that cannot be classified with the
+other exception types.
+
+Exceptions have ids 5xx.
+
+name / id                      | example message | description
+------------------------------ | --------------- | -------------------------
+json.exception.other_error.501 | unsuccessful: {"op":"test","path":"/baz", "value":"bar"} | A JSON Patch operation 'test' failed. The unsuccessful operation is also printed.
+
+@sa @ref exception for the base class of the library exceptions
+@sa @ref parse_error for exceptions indicating a parse error
+@sa @ref invalid_iterator for exceptions indicating errors with iterators
+@sa @ref type_error for exceptions indicating executing a member function with
+                    a wrong type
+@sa @ref out_of_range for exceptions indicating access out of the defined range
+
+@liveexample{The following code shows how an `other_error` exception can be
+caught.,other_error}
+
+@since version 3.0.0
+*/
+class other_error : public exception
+{
+  public:
+    static other_error create(int id_, const Twine& what_arg);
+
+  private:
+    other_error(int id_, const Twine& what_arg) : exception(id_, what_arg) {}
+};
+
+///////////////////////////
+// JSON type enumeration //
+///////////////////////////
+
+/*!
+@brief the JSON type enumeration
+
+This enumeration collects the different JSON types. It is internally used to
+distinguish the stored values, and the functions @ref json::is_null(),
+@ref json::is_object(), @ref json::is_array(),
+@ref json::is_string(), @ref json::is_boolean(),
+@ref json::is_number() (with @ref json::is_number_integer(),
+@ref json::is_number_unsigned(), and @ref json::is_number_float()),
+@ref json::is_discarded(), @ref json::is_primitive(), and
+@ref json::is_structured() rely on it.
+
+@note There are three enumeration entries (number_integer, number_unsigned, and
+number_float), because the library distinguishes these three types for numbers:
+uint64_t is used for unsigned integers,
+int64_t is used for signed integers, and
+double is used for floating-point numbers or to
+approximate integers which do not fit in the limits of their respective type.
+
+@sa @ref json::json(const value_t value_type) -- create a JSON
+value with the default value for a given type
+
+@since version 1.0.0
+*/
+enum class value_t : std::uint8_t
+{
+    null,             ///< null value
+    object,           ///< object (unordered set of name/value pairs)
+    array,            ///< array (ordered collection of values)
+    string,           ///< string value
+    boolean,          ///< boolean value
+    number_integer,   ///< number value (signed integer)
+    number_unsigned,  ///< number value (unsigned integer)
+    number_float,     ///< number value (floating-point)
+    discarded         ///< discarded by the the parser callback function
+};
+
+/*!
+@brief comparison operator for JSON types
+
+Returns an ordering that is similar to Python:
+- order: null < boolean < number < object < array < string
+- furthermore, each type is not smaller than itself
+- discarded values are not comparable
+
+@since version 1.0.0
+*/
+inline bool operator<(const value_t lhs, const value_t rhs) noexcept
+{
+    static constexpr std::array<std::uint8_t, 8> order = {{
+            0 /* null */, 3 /* object */, 4 /* array */, 5 /* string */,
+            1 /* boolean */, 2 /* integer */, 2 /* unsigned */, 2 /* float */
+        }
+    };
+
+    const auto l_index = static_cast<std::size_t>(lhs);
+    const auto r_index = static_cast<std::size_t>(rhs);
+    return l_index < order.size() and r_index < order.size() and order[l_index] < order[r_index];
+}
+
+// overloads for json template parameters
+template<typename BasicJsonType, typename ArithmeticType,
+         enable_if_t<std::is_arithmetic<ArithmeticType>::value and
+                     not std::is_same<ArithmeticType, bool>::value,
+                     int> = 0>
+void get_arithmetic_value(const BasicJsonType& j, ArithmeticType& val)
+{
+    switch (static_cast<value_t>(j))
+    {
+        case value_t::number_unsigned:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const uint64_t*>());
+            break;
+        }
+        case value_t::number_integer:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const int64_t*>());
+            break;
+        }
+        case value_t::number_float:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const double*>());
+            break;
+        }
+
+        default:
+            JSON_THROW(type_error::create(302, "type must be number, but is " + Twine(j.type_name())));
+    }
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, bool& b)
+{
+    if (JSON_UNLIKELY(not j.is_boolean()))
+    {
+        JSON_THROW(type_error::create(302, "type must be boolean, but is " + Twine(j.type_name())));
+    }
+    b = *j.template get_ptr<const bool*>();
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, std::string& s)
+{
+    if (JSON_UNLIKELY(not j.is_string()))
+    {
+        JSON_THROW(type_error::create(302, "type must be string, but is " + Twine(j.type_name())));
+    }
+    s = *j.template get_ptr<const std::string*>();
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, double& val)
+{
+    get_arithmetic_value(j, val);
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, uint64_t& val)
+{
+    get_arithmetic_value(j, val);
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, int64_t& val)
+{
+    get_arithmetic_value(j, val);
+}
+
+template<typename BasicJsonType, typename EnumType,
+         enable_if_t<std::is_enum<EnumType>::value, int> = 0>
+void from_json(const BasicJsonType& j, EnumType& e)
+{
+    typename std::underlying_type<EnumType>::type val;
+    get_arithmetic_value(j, val);
+    e = static_cast<EnumType>(val);
+}
+
+template<typename BasicJsonType>
+void from_json(const BasicJsonType& j, typename BasicJsonType::array_t& arr)
+{
+    if (JSON_UNLIKELY(not j.is_array()))
+    {
+        JSON_THROW(type_error::create(302, "type must be array, but is " + Twine(j.type_name())));
+    }
+    arr = *j.template get_ptr<const typename BasicJsonType::array_t*>();
+}
+
+template<typename BasicJsonType, typename CompatibleArrayType>
+void from_json_array_impl(const BasicJsonType& j, CompatibleArrayType& arr, priority_tag<0> /*unused*/)
+{
+    using std::end;
+
+    std::transform(j.begin(), j.end(),
+                   std::inserter(arr, end(arr)), [](const BasicJsonType & i)
+    {
+        // get<BasicJsonType>() returns *this, this won't call a from_json
+        // method when value_type is BasicJsonType
+        return i.template get<typename CompatibleArrayType::value_type>();
+    });
+}
+
+template<typename BasicJsonType, typename CompatibleArrayType>
+auto from_json_array_impl(const BasicJsonType& j, CompatibleArrayType& arr, priority_tag<1> /*unused*/)
+-> decltype(
+    arr.reserve(std::declval<typename CompatibleArrayType::size_type>()),
+    void())
+{
+    using std::end;
+
+    arr.reserve(j.size());
+    std::transform(j.begin(), j.end(),
+                   std::inserter(arr, end(arr)), [](const BasicJsonType & i)
+    {
+        // get<BasicJsonType>() returns *this, this won't call a from_json
+        // method when value_type is BasicJsonType
+        return i.template get<typename CompatibleArrayType::value_type>();
+    });
+}
+
+template<typename BasicJsonType, typename T, std::size_t N>
+void from_json_array_impl(const BasicJsonType& j, std::array<T, N>& arr, priority_tag<2> /*unused*/)
+{
+    for (std::size_t i = 0; i < N; ++i)
+    {
+        arr[i] = j.at(i).template get<T>();
+    }
+}
+
+template <
+    typename BasicJsonType, typename CompatibleArrayType,
+    enable_if_t <
+        is_compatible_array_type<BasicJsonType, CompatibleArrayType>::value and
+        not std::is_same<typename BasicJsonType::array_t,
+                         CompatibleArrayType>::value and
+        std::is_constructible <
+            BasicJsonType, typename CompatibleArrayType::value_type >::value,
+        int > = 0 >
+void from_json(const BasicJsonType& j, CompatibleArrayType& arr)
+{
+    if (JSON_UNLIKELY(not j.is_array()))
+    {
+        JSON_THROW(type_error::create(302, "type must be array, but is " +
+                                      Twine(j.type_name())));
+    }
+
+    from_json_array_impl(j, arr, priority_tag<2> {});
+}
+
+template<typename BasicJsonType>
+inline
+void from_json(const BasicJsonType& j, typename BasicJsonType::object_t& obj)
+{
+    if (!j.is_object())
+    {
+        JSON_THROW(type_error::create(302, "type must be object, but is " + Twine(j.type_name())));
+    }
+
+    auto inner_object = j.template get_ptr<const typename BasicJsonType::object_t*>();
+    for (const auto& i : *inner_object) {
+        obj.try_emplace(i.first(), i.second);
+    }
+}
+
+template<typename BasicJsonType, typename CompatibleObjectType,
+         enable_if_t<is_compatible_object_type<BasicJsonType, CompatibleObjectType>::value and
+                     not std::is_same<typename BasicJsonType::object_t, CompatibleObjectType>::value, int> = 0>
+void from_json(const BasicJsonType& j, CompatibleObjectType& obj)
+{
+    if (JSON_UNLIKELY(not j.is_object()))
+    {
+        JSON_THROW(type_error::create(302, "type must be object, but is " + Twine(j.type_name())));
+    }
+
+    auto inner_object = j.template get_ptr<const typename BasicJsonType::object_t*>();
+    using std::begin;
+    using std::end;
+    using value_type = typename CompatibleObjectType::value_type;
+    std::vector<value_type> v;
+    v.reserve(j.size());
+    for (const auto& p : *inner_object)
+    {
+        v.emplace_back(
+            p.first(),
+            p.second
+            .template get<typename CompatibleObjectType::mapped_type>());
+    }
+    // we could avoid the assignment, but this might require a for loop, which
+    // might be less efficient than the container constructor for some
+    // containers (would it?)
+    obj = CompatibleObjectType(std::make_move_iterator(begin(v)),
+                               std::make_move_iterator(end(v)));
+}
+
+// overload for arithmetic types, not chosen for json template arguments
+// (BooleanType, etc..); note: Is it really necessary to provide explicit
+// overloads for bool etc. in case of a custom BooleanType which is not
+// an arithmetic type?
+template<typename BasicJsonType, typename ArithmeticType,
+         enable_if_t <
+             std::is_arithmetic<ArithmeticType>::value and
+             not std::is_same<ArithmeticType, uint64_t>::value and
+             not std::is_same<ArithmeticType, int64_t>::value and
+             not std::is_same<ArithmeticType, double>::value and
+             not std::is_same<ArithmeticType, bool>::value,
+             int> = 0>
+void from_json(const BasicJsonType& j, ArithmeticType& val)
+{
+    switch (static_cast<value_t>(j))
+    {
+        case value_t::number_unsigned:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const uint64_t*>());
+            break;
+        }
+        case value_t::number_integer:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const int64_t*>());
+            break;
+        }
+        case value_t::number_float:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const double*>());
+            break;
+        }
+        case value_t::boolean:
+        {
+            val = static_cast<ArithmeticType>(*j.template get_ptr<const bool*>());
+            break;
+        }
+
+        default:
+            JSON_THROW(type_error::create(302, "type must be number, but is " + Twine(j.type_name())));
+    }
+}
+
+template<typename BasicJsonType, typename A1, typename A2>
+void from_json(const BasicJsonType& j, std::pair<A1, A2>& p)
+{
+    p = {j.at(0).template get<A1>(), j.at(1).template get<A2>()};
+}
+
+template<typename BasicJsonType, typename Tuple, std::size_t... Idx>
+void from_json_tuple_impl(const BasicJsonType& j, Tuple& t, index_sequence<Idx...>)
+{
+    t = std::make_tuple(j.at(Idx).template get<typename std::tuple_element<Idx, Tuple>::type>()...);
+}
+
+template<typename BasicJsonType, typename... Args>
+void from_json(const BasicJsonType& j, std::tuple<Args...>& t)
+{
+    from_json_tuple_impl(j, t, index_sequence_for<Args...> {});
+}
+
+struct from_json_fn
+{
+  private:
+    template<typename BasicJsonType, typename T>
+    auto call(const BasicJsonType& j, T& val, priority_tag<1> /*unused*/) const
+    noexcept(noexcept(from_json(j, val)))
+    -> decltype(from_json(j, val), void())
+    {
+        return from_json(j, val);
+    }
+
+    template<typename BasicJsonType, typename T>
+    void call(const BasicJsonType& /*unused*/, T& /*unused*/, priority_tag<0> /*unused*/) const noexcept
+    {
+        static_assert(sizeof(BasicJsonType) == 0,
+                      "could not find from_json() method in T's namespace");
+#ifdef _MSC_VER
+        // MSVC does not show a stacktrace for the above assert
+        using decayed = uncvref_t<T>;
+        static_assert(sizeof(typename decayed::force_msvc_stacktrace) == 0,
+                      "forcing MSVC stacktrace to show which T we're talking about.");
+#endif
+    }
+
+  public:
+    template<typename BasicJsonType, typename T>
+    void operator()(const BasicJsonType& j, T& val) const
+    noexcept(noexcept(std::declval<from_json_fn>().call(j, val, priority_tag<1> {})))
+    {
+        return call(j, val, priority_tag<1> {});
+    }
+};
+}
+
+// namespace to hold default `from_json` function
+// to see why this is required:
+// http://www.open-std.org/jtc1/sc22/wg21/docs/papers/2015/n4381.html
+namespace
+{
+constexpr const auto& from_json = detail::static_const<detail::from_json_fn>::value;
+}
+
+namespace detail
+{
+//////////////////
+// constructors //
+//////////////////
+
+template<value_t> struct external_constructor;
+
+template<>
+struct external_constructor<value_t::boolean>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, bool b) noexcept
+    {
+        j.m_type = value_t::boolean;
+        j.m_value = b;
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::string>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, StringRef s)
+    {
+        j.m_type = value_t::string;
+        j.m_value = s;
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType, typename T,
+             enable_if_t<std::is_same<std::string, T>::value, int> = 0>
+    static void construct(BasicJsonType& j, T&& s)
+    {
+        j.m_type = value_t::string;
+        j.m_value = std::move(s);
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::number_float>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, double val) noexcept
+    {
+        j.m_type = value_t::number_float;
+        j.m_value = val;
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::number_unsigned>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, uint64_t val) noexcept
+    {
+        j.m_type = value_t::number_unsigned;
+        j.m_value = val;
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::number_integer>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, int64_t val) noexcept
+    {
+        j.m_type = value_t::number_integer;
+        j.m_value = val;
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::array>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, const typename BasicJsonType::array_t& arr)
+    {
+        j.m_type = value_t::array;
+        j.m_value = arr;
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
+    {
+        j.m_type = value_t::array;
+        j.m_value = std::move(arr);
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType, typename T>
+    static void construct(BasicJsonType& j, ArrayRef<T> arr)
+    {
+        using std::begin;
+        using std::end;
+        j.m_type = value_t::array;
+        j.m_value.array = j.template create<typename BasicJsonType::array_t>(begin(arr), end(arr));
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType, typename CompatibleArrayType,
+             enable_if_t<not std::is_same<CompatibleArrayType, typename BasicJsonType::array_t>::value,
+                         int> = 0>
+    static void construct(BasicJsonType& j, const CompatibleArrayType& arr)
+    {
+        using std::begin;
+        using std::end;
+        j.m_type = value_t::array;
+        j.m_value.array = j.template create<typename BasicJsonType::array_t>(begin(arr), end(arr));
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, const std::vector<bool>& arr)
+    {
+        j.m_type = value_t::array;
+        j.m_value = value_t::array;
+        j.m_value.array->reserve(arr.size());
+        for (const bool x : arr)
+        {
+            j.m_value.array->push_back(x);
+        }
+        j.assert_invariant();
+    }
+};
+
+template<>
+struct external_constructor<value_t::object>
+{
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, const typename BasicJsonType::object_t& obj)
+    {
+        j.m_type = value_t::object;
+        j.m_value = obj;
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType>
+    static void construct(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
+    {
+        j.m_type = value_t::object;
+        j.m_value = std::move(obj);
+        j.assert_invariant();
+    }
+
+    template<typename BasicJsonType, typename CompatibleObjectType,
+             enable_if_t<not std::is_same<CompatibleObjectType, typename BasicJsonType::object_t>::value, int> = 0>
+    static void construct(BasicJsonType& j, const CompatibleObjectType& obj)
+    {
+        j.m_type = value_t::object;
+        j.m_value = value_t::object;
+        for (const auto& x : obj)
+        {
+            j.m_value.object->try_emplace(x.first, x.second);
+        }
+        j.assert_invariant();
+    }
+};
+
+/////////////
+// to_json //
+/////////////
+
+template<typename BasicJsonType, typename T,
+         enable_if_t<std::is_same<T, bool>::value, int> = 0>
+void to_json(BasicJsonType& j, T b) noexcept
+{
+    external_constructor<value_t::boolean>::construct(j, b);
+}
+
+template<typename BasicJsonType, typename CompatibleString,
+         enable_if_t<std::is_constructible<StringRef, CompatibleString>::value, int> = 0>
+void to_json(BasicJsonType& j, const CompatibleString& s)
+{
+    external_constructor<value_t::string>::construct(j, s);
+}
+
+template<typename BasicJsonType, typename T,
+         enable_if_t<std::is_same<std::string, T>::value, int> = 0>
+void to_json(BasicJsonType& j, T&& s)
+{
+    external_constructor<value_t::string>::construct(j, std::move(s));
+}
+
+template<typename BasicJsonType, typename FloatType,
+         enable_if_t<std::is_floating_point<FloatType>::value, int> = 0>
+void to_json(BasicJsonType& j, FloatType val) noexcept
+{
+    external_constructor<value_t::number_float>::construct(j, static_cast<double>(val));
+}
+
+template<typename BasicJsonType, typename CompatibleNumberUnsignedType,
+         enable_if_t<is_compatible_integer_type<uint64_t, CompatibleNumberUnsignedType>::value, int> = 0>
+void to_json(BasicJsonType& j, CompatibleNumberUnsignedType val) noexcept
+{
+    external_constructor<value_t::number_unsigned>::construct(j, static_cast<uint64_t>(val));
+}
+
+template<typename BasicJsonType, typename CompatibleNumberIntegerType,
+         enable_if_t<is_compatible_integer_type<int64_t, CompatibleNumberIntegerType>::value, int> = 0>
+void to_json(BasicJsonType& j, CompatibleNumberIntegerType val) noexcept
+{
+    external_constructor<value_t::number_integer>::construct(j, static_cast<int64_t>(val));
+}
+
+template<typename BasicJsonType, typename EnumType,
+         enable_if_t<std::is_enum<EnumType>::value, int> = 0>
+void to_json(BasicJsonType& j, EnumType e) noexcept
+{
+    using underlying_type = typename std::underlying_type<EnumType>::type;
+    external_constructor<value_t::number_integer>::construct(j, static_cast<underlying_type>(e));
+}
+
+template<typename BasicJsonType>
+void to_json(BasicJsonType& j, const std::vector<bool>& e)
+{
+    external_constructor<value_t::array>::construct(j, e);
+}
+
+template<typename BasicJsonType, typename CompatibleArrayType,
+         enable_if_t<is_compatible_array_type<BasicJsonType, CompatibleArrayType>::value or
+                     std::is_same<typename BasicJsonType::array_t, CompatibleArrayType>::value,
+                     int> = 0>
+void to_json(BasicJsonType& j, const CompatibleArrayType& arr)
+{
+    external_constructor<value_t::array>::construct(j, arr);
+}
+
+template<typename BasicJsonType>
+void to_json(BasicJsonType& j, typename BasicJsonType::array_t&& arr)
+{
+    external_constructor<value_t::array>::construct(j, std::move(arr));
+}
+
+template<typename BasicJsonType, typename CompatibleObjectType,
+         enable_if_t<is_compatible_object_type<BasicJsonType, CompatibleObjectType>::value, int> = 0>
+void to_json(BasicJsonType& j, const CompatibleObjectType& obj)
+{
+    external_constructor<value_t::object>::construct(j, obj);
+}
+
+template<typename BasicJsonType>
+void to_json(BasicJsonType& j, typename BasicJsonType::object_t&& obj)
+{
+    external_constructor<value_t::object>::construct(j, std::move(obj));
+}
+
+template<typename BasicJsonType, typename T, std::size_t N,
+         enable_if_t<not std::is_constructible<StringRef, T (&)[N]>::value, int> = 0>
+void to_json(BasicJsonType& j, T (&arr)[N])
+{
+    external_constructor<value_t::array>::construct(j, arr);
+}
+
+template<typename BasicJsonType, typename... Args>
+void to_json(BasicJsonType& j, const std::pair<Args...>& p)
+{
+    j = {p.first, p.second};
+}
+
+template<typename BasicJsonType, typename Tuple, std::size_t... Idx>
+void to_json_tuple_impl(BasicJsonType& j, const Tuple& t, index_sequence<Idx...>)
+{
+    j = {std::get<Idx>(t)...};
+}
+
+template<typename BasicJsonType, typename... Args>
+void to_json(BasicJsonType& j, const std::tuple<Args...>& t)
+{
+    to_json_tuple_impl(j, t, index_sequence_for<Args...> {});
+}
+
+struct to_json_fn
+{
+  private:
+    template<typename BasicJsonType, typename T>
+    auto call(BasicJsonType& j, T&& val, priority_tag<1> /*unused*/) const noexcept(noexcept(to_json(j, std::forward<T>(val))))
+    -> decltype(to_json(j, std::forward<T>(val)), void())
+    {
+        return to_json(j, std::forward<T>(val));
+    }
+
+    template<typename BasicJsonType, typename T>
+    void call(BasicJsonType& /*unused*/, T&& /*unused*/, priority_tag<0> /*unused*/) const noexcept
+    {
+        static_assert(sizeof(BasicJsonType) == 0,
+                      "could not find to_json() method in T's namespace");
+
+#ifdef _MSC_VER
+        // MSVC does not show a stacktrace for the above assert
+        using decayed = uncvref_t<T>;
+        static_assert(sizeof(typename decayed::force_msvc_stacktrace) == 0,
+                      "forcing MSVC stacktrace to show which T we're talking about.");
+#endif
+    }
+
+  public:
+    template<typename BasicJsonType, typename T>
+    void operator()(BasicJsonType& j, T&& val) const
+    noexcept(noexcept(std::declval<to_json_fn>().call(j, std::forward<T>(val), priority_tag<1> {})))
+    {
+        return call(j, std::forward<T>(val), priority_tag<1> {});
+    }
+};
+}
+
+// namespace to hold default `to_json` function
+namespace
+{
+constexpr const auto& to_json = detail::static_const<detail::to_json_fn>::value;
+}
+
+namespace detail
+{
+/*
+@brief an iterator for primitive JSON types
+
+This class models an iterator for primitive JSON types (boolean, number,
+string). It's only purpose is to allow the iterator/const_iterator classes
+to "iterate" over primitive values. Internally, the iterator is modeled by
+a `difference_type` variable. Value begin_value (`0`) models the begin,
+end_value (`1`) models past the end.
+*/
+class primitive_iterator_t
+{
+  private:
+    using difference_type = std::ptrdiff_t;
+    static constexpr difference_type begin_value = 0;
+    static constexpr difference_type end_value = begin_value + 1;
+
+    /// iterator as signed integer type
+    difference_type m_it = (std::numeric_limits<std::ptrdiff_t>::min)();
+
+  public:
+    constexpr difference_type get_value() const noexcept
+    {
+        return m_it;
+    }
+
+    /// set iterator to a defined beginning
+    void set_begin() noexcept
+    {
+        m_it = begin_value;
+    }
+
+    /// set iterator to a defined past the end
+    void set_end() noexcept
+    {
+        m_it = end_value;
+    }
+
+    /// return whether the iterator can be dereferenced
+    constexpr bool is_begin() const noexcept
+    {
+        return m_it == begin_value;
+    }
+
+    /// return whether the iterator is at end
+    constexpr bool is_end() const noexcept
+    {
+        return m_it == end_value;
+    }
+
+    friend constexpr bool operator==(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
+    {
+        return lhs.m_it == rhs.m_it;
+    }
+
+    friend constexpr bool operator<(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
+    {
+        return lhs.m_it < rhs.m_it;
+    }
+
+    primitive_iterator_t operator+(difference_type n) noexcept
+    {
+        auto result = *this;
+        result += n;
+        return result;
+    }
+
+    friend constexpr difference_type operator-(primitive_iterator_t lhs, primitive_iterator_t rhs) noexcept
+    {
+        return lhs.m_it - rhs.m_it;
+    }
+
+    primitive_iterator_t& operator++() noexcept
+    {
+        ++m_it;
+        return *this;
+    }
+
+    primitive_iterator_t const operator++(int) noexcept
+    {
+        auto result = *this;
+        m_it++;
+        return result;
+    }
+
+    primitive_iterator_t& operator--() noexcept
+    {
+        --m_it;
+        return *this;
+    }
+
+    primitive_iterator_t const operator--(int) noexcept
+    {
+        auto result = *this;
+        m_it--;
+        return result;
+    }
+
+    primitive_iterator_t& operator+=(difference_type n) noexcept
+    {
+        m_it += n;
+        return *this;
+    }
+
+    primitive_iterator_t& operator-=(difference_type n) noexcept
+    {
+        m_it -= n;
+        return *this;
+    }
+};
+
+/*!
+@brief an iterator value
+
+@note This structure could easily be a union, but MSVC currently does not allow
+unions members with complex constructors, see https://github.com/nlohmann/json/pull/105.
+*/
+template<typename BasicJsonType> struct internal_iterator
+{
+    /// iterator for JSON objects
+    typename BasicJsonType::object_t::iterator object_iterator {};
+    /// iterator for JSON arrays
+    typename BasicJsonType::array_t::iterator array_iterator {};
+    /// generic iterator for all other types
+    primitive_iterator_t primitive_iterator {};
+};
+
+// forward declare, to be able to friend it later on
+template<typename IteratorType> class iteration_proxy;
+
+/*!
+@brief a template for a bidirectional iterator for the @ref json class
+
+This class implements a both iterators (iterator and const_iterator) for the
+@ref json class.
+
+@note An iterator is called *initialized* when a pointer to a JSON value has
+      been set (e.g., by a constructor or a copy assignment). If the iterator is
+      default-constructed, it is *uninitialized* and most methods are undefined.
+      **The library uses assertions to detect calls on uninitialized iterators.**
+
+@requirement The class satisfies the following concept requirements:
+-
+[BidirectionalIterator](http://en.cppreference.com/w/cpp/concept/BidirectionalIterator):
+  The iterator that can be moved can be moved in both directions (i.e.
+  incremented and decremented).
+
+@since version 1.0.0, simplified in version 2.0.9, change to bidirectional
+       iterators in version 3.0.0 (see https://github.com/nlohmann/json/issues/593)
+*/
+template<typename BasicJsonType>
+class iter_impl
+{
+    /// allow json to access private members
+    friend iter_impl<typename std::conditional<std::is_const<BasicJsonType>::value, typename std::remove_const<BasicJsonType>::type, const BasicJsonType>::type>;
+    friend BasicJsonType;
+    friend iteration_proxy<iter_impl>;
+    friend class ::wpi::JsonTest;
+
+    using object_t = typename BasicJsonType::object_t;
+    using array_t = typename BasicJsonType::array_t;
+    // make sure BasicJsonType is json or const json
+    static_assert(is_json<typename std::remove_const<BasicJsonType>::type>::value,
+                  "iter_impl only accepts (const) json");
+
+  public:
+
+    /// The std::iterator class template (used as a base class to provide typedefs) is deprecated in C++17.
+    /// The C++ Standard has never required user-defined iterators to derive from std::iterator.
+    /// A user-defined iterator should provide publicly accessible typedefs named
+    /// iterator_category, value_type, difference_type, pointer, and reference.
+    /// Note that value_type is required to be non-const, even for constant iterators.
+    using iterator_category = std::bidirectional_iterator_tag;
+
+    /// the type of the values when the iterator is dereferenced
+    using value_type = typename BasicJsonType::value_type;
+    /// a type to represent differences between iterators
+    using difference_type = typename BasicJsonType::difference_type;
+    /// defines a pointer to the type iterated over (value_type)
+    using pointer = typename std::conditional<std::is_const<BasicJsonType>::value,
+          typename BasicJsonType::const_pointer,
+          typename BasicJsonType::pointer>::type;
+    /// defines a reference to the type iterated over (value_type)
+    using reference =
+        typename std::conditional<std::is_const<BasicJsonType>::value,
+        typename BasicJsonType::const_reference,
+        typename BasicJsonType::reference>::type;
+
+    /// default constructor
+    iter_impl() = default;
+
+    /*!
+    @brief constructor for a given JSON instance
+    @param[in] object  pointer to a JSON object for this iterator
+    @pre object != nullptr
+    @post The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    explicit iter_impl(pointer object) noexcept : m_object(object)
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                m_it.object_iterator = typename object_t::iterator();
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_it.array_iterator = typename array_t::iterator();
+                break;
+            }
+
+            default:
+            {
+                m_it.primitive_iterator = primitive_iterator_t();
+                break;
+            }
+        }
+    }
+
+    /*!
+    @note The conventional copy constructor and copy assignment are implicitly
+          defined. Combined with the following converting constructor and
+          assignment, they support: (1) copy from iterator to iterator, (2)
+          copy from const iterator to const iterator, and (3) conversion from
+          iterator to const iterator. However conversion from const iterator
+          to iterator is not defined.
+    */
+
+    /*!
+    @brief converting constructor
+    @param[in] other  non-const iterator to copy from
+    @note It is not checked whether @a other is initialized.
+    */
+    iter_impl(const iter_impl<typename std::remove_const<BasicJsonType>::type>& other) noexcept
+        : m_object(other.m_object), m_it(other.m_it) {}
+
+    /*!
+    @brief converting assignment
+    @param[in,out] other  non-const iterator to copy from
+    @return const/non-const iterator
+    @note It is not checked whether @a other is initialized.
+    */
+    iter_impl& operator=(const iter_impl<typename std::remove_const<BasicJsonType>::type>& other) noexcept
+    {
+        m_object = other.m_object;
+        m_it = other.m_it;
+        return *this;
+    }
+
+  private:
+    /*!
+    @brief set the iterator to the first value
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    void set_begin() noexcept
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                m_it.object_iterator = m_object->m_value.object->begin();
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_it.array_iterator = m_object->m_value.array->begin();
+                break;
+            }
+
+            case value_t::null:
+            {
+                // set to end so begin()==end() is true: null is empty
+                m_it.primitive_iterator.set_end();
+                break;
+            }
+
+            default:
+            {
+                m_it.primitive_iterator.set_begin();
+                break;
+            }
+        }
+    }
+
+    /*!
+    @brief set the iterator past the last value
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    void set_end() noexcept
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                m_it.object_iterator = m_object->m_value.object->end();
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_it.array_iterator = m_object->m_value.array->end();
+                break;
+            }
+
+            default:
+            {
+                m_it.primitive_iterator.set_end();
+                break;
+            }
+        }
+    }
+
+  public:
+    /*!
+    @brief return a reference to the value pointed to by the iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    reference operator*() const
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                assert(m_it.object_iterator != m_object->m_value.object->end());
+                return m_it.object_iterator->second;
+            }
+
+            case value_t::array:
+            {
+                assert(m_it.array_iterator != m_object->m_value.array->end());
+                return *m_it.array_iterator;
+            }
+
+            case value_t::null:
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+
+            default:
+            {
+                if (JSON_LIKELY(m_it.primitive_iterator.is_begin()))
+                {
+                    return *m_object;
+                }
+
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+            }
+        }
+    }
+
+    /*!
+    @brief dereference the iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    pointer operator->() const
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                assert(m_it.object_iterator != m_object->m_value.object->end());
+                return &(m_it.object_iterator->second);
+            }
+
+            case value_t::array:
+            {
+                assert(m_it.array_iterator != m_object->m_value.array->end());
+                return &*m_it.array_iterator;
+            }
+
+            default:
+            {
+                if (JSON_LIKELY(m_it.primitive_iterator.is_begin()))
+                {
+                    return m_object;
+                }
+
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+            }
+        }
+    }
+
+    /*!
+    @brief post-increment (it++)
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl const operator++(int)
+    {
+        auto result = *this;
+        ++(*this);
+        return result;
+    }
+
+    /*!
+    @brief pre-increment (++it)
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl& operator++()
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                ++m_it.object_iterator;
+                break;
+            }
+
+            case value_t::array:
+            {
+                std::advance(m_it.array_iterator, 1);
+                break;
+            }
+
+            default:
+            {
+                ++m_it.primitive_iterator;
+                break;
+            }
+        }
+
+        return *this;
+    }
+
+    /*!
+    @brief post-decrement (it--)
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl const operator--(int)
+    {
+        auto result = *this;
+        --(*this);
+        return result;
+    }
+
+    /*!
+    @brief pre-decrement (--it)
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl& operator--()
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+            {
+                --m_it.object_iterator;
+                break;
+            }
+
+            case value_t::array:
+            {
+                std::advance(m_it.array_iterator, -1);
+                break;
+            }
+
+            default:
+            {
+                --m_it.primitive_iterator;
+                break;
+            }
+        }
+
+        return *this;
+    }
+
+    /*!
+    @brief  comparison: equal
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator==(const iter_impl& other) const
+    {
+        // if objects are not the same, the comparison is undefined
+        if (JSON_UNLIKELY(m_object != other.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(212, "cannot compare iterators of different containers"));
+        }
+
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                return (m_it.object_iterator == other.m_it.object_iterator);
+
+            case value_t::array:
+                return (m_it.array_iterator == other.m_it.array_iterator);
+
+            default:
+                return (m_it.primitive_iterator == other.m_it.primitive_iterator);
+        }
+    }
+
+    /*!
+    @brief  comparison: not equal
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator!=(const iter_impl& other) const
+    {
+        return not operator==(other);
+    }
+
+    /*!
+    @brief  comparison: smaller
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator<(const iter_impl& other) const
+    {
+        // if objects are not the same, the comparison is undefined
+        if (JSON_UNLIKELY(m_object != other.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(212, "cannot compare iterators of different containers"));
+        }
+
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                JSON_THROW(invalid_iterator::create(213, "cannot compare order of object iterators"));
+
+            case value_t::array:
+                return (m_it.array_iterator < other.m_it.array_iterator);
+
+            default:
+                return (m_it.primitive_iterator < other.m_it.primitive_iterator);
+        }
+    }
+
+    /*!
+    @brief  comparison: less than or equal
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator<=(const iter_impl& other) const
+    {
+        return not other.operator < (*this);
+    }
+
+    /*!
+    @brief  comparison: greater than
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator>(const iter_impl& other) const
+    {
+        return not operator<=(other);
+    }
+
+    /*!
+    @brief  comparison: greater than or equal
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    bool operator>=(const iter_impl& other) const
+    {
+        return not operator<(other);
+    }
+
+    /*!
+    @brief  add to iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl& operator+=(difference_type i)
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                JSON_THROW(invalid_iterator::create(209, "cannot use offsets with object iterators"));
+
+            case value_t::array:
+            {
+                std::advance(m_it.array_iterator, i);
+                break;
+            }
+
+            default:
+            {
+                m_it.primitive_iterator += i;
+                break;
+            }
+        }
+
+        return *this;
+    }
+
+    /*!
+    @brief  subtract from iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl& operator-=(difference_type i)
+    {
+        return operator+=(-i);
+    }
+
+    /*!
+    @brief  add to iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl operator+(difference_type i) const
+    {
+        auto result = *this;
+        result += i;
+        return result;
+    }
+
+    /*!
+    @brief  addition of distance and iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    friend iter_impl operator+(difference_type i, const iter_impl& it)
+    {
+        auto result = it;
+        result += i;
+        return result;
+    }
+
+    /*!
+    @brief  subtract from iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    iter_impl operator-(difference_type i) const
+    {
+        auto result = *this;
+        result -= i;
+        return result;
+    }
+
+    /*!
+    @brief  return difference
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    difference_type operator-(const iter_impl& other) const
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                JSON_THROW(invalid_iterator::create(209, "cannot use offsets with object iterators"));
+
+            case value_t::array:
+                return m_it.array_iterator - other.m_it.array_iterator;
+
+            default:
+                return m_it.primitive_iterator - other.m_it.primitive_iterator;
+        }
+    }
+
+    /*!
+    @brief  access to successor
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    reference operator[](difference_type n) const
+    {
+        assert(m_object != nullptr);
+
+        switch (m_object->m_type)
+        {
+            case value_t::object:
+                JSON_THROW(invalid_iterator::create(208, "cannot use operator[] for object iterators"));
+
+            case value_t::array:
+                return *std::next(m_it.array_iterator, n);
+
+            case value_t::null:
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+
+            default:
+            {
+                if (JSON_LIKELY(m_it.primitive_iterator.get_value() == -n))
+                {
+                    return *m_object;
+                }
+
+                JSON_THROW(invalid_iterator::create(214, "cannot get value"));
+            }
+        }
+    }
+
+    /*!
+    @brief  return the key of an object iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    StringRef key() const
+    {
+        assert(m_object != nullptr);
+
+        if (JSON_LIKELY(m_object->is_object()))
+        {
+            return m_it.object_iterator->first();
+        }
+
+        JSON_THROW(invalid_iterator::create(207, "cannot use key() for non-object iterators"));
+    }
+
+    /*!
+    @brief  return the value of an iterator
+    @pre The iterator is initialized; i.e. `m_object != nullptr`.
+    */
+    reference value() const
+    {
+        return operator*();
+    }
+
+  private:
+    /// associated JSON instance
+    pointer m_object = nullptr;
+    /// the actual iterator of the associated instance
+    internal_iterator<typename std::remove_const<BasicJsonType>::type> m_it;
+};
+
+/// proxy class for the items() function
+template<typename IteratorType> class iteration_proxy
+{
+  private:
+    /// helper class for iteration
+    class iteration_proxy_internal
+    {
+      private:
+        /// the iterator
+        IteratorType anchor;
+        /// an index for arrays (used to create key names)
+        std::size_t array_index = 0;
+
+      public:
+        explicit iteration_proxy_internal(IteratorType it) noexcept : anchor(it) {}
+
+        /// dereference operator (needed for range-based for)
+        iteration_proxy_internal& operator*()
+        {
+            return *this;
+        }
+
+        /// increment operator (needed for range-based for)
+        iteration_proxy_internal& operator++()
+        {
+            ++anchor;
+            ++array_index;
+
+            return *this;
+        }
+
+        /// inequality operator (needed for range-based for)
+        bool operator!=(const iteration_proxy_internal& o) const noexcept
+        {
+            return anchor != o.anchor;
+        }
+
+        /// return key of the iterator
+        std::string key() const
+        {
+            assert(anchor.m_object != nullptr);
+
+            switch (anchor.m_object->type())
+            {
+                // use integer array index as key
+                case value_t::array:
+                    return std::to_string(array_index);
+
+                // use key from the object
+                case value_t::object:
+                    return anchor.key();
+
+                // use an empty key for all primitive types
+                default:
+                    return "";
+            }
+        }
+
+        /// return value of the iterator
+        typename IteratorType::reference value() const
+        {
+            return anchor.value();
+        }
+    };
+
+    /// the container to iterate
+    typename IteratorType::reference container;
+
+  public:
+    /// construct iteration proxy from a container
+    explicit iteration_proxy(typename IteratorType::reference cont) noexcept
+        : container(cont) {}
+
+    /// return iterator begin (needed for range-based for)
+    iteration_proxy_internal begin() noexcept
+    {
+        return iteration_proxy_internal(container.begin());
+    }
+
+    /// return iterator end (needed for range-based for)
+    iteration_proxy_internal end() noexcept
+    {
+        return iteration_proxy_internal(container.end());
+    }
+};
+
+//////////////////////
+// reverse_iterator //
+//////////////////////
+
+/*!
+@brief a template for a reverse iterator class
+
+@tparam Base the base iterator type to reverse. Valid types are @ref
+iterator (to create @ref reverse_iterator) and @ref const_iterator (to
+create @ref const_reverse_iterator).
+
+@requirement The class satisfies the following concept requirements:
+-
+[BidirectionalIterator](http://en.cppreference.com/w/cpp/concept/BidirectionalIterator):
+  The iterator that can be moved can be moved in both directions (i.e.
+  incremented and decremented).
+- [OutputIterator](http://en.cppreference.com/w/cpp/concept/OutputIterator):
+  It is possible to write to the pointed-to element (only if @a Base is
+  @ref iterator).
+
+@since version 1.0.0
+*/
+template<typename Base>
+class json_reverse_iterator : public std::reverse_iterator<Base>
+{
+  public:
+    using difference_type = std::ptrdiff_t;
+    /// shortcut to the reverse iterator adapter
+    using base_iterator = std::reverse_iterator<Base>;
+    /// the reference type for the pointed-to element
+    using reference = typename Base::reference;
+
+    /// create reverse iterator from iterator
+    json_reverse_iterator(const typename base_iterator::iterator_type& it) noexcept
+        : base_iterator(it) {}
+
+    /// create reverse iterator from base class
+    json_reverse_iterator(const base_iterator& it) noexcept : base_iterator(it) {}
+
+    /// post-increment (it++)
+    json_reverse_iterator const operator++(int)
+    {
+        return static_cast<json_reverse_iterator>(base_iterator::operator++(1));
+    }
+
+    /// pre-increment (++it)
+    json_reverse_iterator& operator++()
+    {
+        return static_cast<json_reverse_iterator&>(base_iterator::operator++());
+    }
+
+    /// post-decrement (it--)
+    json_reverse_iterator const operator--(int)
+    {
+        return static_cast<json_reverse_iterator>(base_iterator::operator--(1));
+    }
+
+    /// pre-decrement (--it)
+    json_reverse_iterator& operator--()
+    {
+        return static_cast<json_reverse_iterator&>(base_iterator::operator--());
+    }
+
+    /// add to iterator
+    json_reverse_iterator& operator+=(difference_type i)
+    {
+        return static_cast<json_reverse_iterator&>(base_iterator::operator+=(i));
+    }
+
+    /// add to iterator
+    json_reverse_iterator operator+(difference_type i) const
+    {
+        return static_cast<json_reverse_iterator>(base_iterator::operator+(i));
+    }
+
+    /// subtract from iterator
+    json_reverse_iterator operator-(difference_type i) const
+    {
+        return static_cast<json_reverse_iterator>(base_iterator::operator-(i));
+    }
+
+    /// return difference
+    difference_type operator-(const json_reverse_iterator& other) const
+    {
+        return base_iterator(*this) - base_iterator(other);
+    }
+
+    /// access to successor
+    reference operator[](difference_type n) const
+    {
+        return *(this->operator+(n));
+    }
+
+    /// return the key of an object iterator
+    auto key() const -> decltype(std::declval<Base>().key())
+    {
+        auto it = --this->base();
+        return it.key();
+    }
+
+    /// return the value of an iterator
+    reference value() const
+    {
+        auto it = --this->base();
+        return it.operator * ();
+    }
+};
+
+template<typename BasicJsonType>
+class json_ref
+{
+  public:
+    using value_type = BasicJsonType;
+
+    json_ref(value_type&& value)
+        : owned_value(std::move(value)), value_ref(&owned_value), is_rvalue(true)
+    {}
+
+    json_ref(const value_type& value)
+        : value_ref(const_cast<value_type*>(&value)), is_rvalue(false)
+    {}
+
+    json_ref(std::initializer_list<json_ref> init)
+        : owned_value(init), value_ref(&owned_value), is_rvalue(true)
+    {}
+
+    template<class... Args>
+    json_ref(Args&& ... args)
+        : owned_value(std::forward<Args>(args)...), value_ref(&owned_value), is_rvalue(true)
+    {}
+
+    // class should be movable only
+    json_ref(json_ref&&) = default;
+    json_ref(const json_ref&) = delete;
+    json_ref& operator=(const json_ref&) = delete;
+
+    value_type moved_or_copied() const
+    {
+        if (is_rvalue)
+        {
+            return std::move(*value_ref);
+        }
+        return *value_ref;
+    }
+
+    value_type const& operator*() const
+    {
+        return *static_cast<value_type const*>(value_ref);
+    }
+
+    value_type const* operator->() const
+    {
+        return static_cast<value_type const*>(value_ref);
+    }
+
+  private:
+    mutable value_type owned_value = nullptr;
+    value_type* value_ref = nullptr;
+    const bool is_rvalue;
+};
+}  // namespace detail
+
+class json_pointer
+{
+    // allow json to access private members
+    friend class json;
+    friend class JsonTest;
+
+  public:
+    /*!
+    @brief create JSON pointer
+
+    Create a JSON pointer according to the syntax described in
+    [Section 3 of RFC6901](https://tools.ietf.org/html/rfc6901#section-3).
+
+    @param[in] s  string representing the JSON pointer; if omitted, the empty
+                  string is assumed which references the whole JSON value
+
+    @throw parse_error.107 if the given JSON pointer @a s is nonempty and does
+                           not begin with a slash (`/`); see example below
+
+    @throw parse_error.108 if a tilde (`~`) in the given JSON pointer @a s is
+    not followed by `0` (representing `~`) or `1` (representing `/`); see
+    example below
+
+    @liveexample{The example shows the construction several valid JSON pointers
+    as well as the exceptional behavior.,json_pointer}
+
+    @since version 2.0.0
+    */
+    explicit json_pointer(const Twine& s = {})
+        : reference_tokens(split(s))
+    {}
+
+    /*!
+    @brief return a string representation of the JSON pointer
+
+    @invariant For each JSON pointer `ptr`, it holds:
+    @code {.cpp}
+    ptr == json_pointer(ptr.to_string());
+    @endcode
+
+    @return a string representation of the JSON pointer
+
+    @liveexample{The example shows the result of `to_string`.,
+    json_pointer__to_string}
+
+    @since version 2.0.0
+    */
+    std::string to_string() const noexcept;
+
+    /// @copydoc to_string()
+    operator std::string() const
+    {
+        return to_string();
+    }
+
+    /*!
+    @param[in] s  reference token to be converted into an array index
+
+    @return integer representation of @a s
+
+    @throw out_of_range.404 if string @a s could not be converted to an integer
+    */
+    static int array_index(const Twine& s);
+
+  private:
+    /*!
+    @brief remove and return last reference pointer
+    @throw out_of_range.405 if JSON pointer has no parent
+    */
+    std::string pop_back()
+    {
+        if (JSON_UNLIKELY(is_root()))
+        {
+            JSON_THROW(detail::out_of_range::create(405, "JSON pointer has no parent"));
+        }
+
+        auto last = reference_tokens.back();
+        reference_tokens.pop_back();
+        return last;
+    }
+
+    /// return whether pointer points to the root document
+    bool is_root() const
+    {
+        return reference_tokens.empty();
+    }
+
+    json_pointer top() const
+    {
+        if (JSON_UNLIKELY(is_root()))
+        {
+            JSON_THROW(detail::out_of_range::create(405, "JSON pointer has no parent"));
+        }
+
+        json_pointer result = *this;
+        result.reference_tokens = {reference_tokens[0]};
+        return result;
+    }
+
+    /*!
+    @brief create and return a reference to the pointed to value
+
+    @complexity Linear in the number of reference tokens.
+
+    @throw parse_error.109 if array index is not a number
+    @throw type_error.313 if value cannot be unflattened
+    */
+    json& get_and_create(json& j) const;
+
+    /*!
+    @brief return a reference to the pointed to value
+
+    @note This version does not throw if a value is not present, but tries to
+          create nested values instead. For instance, calling this function
+          with pointer `"/this/that"` on a null value is equivalent to calling
+          `operator[]("this").operator[]("that")` on that value, effectively
+          changing the null value to an object.
+
+    @param[in] ptr  a JSON value
+
+    @return reference to the JSON value pointed to by the JSON pointer
+
+    @complexity Linear in the length of the JSON pointer.
+
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+    */
+    json& get_unchecked(json* ptr) const;
+
+    /*!
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.402  if the array index '-' is used
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+    */
+    json& get_checked(json* ptr) const;
+
+    /*!
+    @brief return a const reference to the pointed to value
+
+    @param[in] ptr  a JSON value
+
+    @return const reference to the JSON value pointed to by the JSON
+    pointer
+
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.402  if the array index '-' is used
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+    */
+    const json& get_unchecked(const json* ptr) const;
+
+    /*!
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.402  if the array index '-' is used
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+    */
+    const json& get_checked(const json* ptr) const;
+
+    /*!
+    @brief split the string input to reference tokens
+
+    @note This function is only called by the json_pointer constructor.
+          All exceptions below are documented there.
+
+    @throw parse_error.107  if the pointer is not empty or begins with '/'
+    @throw parse_error.108  if character '~' is not followed by '0' or '1'
+    */
+    static std::vector<std::string> split(const Twine& reference_string);
+
+    /*!
+    @brief replace all occurrences of a substring by another string
+
+    @param[in,out] s  the string to manipulate; changed so that all
+                   occurrences of @a f are replaced with @a t
+    @param[in]     f  the substring to replace with @a t
+    @param[in]     t  the string to replace @a f
+
+    @pre The search string @a f must not be empty. **This precondition is
+    enforced with an assertion.**
+
+    @since version 2.0.0
+    */
+    static void replace_substring(std::string& s, const std::string& f,
+                                  const std::string& t);
+
+    /// escape "~"" to "~0" and "/" to "~1"
+    static std::string escape(std::string s);
+
+    /// unescape "~1" to tilde and "~0" to slash (order is important!)
+    static void unescape(std::string& s);
+
+    /*!
+    @param[in] reference_string  the reference string to the current value
+    @param[in] value             the value to consider
+    @param[in,out] result        the result object to insert values to
+
+    @note Empty objects or arrays are flattened to `null`.
+    */
+    static void flatten(const Twine& reference_string,
+                        const json& value,
+                        json& result);
+
+    /*!
+    @param[in] value  flattened JSON
+
+    @return unflattened JSON
+
+    @throw parse_error.109 if array index is not a number
+    @throw type_error.314  if value is not an object
+    @throw type_error.315  if object values are not primitive
+    @throw type_error.313  if value cannot be unflattened
+    */
+    static json
+    unflatten(const json& value);
+
+    friend bool operator==(json_pointer const& lhs,
+                           json_pointer const& rhs) noexcept
+    {
+        return (lhs.reference_tokens == rhs.reference_tokens);
+    }
+
+    friend bool operator!=(json_pointer const& lhs,
+                           json_pointer const& rhs) noexcept
+    {
+        return not (lhs == rhs);
+    }
+
+    /// the reference tokens
+    std::vector<std::string> reference_tokens;
+};
+
+template<typename, typename>
+struct adl_serializer
+{
+    /*!
+    @brief convert a JSON value to any value type
+
+    This function is usually called by the `get()` function of the
+    @ref json class (either explicit or via conversion operators).
+
+    @param[in] j         JSON value to read from
+    @param[in,out] val  value to write to
+    */
+    template<typename BasicJsonType, typename ValueType>
+    static void from_json(BasicJsonType&& j, ValueType& val) noexcept(
+        noexcept(::wpi::from_json(std::forward<BasicJsonType>(j), val)))
+    {
+        ::wpi::from_json(std::forward<BasicJsonType>(j), val);
+    }
+
+    /*!
+    @brief convert any value type to a JSON value
+
+    This function is usually called by the constructors of the @ref json
+    class.
+
+    @param[in,out] j  JSON value to write to
+    @param[in] val     value to read from
+    */
+    template<typename BasicJsonType, typename ValueType>
+    static void to_json(BasicJsonType& j, ValueType&& val) noexcept(
+        noexcept(::wpi::to_json(j, std::forward<ValueType>(val))))
+    {
+        ::wpi::to_json(j, std::forward<ValueType>(val));
+    }
+};
+
+/*!
+@brief a class to store JSON values
+
+@requirement The class satisfies the following concept requirements:
+- Basic
+ - [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible):
+   JSON values can be default constructed. The result will be a JSON null
+   value.
+ - [MoveConstructible](http://en.cppreference.com/w/cpp/concept/MoveConstructible):
+   A JSON value can be constructed from an rvalue argument.
+ - [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible):
+   A JSON value can be copy-constructed from an lvalue expression.
+ - [MoveAssignable](http://en.cppreference.com/w/cpp/concept/MoveAssignable):
+   A JSON value van be assigned from an rvalue argument.
+ - [CopyAssignable](http://en.cppreference.com/w/cpp/concept/CopyAssignable):
+   A JSON value can be copy-assigned from an lvalue expression.
+ - [Destructible](http://en.cppreference.com/w/cpp/concept/Destructible):
+   JSON values can be destructed.
+- Layout
+ - [StandardLayoutType](http://en.cppreference.com/w/cpp/concept/StandardLayoutType):
+   JSON values have
+   [standard layout](http://en.cppreference.com/w/cpp/language/data_members#Standard_layout):
+   All non-static data members are private and standard layout types, the
+   class has no virtual functions or (virtual) base classes.
+- Library-wide
+ - [EqualityComparable](http://en.cppreference.com/w/cpp/concept/EqualityComparable):
+   JSON values can be compared with `==`, see @ref
+   operator==(const_reference,const_reference).
+ - [LessThanComparable](http://en.cppreference.com/w/cpp/concept/LessThanComparable):
+   JSON values can be compared with `<`, see @ref
+   operator<(const_reference,const_reference).
+ - [Swappable](http://en.cppreference.com/w/cpp/concept/Swappable):
+   Any JSON lvalue or rvalue of can be swapped with any lvalue or rvalue of
+   other compatible types, using unqualified function call @ref swap().
+ - [NullablePointer](http://en.cppreference.com/w/cpp/concept/NullablePointer):
+   JSON values can be compared against `std::nullptr_t` objects which are used
+   to model the `null` value.
+- Container
+ - [Container](http://en.cppreference.com/w/cpp/concept/Container):
+   JSON values can be used like STL containers and provide iterator access.
+ - [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer);
+   JSON values can be used like STL containers and provide reverse iterator
+   access.
+
+@invariant The member variables @a m_value and @a m_type have the following
+relationship:
+- If `m_type == value_t::object`, then `m_value.object != nullptr`.
+- If `m_type == value_t::array`, then `m_value.array != nullptr`.
+- If `m_type == value_t::string`, then `m_value.string != nullptr`.
+The invariants are checked by member function assert_invariant().
+
+@internal
+@note ObjectType trick from http://stackoverflow.com/a/9860911
+@endinternal
+
+@see [RFC 7159: The JavaScript Object Notation (JSON) Data Interchange
+Format](http://rfc7159.net/rfc7159)
+
+@since version 1.0.0
+
+@nosubgrouping
+*/
+class json
+{
+  private:
+    template<detail::value_t> friend struct detail::external_constructor;
+    friend ::wpi::json_pointer;
+    template<typename BasicJsonType>
+    friend class ::wpi::detail::iter_impl;
+    friend class JsonTest;
+
+    /// workaround type for MSVC
+    using json_t = json;
+
+    // convenience aliases for types residing in namespace detail;
+    using primitive_iterator_t = ::wpi::detail::primitive_iterator_t;
+    template<typename BasicJsonType>
+    using internal_iterator = ::wpi::detail::internal_iterator<BasicJsonType>;
+    template<typename BasicJsonType>
+    using iter_impl = ::wpi::detail::iter_impl<BasicJsonType>;
+    template<typename Iterator>
+    using iteration_proxy = ::wpi::detail::iteration_proxy<Iterator>;
+    template<typename Base> using json_reverse_iterator = ::wpi::detail::json_reverse_iterator<Base>;
+
+    class binary_reader;
+    class binary_writer;
+    class lexer;
+    class parser;
+    class serializer;
+
+  public:
+    using value_t = detail::value_t;
+    /// @copydoc wpi::json_pointer
+    using json_pointer = ::wpi::json_pointer;
+    template<typename T, typename SFINAE>
+    using json_serializer = adl_serializer<T, SFINAE>;
+    /// helper type for initializer lists of json values
+    using initializer_list_t = std::initializer_list<detail::json_ref<json>>;
+
+    ////////////////
+    // exceptions //
+    ////////////////
+
+    /// @name exceptions
+    /// Classes to implement user-defined exceptions.
+    /// @{
+
+    /// @copydoc detail::exception
+    using exception = detail::exception;
+    /// @copydoc detail::parse_error
+    using parse_error = detail::parse_error;
+    /// @copydoc detail::invalid_iterator
+    using invalid_iterator = detail::invalid_iterator;
+    /// @copydoc detail::type_error
+    using type_error = detail::type_error;
+    /// @copydoc detail::out_of_range
+    using out_of_range = detail::out_of_range;
+    /// @copydoc detail::other_error
+    using other_error = detail::other_error;
+
+    /// @}
+
+
+    /////////////////////
+    // container types //
+    /////////////////////
+
+    /// @name container types
+    /// The canonic container types to use @ref json like any other STL
+    /// container.
+    /// @{
+
+    /// the type of elements in a json container
+    using value_type = json;
+
+    /// the type of an element reference
+    using reference = value_type&;
+    /// the type of an element const reference
+    using const_reference = const value_type&;
+
+    /// a type to represent differences between iterators
+    using difference_type = std::ptrdiff_t;
+    /// a type to represent container sizes
+    using size_type = std::size_t;
+
+    /// the allocator type
+    using allocator_type = std::allocator<json>;
+
+    /// the type of an element pointer
+    using pointer = json*;
+    /// the type of an element const pointer
+    using const_pointer = const json*;
+
+    /// an iterator for a json container
+    using iterator = iter_impl<json>;
+    /// a const iterator for a json container
+    using const_iterator = iter_impl<const json>;
+    /// a reverse iterator for a json container
+    using reverse_iterator = json_reverse_iterator<typename json::iterator>;
+    /// a const reverse iterator for a json container
+    using const_reverse_iterator = json_reverse_iterator<typename json::const_iterator>;
+
+    /// @}
+
+
+    /*!
+    @brief returns the allocator associated with the container
+    */
+    static allocator_type get_allocator()
+    {
+        return allocator_type();
+    }
+
+    /*!
+    @brief returns version information on the library
+
+    This function returns a JSON object with information about the library,
+    including the version number and information on the platform and compiler.
+
+    @return JSON object holding version information
+    key         | description
+    ----------- | ---------------
+    `compiler`  | Information on the used compiler. It is an object with the following keys: `c++` (the used C++ standard), `family` (the compiler family; possible values are `clang`, `icc`, `gcc`, `ilecpp`, `msvc`, `pgcpp`, `sunpro`, and `unknown`), and `version` (the compiler version).
+    `copyright` | The copyright line for the library as string.
+    `name`      | The name of the library as string.
+    `platform`  | The used platform as string. Possible values are `win32`, `linux`, `apple`, `unix`, and `unknown`.
+    `url`       | The URL of the project as string.
+    `version`   | The version of the library. It is an object with the following keys: `major`, `minor`, and `patch` as defined by [Semantic Versioning](http://semver.org), and `string` (the version string).
+
+    @liveexample{The following code shows an example output of the `meta()`
+    function.,meta}
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @complexity Constant.
+
+    @since 2.1.0
+    */
+    static json meta();
+
+
+    ///////////////////////////
+    // JSON value data types //
+    ///////////////////////////
+
+    /// @name JSON value data types
+    /// The data types to store a JSON value. These types are derived from
+    /// the template arguments passed to class @ref json.
+    /// @{
+
+#if defined(JSON_HAS_CPP_14)
+    // Use transparent comparator if possible, combined with perfect forwarding
+    // on find() and count() calls prevents unnecessary string construction.
+    using object_comparator_t = std::less<>;
+#else
+    using object_comparator_t = std::less<std::string>;
+#endif
+
+    /*!
+    @brief a type for an object
+
+    [RFC 7159](http://rfc7159.net/rfc7159) describes JSON objects as follows:
+    > An object is an unordered collection of zero or more name/value pairs,
+    > where a name is a string and a value is a string, number, boolean, null,
+    > object, or array.
+
+    #### Behavior
+
+    The choice of @a object_t influences the behavior of the JSON class. With
+    the default type, objects have the following behavior:
+
+    - When all names are unique, objects will be interoperable in the sense
+      that all software implementations receiving that object will agree on
+      the name-value mappings.
+    - When the names within an object are not unique, it is unspecified which
+      one of the values for a given key will be chosen. For instance,
+      `{"key": 2, "key": 1}` could be equal to either `{"key": 1}` or
+      `{"key": 2}`.
+    - Internally, name/value pairs are stored in lexicographical order of the
+      names. Objects will also be serialized (see @ref dump) in this order.
+      For instance, `{"b": 1, "a": 2}` and `{"a": 2, "b": 1}` will be stored
+      and serialized as `{"a": 2, "b": 1}`.
+    - When comparing objects, the order of the name/value pairs is irrelevant.
+      This makes objects interoperable in the sense that they will not be
+      affected by these differences. For instance, `{"b": 1, "a": 2}` and
+      `{"a": 2, "b": 1}` will be treated as equal.
+
+    #### Limits
+
+    [RFC 7159](http://rfc7159.net/rfc7159) specifies:
+    > An implementation may set limits on the maximum depth of nesting.
+
+    In this class, the object's limit of nesting is not explicitly constrained.
+    However, a maximum depth of nesting may be introduced by the compiler or
+    runtime environment. A theoretical limit can be queried by calling the
+    @ref max_size function of a JSON object.
+
+    #### Storage
+
+    Objects are stored as pointers in a @ref json type. That is, for any
+    access to object values, a pointer of type `object_t*` must be
+    dereferenced.
+
+    @since version 1.0.0
+
+    @note The order name/value pairs are added to the object is *not*
+    preserved by the library. Therefore, iterating an object may return
+    name/value pairs in a different order than they were originally stored. In
+    fact, keys will be traversed in alphabetical order as `std::map` with
+    `std::less` is used by default. Please note this behavior conforms to [RFC
+    7159](http://rfc7159.net/rfc7159), because any order implements the
+    specified "unordered" nature of JSON objects.
+    */
+    using object_t = StringMap<json>;
+
+    /*!
+    @brief a type for an array
+
+    [RFC 7159](http://rfc7159.net/rfc7159) describes JSON arrays as follows:
+    > An array is an ordered sequence of zero or more values.
+
+    #### Limits
+
+    [RFC 7159](http://rfc7159.net/rfc7159) specifies:
+    > An implementation may set limits on the maximum depth of nesting.
+
+    In this class, the array's limit of nesting is not explicitly constrained.
+    However, a maximum depth of nesting may be introduced by the compiler or
+    runtime environment. A theoretical limit can be queried by calling the
+    @ref max_size function of a JSON array.
+
+    #### Storage
+
+    Arrays are stored as pointers in a @ref json type. That is, for any
+    access to array values, a pointer of type `array_t*` must be dereferenced.
+
+    @sa @ref object_t -- type for an object value
+
+    @since version 1.0.0
+    */
+    using array_t = std::vector<json>;
+
+    /// @}
+
+  private:
+
+    /// helper for exception-safe object creation
+    template<typename T, typename... Args>
+    static T* create(Args&& ... args)
+    {
+        std::allocator<T> alloc;
+
+        auto deleter = [&](T * object)
+        {
+            alloc.deallocate(object, 1);
+        };
+        std::unique_ptr<T, decltype(deleter)> object(alloc.allocate(1), deleter);
+        alloc.construct(object.get(), std::forward<Args>(args)...);
+        assert(object != nullptr);
+        return object.release();
+    }
+
+    ////////////////////////
+    // JSON value storage //
+    ////////////////////////
+
+    /*!
+    @brief a JSON value
+
+    The actual storage for a JSON value of the @ref json class. This
+    union combines the different storage types for the JSON value types
+    defined in @ref value_t.
+
+    JSON type | value_t type    | used type
+    --------- | --------------- | ------------------------
+    object    | object          | pointer to @ref object_t
+    array     | array           | pointer to @ref array_t
+    string    | string          | pointer to std::string
+    boolean   | boolean         | bool
+    number    | number_integer  | int64_t
+    number    | number_unsigned | uint64_t
+    number    | number_float    | double
+    null      | null            | *no value is stored*
+
+    @note Variable-length types (objects, arrays, and strings) are stored as
+    pointers. The size of the union should not exceed 64 bits if the default
+    value types are used.
+
+    @since version 1.0.0
+    */
+    union json_value
+    {
+        /// object (stored with pointer to save storage)
+        object_t* object;
+        /// array (stored with pointer to save storage)
+        array_t* array;
+        /// string (stored with pointer to save storage)
+        std::string* string;
+        /// boolean
+        bool boolean;
+        /// number (integer)
+        int64_t number_integer;
+        /// number (unsigned integer)
+        uint64_t number_unsigned;
+        /// number (floating-point)
+        double number_float;
+
+        /// default constructor (for null values)
+        json_value() = default;
+        /// constructor for booleans
+        json_value(bool v) noexcept : boolean(v) {}
+        /// constructor for numbers (integer)
+        json_value(int64_t v) noexcept : number_integer(v) {}
+        /// constructor for numbers (unsigned)
+        json_value(uint64_t v) noexcept : number_unsigned(v) {}
+        /// constructor for numbers (floating-point)
+        json_value(double v) noexcept : number_float(v) {}
+        /// constructor for empty values of a given type
+        json_value(value_t t);
+
+        /// constructor for strings
+        json_value(StringRef value)
+        {
+            string = create<std::string>(value);
+        }
+
+        /// constructor for strings
+        json_value(const std::string& value)
+        {
+            string = create<std::string>(value);
+        }
+
+        /// constructor for rvalue strings
+        json_value(std::string&& value)
+        {
+            string = create<std::string>(std::move(value));
+        }
+
+        /// constructor for objects
+        json_value(const object_t& value)
+        {
+            object = create<object_t>(value);
+        }
+
+        /// constructor for rvalue objects
+        json_value(object_t&& value)
+        {
+            object = create<object_t>(std::move(value));
+        }
+
+        /// constructor for arrays
+        json_value(const array_t& value)
+        {
+            array = create<array_t>(value);
+        }
+
+        /// constructor for rvalue arrays
+        json_value(array_t&& value)
+        {
+            array = create<array_t>(std::move(value));
+        }
+
+        void destroy(value_t t) noexcept;
+    };
+
+    /*!
+    @brief checks the class invariants
+
+    This function asserts the class invariants. It needs to be called at the
+    end of every constructor to make sure that created objects respect the
+    invariant. Furthermore, it has to be called each time the type of a JSON
+    value is changed, because the invariant expresses a relationship between
+    @a m_type and @a m_value.
+    */
+    void assert_invariant() const noexcept
+    {
+        assert(m_type != value_t::object or m_value.object != nullptr);
+        assert(m_type != value_t::array or m_value.array != nullptr);
+        assert(m_type != value_t::string or m_value.string != nullptr);
+    }
+
+  public:
+    //////////////////////////
+    // JSON parser callback //
+    //////////////////////////
+
+    /*!
+    @brief parser event types
+
+    The parser callback distinguishes the following events:
+    - `object_start`: the parser read `{` and started to process a JSON object
+    - `key`: the parser read a key of a value in an object
+    - `object_end`: the parser read `}` and finished processing a JSON object
+    - `array_start`: the parser read `[` and started to process a JSON array
+    - `array_end`: the parser read `]` and finished processing a JSON array
+    - `value`: the parser finished reading a JSON value
+
+    @image html callback_events.png "Example when certain parse events are triggered"
+
+    @sa @ref parser_callback_t for more information and examples
+    */
+    enum class parse_event_t : uint8_t
+    {
+        /// the parser read `{` and started to process a JSON object
+        object_start,
+        /// the parser read `}` and finished processing a JSON object
+        object_end,
+        /// the parser read `[` and started to process a JSON array
+        array_start,
+        /// the parser read `]` and finished processing a JSON array
+        array_end,
+        /// the parser read a key of a value in an object
+        key,
+        /// the parser finished reading a JSON value
+        value
+    };
+
+    /*!
+    @brief per-element parser callback type
+
+    With a parser callback function, the result of parsing a JSON text can be
+    influenced. When passed to @ref parse, it is called on certain events
+    (passed as @ref parse_event_t via parameter @a event) with a set recursion
+    depth @a depth and context JSON value @a parsed. The return value of the
+    callback function is a boolean indicating whether the element that emitted
+    the callback shall be kept or not.
+
+    We distinguish six scenarios (determined by the event type) in which the
+    callback function can be called. The following table describes the values
+    of the parameters @a depth, @a event, and @a parsed.
+
+    parameter @a event | description | parameter @a depth | parameter @a parsed
+    ------------------ | ----------- | ------------------ | -------------------
+    parse_event_t::object_start | the parser read `{` and started to process a JSON object | depth of the parent of the JSON object | a JSON value with type discarded
+    parse_event_t::key | the parser read a key of a value in an object | depth of the currently parsed JSON object | a JSON string containing the key
+    parse_event_t::object_end | the parser read `}` and finished processing a JSON object | depth of the parent of the JSON object | the parsed JSON object
+    parse_event_t::array_start | the parser read `[` and started to process a JSON array | depth of the parent of the JSON array | a JSON value with type discarded
+    parse_event_t::array_end | the parser read `]` and finished processing a JSON array | depth of the parent of the JSON array | the parsed JSON array
+    parse_event_t::value | the parser finished reading a JSON value | depth of the value | the parsed JSON value
+
+    @image html callback_events.png "Example when certain parse events are triggered"
+
+    Discarding a value (i.e., returning `false`) has different effects
+    depending on the context in which function was called:
+
+    - Discarded values in structured types are skipped. That is, the parser
+      will behave as if the discarded value was never read.
+    - In case a value outside a structured type is skipped, it is replaced
+      with `null`. This case happens if the top-level element is skipped.
+
+    @param[in] depth  the depth of the recursion during parsing
+
+    @param[in] event  an event of type parse_event_t indicating the context in
+    the callback function has been called
+
+    @param[in,out] parsed  the current intermediate parse result; note that
+    writing to this value has no effect for parse_event_t::key events
+
+    @return Whether the JSON value which called the function during parsing
+    should be kept (`true`) or not (`false`). In the latter case, it is either
+    skipped completely or replaced by an empty discarded object.
+
+    @sa @ref parse for examples
+
+    @since version 1.0.0
+    */
+    using parser_callback_t =
+        std::function<bool(int depth, parse_event_t event, json& parsed)>;
+
+
+    //////////////////
+    // constructors //
+    //////////////////
+
+    /// @name constructors and destructors
+    /// Constructors of class @ref json, copy/move constructor, copy
+    /// assignment, static functions creating objects, and the destructor.
+    /// @{
+
+    /*!
+    @brief create an empty value with a given type
+
+    Create an empty JSON value with a given type. The value will be default
+    initialized with an empty value which depends on the type:
+
+    Value type  | initial value
+    ----------- | -------------
+    null        | `null`
+    boolean     | `false`
+    string      | `""`
+    number      | `0`
+    object      | `{}`
+    array       | `[]`
+
+    @param[in] v  the type of the value to create
+
+    @complexity Constant.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The following code shows the constructor for different @ref
+    value_t values,json__value_t}
+
+    @sa @ref clear() -- restores the postcondition of this constructor
+
+    @since version 1.0.0
+    */
+    json(const value_t v)
+        : m_type(v), m_value(v)
+    {
+        assert_invariant();
+    }
+
+    /*!
+    @brief create a null object
+
+    Create a `null` JSON value. It either takes a null pointer as parameter
+    (explicitly creating `null`) or no parameter (implicitly creating `null`).
+    The passed null pointer itself is not read -- it is only used to choose
+    the right constructor.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this constructor never throws
+    exceptions.
+
+    @liveexample{The following code shows the constructor with and without a
+    null pointer parameter.,json__nullptr_t}
+
+    @since version 1.0.0
+    */
+    json(std::nullptr_t = nullptr) noexcept
+        : json(value_t::null)
+    {
+        assert_invariant();
+    }
+
+    /*!
+    @brief create a JSON value
+
+    This is a "catch all" constructor for all compatible JSON types; that is,
+    types for which a `to_json()` method exists. The constructor forwards the
+    parameter @a val to that method (to `json_serializer<U>::to_json` method
+    with `U = uncvref_t<CompatibleType>`, to be exact).
+
+    Template type @a CompatibleType includes, but is not limited to, the
+    following types:
+    - **arrays**: @ref array_t and all kinds of compatible containers such as
+      `std::vector`, `std::deque`, `std::list`,
+      `std::array`, `std::set`, `std::unordered_set`,
+      `std::multiset`, and `std::unordered_multiset` with a `value_type` from
+      which a @ref json value can be constructed.
+    - **objects**: @ref object_t and all kinds of compatible associative
+      containers such as `std::map`, `std::unordered_map`, `std::multimap`,
+      and `std::unordered_multimap` with a `key_type` compatible to
+      `std::string` and a `value_type` from which a @ref json value can
+      be constructed.
+    - **strings**: `std::string`, string literals, and all compatible string
+      containers can be used.
+    - **numbers**: int64_t, uint64_t,
+      double, and all convertible number types such as `int`,
+      `size_t`, `int64_t`, `float` or `double` can be used.
+    - **boolean**: `bool` can be used.
+
+    See the examples below.
+
+    @tparam CompatibleType a type such that:
+    - @a CompatibleType is not derived from `std::istream`,
+    - @a CompatibleType is not @ref json (to avoid hijacking copy/move
+         constructors),
+    - @a CompatibleType is not a different @ref json type (i.e. with different template arguments)
+    - @a CompatibleType is not a @ref json nested type (e.g.,
+         @ref json_pointer, @ref iterator, etc ...)
+    - @ref @ref json_serializer<U> has a
+         `to_json(json_t&, CompatibleType&&)` method
+
+    @tparam U = `uncvref_t<CompatibleType>`
+
+    @param[in] val the value to be forwarded to the respective constructor
+
+    @complexity Usually linear in the size of the passed @a val, also
+                depending on the implementation of the called `to_json()`
+                method.
+
+    @exceptionsafety Depends on the called constructor. For types directly
+    supported by the library (i.e., all types for which no `to_json()` function
+    was provided), strong guarantee holds: if an exception is thrown, there are
+    no changes to any JSON value.
+
+    @liveexample{The following code shows the constructor with several
+    compatible types.,json__CompatibleType}
+
+    @since version 2.1.0
+    */
+    template <typename CompatibleType,
+              typename U = detail::uncvref_t<CompatibleType>,
+              detail::enable_if_t<
+                  detail::is_compatible_type<json_t, U>::value, int> = 0>
+    json(CompatibleType && val) noexcept(noexcept(
+                adl_serializer<U, void>::to_json(std::declval<json_t&>(),
+                                           std::forward<CompatibleType>(val))))
+    {
+        adl_serializer<U, void>::to_json(*this, std::forward<CompatibleType>(val));
+        assert_invariant();
+    }
+
+    /*!
+    @brief create a container (array or object) from an initializer list
+
+    Creates a JSON value of type array or object from the passed initializer
+    list @a init. In case @a type_deduction is `true` (default), the type of
+    the JSON value to be created is deducted from the initializer list @a init
+    according to the following rules:
+
+    1. If the list is empty, an empty JSON object value `{}` is created.
+    2. If the list consists of pairs whose first element is a string, a JSON
+       object value is created where the first elements of the pairs are
+       treated as keys and the second elements are as values.
+    3. In all other cases, an array is created.
+
+    The rules aim to create the best fit between a C++ initializer list and
+    JSON values. The rationale is as follows:
+
+    1. The empty initializer list is written as `{}` which is exactly an empty
+       JSON object.
+    2. C++ has no way of describing mapped types other than to list a list of
+       pairs. As JSON requires that keys must be of type string, rule 2 is the
+       weakest constraint one can pose on initializer lists to interpret them
+       as an object.
+    3. In all other cases, the initializer list could not be interpreted as
+       JSON object type, so interpreting it as JSON array type is safe.
+
+    With the rules described above, the following JSON values cannot be
+    expressed by an initializer list:
+
+    - the empty array (`[]`): use @ref array(initializer_list_t)
+      with an empty initializer list in this case
+    - arrays whose elements satisfy rule 2: use @ref
+      array(initializer_list_t) with the same initializer list
+      in this case
+
+    @note When used without parentheses around an empty initializer list, @ref
+    json() is called instead of this function, yielding the JSON null
+    value.
+
+    @param[in] init  initializer list with JSON values
+
+    @param[in] type_deduction internal parameter; when set to `true`, the type
+    of the JSON value is deducted from the initializer list @a init; when set
+    to `false`, the type provided via @a manual_type is forced. This mode is
+    used by the functions @ref array(initializer_list_t) and
+    @ref object(initializer_list_t).
+
+    @param[in] manual_type internal parameter; when @a type_deduction is set
+    to `false`, the created JSON value will use the provided type (only @ref
+    value_t::array and @ref value_t::object are valid); when @a type_deduction
+    is set to `true`, this parameter has no effect
+
+    @throw type_error.301 if @a type_deduction is `false`, @a manual_type is
+    `value_t::object`, but @a init contains an element which is not a pair
+    whose first element is a string. In this case, the constructor could not
+    create an object. If @a type_deduction would have be `true`, an array
+    would have been created. See @ref object(initializer_list_t)
+    for an example.
+
+    @complexity Linear in the size of the initializer list @a init.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The example below shows how JSON values are created from
+    initializer lists.,json__list_init_t}
+
+    @sa @ref array(initializer_list_t) -- create a JSON array
+    value from an initializer list
+    @sa @ref object(initializer_list_t) -- create a JSON object
+    value from an initializer list
+
+    @since version 1.0.0
+    */
+    json(initializer_list_t init,
+               bool type_deduction = true,
+               value_t manual_type = value_t::array);
+
+    /*!
+    @brief explicitly create an array from an initializer list
+
+    Creates a JSON array value from a given initializer list. That is, given a
+    list of values `a, b, c`, creates the JSON value `[a, b, c]`. If the
+    initializer list is empty, the empty array `[]` is created.
+
+    @note This function is only needed to express two edge cases that cannot
+    be realized with the initializer list constructor (@ref
+    json(initializer_list_t, bool, value_t)). These cases
+    are:
+    1. creating an array whose elements are all pairs whose first element is a
+    string -- in this case, the initializer list constructor would create an
+    object, taking the first elements as keys
+    2. creating an empty array -- passing the empty initializer list to the
+    initializer list constructor yields an empty object
+
+    @param[in] init  initializer list with JSON values to create an array from
+    (optional)
+
+    @return JSON array value
+
+    @complexity Linear in the size of @a init.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The following code shows an example for the `array`
+    function.,array}
+
+    @sa @ref json(initializer_list_t, bool, value_t) --
+    create a JSON value from an initializer list
+    @sa @ref object(initializer_list_t) -- create a JSON object
+    value from an initializer list
+
+    @since version 1.0.0
+    */
+    static json array(initializer_list_t init = {})
+    {
+        return json(init, false, value_t::array);
+    }
+
+    /*!
+    @brief explicitly create an object from an initializer list
+
+    Creates a JSON object value from a given initializer list. The initializer
+    lists elements must be pairs, and their first elements must be strings. If
+    the initializer list is empty, the empty object `{}` is created.
+
+    @note This function is only added for symmetry reasons. In contrast to the
+    related function @ref array(initializer_list_t), there are
+    no cases which can only be expressed by this function. That is, any
+    initializer list @a init can also be passed to the initializer list
+    constructor @ref json(initializer_list_t, bool, value_t).
+
+    @param[in] init  initializer list to create an object from (optional)
+
+    @return JSON object value
+
+    @throw type_error.301 if @a init is not a list of pairs whose first
+    elements are strings. In this case, no object can be created. When such a
+    value is passed to @ref json(initializer_list_t, bool, value_t),
+    an array would have been created from the passed initializer list @a init.
+    See example below.
+
+    @complexity Linear in the size of @a init.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The following code shows an example for the `object`
+    function.,object}
+
+    @sa @ref json(initializer_list_t, bool, value_t) --
+    create a JSON value from an initializer list
+    @sa @ref array(initializer_list_t) -- create a JSON array
+    value from an initializer list
+
+    @since version 1.0.0
+    */
+    static json object(initializer_list_t init = {})
+    {
+        return json(init, false, value_t::object);
+    }
+
+    /*!
+    @brief construct an array with count copies of given value
+
+    Constructs a JSON array value by creating @a cnt copies of a passed value.
+    In case @a cnt is `0`, an empty array is created.
+
+    @param[in] cnt  the number of JSON copies of @a val to create
+    @param[in] val  the JSON value to copy
+
+    @post `std::distance(begin(),end()) == cnt` holds.
+
+    @complexity Linear in @a cnt.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The following code shows examples for the @ref
+    json(size_type\, const json&)
+    constructor.,json__size_type_json}
+
+    @since version 1.0.0
+    */
+    json(size_type cnt, const json& val);
+
+    /*!
+    @brief construct a JSON container given an iterator range
+
+    Constructs the JSON value with the contents of the range `[first, last)`.
+    The semantics depends on the different types a JSON value can have:
+    - In case of a null type, invalid_iterator.206 is thrown.
+    - In case of other primitive types (number, boolean, or string), @a first
+      must be `begin()` and @a last must be `end()`. In this case, the value is
+      copied. Otherwise, invalid_iterator.204 is thrown.
+    - In case of structured types (array, object), the constructor behaves as
+      similar versions for `std::vector` or `std::map`; that is, a JSON array
+      or object is constructed from the values in the range.
+
+    @tparam InputIT an input iterator type (@ref iterator or @ref
+    const_iterator)
+
+    @param[in] first begin of the range to copy from (included)
+    @param[in] last end of the range to copy from (excluded)
+
+    @pre Iterators @a first and @a last must be initialized. **This
+         precondition is enforced with an assertion (see warning).** If
+         assertions are switched off, a violation of this precondition yields
+         undefined behavior.
+
+    @pre Range `[first, last)` is valid. Usually, this precondition cannot be
+         checked efficiently. Only certain edge cases are detected; see the
+         description of the exceptions below. A violation of this precondition
+         yields undefined behavior.
+
+    @warning A precondition is enforced with a runtime assertion that will
+             result in calling `std::abort` if this precondition is not met.
+             Assertions can be disabled by defining `NDEBUG` at compile time.
+             See http://en.cppreference.com/w/cpp/error/assert for more
+             information.
+
+    @throw invalid_iterator.201 if iterators @a first and @a last are not
+    compatible (i.e., do not belong to the same JSON value). In this case,
+    the range `[first, last)` is undefined.
+    @throw invalid_iterator.204 if iterators @a first and @a last belong to a
+    primitive type (number, boolean, or string), but @a first does not point
+    to the first element any more. In this case, the range `[first, last)` is
+    undefined. See example code below.
+    @throw invalid_iterator.206 if iterators @a first and @a last belong to a
+    null value. In this case, the range `[first, last)` is undefined.
+
+    @complexity Linear in distance between @a first and @a last.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @liveexample{The example below shows several ways to create JSON values by
+    specifying a subrange with iterators.,json__InputIt_InputIt}
+
+    @since version 1.0.0
+    */
+    template<class InputIT, typename std::enable_if<
+                 std::is_same<InputIT, typename json_t::iterator>::value or
+                 std::is_same<InputIT, typename json_t::const_iterator>::value, int>::type = 0>
+    json(InputIT first, InputIT last)
+    {
+        assert(first.m_object != nullptr);
+        assert(last.m_object != nullptr);
+
+        // make sure iterator fits the current value
+        if (JSON_UNLIKELY(first.m_object != last.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(201, "iterators are not compatible"));
+        }
+
+        // copy type from first iterator
+        m_type = first.m_object->m_type;
+
+        // check if iterator range is complete for primitive values
+        switch (m_type)
+        {
+            case value_t::boolean:
+            case value_t::number_float:
+            case value_t::number_integer:
+            case value_t::number_unsigned:
+            case value_t::string:
+            {
+                if (JSON_UNLIKELY(not first.m_it.primitive_iterator.is_begin()
+                                  or not last.m_it.primitive_iterator.is_end()))
+                {
+                    JSON_THROW(invalid_iterator::create(204, "iterators out of range"));
+                }
+                break;
+            }
+
+            default:
+                break;
+        }
+
+        switch (m_type)
+        {
+            case value_t::number_integer:
+            {
+                m_value.number_integer = first.m_object->m_value.number_integer;
+                break;
+            }
+
+            case value_t::number_unsigned:
+            {
+                m_value.number_unsigned = first.m_object->m_value.number_unsigned;
+                break;
+            }
+
+            case value_t::number_float:
+            {
+                m_value.number_float = first.m_object->m_value.number_float;
+                break;
+            }
+
+            case value_t::boolean:
+            {
+                m_value.boolean = first.m_object->m_value.boolean;
+                break;
+            }
+
+            case value_t::string:
+            {
+                m_value = *first.m_object->m_value.string;
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_value.array = create<array_t>(first.m_it.array_iterator,
+                                                last.m_it.array_iterator);
+                break;
+            }
+
+            default:
+                JSON_THROW(invalid_iterator::create(206, "cannot construct with iterators from " +
+                                                    Twine(first.m_object->type_name())));
+        }
+
+        assert_invariant();
+    }
+
+
+    ///////////////////////////////////////
+    // other constructors and destructor //
+    ///////////////////////////////////////
+
+    /// @private
+    json(const detail::json_ref<json>& ref)
+        : json(ref.moved_or_copied())
+    {}
+
+    /*!
+    @brief copy constructor
+
+    Creates a copy of a given JSON value.
+
+    @param[in] other  the JSON value to copy
+
+    @post `*this == other`
+
+    @complexity Linear in the size of @a other.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes to any JSON value.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is linear.
+    - As postcondition, it holds: `other == json(other)`.
+
+    @liveexample{The following code shows an example for the copy
+    constructor.,json__json}
+
+    @since version 1.0.0
+    */
+    json(const json& other);
+
+    /*!
+    @brief move constructor
+
+    Move constructor. Constructs a JSON value with the contents of the given
+    value @a other using move semantics. It "steals" the resources from @a
+    other and leaves it as JSON null value.
+
+    @param[in,out] other  value to move to this object
+
+    @post `*this` has the same value as @a other before the call.
+    @post @a other is a JSON null value.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this constructor never throws
+    exceptions.
+
+    @requirement This function helps `json` satisfying the
+    [MoveConstructible](http://en.cppreference.com/w/cpp/concept/MoveConstructible)
+    requirements.
+
+    @liveexample{The code below shows the move constructor explicitly called
+    via std::move.,json__moveconstructor}
+
+    @since version 1.0.0
+    */
+    json(json&& other) noexcept
+        : m_type(std::move(other.m_type)),
+          m_value(std::move(other.m_value))
+    {
+        // check that passed value is valid
+        other.assert_invariant();
+
+        // invalidate payload
+        other.m_type = value_t::null;
+        other.m_value = {};
+
+        assert_invariant();
+    }
+
+    /*!
+    @brief copy assignment
+
+    Copy assignment operator. Copies a JSON value via the "copy and swap"
+    strategy: It is expressed in terms of the copy constructor, destructor,
+    and the `swap()` member function.
+
+    @param[in] other  value to copy from
+
+    @complexity Linear.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is linear.
+
+    @liveexample{The code below shows and example for the copy assignment. It
+    creates a copy of value `a` which is then swapped with `b`. Finally\, the
+    copy of `a` (which is the null value after the swap) is
+    destroyed.,json__copyassignment}
+
+    @since version 1.0.0
+    */
+    reference& operator=(json other) noexcept (
+        std::is_nothrow_move_constructible<value_t>::value and
+        std::is_nothrow_move_assignable<value_t>::value and
+        std::is_nothrow_move_constructible<json_value>::value and
+        std::is_nothrow_move_assignable<json_value>::value
+    )
+    {
+        // check that passed value is valid
+        other.assert_invariant();
+
+        using std::swap;
+        swap(m_type, other.m_type);
+        swap(m_value, other.m_value);
+
+        assert_invariant();
+        return *this;
+    }
+
+    /*!
+    @brief destructor
+
+    Destroys the JSON value and frees all allocated memory.
+
+    @complexity Linear.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is linear.
+    - All stored elements are destroyed and all memory is freed.
+
+    @since version 1.0.0
+    */
+    ~json() noexcept
+    {
+        assert_invariant();
+        m_value.destroy(m_type);
+    }
+
+    /// @}
+
+  public:
+    ///////////////////////
+    // object inspection //
+    ///////////////////////
+
+    /// @name object inspection
+    /// Functions to inspect the type of a JSON value.
+    /// @{
+
+    /*!
+    @brief serialization
+
+    Serialization function for JSON values. The function tries to mimic
+    Python's `json.dumps()` function, and currently supports its @a indent
+    and @a ensure_ascii parameters.
+
+    @param[in] indent If indent is nonnegative, then array elements and object
+    members will be pretty-printed with that indent level. An indent level of
+    `0` will only insert newlines. `-1` (the default) selects the most compact
+    representation.
+    @param[in] indent_char The character to use for indentation if @a indent is
+    greater than `0`. The default is ` ` (space).
+    @param[in] ensure_ascii If @a ensure_ascii is true, all non-ASCII characters
+    in the output are escaped with `\uXXXX` sequences, and the result consists
+    of ASCII characters only.
+
+    @return string containing the serialization of the JSON value
+
+    @throw type_error.316 if a string stored inside the JSON value is not
+                          UTF-8 encoded
+
+    @complexity Linear.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @liveexample{The following example shows the effect of different @a indent\,
+    @a indent_char\, and @a ensure_ascii parameters to the result of the
+    serialization.,dump}
+
+    @see https://docs.python.org/2/library/json.html#json.dump
+
+    @since version 1.0.0; indentation character @a indent_char, option
+           @a ensure_ascii and exceptions added in version 3.0.0
+    */
+    std::string dump(const int indent = -1, const char indent_char = ' ',
+                     const bool ensure_ascii = false) const;
+
+    void dump(raw_ostream& os, int indent = -1, const char indent_char = ' ',
+              const bool ensure_ascii = false) const;
+
+    /*!
+    @brief return the type of the JSON value (explicit)
+
+    Return the type of the JSON value as a value from the @ref value_t
+    enumeration.
+
+    @return the type of the JSON value
+            Value type                | return value
+            ------------------------- | -------------------------
+            null                      | value_t::null
+            boolean                   | value_t::boolean
+            string                    | value_t::string
+            number (integer)          | value_t::number_integer
+            number (unsigned integer) | value_t::number_unsigned
+            number (floating-point)   | value_t::number_float
+            object                    | value_t::object
+            array                     | value_t::array
+            discarded                 | value_t::discarded
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `type()` for all JSON
+    types.,type}
+
+    @sa @ref operator value_t() -- return the type of the JSON value (implicit)
+    @sa @ref type_name() -- return the type as string
+
+    @since version 1.0.0
+    */
+    value_t type() const noexcept
+    {
+        return m_type;
+    }
+
+    /*!
+    @brief return whether type is primitive
+
+    This function returns true if and only if the JSON type is primitive
+    (string, number, boolean, or null).
+
+    @return `true` if type is primitive (string, number, boolean, or null),
+    `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_primitive()` for all JSON
+    types.,is_primitive}
+
+    @sa @ref is_structured() -- returns whether JSON value is structured
+    @sa @ref is_null() -- returns whether JSON value is `null`
+    @sa @ref is_string() -- returns whether JSON value is a string
+    @sa @ref is_boolean() -- returns whether JSON value is a boolean
+    @sa @ref is_number() -- returns whether JSON value is a number
+
+    @since version 1.0.0
+    */
+    bool is_primitive() const noexcept
+    {
+        return is_null() or is_string() or is_boolean() or is_number();
+    }
+
+    /*!
+    @brief return whether type is structured
+
+    This function returns true if and only if the JSON type is structured
+    (array or object).
+
+    @return `true` if type is structured (array or object), `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_structured()` for all JSON
+    types.,is_structured}
+
+    @sa @ref is_primitive() -- returns whether value is primitive
+    @sa @ref is_array() -- returns whether value is an array
+    @sa @ref is_object() -- returns whether value is an object
+
+    @since version 1.0.0
+    */
+    bool is_structured() const noexcept
+    {
+        return is_array() or is_object();
+    }
+
+    /*!
+    @brief return whether value is null
+
+    This function returns true if and only if the JSON value is null.
+
+    @return `true` if type is null, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_null()` for all JSON
+    types.,is_null}
+
+    @since version 1.0.0
+    */
+    bool is_null() const noexcept
+    {
+        return (m_type == value_t::null);
+    }
+
+    /*!
+    @brief return whether value is a boolean
+
+    This function returns true if and only if the JSON value is a boolean.
+
+    @return `true` if type is boolean, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_boolean()` for all JSON
+    types.,is_boolean}
+
+    @since version 1.0.0
+    */
+    bool is_boolean() const noexcept
+    {
+        return (m_type == value_t::boolean);
+    }
+
+    /*!
+    @brief return whether value is a number
+
+    This function returns true if and only if the JSON value is a number. This
+    includes both integer (signed and unsigned) and floating-point values.
+
+    @return `true` if type is number (regardless whether integer, unsigned
+    integer or floating-type), `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_number()` for all JSON
+    types.,is_number}
+
+    @sa @ref is_number_integer() -- check if value is an integer or unsigned
+    integer number
+    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
+    number
+    @sa @ref is_number_float() -- check if value is a floating-point number
+
+    @since version 1.0.0
+    */
+    bool is_number() const noexcept
+    {
+        return is_number_integer() or is_number_float();
+    }
+
+    /*!
+    @brief return whether value is an integer number
+
+    This function returns true if and only if the JSON value is a signed or
+    unsigned integer number. This excludes floating-point values.
+
+    @return `true` if type is an integer or unsigned integer number, `false`
+    otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_number_integer()` for all
+    JSON types.,is_number_integer}
+
+    @sa @ref is_number() -- check if value is a number
+    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
+    number
+    @sa @ref is_number_float() -- check if value is a floating-point number
+
+    @since version 1.0.0
+    */
+    bool is_number_integer() const noexcept
+    {
+        return (m_type == value_t::number_integer or m_type == value_t::number_unsigned);
+    }
+
+    /*!
+    @brief return whether value is an unsigned integer number
+
+    This function returns true if and only if the JSON value is an unsigned
+    integer number. This excludes floating-point and signed integer values.
+
+    @return `true` if type is an unsigned integer number, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_number_unsigned()` for all
+    JSON types.,is_number_unsigned}
+
+    @sa @ref is_number() -- check if value is a number
+    @sa @ref is_number_integer() -- check if value is an integer or unsigned
+    integer number
+    @sa @ref is_number_float() -- check if value is a floating-point number
+
+    @since version 2.0.0
+    */
+    bool is_number_unsigned() const noexcept
+    {
+        return (m_type == value_t::number_unsigned);
+    }
+
+    /*!
+    @brief return whether value is a floating-point number
+
+    This function returns true if and only if the JSON value is a
+    floating-point number. This excludes signed and unsigned integer values.
+
+    @return `true` if type is a floating-point number, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_number_float()` for all
+    JSON types.,is_number_float}
+
+    @sa @ref is_number() -- check if value is number
+    @sa @ref is_number_integer() -- check if value is an integer number
+    @sa @ref is_number_unsigned() -- check if value is an unsigned integer
+    number
+
+    @since version 1.0.0
+    */
+    bool is_number_float() const noexcept
+    {
+        return (m_type == value_t::number_float);
+    }
+
+    /*!
+    @brief return whether value is an object
+
+    This function returns true if and only if the JSON value is an object.
+
+    @return `true` if type is object, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_object()` for all JSON
+    types.,is_object}
+
+    @since version 1.0.0
+    */
+    bool is_object() const noexcept
+    {
+        return (m_type == value_t::object);
+    }
+
+    /*!
+    @brief return whether value is an array
+
+    This function returns true if and only if the JSON value is an array.
+
+    @return `true` if type is array, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_array()` for all JSON
+    types.,is_array}
+
+    @since version 1.0.0
+    */
+    bool is_array() const noexcept
+    {
+        return (m_type == value_t::array);
+    }
+
+    /*!
+    @brief return whether value is a string
+
+    This function returns true if and only if the JSON value is a string.
+
+    @return `true` if type is string, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_string()` for all JSON
+    types.,is_string}
+
+    @since version 1.0.0
+    */
+    bool is_string() const noexcept
+    {
+        return (m_type == value_t::string);
+    }
+
+    /*!
+    @brief return whether value is discarded
+
+    This function returns true if and only if the JSON value was discarded
+    during parsing with a callback function (see @ref parser_callback_t).
+
+    @note This function will always be `false` for JSON values after parsing.
+    That is, discarded values can only occur during parsing, but will be
+    removed when inside a structured value or replaced by null in other cases.
+
+    @return `true` if type is discarded, `false` otherwise.
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies `is_discarded()` for all JSON
+    types.,is_discarded}
+
+    @since version 1.0.0
+    */
+    bool is_discarded() const noexcept
+    {
+        return (m_type == value_t::discarded);
+    }
+
+    /*!
+    @brief return the type of the JSON value (implicit)
+
+    Implicitly return the type of the JSON value as a value from the @ref
+    value_t enumeration.
+
+    @return the type of the JSON value
+
+    @complexity Constant.
+
+    @exceptionsafety No-throw guarantee: this member function never throws
+    exceptions.
+
+    @liveexample{The following code exemplifies the @ref value_t operator for
+    all JSON types.,operator__value_t}
+
+    @sa @ref type() -- return the type of the JSON value (explicit)
+    @sa @ref type_name() -- return the type as string
+
+    @since version 1.0.0
+    */
+    operator value_t() const noexcept
+    {
+        return m_type;
+    }
+
+    /// @}
+
+  private:
+    //////////////////
+    // value access //
+    //////////////////
+
+    /// get a boolean (explicit)
+    bool get_impl(bool* /*unused*/) const
+    {
+        if (JSON_LIKELY(is_boolean()))
+        {
+            return m_value.boolean;
+        }
+
+        JSON_THROW(type_error::create(302, "type must be boolean, but is " + Twine(type_name())));
+    }
+
+    /// get a pointer to the value (object)
+    object_t* get_impl_ptr(object_t* /*unused*/) noexcept
+    {
+        return is_object() ? m_value.object : nullptr;
+    }
+
+    /// get a pointer to the value (object)
+    const object_t* get_impl_ptr(const object_t* /*unused*/) const noexcept
+    {
+        return is_object() ? m_value.object : nullptr;
+    }
+
+    /// get a pointer to the value (array)
+    array_t* get_impl_ptr(array_t* /*unused*/) noexcept
+    {
+        return is_array() ? m_value.array : nullptr;
+    }
+
+    /// get a pointer to the value (array)
+    const array_t* get_impl_ptr(const array_t* /*unused*/) const noexcept
+    {
+        return is_array() ? m_value.array : nullptr;
+    }
+
+    /// get a pointer to the value (string)
+    std::string* get_impl_ptr(std::string* /*unused*/) noexcept
+    {
+        return is_string() ? m_value.string : nullptr;
+    }
+
+    /// get a pointer to the value (string)
+    const std::string* get_impl_ptr(const std::string* /*unused*/) const noexcept
+    {
+        return is_string() ? m_value.string : nullptr;
+    }
+
+    /// get a pointer to the value (boolean)
+    bool* get_impl_ptr(bool* /*unused*/) noexcept
+    {
+        return is_boolean() ? &m_value.boolean : nullptr;
+    }
+
+    /// get a pointer to the value (boolean)
+    const bool* get_impl_ptr(const bool* /*unused*/) const noexcept
+    {
+        return is_boolean() ? &m_value.boolean : nullptr;
+    }
+
+    /// get a pointer to the value (integer number)
+    int64_t* get_impl_ptr(int64_t* /*unused*/) noexcept
+    {
+        return is_number_integer() ? &m_value.number_integer : nullptr;
+    }
+
+    /// get a pointer to the value (integer number)
+    const int64_t* get_impl_ptr(const int64_t* /*unused*/) const noexcept
+    {
+        return is_number_integer() ? &m_value.number_integer : nullptr;
+    }
+
+    /// get a pointer to the value (unsigned number)
+    uint64_t* get_impl_ptr(uint64_t* /*unused*/) noexcept
+    {
+        return is_number_unsigned() ? &m_value.number_unsigned : nullptr;
+    }
+
+    /// get a pointer to the value (unsigned number)
+    const uint64_t* get_impl_ptr(const uint64_t* /*unused*/) const noexcept
+    {
+        return is_number_unsigned() ? &m_value.number_unsigned : nullptr;
+    }
+
+    /// get a pointer to the value (floating-point number)
+    double* get_impl_ptr(double* /*unused*/) noexcept
+    {
+        return is_number_float() ? &m_value.number_float : nullptr;
+    }
+
+    /// get a pointer to the value (floating-point number)
+    const double* get_impl_ptr(const double* /*unused*/) const noexcept
+    {
+        return is_number_float() ? &m_value.number_float : nullptr;
+    }
+
+    /*!
+    @brief helper function to implement get_ref()
+
+    This function helps to implement get_ref() without code duplication for
+    const and non-const overloads
+
+    @tparam ThisType will be deduced as `json` or `const json`
+
+    @throw type_error.303 if ReferenceType does not match underlying value
+    type of the current JSON
+    */
+    template<typename ReferenceType, typename ThisType>
+    static ReferenceType get_ref_impl(ThisType& obj)
+    {
+        // delegate the call to get_ptr<>()
+        auto ptr = obj.template get_ptr<typename std::add_pointer<ReferenceType>::type>();
+
+        if (JSON_LIKELY(ptr != nullptr))
+        {
+            return *ptr;
+        }
+
+        JSON_THROW(type_error::create(303, "incompatible ReferenceType for get_ref, actual type is " + Twine(obj.type_name())));
+    }
+
+  public:
+    /// @name value access
+    /// Direct access to the stored value of a JSON value.
+    /// @{
+
+    /*!
+    @brief get special-case overload
+
+    This overloads avoids a lot of template boilerplate, it can be seen as the
+    identity method
+
+    @tparam BasicJsonType == @ref json
+
+    @return a copy of *this
+
+    @complexity Constant.
+
+    @since version 2.1.0
+    */
+    template<typename BasicJsonType, detail::enable_if_t<
+                 std::is_same<typename std::remove_const<BasicJsonType>::type, json_t>::value,
+                 int> = 0>
+    json get() const
+    {
+        return *this;
+    }
+
+    /*!
+    @brief get a value (explicit)
+
+    Explicit type conversion between the JSON value and a compatible value
+    which is [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible)
+    and [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible).
+    The value is converted by calling the @ref json_serializer<ValueType>
+    `from_json()` method.
+
+    The function is equivalent to executing
+    @code {.cpp}
+    ValueType ret;
+    adl_serializer<ValueType, void>::from_json(*this, ret);
+    return ret;
+    @endcode
+
+    This overloads is chosen if:
+    - @a ValueType is not @ref json,
+    - @ref json_serializer<ValueType> has a `from_json()` method of the form
+      `void from_json(const json&, ValueType&)`, and
+    - @ref json_serializer<ValueType> does not have a `from_json()` method of
+      the form `ValueType from_json(const json&)`
+
+    @tparam ValueTypeCV the provided value type
+    @tparam ValueType the returned value type
+
+    @return copy of the JSON value, converted to @a ValueType
+
+    @throw what @ref json_serializer<ValueType> `from_json()` method throws
+
+    @liveexample{The example below shows several conversions from JSON values
+    to other types. There a few things to note: (1) Floating-point numbers can
+    be converted to integers\, (2) A JSON array can be converted to a standard
+    `std::vector<short>`\, (3) A JSON object can be converted to C++
+    associative containers such as `std::unordered_map<std::string\,
+    json>`.,get__ValueType_const}
+
+    @since version 2.1.0
+    */
+    template<typename ValueTypeCV, typename ValueType = detail::uncvref_t<ValueTypeCV>,
+             detail::enable_if_t <
+                 not detail::is_json<ValueType>::value and
+                 detail::has_from_json<json_t, ValueType>::value and
+                 not detail::has_non_default_from_json<json_t, ValueType>::value,
+                 int> = 0>
+    ValueType get() const noexcept(noexcept(
+                                       adl_serializer<ValueType, void>::from_json(std::declval<const json_t&>(), std::declval<ValueType&>())))
+    {
+        // we cannot static_assert on ValueTypeCV being non-const, because
+        // there is support for get<const json_t>(), which is why we
+        // still need the uncvref
+        static_assert(not std::is_reference<ValueTypeCV>::value,
+                      "get() cannot be used with reference types, you might want to use get_ref()");
+        static_assert(std::is_default_constructible<ValueType>::value,
+                      "types must be DefaultConstructible when used with get()");
+
+        ValueType ret;
+        adl_serializer<ValueType, void>::from_json(*this, ret);
+        return ret;
+    }
+
+    /*!
+    @brief get a value (explicit); special case
+
+    Explicit type conversion between the JSON value and a compatible value
+    which is **not** [CopyConstructible](http://en.cppreference.com/w/cpp/concept/CopyConstructible)
+    and **not** [DefaultConstructible](http://en.cppreference.com/w/cpp/concept/DefaultConstructible).
+    The value is converted by calling the @ref json_serializer<ValueType>
+    `from_json()` method.
+
+    The function is equivalent to executing
+    @code {.cpp}
+    return adl_serializer<ValueTypeCV, void>::from_json(*this);
+    @endcode
+
+    This overloads is chosen if:
+    - @a ValueType is not @ref json and
+    - @ref json_serializer<ValueType> has a `from_json()` method of the form
+      `ValueType from_json(const json&)`
+
+    @note If @ref json_serializer<ValueType> has both overloads of
+    `from_json()`, this one is chosen.
+
+    @tparam ValueTypeCV the provided value type
+    @tparam ValueType the returned value type
+
+    @return copy of the JSON value, converted to @a ValueType
+
+    @throw what @ref json_serializer<ValueType> `from_json()` method throws
+
+    @since version 2.1.0
+    */
+    template<typename ValueTypeCV, typename ValueType = detail::uncvref_t<ValueTypeCV>,
+             detail::enable_if_t<not std::is_same<json_t, ValueType>::value and
+                                 detail::has_non_default_from_json<json_t, ValueType>::value,
+                                 int> = 0>
+    ValueType get() const noexcept(noexcept(
+                                       adl_serializer<ValueTypeCV, void>::from_json(std::declval<const json_t&>())))
+    {
+        static_assert(not std::is_reference<ValueTypeCV>::value,
+                      "get() cannot be used with reference types, you might want to use get_ref()");
+        return adl_serializer<ValueTypeCV, void>::from_json(*this);
+    }
+
+    /*!
+    @brief get a pointer value (explicit)
+
+    Explicit pointer access to the internally stored JSON value. No copies are
+    made.
+
+    @warning The pointer becomes invalid if the underlying JSON object
+    changes.
+
+    @tparam PointerType pointer type; must be a pointer to @ref array_t, @ref
+    object_t, `std::string`, bool, int64_t, uint64_t, or double.
+
+    @return pointer to the internally stored JSON value if the requested
+    pointer type @a PointerType fits to the JSON value; `nullptr` otherwise
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how pointers to internal values of a
+    JSON value can be requested. Note that no type conversions are made and a
+    `nullptr` is returned if the value and the requested pointer type does not
+    match.,get__PointerType}
+
+    @sa @ref get_ptr() for explicit pointer-member access
+
+    @since version 1.0.0
+    */
+    template<typename PointerType, typename std::enable_if<
+                 std::is_pointer<PointerType>::value, int>::type = 0>
+    PointerType get() noexcept
+    {
+        // delegate the call to get_ptr
+        return get_ptr<PointerType>();
+    }
+
+    /*!
+    @brief get a pointer value (explicit)
+    @copydoc get()
+    */
+    template<typename PointerType, typename std::enable_if<
+                 std::is_pointer<PointerType>::value, int>::type = 0>
+    const PointerType get() const noexcept
+    {
+        // delegate the call to get_ptr
+        return get_ptr<PointerType>();
+    }
+
+    /*!
+    @brief get a pointer value (implicit)
+
+    Implicit pointer access to the internally stored JSON value. No copies are
+    made.
+
+    @warning Writing data to the pointee of the result yields an undefined
+    state.
+
+    @tparam PointerType pointer type; must be a pointer to @ref array_t, @ref
+    object_t, `std::string`, bool, int64_t,
+    uint64_t, or double. Enforced by a static assertion.
+
+    @return pointer to the internally stored JSON value if the requested
+    pointer type @a PointerType fits to the JSON value; `nullptr` otherwise
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how pointers to internal values of a
+    JSON value can be requested. Note that no type conversions are made and a
+    `nullptr` is returned if the value and the requested pointer type does not
+    match.,get_ptr}
+
+    @since version 1.0.0
+    */
+    template<typename PointerType, typename std::enable_if<
+                 std::is_pointer<PointerType>::value, int>::type = 0>
+    PointerType get_ptr() noexcept
+    {
+        // get the type of the PointerType (remove pointer and const)
+        using pointee_t = typename std::remove_const<typename
+                          std::remove_pointer<typename
+                          std::remove_const<PointerType>::type>::type>::type;
+        // make sure the type matches the allowed types
+        static_assert(
+            std::is_same<object_t, pointee_t>::value
+            or std::is_same<array_t, pointee_t>::value
+            or std::is_same<std::string, pointee_t>::value
+            or std::is_same<bool, pointee_t>::value
+            or std::is_same<int64_t, pointee_t>::value
+            or std::is_same<uint64_t, pointee_t>::value
+            or std::is_same<double, pointee_t>::value
+            , "incompatible pointer type");
+
+        // delegate the call to get_impl_ptr<>()
+        return get_impl_ptr(static_cast<PointerType>(nullptr));
+    }
+
+    /*!
+    @brief get a pointer value (implicit)
+    @copydoc get_ptr()
+    */
+    template<typename PointerType, typename std::enable_if<
+                 std::is_pointer<PointerType>::value and
+                 std::is_const<typename std::remove_pointer<PointerType>::type>::value, int>::type = 0>
+    const PointerType get_ptr() const noexcept
+    {
+        // get the type of the PointerType (remove pointer and const)
+        using pointee_t = typename std::remove_const<typename
+                          std::remove_pointer<typename
+                          std::remove_const<PointerType>::type>::type>::type;
+        // make sure the type matches the allowed types
+        static_assert(
+            std::is_same<object_t, pointee_t>::value
+            or std::is_same<array_t, pointee_t>::value
+            or std::is_same<std::string, pointee_t>::value
+            or std::is_same<bool, pointee_t>::value
+            or std::is_same<int64_t, pointee_t>::value
+            or std::is_same<uint64_t, pointee_t>::value
+            or std::is_same<double, pointee_t>::value
+            , "incompatible pointer type");
+
+        // delegate the call to get_impl_ptr<>() const
+        return get_impl_ptr(static_cast<PointerType>(nullptr));
+    }
+
+    /*!
+    @brief get a reference value (implicit)
+
+    Implicit reference access to the internally stored JSON value. No copies
+    are made.
+
+    @warning Writing data to the referee of the result yields an undefined
+    state.
+
+    @tparam ReferenceType reference type; must be a reference to @ref array_t,
+    @ref object_t, std::string, bool, int64_t, or
+    double. Enforced by static assertion.
+
+    @return reference to the internally stored JSON value if the requested
+    reference type @a ReferenceType fits to the JSON value; throws
+    type_error.303 otherwise
+
+    @throw type_error.303 in case passed type @a ReferenceType is incompatible
+    with the stored JSON value; see example below
+
+    @complexity Constant.
+
+    @liveexample{The example shows several calls to `get_ref()`.,get_ref}
+
+    @since version 1.1.0
+    */
+    template<typename ReferenceType, typename std::enable_if<
+                 std::is_reference<ReferenceType>::value, int>::type = 0>
+    ReferenceType get_ref()
+    {
+        // delegate call to get_ref_impl
+        return get_ref_impl<ReferenceType>(*this);
+    }
+
+    /*!
+    @brief get a reference value (implicit)
+    @copydoc get_ref()
+    */
+    template<typename ReferenceType, typename std::enable_if<
+                 std::is_reference<ReferenceType>::value and
+                 std::is_const<typename std::remove_reference<ReferenceType>::type>::value, int>::type = 0>
+    ReferenceType get_ref() const
+    {
+        // delegate call to get_ref_impl
+        return get_ref_impl<ReferenceType>(*this);
+    }
+
+    /*!
+    @brief get a value (implicit)
+
+    Implicit type conversion between the JSON value and a compatible value.
+    The call is realized by calling @ref get() const.
+
+    @tparam ValueType non-pointer type compatible to the JSON value, for
+    instance `int` for JSON integer numbers, `bool` for JSON booleans, or
+    `std::vector` types for JSON arrays. The character type of `std::string`
+    as well as an initializer list of this type is excluded to avoid
+    ambiguities as these types implicitly convert to `std::string`.
+
+    @return copy of the JSON value, converted to type @a ValueType
+
+    @throw type_error.302 in case passed type @a ValueType is incompatible
+    to the JSON value type (e.g., the JSON value is of type boolean, but a
+    string is requested); see example below
+
+    @complexity Linear in the size of the JSON value.
+
+    @liveexample{The example below shows several conversions from JSON values
+    to other types. There a few things to note: (1) Floating-point numbers can
+    be converted to integers\, (2) A JSON array can be converted to a standard
+    `std::vector<short>`\, (3) A JSON object can be converted to C++
+    associative containers such as `std::unordered_map<std::string\,
+    json>`.,operator__ValueType}
+
+    @since version 1.0.0
+    */
+    template < typename ValueType, typename std::enable_if <
+                   not std::is_pointer<ValueType>::value and
+                   not std::is_same<ValueType, detail::json_ref<json>>::value and
+                   not std::is_same<ValueType, std::string::value_type>::value and
+                   not detail::is_json<ValueType>::value
+#ifndef _MSC_VER  // fix for issue #167 operator<< ambiguity under VS2015
+                   and not std::is_same<ValueType, std::initializer_list<std::string::value_type>>::value
+#endif
+#if defined(JSON_HAS_CPP_17)
+                   and not std::is_same<ValueType, typename std::string_view>::value
+#endif
+                   , int >::type = 0 >
+    operator ValueType() const
+    {
+        // delegate the call to get<>() const
+        return get<ValueType>();
+    }
+
+    /// @}
+
+
+    ////////////////////
+    // element access //
+    ////////////////////
+
+    /// @name element access
+    /// Access to the JSON value.
+    /// @{
+
+    /*!
+    @brief access specified array element with bounds checking
+
+    Returns a reference to the element at specified location @a idx, with
+    bounds checking.
+
+    @param[in] idx  index of the element to access
+
+    @return reference to the element at index @a idx
+
+    @throw type_error.304 if the JSON value is not an array; in this case,
+    calling `at` with an index makes no sense. See example below.
+    @throw out_of_range.401 if the index @a idx is out of range of the array;
+    that is, `idx >= size()`. See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 1.0.0
+
+    @liveexample{The example below shows how array elements can be read and
+    written using `at()`. It also demonstrates the different exceptions that
+    can be thrown.,at__size_type}
+    */
+    reference at(size_type idx);
+
+    /*!
+    @brief access specified array element with bounds checking
+
+    Returns a const reference to the element at specified location @a idx,
+    with bounds checking.
+
+    @param[in] idx  index of the element to access
+
+    @return const reference to the element at index @a idx
+
+    @throw type_error.304 if the JSON value is not an array; in this case,
+    calling `at` with an index makes no sense. See example below.
+    @throw out_of_range.401 if the index @a idx is out of range of the array;
+    that is, `idx >= size()`. See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 1.0.0
+
+    @liveexample{The example below shows how array elements can be read using
+    `at()`. It also demonstrates the different exceptions that can be thrown.,
+    at__size_type_const}
+    */
+    const_reference at(size_type idx) const;
+
+    /*!
+    @brief access specified object element with bounds checking
+
+    Returns a reference to the element at with specified key @a key, with
+    bounds checking.
+
+    @param[in] key  key of the element to access
+
+    @return reference to the element at key @a key
+
+    @throw type_error.304 if the JSON value is not an object; in this case,
+    calling `at` with a key makes no sense. See example below.
+    @throw out_of_range.403 if the key @a key is is not stored in the object;
+    that is, `find(key) == end()`. See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Logarithmic in the size of the container.
+
+    @sa @ref operator[](const typename object_t::key_type&) for unchecked
+    access by reference
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.0.0
+
+    @liveexample{The example below shows how object elements can be read and
+    written using `at()`. It also demonstrates the different exceptions that
+    can be thrown.,at__object_t_key_type}
+    */
+    reference at(StringRef key);
+
+    /*!
+    @brief access specified object element with bounds checking
+
+    Returns a const reference to the element at with specified key @a key,
+    with bounds checking.
+
+    @param[in] key  key of the element to access
+
+    @return const reference to the element at key @a key
+
+    @throw type_error.304 if the JSON value is not an object; in this case,
+    calling `at` with a key makes no sense. See example below.
+    @throw out_of_range.403 if the key @a key is is not stored in the object;
+    that is, `find(key) == end()`. See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Logarithmic in the size of the container.
+
+    @sa @ref operator[](const typename object_t::key_type&) for unchecked
+    access by reference
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.0.0
+
+    @liveexample{The example below shows how object elements can be read using
+    `at()`. It also demonstrates the different exceptions that can be thrown.,
+    at__object_t_key_type_const}
+    */
+    const_reference at(StringRef key) const;
+
+    /*!
+    @brief access specified array element
+
+    Returns a reference to the element at specified location @a idx.
+
+    @note If @a idx is beyond the range of the array (i.e., `idx >= size()`),
+    then the array is silently filled up with `null` values to make `idx` a
+    valid reference to the last stored element.
+
+    @param[in] idx  index of the element to access
+
+    @return reference to the element at index @a idx
+
+    @throw type_error.305 if the JSON value is not an array or null; in that
+    cases, using the [] operator with an index makes no sense.
+
+    @complexity Constant if @a idx is in the range of the array. Otherwise
+    linear in `idx - size()`.
+
+    @liveexample{The example below shows how array elements can be read and
+    written using `[]` operator. Note the addition of `null`
+    values.,operatorarray__size_type}
+
+    @since version 1.0.0
+    */
+    reference operator[](size_type idx);
+
+    /*!
+    @brief access specified array element
+
+    Returns a const reference to the element at specified location @a idx.
+
+    @param[in] idx  index of the element to access
+
+    @return const reference to the element at index @a idx
+
+    @throw type_error.305 if the JSON value is not an array; in that case,
+    using the [] operator with an index makes no sense.
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how array elements can be read using
+    the `[]` operator.,operatorarray__size_type_const}
+
+    @since version 1.0.0
+    */
+    const_reference operator[](size_type idx) const;
+
+    /*!
+    @brief access specified object element
+
+    Returns a reference to the element at with specified key @a key.
+
+    @note If @a key is not found in the object, then it is silently added to
+    the object and filled with a `null` value to make `key` a valid reference.
+    In case the value was `null` before, it is converted to an object.
+
+    @param[in] key  key of the element to access
+
+    @return reference to the element at key @a key
+
+    @throw type_error.305 if the JSON value is not an object or null; in that
+    cases, using the [] operator with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be read and
+    written using the `[]` operator.,operatorarray__key_type}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.0.0
+    */
+    reference operator[](StringRef key);
+
+    /*!
+    @brief read-only access specified object element
+
+    Returns a const reference to the element at with specified key @a key. No
+    bounds checking is performed.
+
+    @warning If the element with key @a key does not exist, the behavior is
+    undefined.
+
+    @param[in] key  key of the element to access
+
+    @return const reference to the element at key @a key
+
+    @pre The element with key @a key must exist. **This precondition is
+         enforced with an assertion.**
+
+    @throw type_error.305 if the JSON value is not an object; in that case,
+    using the [] operator with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be read using
+    the `[]` operator.,operatorarray__key_type_const}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.0.0
+    */
+    const_reference operator[](StringRef key) const;
+
+    /*!
+    @brief access specified object element
+
+    Returns a reference to the element at with specified key @a key.
+
+    @note If @a key is not found in the object, then it is silently added to
+    the object and filled with a `null` value to make `key` a valid reference.
+    In case the value was `null` before, it is converted to an object.
+
+    @param[in] key  key of the element to access
+
+    @return reference to the element at key @a key
+
+    @throw type_error.305 if the JSON value is not an object or null; in that
+    cases, using the [] operator with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be read and
+    written using the `[]` operator.,operatorarray__key_type}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.1.0
+    */
+    template<typename T>
+    reference operator[](T* key)
+    {
+        // implicitly convert null to object
+        if (is_null())
+        {
+            m_type = value_t::object;
+            m_value = value_t::object;
+            assert_invariant();
+        }
+
+        // at only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            return m_value.object->operator[](key);
+        }
+
+        JSON_THROW(type_error::create(305, "cannot use operator[] with " + Twine(type_name())));
+    }
+
+    /*!
+    @brief read-only access specified object element
+
+    Returns a const reference to the element at with specified key @a key. No
+    bounds checking is performed.
+
+    @warning If the element with key @a key does not exist, the behavior is
+    undefined.
+
+    @param[in] key  key of the element to access
+
+    @return const reference to the element at key @a key
+
+    @pre The element with key @a key must exist. **This precondition is
+         enforced with an assertion.**
+
+    @throw type_error.305 if the JSON value is not an object; in that case,
+    using the [] operator with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be read using
+    the `[]` operator.,operatorarray__key_type_const}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref value() for access by value with a default value
+
+    @since version 1.1.0
+    */
+    template<typename T>
+    const_reference operator[](T* key) const
+    {
+        // at only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            assert(m_value.object->find(key) != m_value.object->end());
+            return m_value.object->find(key)->second;
+        }
+
+        JSON_THROW(type_error::create(305, "cannot use operator[] with " + Twine(type_name())));
+    }
+
+    /*!
+    @brief access specified object element with default value
+
+    Returns either a copy of an object's element at the specified key @a key
+    or a given default value if no element with key @a key exists.
+
+    The function is basically equivalent to executing
+    @code {.cpp}
+    try {
+        return at(key);
+    } catch(out_of_range) {
+        return default_value;
+    }
+    @endcode
+
+    @note Unlike @ref at(const typename object_t::key_type&), this function
+    does not throw if the given key @a key was not found.
+
+    @note Unlike @ref operator[](const typename object_t::key_type& key), this
+    function does not implicitly add an element to the position defined by @a
+    key. This function is furthermore also applicable to const objects.
+
+    @param[in] key  key of the element to access
+    @param[in] default_value  the value to return if @a key is not found
+
+    @tparam ValueType type compatible to JSON values, for instance `int` for
+    JSON integer numbers, `bool` for JSON booleans, or `std::vector` types for
+    JSON arrays. Note the type of the expected value at @a key and the default
+    value @a default_value must be compatible.
+
+    @return copy of the element at key @a key or @a default_value if @a key
+    is not found
+
+    @throw type_error.306 if the JSON value is not an object; in that case,
+    using `value()` with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be queried
+    with a default value.,json__value}
+
+    @sa @ref at(const typename object_t::key_type&) for access by reference
+    with range checking
+    @sa @ref operator[](const typename object_t::key_type&) for unchecked
+    access by reference
+
+    @since version 1.0.0
+    */
+    template<class ValueType, typename std::enable_if<
+                 std::is_convertible<json_t, ValueType>::value, int>::type = 0>
+    ValueType value(StringRef key, const ValueType& default_value) const
+    {
+        // at only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            // if key is found, return value and given default value otherwise
+            const auto it = find(key);
+            if (it != end())
+            {
+                return *it;
+            }
+
+            return default_value;
+        }
+
+        JSON_THROW(type_error::create(306, "cannot use value() with " + Twine(type_name())));
+    }
+
+    /*!
+    @brief overload for a default value of type const char*
+    @copydoc json::value(const typename object_t::key_type&, ValueType) const
+    */
+    std::string value(StringRef key, const char* default_value) const
+    {
+        return value(key, std::string(default_value));
+    }
+
+    /*!
+    @brief access specified object element via JSON Pointer with default value
+
+    Returns either a copy of an object's element at the specified key @a key
+    or a given default value if no element with key @a key exists.
+
+    The function is basically equivalent to executing
+    @code {.cpp}
+    try {
+        return at(ptr);
+    } catch(out_of_range) {
+        return default_value;
+    }
+    @endcode
+
+    @note Unlike @ref at(const json_pointer&), this function does not throw
+    if the given key @a key was not found.
+
+    @param[in] ptr  a JSON pointer to the element to access
+    @param[in] default_value  the value to return if @a ptr found no value
+
+    @tparam ValueType type compatible to JSON values, for instance `int` for
+    JSON integer numbers, `bool` for JSON booleans, or `std::vector` types for
+    JSON arrays. Note the type of the expected value at @a key and the default
+    value @a default_value must be compatible.
+
+    @return copy of the element at key @a key or @a default_value if @a key
+    is not found
+
+    @throw type_error.306 if the JSON value is not an object; in that case,
+    using `value()` with a key makes no sense.
+
+    @complexity Logarithmic in the size of the container.
+
+    @liveexample{The example below shows how object elements can be queried
+    with a default value.,json__value_ptr}
+
+    @sa @ref operator[](const json_pointer&) for unchecked access by reference
+
+    @since version 2.0.2
+    */
+    template<class ValueType, typename std::enable_if<
+                 std::is_convertible<json_t, ValueType>::value, int>::type = 0>
+    ValueType value(const json_pointer& ptr, const ValueType& default_value) const
+    {
+        // at only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            // if pointer resolves a value, return it or use default value
+            JSON_TRY
+            {
+                return ptr.get_checked(this);
+            }
+            JSON_CATCH (out_of_range&)
+            {
+                return default_value;
+            }
+        }
+
+        JSON_THROW(type_error::create(306, "cannot use value() with " + Twine(type_name())));
+    }
+
+    /*!
+    @brief overload for a default value of type const char*
+    @copydoc json::value(const json_pointer&, ValueType) const
+    */
+    std::string value(const json_pointer& ptr, const char* default_value) const
+    {
+        return value(ptr, std::string(default_value));
+    }
+
+    /*!
+    @brief access the first element
+
+    Returns a reference to the first element in the container. For a JSON
+    container `c`, the expression `c.front()` is equivalent to `*c.begin()`.
+
+    @return In case of a structured type (array or object), a reference to the
+    first element is returned. In case of number, string, or boolean values, a
+    reference to the value is returned.
+
+    @complexity Constant.
+
+    @pre The JSON value must not be `null` (would throw `std::out_of_range`)
+    or an empty array or object (undefined behavior, **guarded by
+    assertions**).
+    @post The JSON value remains unchanged.
+
+    @throw invalid_iterator.214 when called on `null` value
+
+    @liveexample{The following code shows an example for `front()`.,front}
+
+    @sa @ref back() -- access the last element
+
+    @since version 1.0.0
+    */
+    reference front()
+    {
+        return *begin();
+    }
+
+    /*!
+    @copydoc json::front()
+    */
+    const_reference front() const
+    {
+        return *cbegin();
+    }
+
+    /*!
+    @brief access the last element
+
+    Returns a reference to the last element in the container. For a JSON
+    container `c`, the expression `c.back()` is equivalent to
+    @code {.cpp}
+    auto tmp = c.end();
+    --tmp;
+    return *tmp;
+    @endcode
+
+    @return In case of a structured type (array or object), a reference to the
+    last element is returned. In case of number, string, or boolean values, a
+    reference to the value is returned.
+
+    @complexity Constant.
+
+    @pre The JSON value must not be `null` (would throw `std::out_of_range`)
+    or an empty array or object (undefined behavior, **guarded by
+    assertions**).
+    @post The JSON value remains unchanged.
+
+    @throw invalid_iterator.214 when called on a `null` value. See example
+    below.
+
+    @liveexample{The following code shows an example for `back()`.,back}
+
+    @sa @ref front() -- access the first element
+
+    @since version 1.0.0
+    */
+    reference back()
+    {
+        auto tmp = end();
+        --tmp;
+        return *tmp;
+    }
+
+    /*!
+    @copydoc json::back()
+    */
+    const_reference back() const
+    {
+        auto tmp = cend();
+        --tmp;
+        return *tmp;
+    }
+
+    /*!
+    @brief remove element given an iterator
+
+    Removes the element specified by iterator @a pos. The iterator @a pos must
+    be valid and dereferenceable. Thus the `end()` iterator (which is valid,
+    but is not dereferenceable) cannot be used as a value for @a pos.
+
+    If called on a primitive type other than `null`, the resulting JSON value
+    will be `null`.
+
+    @param[in] pos iterator to the element to remove
+
+    @tparam IteratorType an @ref iterator or @ref const_iterator
+
+    @post Invalidates iterators and references at or after the point of the
+    erase, including the `end()` iterator.
+
+    @throw type_error.307 if called on a `null` value; example: `"cannot use
+    erase() with null"`
+    @throw invalid_iterator.202 if called on an iterator which does not belong
+    to the current JSON value; example: `"iterator does not fit current
+    value"`
+    @throw invalid_iterator.205 if called on a primitive type with invalid
+    iterator (i.e., any iterator which is not `begin()`); example: `"iterator
+    out of range"`
+
+    @complexity The complexity depends on the type:
+    - objects: amortized constant
+    - arrays: linear in distance between @a pos and the end of the container
+    - strings: linear in the length of the string
+    - other types: constant
+
+    @liveexample{The example shows the result of `erase()` for different JSON
+    types.,erase__IteratorType}
+
+    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
+    the given range
+    @sa @ref erase(StringRef) -- removes the element
+    from an object at the given key
+    @sa @ref erase(const size_type) -- removes the element from an array at
+    the given index
+
+    @since version 1.0.0
+    */
+    template<class IteratorType, typename std::enable_if<
+                 std::is_same<IteratorType, typename json_t::iterator>::value or
+                 std::is_same<IteratorType, typename json_t::const_iterator>::value, int>::type
+             = 0>
+    void erase(IteratorType pos)
+    {
+        // make sure iterator fits the current value
+        if (JSON_UNLIKELY(this != pos.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(202, "iterator does not fit current value"));
+        }
+
+        switch (m_type)
+        {
+            case value_t::boolean:
+            case value_t::number_float:
+            case value_t::number_integer:
+            case value_t::number_unsigned:
+            case value_t::string:
+            {
+                if (JSON_UNLIKELY(not pos.m_it.primitive_iterator.is_begin()))
+                {
+                    JSON_THROW(invalid_iterator::create(205, "iterator out of range"));
+                }
+
+                if (is_string())
+                {
+                    std::allocator<std::string> alloc;
+                    alloc.destroy(m_value.string);
+                    alloc.deallocate(m_value.string, 1);
+                    m_value.string = nullptr;
+                }
+
+                m_type = value_t::null;
+                assert_invariant();
+                break;
+            }
+
+            case value_t::object:
+            {
+                m_value.object->erase(pos.m_it.object_iterator);
+                break;
+            }
+
+            case value_t::array:
+            {
+                m_value.array->erase(pos.m_it.array_iterator);
+                break;
+            }
+
+            default:
+                JSON_THROW(type_error::create(307, "cannot use erase() with " + Twine(type_name())));
+        }
+    }
+
+    /*!
+    @brief remove elements given an iterator range
+
+    Removes the element specified by the range `[first; last)`. The iterator
+    @a first does not need to be dereferenceable if `first == last`: erasing
+    an empty range is a no-op.
+
+    If called on a primitive type other than `null`, the resulting JSON value
+    will be `null`.
+
+    @param[in] first iterator to the beginning of the range to remove
+    @param[in] last iterator past the end of the range to remove
+    @return Iterator following the last removed element. If the iterator @a
+    second refers to the last element, the `end()` iterator is returned.
+
+    @tparam IteratorType an @ref iterator or @ref const_iterator
+
+    @post Invalidates iterators and references at or after the point of the
+    erase, including the `end()` iterator.
+
+    @throw type_error.307 if called on a `null` value; example: `"cannot use
+    erase() with null"`
+    @throw invalid_iterator.203 if called on iterators which does not belong
+    to the current JSON value; example: `"iterators do not fit current value"`
+    @throw invalid_iterator.204 if called on a primitive type with invalid
+    iterators (i.e., if `first != begin()` and `last != end()`); example:
+    `"iterators out of range"`
+
+    @complexity The complexity depends on the type:
+    - objects: `log(size()) + std::distance(first, last)`
+    - arrays: linear in the distance between @a first and @a last, plus linear
+      in the distance between @a last and end of the container
+    - strings: linear in the length of the string
+    - other types: constant
+
+    @liveexample{The example shows the result of `erase()` for different JSON
+    types.,erase__IteratorType_IteratorType}
+
+    @sa @ref erase(IteratorType) -- removes the element at a given position
+    @sa @ref erase(const typename object_t::key_type&) -- removes the element
+    from an object at the given key
+    @sa @ref erase(const size_type) -- removes the element from an array at
+    the given index
+
+    @since version 1.0.0
+    */
+    template<class IteratorType, typename std::enable_if<
+                 std::is_same<IteratorType, typename json_t::iterator>::value or
+                 std::is_same<IteratorType, typename json_t::const_iterator>::value, int>::type
+             = 0>
+    IteratorType erase(IteratorType first, IteratorType last)
+    {
+        // make sure iterator fits the current value
+        if (JSON_UNLIKELY(this != first.m_object or this != last.m_object))
+        {
+            JSON_THROW(invalid_iterator::create(203, "iterators do not fit current value"));
+        }
+
+        IteratorType result = end();
+
+        switch (m_type)
+        {
+            case value_t::boolean:
+            case value_t::number_float:
+            case value_t::number_integer:
+            case value_t::number_unsigned:
+            case value_t::string:
+            {
+                if (JSON_LIKELY(not first.m_it.primitive_iterator.is_begin()
+                                or not last.m_it.primitive_iterator.is_end()))
+                {
+                    JSON_THROW(invalid_iterator::create(204, "iterators out of range"));
+                }
+
+                if (is_string())
+                {
+                    std::allocator<std::string> alloc;
+                    alloc.destroy(m_value.string);
+                    alloc.deallocate(m_value.string, 1);
+                    m_value.string = nullptr;
+                }
+
+                m_type = value_t::null;
+                assert_invariant();
+                break;
+            }
+
+            case value_t::array:
+            {
+                result.m_it.array_iterator = m_value.array->erase(first.m_it.array_iterator,
+                                             last.m_it.array_iterator);
+                break;
+            }
+
+            default:
+                JSON_THROW(type_error::create(307, "cannot use erase() with " + Twine(type_name())));
+        }
+
+        return result;
+    }
+
+    /*!
+    @brief remove element from a JSON object given a key
+
+    Removes elements from a JSON object with the key value @a key.
+
+    @param[in] key value of the elements to remove
+
+    @return Number of elements removed. If @a ObjectType is the default
+    `std::map` type, the return value will always be `0` (@a key was not
+    found) or `1` (@a key was found).
+
+    @post References and iterators to the erased elements are invalidated.
+    Other references and iterators are not affected.
+
+    @throw type_error.307 when called on a type other than JSON object;
+    example: `"cannot use erase() with null"`
+
+    @complexity `log(size()) + count(key)`
+
+    @liveexample{The example shows the effect of `erase()`.,erase__key_type}
+
+    @sa @ref erase(IteratorType) -- removes the element at a given position
+    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
+    the given range
+    @sa @ref erase(const size_type) -- removes the element from an array at
+    the given index
+
+    @since version 1.0.0
+    */
+    size_type erase(StringRef key);
+
+    /*!
+    @brief remove element from a JSON array given an index
+
+    Removes element from a JSON array at the index @a idx.
+
+    @param[in] idx index of the element to remove
+
+    @throw type_error.307 when called on a type other than JSON object;
+    example: `"cannot use erase() with null"`
+    @throw out_of_range.401 when `idx >= size()`; example: `"array index 17
+    is out of range"`
+
+    @complexity Linear in distance between @a idx and the end of the container.
+
+    @liveexample{The example shows the effect of `erase()`.,erase__size_type}
+
+    @sa @ref erase(IteratorType) -- removes the element at a given position
+    @sa @ref erase(IteratorType, IteratorType) -- removes the elements in
+    the given range
+    @sa @ref erase(const typename object_t::key_type&) -- removes the element
+    from an object at the given key
+
+    @since version 1.0.0
+    */
+    void erase(const size_type idx);
+
+    /// @}
+
+
+    ////////////
+    // lookup //
+    ////////////
+
+    /// @name lookup
+    /// @{
+
+    /*!
+    @brief find an element in a JSON object
+
+    Finds an element in a JSON object with key equivalent to @a key. If the
+    element is not found or the JSON value is not an object, end() is
+    returned.
+
+    @note This method always returns @ref end() when executed on a JSON type
+          that is not an object.
+
+    @param[in] key key value of the element to search for.
+
+    @return Iterator to an element with key equivalent to @a key. If no such
+    element is found or the JSON value is not an object, past-the-end (see
+    @ref end()) iterator is returned.
+
+    @complexity Logarithmic in the size of the JSON object.
+
+    @liveexample{The example shows how `find()` is used.,find__key_type}
+
+    @since version 1.0.0
+    */
+    iterator find(StringRef key);
+
+    /*!
+    @brief find an element in a JSON object
+    @copydoc find(KeyT&&)
+    */
+    const_iterator find(StringRef key) const;
+
+    /*!
+    @brief returns the number of occurrences of a key in a JSON object
+
+    Returns the number of elements with key @a key. If ObjectType is the
+    default `std::map` type, the return value will always be `0` (@a key was
+    not found) or `1` (@a key was found).
+
+    @note This method always returns `0` when executed on a JSON type that is
+          not an object.
+
+    @param[in] key key value of the element to count
+
+    @return Number of elements with key @a key. If the JSON value is not an
+    object, the return value will be `0`.
+
+    @complexity Logarithmic in the size of the JSON object.
+
+    @liveexample{The example shows how `count()` is used.,count}
+
+    @since version 1.0.0
+    */
+    size_type count(StringRef key) const;
+
+    /// @}
+
+
+    ///////////////
+    // iterators //
+    ///////////////
+
+    /// @name iterators
+    /// @{
+
+    /*!
+    @brief returns an iterator to the first element
+
+    Returns an iterator to the first element.
+
+    @image html range-begin-end.svg "Illustration from cppreference.com"
+
+    @return iterator to the first element
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+
+    @liveexample{The following code shows an example for `begin()`.,begin}
+
+    @sa @ref cbegin() -- returns a const iterator to the beginning
+    @sa @ref end() -- returns an iterator to the end
+    @sa @ref cend() -- returns a const iterator to the end
+
+    @since version 1.0.0
+    */
+    iterator begin() noexcept
+    {
+        iterator result(this);
+        result.set_begin();
+        return result;
+    }
+
+    /*!
+    @copydoc json::cbegin()
+    */
+    const_iterator begin() const noexcept
+    {
+        return cbegin();
+    }
+
+    /*!
+    @brief returns a const iterator to the first element
+
+    Returns a const iterator to the first element.
+
+    @image html range-begin-end.svg "Illustration from cppreference.com"
+
+    @return const iterator to the first element
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `const_cast<const json&>(*this).begin()`.
+
+    @liveexample{The following code shows an example for `cbegin()`.,cbegin}
+
+    @sa @ref begin() -- returns an iterator to the beginning
+    @sa @ref end() -- returns an iterator to the end
+    @sa @ref cend() -- returns a const iterator to the end
+
+    @since version 1.0.0
+    */
+    const_iterator cbegin() const noexcept
+    {
+        const_iterator result(this);
+        result.set_begin();
+        return result;
+    }
+
+    /*!
+    @brief returns an iterator to one past the last element
+
+    Returns an iterator to one past the last element.
+
+    @image html range-begin-end.svg "Illustration from cppreference.com"
+
+    @return iterator one past the last element
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+
+    @liveexample{The following code shows an example for `end()`.,end}
+
+    @sa @ref cend() -- returns a const iterator to the end
+    @sa @ref begin() -- returns an iterator to the beginning
+    @sa @ref cbegin() -- returns a const iterator to the beginning
+
+    @since version 1.0.0
+    */
+    iterator end() noexcept
+    {
+        iterator result(this);
+        result.set_end();
+        return result;
+    }
+
+    /*!
+    @copydoc json::cend()
+    */
+    const_iterator end() const noexcept
+    {
+        return cend();
+    }
+
+    /*!
+    @brief returns a const iterator to one past the last element
+
+    Returns a const iterator to one past the last element.
+
+    @image html range-begin-end.svg "Illustration from cppreference.com"
+
+    @return const iterator one past the last element
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `const_cast<const json&>(*this).end()`.
+
+    @liveexample{The following code shows an example for `cend()`.,cend}
+
+    @sa @ref end() -- returns an iterator to the end
+    @sa @ref begin() -- returns an iterator to the beginning
+    @sa @ref cbegin() -- returns a const iterator to the beginning
+
+    @since version 1.0.0
+    */
+    const_iterator cend() const noexcept
+    {
+        const_iterator result(this);
+        result.set_end();
+        return result;
+    }
+
+    /*!
+    @brief returns an iterator to the reverse-beginning
+
+    Returns an iterator to the reverse-beginning; that is, the last element.
+
+    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `reverse_iterator(end())`.
+
+    @liveexample{The following code shows an example for `rbegin()`.,rbegin}
+
+    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
+    @sa @ref rend() -- returns a reverse iterator to the end
+    @sa @ref crend() -- returns a const reverse iterator to the end
+
+    @since version 1.0.0
+    */
+    reverse_iterator rbegin() noexcept
+    {
+        return reverse_iterator(end());
+    }
+
+    /*!
+    @copydoc json::crbegin()
+    */
+    const_reverse_iterator rbegin() const noexcept
+    {
+        return crbegin();
+    }
+
+    /*!
+    @brief returns an iterator to the reverse-end
+
+    Returns an iterator to the reverse-end; that is, one before the first
+    element.
+
+    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `reverse_iterator(begin())`.
+
+    @liveexample{The following code shows an example for `rend()`.,rend}
+
+    @sa @ref crend() -- returns a const reverse iterator to the end
+    @sa @ref rbegin() -- returns a reverse iterator to the beginning
+    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
+
+    @since version 1.0.0
+    */
+    reverse_iterator rend() noexcept
+    {
+        return reverse_iterator(begin());
+    }
+
+    /*!
+    @copydoc json::crend()
+    */
+    const_reverse_iterator rend() const noexcept
+    {
+        return crend();
+    }
+
+    /*!
+    @brief returns a const reverse iterator to the last element
+
+    Returns a const iterator to the reverse-beginning; that is, the last
+    element.
+
+    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `const_cast<const json&>(*this).rbegin()`.
+
+    @liveexample{The following code shows an example for `crbegin()`.,crbegin}
+
+    @sa @ref rbegin() -- returns a reverse iterator to the beginning
+    @sa @ref rend() -- returns a reverse iterator to the end
+    @sa @ref crend() -- returns a const reverse iterator to the end
+
+    @since version 1.0.0
+    */
+    const_reverse_iterator crbegin() const noexcept
+    {
+        return const_reverse_iterator(cend());
+    }
+
+    /*!
+    @brief returns a const reverse iterator to one before the first
+
+    Returns a const reverse iterator to the reverse-end; that is, one before
+    the first element.
+
+    @image html range-rbegin-rend.svg "Illustration from cppreference.com"
+
+    @complexity Constant.
+
+    @requirement This function helps `json` satisfying the
+    [ReversibleContainer](http://en.cppreference.com/w/cpp/concept/ReversibleContainer)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `const_cast<const json&>(*this).rend()`.
+
+    @liveexample{The following code shows an example for `crend()`.,crend}
+
+    @sa @ref rend() -- returns a reverse iterator to the end
+    @sa @ref rbegin() -- returns a reverse iterator to the beginning
+    @sa @ref crbegin() -- returns a const reverse iterator to the beginning
+
+    @since version 1.0.0
+    */
+    const_reverse_iterator crend() const noexcept
+    {
+        return const_reverse_iterator(cbegin());
+    }
+
+  public:
+    /*!
+    @brief helper to access iterator member functions in range-based for
+
+    This function allows to access @ref iterator::key() and @ref
+    iterator::value() during range-based for loops. In these loops, a
+    reference to the JSON values is returned, so there is no access to the
+    underlying iterator.
+
+    For loop without `items()` function:
+
+    @code{cpp}
+    for (auto it = j_object.begin(); it != j_object.end(); ++it)
+    {
+        std::cout << "key: " << it.key() << ", value:" << it.value() << '\n';
+    }
+    @endcode
+
+    Range-based for loop without `items()` function:
+
+    @code{cpp}
+    for (auto it : j_object)
+    {
+        // "it" is of type json::reference and has no key() member
+        std::cout << "value: " << it << '\n';
+    }
+    @endcode
+
+    Range-based for loop with `items()` function:
+
+    @code{cpp}
+    for (auto it : j_object.items())
+    {
+        std::cout << "key: " << it.key() << ", value:" << it.value() << '\n';
+    }
+    @endcode
+
+    @note When iterating over an array, `key()` will return the index of the
+          element as string (see example). For primitive types (e.g., numbers),
+          `key()` returns an empty string.
+
+    @return iteration proxy object wrapping @a ref with an interface to use in
+            range-based for loops
+
+    @liveexample{The following code shows how the function is used.,items}
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 3.x.x.
+    */
+    iteration_proxy<iterator> items() noexcept
+    {
+        return iteration_proxy<iterator>(*this);
+    }
+
+    /*!
+    @copydoc items()
+    */
+    iteration_proxy<const_iterator> items() const noexcept
+    {
+        return iteration_proxy<const_iterator>(*this);
+    }
+
+    /// @}
+
+
+    //////////////
+    // capacity //
+    //////////////
+
+    /// @name capacity
+    /// @{
+
+    /*!
+    @brief checks whether the container is empty.
+
+    Checks if a JSON value has no elements (i.e. whether its @ref size is `0`).
+
+    @return The return value depends on the different types and is
+            defined as follows:
+            Value type  | return value
+            ----------- | -------------
+            null        | `true`
+            boolean     | `false`
+            string      | `false`
+            number      | `false`
+            object      | result of function `object_t::empty()`
+            array       | result of function `array_t::empty()`
+
+    @liveexample{The following code uses `empty()` to check if a JSON
+    object contains any elements.,empty}
+
+    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
+    the Container concept; that is, their `empty()` functions have constant
+    complexity.
+
+    @iterators No changes.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @note This function does not return whether a string stored as JSON value
+    is empty - it returns whether the JSON container itself is empty which is
+    false in the case of a string.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `begin() == end()`.
+
+    @sa @ref size() -- returns the number of elements
+
+    @since version 1.0.0
+    */
+    bool empty() const noexcept;
+
+    /*!
+    @brief returns the number of elements
+
+    Returns the number of elements in a JSON value.
+
+    @return The return value depends on the different types and is
+            defined as follows:
+            Value type  | return value
+            ----------- | -------------
+            null        | `0`
+            boolean     | `1`
+            string      | `1`
+            number      | `1`
+            object      | result of function object_t::size()
+            array       | result of function array_t::size()
+
+    @liveexample{The following code calls `size()` on the different value
+    types.,size}
+
+    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
+    the Container concept; that is, their size() functions have constant
+    complexity.
+
+    @iterators No changes.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @note This function does not return the length of a string stored as JSON
+    value - it returns the number of elements in the JSON value which is 1 in
+    the case of a string.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of `std::distance(begin(), end())`.
+
+    @sa @ref empty() -- checks whether the container is empty
+    @sa @ref max_size() -- returns the maximal number of elements
+
+    @since version 1.0.0
+    */
+    size_type size() const noexcept;
+
+    /*!
+    @brief returns the maximum possible number of elements
+
+    Returns the maximum number of elements a JSON value is able to hold due to
+    system or library implementation limitations, i.e. `std::distance(begin(),
+    end())` for the JSON value.
+
+    @return The return value depends on the different types and is
+            defined as follows:
+            Value type  | return value
+            ----------- | -------------
+            null        | `0` (same as `size()`)
+            boolean     | `1` (same as `size()`)
+            string      | `1` (same as `size()`)
+            number      | `1` (same as `size()`)
+            object      | result of function `object_t::max_size()`
+            array       | result of function `array_t::max_size()`
+
+    @liveexample{The following code calls `max_size()` on the different value
+    types. Note the output is implementation specific.,max_size}
+
+    @complexity Constant, as long as @ref array_t and @ref object_t satisfy
+    the Container concept; that is, their `max_size()` functions have constant
+    complexity.
+
+    @iterators No changes.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @requirement This function helps `json` satisfying the
+    [Container](http://en.cppreference.com/w/cpp/concept/Container)
+    requirements:
+    - The complexity is constant.
+    - Has the semantics of returning `b.size()` where `b` is the largest
+      possible JSON value.
+
+    @sa @ref size() -- returns the number of elements
+
+    @since version 1.0.0
+    */
+    size_type max_size() const noexcept;
+
+    /// @}
+
+
+    ///////////////
+    // modifiers //
+    ///////////////
+
+    /// @name modifiers
+    /// @{
+
+    /*!
+    @brief clears the contents
+
+    Clears the content of a JSON value and resets it to the default value as
+    if @ref json(value_t) would have been called with the current value
+    type from @ref type():
+
+    Value type  | initial value
+    ----------- | -------------
+    null        | `null`
+    boolean     | `false`
+    string      | `""`
+    number      | `0`
+    object      | `{}`
+    array       | `[]`
+
+    @post Has the same effect as calling
+    @code {.cpp}
+    *this = json(type());
+    @endcode
+
+    @liveexample{The example below shows the effect of `clear()` to different
+    JSON types.,clear}
+
+    @complexity Linear in the size of the JSON value.
+
+    @iterators All iterators, pointers and references related to this container
+               are invalidated.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @sa @ref json(value_t) -- constructor that creates an object with the
+        same value than calling `clear()`
+
+    @since version 1.0.0
+    */
+    void clear() noexcept;
+
+    /*!
+    @brief add an object to an array
+
+    Appends the given element @a val to the end of the JSON value. If the
+    function is called on a JSON null value, an empty array is created before
+    appending @a val.
+
+    @param[in] val the value to add to the JSON array
+
+    @throw type_error.308 when called on a type other than JSON array or
+    null; example: `"cannot use push_back() with number"`
+
+    @complexity Amortized constant.
+
+    @liveexample{The example shows how `push_back()` and `+=` can be used to
+    add elements to a JSON array. Note how the `null` value was silently
+    converted to a JSON array.,push_back}
+
+    @since version 1.0.0
+    */
+    void push_back(json&& val);
+
+    /*!
+    @brief add an object to an array
+    @copydoc push_back(json&&)
+    */
+    reference operator+=(json&& val)
+    {
+        push_back(std::move(val));
+        return *this;
+    }
+
+    /*!
+    @brief add an object to an array
+    @copydoc push_back(json&&)
+    */
+    void push_back(const json& val);
+
+    /*!
+    @brief add an object to an array
+    @copydoc push_back(json&&)
+    */
+    reference operator+=(const json& val)
+    {
+        push_back(val);
+        return *this;
+    }
+
+    /*!
+    @brief add an object to an object
+
+    Inserts the given element @a val to the JSON object. If the function is
+    called on a JSON null value, an empty object is created before inserting
+    @a val.
+
+    @param[in] val the value to add to the JSON object
+
+    @throw type_error.308 when called on a type other than JSON object or
+    null; example: `"cannot use push_back() with number"`
+
+    @complexity Logarithmic in the size of the container, O(log(`size()`)).
+
+    @liveexample{The example shows how `push_back()` and `+=` can be used to
+    add elements to a JSON object. Note how the `null` value was silently
+    converted to a JSON object.,push_back__object_t__value}
+
+    @since version 1.0.0
+    */
+    template<typename T, typename U>
+    void push_back(const std::pair<T, U>& val)
+    {
+        // push_back only works for null objects or objects
+        if (JSON_UNLIKELY(not(is_null() or is_object())))
+        {
+            JSON_THROW(type_error::create(308, "cannot use push_back() with " + Twine(type_name())));
+        }
+
+        // transform null object into an object
+        if (is_null())
+        {
+            m_type = value_t::object;
+            m_value = value_t::object;
+            assert_invariant();
+        }
+
+        // add element to array
+        m_value.object->try_emplace(val.first, std::move(val.second));
+    }
+
+    /*!
+    @brief add an object to an object
+    @copydoc push_back(const typename object_t::value_type&)
+    */
+    template<typename T, typename U>
+    reference operator+=(const std::pair<T, U>& val)
+    {
+        push_back(val);
+        return *this;
+    }
+
+    /*!
+    @brief add an object to an object
+
+    This function allows to use `push_back` with an initializer list. In case
+
+    1. the current value is an object,
+    2. the initializer list @a init contains only two elements, and
+    3. the first element of @a init is a string,
+
+    @a init is converted into an object element and added using
+    @ref push_back(const typename object_t::value_type&). Otherwise, @a init
+    is converted to a JSON value and added using @ref push_back(json&&).
+
+    @param[in] init  an initializer list
+
+    @complexity Linear in the size of the initializer list @a init.
+
+    @note This function is required to resolve an ambiguous overload error,
+          because pairs like `{"key", "value"}` can be both interpreted as
+          `object_t::value_type` or `std::initializer_list<json>`, see
+          https://github.com/nlohmann/json/issues/235 for more information.
+
+    @liveexample{The example shows how initializer lists are treated as
+    objects when possible.,push_back__initializer_list}
+    */
+    void push_back(initializer_list_t init);
+
+    /*!
+    @brief add an object to an object
+    @copydoc push_back(initializer_list_t)
+    */
+    reference operator+=(initializer_list_t init)
+    {
+        push_back(init);
+        return *this;
+    }
+
+    /*!
+    @brief add an object to an array
+
+    Creates a JSON value from the passed parameters @a args to the end of the
+    JSON value. If the function is called on a JSON null value, an empty array
+    is created before appending the value created from @a args.
+
+    @param[in] args arguments to forward to a constructor of @ref json
+    @tparam Args compatible types to create a @ref json object
+
+    @throw type_error.311 when called on a type other than JSON array or
+    null; example: `"cannot use emplace_back() with number"`
+
+    @complexity Amortized constant.
+
+    @liveexample{The example shows how `push_back()` can be used to add
+    elements to a JSON array. Note how the `null` value was silently converted
+    to a JSON array.,emplace_back}
+
+    @since version 2.0.8
+    */
+    template<class... Args>
+    void emplace_back(Args&& ... args)
+    {
+        // emplace_back only works for null objects or arrays
+        if (JSON_UNLIKELY(not(is_null() or is_array())))
+        {
+            JSON_THROW(type_error::create(311, "cannot use emplace_back() with " + Twine(type_name())));
+        }
+
+        // transform null object into an array
+        if (is_null())
+        {
+            m_type = value_t::array;
+            m_value = value_t::array;
+            assert_invariant();
+        }
+
+        // add element to array (perfect forwarding)
+        m_value.array->emplace_back(std::forward<Args>(args)...);
+    }
+
+    /*!
+    @brief add an object to an object if key does not exist
+
+    Inserts a new element into a JSON object constructed in-place with the
+    given @a args if there is no element with the key in the container. If the
+    function is called on a JSON null value, an empty object is created before
+    appending the value created from @a args.
+
+    @param[in] args arguments to forward to a constructor of @ref json
+    @tparam Args compatible types to create a @ref json object
+
+    @return a pair consisting of an iterator to the inserted element, or the
+            already-existing element if no insertion happened, and a bool
+            denoting whether the insertion took place.
+
+    @throw type_error.311 when called on a type other than JSON object or
+    null; example: `"cannot use emplace() with number"`
+
+    @complexity Logarithmic in the size of the container, O(log(`size()`)).
+
+    @liveexample{The example shows how `emplace()` can be used to add elements
+    to a JSON object. Note how the `null` value was silently converted to a
+    JSON object. Further note how no value is added if there was already one
+    value stored with the same key.,emplace}
+
+    @since version 2.0.8
+    */
+    template<class... Args>
+    std::pair<iterator, bool> emplace(StringRef key, Args&& ... args)
+    {
+        // emplace only works for null objects or arrays
+        if (JSON_UNLIKELY(not(is_null() or is_object())))
+        {
+            JSON_THROW(type_error::create(311, "cannot use emplace() with " + Twine(type_name())));
+        }
+
+        // transform null object into an object
+        if (is_null())
+        {
+            m_type = value_t::object;
+            m_value = value_t::object;
+            assert_invariant();
+        }
+
+        // add element to array (perfect forwarding)
+        auto res = m_value.object->try_emplace(key, std::forward<Args>(args)...);
+        // create result iterator and set iterator to the result of emplace
+        auto it = begin();
+        it.m_it.object_iterator = res.first;
+
+        // return pair of iterator and boolean
+        return {it, res.second};
+    }
+
+    /*!
+    @brief inserts element
+
+    Inserts element @a val before iterator @a pos.
+
+    @param[in] pos iterator before which the content will be inserted; may be
+    the end() iterator
+    @param[in] val element to insert
+    @return iterator pointing to the inserted @a val.
+
+    @throw type_error.309 if called on JSON values other than arrays;
+    example: `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
+    example: `"iterator does not fit current value"`
+
+    @complexity Constant plus linear in the distance between @a pos and end of
+    the container.
+
+    @liveexample{The example shows how `insert()` is used.,insert}
+
+    @since version 1.0.0
+    */
+    iterator insert(const_iterator pos, const json& val);
+
+    /*!
+    @brief inserts element
+    @copydoc insert(const_iterator, const json&)
+    */
+    iterator insert(const_iterator pos, json&& val)
+    {
+        return insert(pos, val);
+    }
+
+    /*!
+    @brief inserts elements
+
+    Inserts @a cnt copies of @a val before iterator @a pos.
+
+    @param[in] pos iterator before which the content will be inserted; may be
+    the end() iterator
+    @param[in] cnt number of copies of @a val to insert
+    @param[in] val element to insert
+    @return iterator pointing to the first element inserted, or @a pos if
+    `cnt==0`
+
+    @throw type_error.309 if called on JSON values other than arrays; example:
+    `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
+    example: `"iterator does not fit current value"`
+
+    @complexity Linear in @a cnt plus linear in the distance between @a pos
+    and end of the container.
+
+    @liveexample{The example shows how `insert()` is used.,insert__count}
+
+    @since version 1.0.0
+    */
+    iterator insert(const_iterator pos, size_type cnt, const json& val);
+
+    /*!
+    @brief inserts elements
+
+    Inserts elements from range `[first, last)` before iterator @a pos.
+
+    @param[in] pos iterator before which the content will be inserted; may be
+    the end() iterator
+    @param[in] first begin of the range of elements to insert
+    @param[in] last end of the range of elements to insert
+
+    @throw type_error.309 if called on JSON values other than arrays; example:
+    `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
+    example: `"iterator does not fit current value"`
+    @throw invalid_iterator.210 if @a first and @a last do not belong to the
+    same JSON value; example: `"iterators do not fit"`
+    @throw invalid_iterator.211 if @a first or @a last are iterators into
+    container for which insert is called; example: `"passed iterators may not
+    belong to container"`
+
+    @return iterator pointing to the first element inserted, or @a pos if
+    `first==last`
+
+    @complexity Linear in `std::distance(first, last)` plus linear in the
+    distance between @a pos and end of the container.
+
+    @liveexample{The example shows how `insert()` is used.,insert__range}
+
+    @since version 1.0.0
+    */
+    iterator insert(const_iterator pos, const_iterator first, const_iterator last);
+
+    /*!
+    @brief inserts elements
+
+    Inserts elements from initializer list @a ilist before iterator @a pos.
+
+    @param[in] pos iterator before which the content will be inserted; may be
+    the end() iterator
+    @param[in] ilist initializer list to insert the values from
+
+    @throw type_error.309 if called on JSON values other than arrays; example:
+    `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if @a pos is not an iterator of *this;
+    example: `"iterator does not fit current value"`
+
+    @return iterator pointing to the first element inserted, or @a pos if
+    `ilist` is empty
+
+    @complexity Linear in `ilist.size()` plus linear in the distance between
+    @a pos and end of the container.
+
+    @liveexample{The example shows how `insert()` is used.,insert__ilist}
+
+    @since version 1.0.0
+    */
+    iterator insert(const_iterator pos, initializer_list_t ilist);
+
+    /*!
+    @brief inserts elements
+
+    Inserts elements from range `[first, last)`.
+
+    @param[in] first begin of the range of elements to insert
+    @param[in] last end of the range of elements to insert
+
+    @throw type_error.309 if called on JSON values other than objects; example:
+    `"cannot use insert() with string"`
+    @throw invalid_iterator.202 if iterator @a first or @a last does does not
+    point to an object; example: `"iterators first and last must point to
+    objects"`
+    @throw invalid_iterator.210 if @a first and @a last do not belong to the
+    same JSON value; example: `"iterators do not fit"`
+
+    @complexity Logarithmic: `O(N*log(size() + N))`, where `N` is the number
+    of elements to insert.
+
+    @liveexample{The example shows how `insert()` is used.,insert__range_object}
+
+    @since version 3.0.0
+    */
+    void insert(const_iterator first, const_iterator last);
+
+    /*!
+    @brief updates a JSON object from another object, overwriting existing keys
+
+    Inserts all values from JSON object @a j and overwrites existing keys.
+
+    @param[in] j  JSON object to read values from
+
+    @throw type_error.312 if called on JSON values other than objects; example:
+    `"cannot use update() with string"`
+
+    @complexity O(N*log(size() + N)), where N is the number of elements to
+                insert.
+
+    @liveexample{The example shows how `update()` is used.,update}
+
+    @sa https://docs.python.org/3.6/library/stdtypes.html#dict.update
+
+    @since version 3.0.0
+    */
+    void update(const_reference j);
+
+    /*!
+    @brief updates a JSON object from another object, overwriting existing keys
+
+    Inserts all values from from range `[first, last)` and overwrites existing
+    keys.
+
+    @param[in] first begin of the range of elements to insert
+    @param[in] last end of the range of elements to insert
+
+    @throw type_error.312 if called on JSON values other than objects; example:
+    `"cannot use update() with string"`
+    @throw invalid_iterator.202 if iterator @a first or @a last does does not
+    point to an object; example: `"iterators first and last must point to
+    objects"`
+    @throw invalid_iterator.210 if @a first and @a last do not belong to the
+    same JSON value; example: `"iterators do not fit"`
+
+    @complexity O(N*log(size() + N)), where N is the number of elements to
+                insert.
+
+    @liveexample{The example shows how `update()` is used__range.,update}
+
+    @sa https://docs.python.org/3.6/library/stdtypes.html#dict.update
+
+    @since version 3.0.0
+    */
+    void update(const_iterator first, const_iterator last);
+
+    /*!
+    @brief exchanges the values
+
+    Exchanges the contents of the JSON value with those of @a other. Does not
+    invoke any move, copy, or swap operations on individual elements. All
+    iterators and references remain valid. The past-the-end iterator is
+    invalidated.
+
+    @param[in,out] other JSON value to exchange the contents with
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how JSON values can be swapped with
+    `swap()`.,swap__reference}
+
+    @since version 1.0.0
+    */
+    void swap(reference other) noexcept (
+        std::is_nothrow_move_constructible<value_t>::value and
+        std::is_nothrow_move_assignable<value_t>::value and
+        std::is_nothrow_move_constructible<json_value>::value and
+        std::is_nothrow_move_assignable<json_value>::value
+    )
+    {
+        std::swap(m_type, other.m_type);
+        std::swap(m_value, other.m_value);
+        assert_invariant();
+    }
+
+    /*!
+    @brief exchanges the values
+
+    Exchanges the contents of a JSON array with those of @a other. Does not
+    invoke any move, copy, or swap operations on individual elements. All
+    iterators and references remain valid. The past-the-end iterator is
+    invalidated.
+
+    @param[in,out] other array to exchange the contents with
+
+    @throw type_error.310 when JSON value is not an array; example: `"cannot
+    use swap() with string"`
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how arrays can be swapped with
+    `swap()`.,swap__std_vector_json}
+
+    @since version 1.0.0
+    */
+    void swap(array_t& other)
+    {
+        // swap only works for arrays
+        if (JSON_LIKELY(is_array()))
+        {
+            std::swap(*(m_value.array), other);
+        }
+        else
+        {
+            JSON_THROW(type_error::create(310, "cannot use swap() with " + Twine(type_name())));
+        }
+    }
+
+    /*!
+    @brief exchanges the values
+
+    Exchanges the contents of a JSON object with those of @a other. Does not
+    invoke any move, copy, or swap operations on individual elements. All
+    iterators and references remain valid. The past-the-end iterator is
+    invalidated.
+
+    @param[in,out] other object to exchange the contents with
+
+    @throw type_error.310 when JSON value is not an object; example:
+    `"cannot use swap() with string"`
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how objects can be swapped with
+    `swap()`.,swap__object_t}
+
+    @since version 1.0.0
+    */
+    void swap(object_t& other)
+    {
+        // swap only works for objects
+        if (JSON_LIKELY(is_object()))
+        {
+            std::swap(*(m_value.object), other);
+        }
+        else
+        {
+            JSON_THROW(type_error::create(310, "cannot use swap() with " + Twine(type_name())));
+        }
+    }
+
+    /*!
+    @brief exchanges the values
+
+    Exchanges the contents of a JSON string with those of @a other. Does not
+    invoke any move, copy, or swap operations on individual elements. All
+    iterators and references remain valid. The past-the-end iterator is
+    invalidated.
+
+    @param[in,out] other string to exchange the contents with
+
+    @throw type_error.310 when JSON value is not a string; example: `"cannot
+    use swap() with boolean"`
+
+    @complexity Constant.
+
+    @liveexample{The example below shows how strings can be swapped with
+    `swap()`.,swap__std_string}
+
+    @since version 1.0.0
+    */
+    void swap(std::string& other)
+    {
+        // swap only works for strings
+        if (JSON_LIKELY(is_string()))
+        {
+            std::swap(*(m_value.string), other);
+        }
+        else
+        {
+            JSON_THROW(type_error::create(310, "cannot use swap() with " + Twine(type_name())));
+        }
+    }
+
+    /// @}
+
+  public:
+    //////////////////////////////////////////
+    // lexicographical comparison operators //
+    //////////////////////////////////////////
+
+    /// @name lexicographical comparison operators
+    /// @{
+
+    /*!
+    @brief comparison: equal
+
+    Compares two JSON values for equality according to the following rules:
+    - Two JSON values are equal if (1) they are from the same type and (2)
+      their stored values are the same according to their respective
+      `operator==`.
+    - Integer and floating-point numbers are automatically converted before
+      comparison. Note than two NaN values are always treated as unequal.
+    - Two JSON null values are equal.
+
+    @note Floating-point inside JSON values numbers are compared with
+    `double::operator==`.
+    To compare floating-point while respecting an epsilon, an alternative
+    [comparison function](https://github.com/mariokonrad/marnav/blob/master/src/marnav/math/floatingpoint.hpp#L34-#L39)
+    could be used, for instance
+    @code {.cpp}
+    template<typename T, typename = typename std::enable_if<std::is_floating_point<T>::value, T>::type>
+    inline bool is_same(T a, T b, T epsilon = std::numeric_limits<T>::epsilon()) noexcept
+    {
+        return std::abs(a - b) <= epsilon;
+    }
+    @endcode
+
+    @note NaN values never compare equal to themselves or to other NaN values.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether the values @a lhs and @a rhs are equal
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @complexity Linear.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__equal}
+
+    @since version 1.0.0
+    */
+    friend bool operator==(const_reference lhs, const_reference rhs) noexcept;
+
+    /*!
+    @brief comparison: equal
+    @copydoc operator==(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator==(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs == json(rhs));
+    }
+
+    /*!
+    @brief comparison: equal
+    @copydoc operator==(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator==(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) == rhs);
+    }
+
+    /*!
+    @brief comparison: not equal
+
+    Compares two JSON values for inequality by calculating `not (lhs == rhs)`.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether the values @a lhs and @a rhs are not equal
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__notequal}
+
+    @since version 1.0.0
+    */
+    friend bool operator!=(const_reference lhs, const_reference rhs) noexcept
+    {
+        return not (lhs == rhs);
+    }
+
+    /*!
+    @brief comparison: not equal
+    @copydoc operator!=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator!=(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs != json(rhs));
+    }
+
+    /*!
+    @brief comparison: not equal
+    @copydoc operator!=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator!=(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) != rhs);
+    }
+
+    /*!
+    @brief comparison: less than
+
+    Compares whether one JSON value @a lhs is less than another JSON value @a
+    rhs according to the following rules:
+    - If @a lhs and @a rhs have the same type, the values are compared using
+      the default `<` operator.
+    - Integer and floating-point numbers are automatically converted before
+      comparison
+    - In case @a lhs and @a rhs have different types, the values are ignored
+      and the order of the types is considered, see
+      @ref operator<(const value_t, const value_t).
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether @a lhs is less than @a rhs
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__less}
+
+    @since version 1.0.0
+    */
+    friend bool operator<(const_reference lhs, const_reference rhs) noexcept;
+
+    /*!
+    @brief comparison: less than
+    @copydoc operator<(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator<(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs < json(rhs));
+    }
+
+    /*!
+    @brief comparison: less than
+    @copydoc operator<(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator<(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) < rhs);
+    }
+
+    /*!
+    @brief comparison: less than or equal
+
+    Compares whether one JSON value @a lhs is less than or equal to another
+    JSON value by calculating `not (rhs < lhs)`.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether @a lhs is less than or equal to @a rhs
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__greater}
+
+    @since version 1.0.0
+    */
+    friend bool operator<=(const_reference lhs, const_reference rhs) noexcept
+    {
+        return not (rhs < lhs);
+    }
+
+    /*!
+    @brief comparison: less than or equal
+    @copydoc operator<=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator<=(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs <= json(rhs));
+    }
+
+    /*!
+    @brief comparison: less than or equal
+    @copydoc operator<=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator<=(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) <= rhs);
+    }
+
+    /*!
+    @brief comparison: greater than
+
+    Compares whether one JSON value @a lhs is greater than another
+    JSON value by calculating `not (lhs <= rhs)`.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether @a lhs is greater than to @a rhs
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__lessequal}
+
+    @since version 1.0.0
+    */
+    friend bool operator>(const_reference lhs, const_reference rhs) noexcept
+    {
+        return not (lhs <= rhs);
+    }
+
+    /*!
+    @brief comparison: greater than
+    @copydoc operator>(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator>(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs > json(rhs));
+    }
+
+    /*!
+    @brief comparison: greater than
+    @copydoc operator>(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator>(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) > rhs);
+    }
+
+    /*!
+    @brief comparison: greater than or equal
+
+    Compares whether one JSON value @a lhs is greater than or equal to another
+    JSON value by calculating `not (lhs < rhs)`.
+
+    @param[in] lhs  first JSON value to consider
+    @param[in] rhs  second JSON value to consider
+    @return whether @a lhs is greater than or equal to @a rhs
+
+    @complexity Linear.
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @liveexample{The example demonstrates comparing several JSON
+    types.,operator__greaterequal}
+
+    @since version 1.0.0
+    */
+    friend bool operator>=(const_reference lhs, const_reference rhs) noexcept
+    {
+        return not (lhs < rhs);
+    }
+
+    /*!
+    @brief comparison: greater than or equal
+    @copydoc operator>=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator>=(const_reference lhs, const ScalarType rhs) noexcept
+    {
+        return (lhs >= json(rhs));
+    }
+
+    /*!
+    @brief comparison: greater than or equal
+    @copydoc operator>=(const_reference, const_reference)
+    */
+    template<typename ScalarType, typename std::enable_if<
+                 std::is_scalar<ScalarType>::value, int>::type = 0>
+    friend bool operator>=(const ScalarType lhs, const_reference rhs) noexcept
+    {
+        return (json(lhs) >= rhs);
+    }
+
+    /// @}
+
+    ///////////////////
+    // serialization //
+    ///////////////////
+
+    /// @name serialization
+    /// @{
+
+    /*!
+    @brief serialize to stream
+
+    Serialize the given JSON value @a j to the output stream @a o. The JSON
+    value will be serialized using the @ref dump member function.
+
+    - The indentation of the output can be controlled with the member variable
+      `width` of the output stream @a o. For instance, using the manipulator
+      `std::setw(4)` on @a o sets the indentation level to `4` and the
+      serialization result is the same as calling `dump(4)`.
+
+    - The indentation character can be controlled with the member variable
+      `fill` of the output stream @a o. For instance, the manipulator
+      `std::setfill('\\t')` sets indentation to use a tab character rather than
+      the default space character.
+
+    @param[in,out] o  stream to serialize to
+    @param[in] j  JSON value to serialize
+
+    @return the stream @a o
+
+    @throw type_error.316 if a string stored inside the JSON value is not
+                          UTF-8 encoded
+
+    @complexity Linear.
+
+    @liveexample{The example below shows the serialization with different
+    parameters to `width` to adjust the indentation level.,operator_serialize}
+
+    @since version 1.0.0; indentation character added in version 3.0.0
+    */
+    friend raw_ostream& operator<<(raw_ostream& o, const json& j);
+
+    /// @}
+
+
+    /////////////////////
+    // deserialization //
+    /////////////////////
+
+    /// @name deserialization
+    /// @{
+
+    /*!
+    @brief deserialize from a compatible input
+
+    This function reads from a compatible input. Examples are:
+    - an array of 1-byte values
+    - strings with character/literal type with size of 1 byte
+    - input streams
+    - container with contiguous storage of 1-byte values. Compatible container
+      types include `std::vector`, `std::string`, `std::array`,
+      and `std::initializer_list`. Furthermore, C-style
+      arrays can be used with `std::begin()`/`std::end()`. User-defined
+      containers can be used as long as they implement random-access iterators
+      and a contiguous storage.
+
+    @pre Each element of the container has a size of 1 byte. Violating this
+    precondition yields undefined behavior. **This precondition is enforced
+    with a static assertion.**
+
+    @pre The container storage is contiguous. Violating this precondition
+    yields undefined behavior. **This precondition is enforced with an
+    assertion.**
+    @pre Each element of the container has a size of 1 byte. Violating this
+    precondition yields undefined behavior. **This precondition is enforced
+    with a static assertion.**
+
+    @warning There is no way to enforce all preconditions at compile-time. If
+             the function is called with a noncompliant container and with
+             assertions switched off, the behavior is undefined and will most
+             likely yield segmentation violation.
+
+    @param[in] i  input to read from
+    @param[in] cb  a parser callback function of type @ref parser_callback_t
+    which is used to control the deserialization by filtering unwanted values
+    (optional)
+
+    @return result of the deserialization
+
+    @throw parse_error.101 if a parse error occurs; example: `""unexpected end
+    of input; expected string literal""`
+    @throw parse_error.102 if to_unicode fails or surrogate error
+    @throw parse_error.103 if to_unicode fails
+
+    @complexity Linear in the length of the input. The parser is a predictive
+    LL(1) parser. The complexity can be higher if the parser callback function
+    @a cb has a super-linear complexity.
+
+    @note A UTF-8 byte order mark is silently ignored.
+
+    @liveexample{The example below demonstrates the `parse()` function reading
+    from an array.,parse__array__parser_callback_t}
+
+    @liveexample{The example below demonstrates the `parse()` function with
+    and without callback function.,parse__string__parser_callback_t}
+
+    @liveexample{The example below demonstrates the `parse()` function with
+    and without callback function.,parse__istream__parser_callback_t}
+
+    @liveexample{The example below demonstrates the `parse()` function reading
+    from a contiguous container.,parse__contiguouscontainer__parser_callback_t}
+
+    @since version 2.0.3 (contiguous containers)
+    */
+    static json parse(StringRef s,
+                            const parser_callback_t cb = nullptr,
+                            const bool allow_exceptions = true);
+
+    static json parse(ArrayRef<uint8_t> arr,
+                            const parser_callback_t cb = nullptr,
+                            const bool allow_exceptions = true);
+
+    /*!
+    @copydoc json parse(raw_istream&, const parser_callback_t)
+    */
+    static json parse(raw_istream& i,
+                            const parser_callback_t cb = nullptr,
+                            const bool allow_exceptions = true);
+
+    static bool accept(StringRef s);
+
+    static bool accept(ArrayRef<uint8_t> arr);
+
+    static bool accept(raw_istream& i);
+
+    /*!
+    @brief deserialize from stream
+
+    Deserializes an input stream to a JSON value.
+
+    @param[in,out] i  input stream to read a serialized JSON value from
+    @param[in,out] j  JSON value to write the deserialized input to
+
+    @throw parse_error.101 in case of an unexpected token
+    @throw parse_error.102 if to_unicode fails or surrogate error
+    @throw parse_error.103 if to_unicode fails
+
+    @complexity Linear in the length of the input. The parser is a predictive
+    LL(1) parser.
+
+    @note A UTF-8 byte order mark is silently ignored.
+
+    @liveexample{The example below shows how a JSON value is constructed by
+    reading a serialization from a stream.,operator_deserialize}
+
+    @sa parse(std::istream&, const parser_callback_t) for a variant with a
+    parser callback function to filter values while parsing
+
+    @since version 1.0.0
+    */
+    friend raw_istream& operator>>(raw_istream& i, json& j);
+
+    /// @}
+
+    ///////////////////////////
+    // convenience functions //
+    ///////////////////////////
+
+    /*!
+    @brief return the type as string
+
+    Returns the type name as string to be used in error messages - usually to
+    indicate that a function was called on a wrong JSON type.
+
+    @return a string representation of a the @a m_type member:
+            Value type  | return value
+            ----------- | -------------
+            null        | `"null"`
+            boolean     | `"boolean"`
+            string      | `"string"`
+            number      | `"number"` (for all number types)
+            object      | `"object"`
+            array       | `"array"`
+            discarded   | `"discarded"`
+
+    @exceptionsafety No-throw guarantee: this function never throws exceptions.
+
+    @complexity Constant.
+
+    @liveexample{The following code exemplifies `type_name()` for all JSON
+    types.,type_name}
+
+    @sa @ref type() -- return the type of the JSON value
+    @sa @ref operator value_t() -- return the type of the JSON value (implicit)
+
+    @since version 1.0.0, public since 2.1.0, `const char*` and `noexcept`
+    since 3.0.0
+    */
+    const char* type_name() const noexcept;
+
+
+  private:
+    //////////////////////
+    // member variables //
+    //////////////////////
+
+    /// the type of the current element
+    value_t m_type = value_t::null;
+
+    /// the value of the current element
+    json_value m_value = {};
+
+    //////////////////////////////////////////
+    // binary serialization/deserialization //
+    //////////////////////////////////////////
+
+    /// @name binary serialization/deserialization support
+    /// @{
+
+  public:
+    /*!
+    @brief create a CBOR serialization of a given JSON value
+
+    Serializes a given JSON value @a j to a byte vector using the CBOR (Concise
+    Binary Object Representation) serialization format. CBOR is a binary
+    serialization format which aims to be more compact than JSON itself, yet
+    more efficient to parse.
+
+    The library uses the following mapping from JSON values types to
+    CBOR types according to the CBOR specification (RFC 7049):
+
+    JSON value type | value/range                                | CBOR type                          | first byte
+    --------------- | ------------------------------------------ | ---------------------------------- | ---------------
+    null            | `null`                                     | Null                               | 0xF6
+    boolean         | `true`                                     | True                               | 0xF5
+    boolean         | `false`                                    | False                              | 0xF4
+    number_integer  | -9223372036854775808..-2147483649          | Negative integer (8 bytes follow)  | 0x3B
+    number_integer  | -2147483648..-32769                        | Negative integer (4 bytes follow)  | 0x3A
+    number_integer  | -32768..-129                               | Negative integer (2 bytes follow)  | 0x39
+    number_integer  | -128..-25                                  | Negative integer (1 byte follow)   | 0x38
+    number_integer  | -24..-1                                    | Negative integer                   | 0x20..0x37
+    number_integer  | 0..23                                      | Integer                            | 0x00..0x17
+    number_integer  | 24..255                                    | Unsigned integer (1 byte follow)   | 0x18
+    number_integer  | 256..65535                                 | Unsigned integer (2 bytes follow)  | 0x19
+    number_integer  | 65536..4294967295                          | Unsigned integer (4 bytes follow)  | 0x1A
+    number_integer  | 4294967296..18446744073709551615           | Unsigned integer (8 bytes follow)  | 0x1B
+    number_unsigned | 0..23                                      | Integer                            | 0x00..0x17
+    number_unsigned | 24..255                                    | Unsigned integer (1 byte follow)   | 0x18
+    number_unsigned | 256..65535                                 | Unsigned integer (2 bytes follow)  | 0x19
+    number_unsigned | 65536..4294967295                          | Unsigned integer (4 bytes follow)  | 0x1A
+    number_unsigned | 4294967296..18446744073709551615           | Unsigned integer (8 bytes follow)  | 0x1B
+    number_float    | *any value*                                | Double-Precision Float             | 0xFB
+    string          | *length*: 0..23                            | UTF-8 string                       | 0x60..0x77
+    string          | *length*: 23..255                          | UTF-8 string (1 byte follow)       | 0x78
+    string          | *length*: 256..65535                       | UTF-8 string (2 bytes follow)      | 0x79
+    string          | *length*: 65536..4294967295                | UTF-8 string (4 bytes follow)      | 0x7A
+    string          | *length*: 4294967296..18446744073709551615 | UTF-8 string (8 bytes follow)      | 0x7B
+    array           | *size*: 0..23                              | array                              | 0x80..0x97
+    array           | *size*: 23..255                            | array (1 byte follow)              | 0x98
+    array           | *size*: 256..65535                         | array (2 bytes follow)             | 0x99
+    array           | *size*: 65536..4294967295                  | array (4 bytes follow)             | 0x9A
+    array           | *size*: 4294967296..18446744073709551615   | array (8 bytes follow)             | 0x9B
+    object          | *size*: 0..23                              | map                                | 0xA0..0xB7
+    object          | *size*: 23..255                            | map (1 byte follow)                | 0xB8
+    object          | *size*: 256..65535                         | map (2 bytes follow)               | 0xB9
+    object          | *size*: 65536..4294967295                  | map (4 bytes follow)               | 0xBA
+    object          | *size*: 4294967296..18446744073709551615   | map (8 bytes follow)               | 0xBB
+
+    @note The mapping is **complete** in the sense that any JSON value type
+          can be converted to a CBOR value.
+
+    @note If NaN or Infinity are stored inside a JSON number, they are
+          serialized properly. This behavior differs from the @ref dump()
+          function which serializes NaN or Infinity to `null`.
+
+    @note The following CBOR types are not used in the conversion:
+          - byte strings (0x40..0x5F)
+          - UTF-8 strings terminated by "break" (0x7F)
+          - arrays terminated by "break" (0x9F)
+          - maps terminated by "break" (0xBF)
+          - date/time (0xC0..0xC1)
+          - bignum (0xC2..0xC3)
+          - decimal fraction (0xC4)
+          - bigfloat (0xC5)
+          - tagged items (0xC6..0xD4, 0xD8..0xDB)
+          - expected conversions (0xD5..0xD7)
+          - simple values (0xE0..0xF3, 0xF8)
+          - undefined (0xF7)
+          - half and single-precision floats (0xF9-0xFA)
+          - break (0xFF)
+
+    @param[in] j  JSON value to serialize
+    @return MessagePack serialization as byte vector
+
+    @complexity Linear in the size of the JSON value @a j.
+
+    @liveexample{The example shows the serialization of a JSON value to a byte
+    vector in CBOR format.,to_cbor}
+
+    @sa http://cbor.io
+    @sa @ref from_cbor(raw_istream&, const bool strict) for the
+        analogous deserialization
+    @sa @ref to_msgpack(const json&) for the related MessagePack format
+    @sa @ref to_ubjson(const json&, const bool, const bool) for the
+             related UBJSON format
+
+    @since version 2.0.9
+    */
+    static std::vector<uint8_t> to_cbor(const json& j);
+    static ArrayRef<uint8_t> to_cbor(const json& j, std::vector<uint8_t>& buf);
+    static ArrayRef<uint8_t> to_cbor(const json& j, SmallVectorImpl<uint8_t>& buf);
+    static void to_cbor(raw_ostream& os, const json& j);
+
+    /*!
+    @brief create a MessagePack serialization of a given JSON value
+
+    Serializes a given JSON value @a j to a byte vector using the MessagePack
+    serialization format. MessagePack is a binary serialization format which
+    aims to be more compact than JSON itself, yet more efficient to parse.
+
+    The library uses the following mapping from JSON values types to
+    MessagePack types according to the MessagePack specification:
+
+    JSON value type | value/range                       | MessagePack type | first byte
+    --------------- | --------------------------------- | ---------------- | ----------
+    null            | `null`                            | nil              | 0xC0
+    boolean         | `true`                            | true             | 0xC3
+    boolean         | `false`                           | false            | 0xC2
+    number_integer  | -9223372036854775808..-2147483649 | int64            | 0xD3
+    number_integer  | -2147483648..-32769               | int32            | 0xD2
+    number_integer  | -32768..-129                      | int16            | 0xD1
+    number_integer  | -128..-33                         | int8             | 0xD0
+    number_integer  | -32..-1                           | negative fixint  | 0xE0..0xFF
+    number_integer  | 0..127                            | positive fixint  | 0x00..0x7F
+    number_integer  | 128..255                          | uint 8           | 0xCC
+    number_integer  | 256..65535                        | uint 16          | 0xCD
+    number_integer  | 65536..4294967295                 | uint 32          | 0xCE
+    number_integer  | 4294967296..18446744073709551615  | uint 64          | 0xCF
+    number_unsigned | 0..127                            | positive fixint  | 0x00..0x7F
+    number_unsigned | 128..255                          | uint 8           | 0xCC
+    number_unsigned | 256..65535                        | uint 16          | 0xCD
+    number_unsigned | 65536..4294967295                 | uint 32          | 0xCE
+    number_unsigned | 4294967296..18446744073709551615  | uint 64          | 0xCF
+    number_float    | *any value*                       | float 64         | 0xCB
+    string          | *length*: 0..31                   | fixstr           | 0xA0..0xBF
+    string          | *length*: 32..255                 | str 8            | 0xD9
+    string          | *length*: 256..65535              | str 16           | 0xDA
+    string          | *length*: 65536..4294967295       | str 32           | 0xDB
+    array           | *size*: 0..15                     | fixarray         | 0x90..0x9F
+    array           | *size*: 16..65535                 | array 16         | 0xDC
+    array           | *size*: 65536..4294967295         | array 32         | 0xDD
+    object          | *size*: 0..15                     | fix map          | 0x80..0x8F
+    object          | *size*: 16..65535                 | map 16           | 0xDE
+    object          | *size*: 65536..4294967295         | map 32           | 0xDF
+
+    @note The mapping is **complete** in the sense that any JSON value type
+          can be converted to a MessagePack value.
+
+    @note The following values can **not** be converted to a MessagePack value:
+          - strings with more than 4294967295 bytes
+          - arrays with more than 4294967295 elements
+          - objects with more than 4294967295 elements
+
+    @note The following MessagePack types are not used in the conversion:
+          - bin 8 - bin 32 (0xC4..0xC6)
+          - ext 8 - ext 32 (0xC7..0xC9)
+          - float 32 (0xCA)
+          - fixext 1 - fixext 16 (0xD4..0xD8)
+
+    @note Any MessagePack output created @ref to_msgpack can be successfully
+          parsed by @ref from_msgpack.
+
+    @note If NaN or Infinity are stored inside a JSON number, they are
+          serialized properly. This behavior differs from the @ref dump()
+          function which serializes NaN or Infinity to `null`.
+
+    @param[in] j  JSON value to serialize
+    @return MessagePack serialization as byte vector
+
+    @complexity Linear in the size of the JSON value @a j.
+
+    @liveexample{The example shows the serialization of a JSON value to a byte
+    vector in MessagePack format.,to_msgpack}
+
+    @sa http://msgpack.org
+    @sa @ref from_msgpack(const std::vector<uint8_t>&, const size_t) for the
+        analogous deserialization
+    @sa @ref to_cbor(const json& for the related CBOR format
+    @sa @ref to_ubjson(const json&, const bool, const bool) for the
+             related UBJSON format
+
+    @since version 2.0.9
+    */
+    static std::vector<uint8_t> to_msgpack(const json& j);
+    static ArrayRef<uint8_t> to_msgpack(const json& j, std::vector<uint8_t>& buf);
+    static ArrayRef<uint8_t> to_msgpack(const json& j, SmallVectorImpl<uint8_t>& buf);
+    static void to_msgpack(raw_ostream& os, const json& j);
+
+    /*!
+    @brief create a UBJSON serialization of a given JSON value
+
+    Serializes a given JSON value @a j to a byte vector using the UBJSON
+    (Universal Binary JSON) serialization format. UBJSON aims to be more compact
+    than JSON itself, yet more efficient to parse.
+
+    The library uses the following mapping from JSON values types to
+    UBJSON types according to the UBJSON specification:
+
+    JSON value type | value/range                       | UBJSON type | marker
+    --------------- | --------------------------------- | ----------- | ------
+    null            | `null`                            | null        | `Z`
+    boolean         | `true`                            | true        | `T`
+    boolean         | `false`                           | false       | `F`
+    number_integer  | -9223372036854775808..-2147483649 | int64       | `L`
+    number_integer  | -2147483648..-32769               | int32       | `l`
+    number_integer  | -32768..-129                      | int16       | `I`
+    number_integer  | -128..127                         | int8        | `i`
+    number_integer  | 128..255                          | uint8       | `U`
+    number_integer  | 256..32767                        | int16       | `I`
+    number_integer  | 32768..2147483647                 | int32       | `l`
+    number_integer  | 2147483648..9223372036854775807   | int64       | `L`
+    number_unsigned | 0..127                            | int8        | `i`
+    number_unsigned | 128..255                          | uint8       | `U`
+    number_unsigned | 256..32767                        | int16       | `I`
+    number_unsigned | 32768..2147483647                 | int32       | `l`
+    number_unsigned | 2147483648..9223372036854775807   | int64       | `L`
+    number_float    | *any value*                       | float64     | `D`
+    string          | *with shortest length indicator*  | string      | `S`
+    array           | *see notes on optimized format*   | array       | `[`
+    object          | *see notes on optimized format*   | map         | `{`
+
+    @note The mapping is **complete** in the sense that any JSON value type
+          can be converted to a UBJSON value.
+
+    @note The following values can **not** be converted to a UBJSON value:
+          - strings with more than 9223372036854775807 bytes (theoretical)
+          - unsigned integer numbers above 9223372036854775807
+
+    @note The following markers are not used in the conversion:
+          - `Z`: no-op values are not created.
+          - `C`: single-byte strings are serialized with `S` markers.
+
+    @note Any UBJSON output created @ref to_ubjson can be successfully parsed
+          by @ref from_ubjson.
+
+    @note If NaN or Infinity are stored inside a JSON number, they are
+          serialized properly. This behavior differs from the @ref dump()
+          function which serializes NaN or Infinity to `null`.
+
+    @note The optimized formats for containers are supported: Parameter
+          @a use_size adds size information to the beginning of a container and
+          removes the closing marker. Parameter @a use_type further checks
+          whether all elements of a container have the same type and adds the
+          type marker to the beginning of the container. The @a use_type
+          parameter must only be used together with @a use_size = true. Note
+          that @a use_size = true alone may result in larger representations -
+          the benefit of this parameter is that the receiving side is
+          immediately informed on the number of elements of the container.
+
+    @param[in] j  JSON value to serialize
+    @param[in] use_size  whether to add size annotations to container types
+    @param[in] use_type  whether to add type annotations to container types
+                         (must be combined with @a use_size = true)
+    @return UBJSON serialization as byte vector
+
+    @complexity Linear in the size of the JSON value @a j.
+
+    @liveexample{The example shows the serialization of a JSON value to a byte
+    vector in UBJSON format.,to_ubjson}
+
+    @sa http://ubjson.org
+    @sa @ref from_ubjson(raw_istream&, const bool strict) for the
+        analogous deserialization
+    @sa @ref to_cbor(const json& for the related CBOR format
+    @sa @ref to_msgpack(const json&) for the related MessagePack format
+
+    @since version 3.1.0
+    */
+    static std::vector<uint8_t> to_ubjson(const json& j,
+                                          const bool use_size = false,
+                                          const bool use_type = false);
+    static ArrayRef<uint8_t> to_ubjson(const json& j, std::vector<uint8_t>& buf,
+                                       const bool use_size = false, const bool use_type = false);
+    static ArrayRef<uint8_t> to_ubjson(const json& j, SmallVectorImpl<uint8_t>& buf,
+                                       const bool use_size = false, const bool use_type = false);
+    static void to_ubjson(raw_ostream& os, const json& j,
+                          const bool use_size = false, const bool use_type = false);
+
+    /*!
+    @brief create a JSON value from an input in CBOR format
+
+    Deserializes a given input @a i to a JSON value using the CBOR (Concise
+    Binary Object Representation) serialization format.
+
+    The library maps CBOR types to JSON value types as follows:
+
+    CBOR type              | JSON value type | first byte
+    ---------------------- | --------------- | ----------
+    Integer                | number_unsigned | 0x00..0x17
+    Unsigned integer       | number_unsigned | 0x18
+    Unsigned integer       | number_unsigned | 0x19
+    Unsigned integer       | number_unsigned | 0x1A
+    Unsigned integer       | number_unsigned | 0x1B
+    Negative integer       | number_integer  | 0x20..0x37
+    Negative integer       | number_integer  | 0x38
+    Negative integer       | number_integer  | 0x39
+    Negative integer       | number_integer  | 0x3A
+    Negative integer       | number_integer  | 0x3B
+    Negative integer       | number_integer  | 0x40..0x57
+    UTF-8 string           | string          | 0x60..0x77
+    UTF-8 string           | string          | 0x78
+    UTF-8 string           | string          | 0x79
+    UTF-8 string           | string          | 0x7A
+    UTF-8 string           | string          | 0x7B
+    UTF-8 string           | string          | 0x7F
+    array                  | array           | 0x80..0x97
+    array                  | array           | 0x98
+    array                  | array           | 0x99
+    array                  | array           | 0x9A
+    array                  | array           | 0x9B
+    array                  | array           | 0x9F
+    map                    | object          | 0xA0..0xB7
+    map                    | object          | 0xB8
+    map                    | object          | 0xB9
+    map                    | object          | 0xBA
+    map                    | object          | 0xBB
+    map                    | object          | 0xBF
+    False                  | `false`         | 0xF4
+    True                   | `true`          | 0xF5
+    Nill                   | `null`          | 0xF6
+    Half-Precision Float   | number_float    | 0xF9
+    Single-Precision Float | number_float    | 0xFA
+    Double-Precision Float | number_float    | 0xFB
+
+    @warning The mapping is **incomplete** in the sense that not all CBOR
+             types can be converted to a JSON value. The following CBOR types
+             are not supported and will yield parse errors (parse_error.112):
+             - byte strings (0x40..0x5F)
+             - date/time (0xC0..0xC1)
+             - bignum (0xC2..0xC3)
+             - decimal fraction (0xC4)
+             - bigfloat (0xC5)
+             - tagged items (0xC6..0xD4, 0xD8..0xDB)
+             - expected conversions (0xD5..0xD7)
+             - simple values (0xE0..0xF3, 0xF8)
+             - undefined (0xF7)
+
+    @warning CBOR allows map keys of any type, whereas JSON only allows
+             strings as keys in object values. Therefore, CBOR maps with keys
+             other than UTF-8 strings are rejected (parse_error.113).
+
+    @note Any CBOR output created @ref to_cbor can be successfully parsed by
+          @ref from_cbor.
+
+    @param[in] i  an input in CBOR format convertible to an input adapter
+    @param[in] strict  whether to expect the input to be consumed until EOF
+                       (true by default)
+    @return deserialized JSON value
+
+    @throw parse_error.110 if the given input ends prematurely or the end of
+    file was not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported features from CBOR were
+    used in the given input @a v or if the input is not valid CBOR
+    @throw parse_error.113 if a string was expected as map key, but not found
+
+    @complexity Linear in the size of the input @a i.
+
+    @liveexample{The example shows the deserialization of a byte vector in CBOR
+    format to a JSON value.,from_cbor}
+
+    @sa http://cbor.io
+    @sa @ref to_cbor(const json&) for the analogous serialization
+    @sa @ref from_msgpack(raw_istream&, const bool) for the
+        related MessagePack format
+    @sa @ref from_ubjson(raw_istream&, const bool) for the related
+        UBJSON format
+
+    @since version 2.0.9; parameter @a start_index since 2.1.1; changed to
+           consume input adapters, removed start_index parameter, and added
+           @a strict parameter since 3.0.0
+    */
+    static json from_cbor(raw_istream& is,
+                                const bool strict = true);
+
+    /*!
+    @copydoc from_cbor(raw_istream&, const bool)
+    */
+    static json from_cbor(ArrayRef<uint8_t> arr, const bool strict = true);
+
+    /*!
+    @brief create a JSON value from an input in MessagePack format
+
+    Deserializes a given input @a i to a JSON value using the MessagePack
+    serialization format.
+
+    The library maps MessagePack types to JSON value types as follows:
+
+    MessagePack type | JSON value type | first byte
+    ---------------- | --------------- | ----------
+    positive fixint  | number_unsigned | 0x00..0x7F
+    fixmap           | object          | 0x80..0x8F
+    fixarray         | array           | 0x90..0x9F
+    fixstr           | string          | 0xA0..0xBF
+    nil              | `null`          | 0xC0
+    false            | `false`         | 0xC2
+    true             | `true`          | 0xC3
+    float 32         | number_float    | 0xCA
+    float 64         | number_float    | 0xCB
+    uint 8           | number_unsigned | 0xCC
+    uint 16          | number_unsigned | 0xCD
+    uint 32          | number_unsigned | 0xCE
+    uint 64          | number_unsigned | 0xCF
+    int 8            | number_integer  | 0xD0
+    int 16           | number_integer  | 0xD1
+    int 32           | number_integer  | 0xD2
+    int 64           | number_integer  | 0xD3
+    str 8            | string          | 0xD9
+    str 16           | string          | 0xDA
+    str 32           | string          | 0xDB
+    array 16         | array           | 0xDC
+    array 32         | array           | 0xDD
+    map 16           | object          | 0xDE
+    map 32           | object          | 0xDF
+    negative fixint  | number_integer  | 0xE0-0xFF
+
+    @warning The mapping is **incomplete** in the sense that not all
+             MessagePack types can be converted to a JSON value. The following
+             MessagePack types are not supported and will yield parse errors:
+              - bin 8 - bin 32 (0xC4..0xC6)
+              - ext 8 - ext 32 (0xC7..0xC9)
+              - fixext 1 - fixext 16 (0xD4..0xD8)
+
+    @note Any MessagePack output created @ref to_msgpack can be successfully
+          parsed by @ref from_msgpack.
+
+    @param[in] i  an input in MessagePack format convertible to an input
+                  adapter
+    @param[in] strict  whether to expect the input to be consumed until EOF
+                       (true by default)
+
+    @throw parse_error.110 if the given input ends prematurely or the end of
+    file was not reached when @a strict was set to true
+    @throw parse_error.112 if unsupported features from MessagePack were
+    used in the given input @a i or if the input is not valid MessagePack
+    @throw parse_error.113 if a string was expected as map key, but not found
+
+    @complexity Linear in the size of the input @a i.
+
+    @liveexample{The example shows the deserialization of a byte vector in
+    MessagePack format to a JSON value.,from_msgpack}
+
+    @sa http://msgpack.org
+    @sa @ref to_msgpack(const json&) for the analogous serialization
+    @sa @ref from_cbor(raw_istream&, const bool) for the related CBOR
+        format
+    @sa @ref from_ubjson(raw_istream&, const bool) for the related
+        UBJSON format
+
+    @since version 2.0.9; parameter @a start_index since 2.1.1; changed to
+           consume input adapters, removed start_index parameter, and added
+           @a strict parameter since 3.0.0
+    */
+    static json from_msgpack(raw_istream& is,
+                                   const bool strict = true);
+
+    /*!
+    @copydoc from_msgpack(raw_istream, const bool)
+    */
+    static json from_msgpack(ArrayRef<uint8_t> arr, const bool strict = true);
+
+    /*!
+    @brief create a JSON value from an input in UBJSON format
+
+    Deserializes a given input @a i to a JSON value using the UBJSON (Universal
+    Binary JSON) serialization format.
+
+    The library maps UBJSON types to JSON value types as follows:
+
+    UBJSON type | JSON value type                         | marker
+    ----------- | --------------------------------------- | ------
+    no-op       | *no value, next value is read*          | `N`
+    null        | `null`                                  | `Z`
+    false       | `false`                                 | `F`
+    true        | `true`                                  | `T`
+    float32     | number_float                            | `d`
+    float64     | number_float                            | `D`
+    uint8       | number_unsigned                         | `U`
+    int8        | number_integer                          | `i`
+    int16       | number_integer                          | `I`
+    int32       | number_integer                          | `l`
+    int64       | number_integer                          | `L`
+    string      | string                                  | `S`
+    char        | string                                  | `C`
+    array       | array (optimized values are supported)  | `[`
+    object      | object (optimized values are supported) | `{`
+
+    @note The mapping is **complete** in the sense that any UBJSON value can
+          be converted to a JSON value.
+
+    @param[in] i  an input in UBJSON format convertible to an input adapter
+    @param[in] strict  whether to expect the input to be consumed until EOF
+                       (true by default)
+
+    @throw parse_error.110 if the given input ends prematurely or the end of
+    file was not reached when @a strict was set to true
+    @throw parse_error.112 if a parse error occurs
+    @throw parse_error.113 if a string could not be parsed successfully
+
+    @complexity Linear in the size of the input @a i.
+
+    @liveexample{The example shows the deserialization of a byte vector in
+    UBJSON format to a JSON value.,from_ubjson}
+
+    @sa http://ubjson.org
+    @sa @ref to_ubjson(const json&, const bool, const bool) for the
+             analogous serialization
+    @sa @ref from_cbor(raw_istream&, const bool) for the related CBOR
+        format
+    @sa @ref from_msgpack(raw_istream&, const bool) for the related
+        MessagePack format
+
+    @since version 3.1.0
+    */
+    static json from_ubjson(raw_istream& is,
+                                  const bool strict = true);
+
+    static json from_ubjson(ArrayRef<uint8_t> arr, const bool strict = true);
+
+    /// @}
+
+    //////////////////////////
+    // JSON Pointer support //
+    //////////////////////////
+
+    /// @name JSON Pointer functions
+    /// @{
+
+    /*!
+    @brief access specified element via JSON Pointer
+
+    Uses a JSON pointer to retrieve a reference to the respective JSON value.
+    No bound checking is performed. Similar to @ref operator[](const typename
+    object_t::key_type&), `null` values are created in arrays and objects if
+    necessary.
+
+    In particular:
+    - If the JSON pointer points to an object key that does not exist, it
+      is created an filled with a `null` value before a reference to it
+      is returned.
+    - If the JSON pointer points to an array index that does not exist, it
+      is created an filled with a `null` value before a reference to it
+      is returned. All indices between the current maximum and the given
+      index are also filled with `null`.
+    - The special value `-` is treated as a synonym for the index past the
+      end.
+
+    @param[in] ptr  a JSON pointer
+
+    @return reference to the element pointed to by @a ptr
+
+    @complexity Constant.
+
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+
+    @liveexample{The behavior is shown in the example.,operatorjson_pointer}
+
+    @since version 2.0.0
+    */
+    reference operator[](const json_pointer& ptr)
+    {
+        return ptr.get_unchecked(this);
+    }
+
+    /*!
+    @brief access specified element via JSON Pointer
+
+    Uses a JSON pointer to retrieve a reference to the respective JSON value.
+    No bound checking is performed. The function does not change the JSON
+    value; no `null` values are created. In particular, the the special value
+    `-` yields an exception.
+
+    @param[in] ptr  JSON pointer to the desired element
+
+    @return const reference to the element pointed to by @a ptr
+
+    @complexity Constant.
+
+    @throw parse_error.106   if an array index begins with '0'
+    @throw parse_error.109   if an array index was not a number
+    @throw out_of_range.402  if the array index '-' is used
+    @throw out_of_range.404  if the JSON pointer can not be resolved
+
+    @liveexample{The behavior is shown in the example.,operatorjson_pointer_const}
+
+    @since version 2.0.0
+    */
+    const_reference operator[](const json_pointer& ptr) const
+    {
+        return ptr.get_unchecked(this);
+    }
+
+    /*!
+    @brief access specified element via JSON Pointer
+
+    Returns a reference to the element at with specified JSON pointer @a ptr,
+    with bounds checking.
+
+    @param[in] ptr  JSON pointer to the desired element
+
+    @return reference to the element pointed to by @a ptr
+
+    @throw parse_error.106 if an array index in the passed JSON pointer @a ptr
+    begins with '0'. See example below.
+
+    @throw parse_error.109 if an array index in the passed JSON pointer @a ptr
+    is not a number. See example below.
+
+    @throw out_of_range.401 if an array index in the passed JSON pointer @a ptr
+    is out of range. See example below.
+
+    @throw out_of_range.402 if the array index '-' is used in the passed JSON
+    pointer @a ptr. As `at` provides checked access (and no elements are
+    implicitly inserted), the index '-' is always invalid. See example below.
+
+    @throw out_of_range.403 if the JSON pointer describes a key of an object
+    which cannot be found. See example below.
+
+    @throw out_of_range.404 if the JSON pointer @a ptr can not be resolved.
+    See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 2.0.0
+
+    @liveexample{The behavior is shown in the example.,at_json_pointer}
+    */
+    reference at(const json_pointer& ptr)
+    {
+        return ptr.get_checked(this);
+    }
+
+    /*!
+    @brief access specified element via JSON Pointer
+
+    Returns a const reference to the element at with specified JSON pointer @a
+    ptr, with bounds checking.
+
+    @param[in] ptr  JSON pointer to the desired element
+
+    @return reference to the element pointed to by @a ptr
+
+    @throw parse_error.106 if an array index in the passed JSON pointer @a ptr
+    begins with '0'. See example below.
+
+    @throw parse_error.109 if an array index in the passed JSON pointer @a ptr
+    is not a number. See example below.
+
+    @throw out_of_range.401 if an array index in the passed JSON pointer @a ptr
+    is out of range. See example below.
+
+    @throw out_of_range.402 if the array index '-' is used in the passed JSON
+    pointer @a ptr. As `at` provides checked access (and no elements are
+    implicitly inserted), the index '-' is always invalid. See example below.
+
+    @throw out_of_range.403 if the JSON pointer describes a key of an object
+    which cannot be found. See example below.
+
+    @throw out_of_range.404 if the JSON pointer @a ptr can not be resolved.
+    See example below.
+
+    @exceptionsafety Strong guarantee: if an exception is thrown, there are no
+    changes in the JSON value.
+
+    @complexity Constant.
+
+    @since version 2.0.0
+
+    @liveexample{The behavior is shown in the example.,at_json_pointer_const}
+    */
+    const_reference at(const json_pointer& ptr) const
+    {
+        return ptr.get_checked(this);
+    }
+
+    /*!
+    @brief return flattened JSON value
+
+    The function creates a JSON object whose keys are JSON pointers (see [RFC
+    6901](https://tools.ietf.org/html/rfc6901)) and whose values are all
+    primitive. The original JSON value can be restored using the @ref
+    unflatten() function.
+
+    @return an object that maps JSON pointers to primitive values
+
+    @note Empty objects and arrays are flattened to `null` and will not be
+          reconstructed correctly by the @ref unflatten() function.
+
+    @complexity Linear in the size the JSON value.
+
+    @liveexample{The following code shows how a JSON object is flattened to an
+    object whose keys consist of JSON pointers.,flatten}
+
+    @sa @ref unflatten() for the reverse function
+
+    @since version 2.0.0
+    */
+    json flatten() const
+    {
+        json result(value_t::object);
+        json_pointer::flatten("", *this, result);
+        return result;
+    }
+
+    /*!
+    @brief unflatten a previously flattened JSON value
+
+    The function restores the arbitrary nesting of a JSON value that has been
+    flattened before using the @ref flatten() function. The JSON value must
+    meet certain constraints:
+    1. The value must be an object.
+    2. The keys must be JSON pointers (see
+       [RFC 6901](https://tools.ietf.org/html/rfc6901))
+    3. The mapped values must be primitive JSON types.
+
+    @return the original JSON from a flattened version
+
+    @note Empty objects and arrays are flattened by @ref flatten() to `null`
+          values and can not unflattened to their original type. Apart from
+          this example, for a JSON value `j`, the following is always true:
+          `j == j.flatten().unflatten()`.
+
+    @complexity Linear in the size the JSON value.
+
+    @throw type_error.314  if value is not an object
+    @throw type_error.315  if object values are not primitive
+
+    @liveexample{The following code shows how a flattened JSON object is
+    unflattened into the original nested JSON object.,unflatten}
+
+    @sa @ref flatten() for the reverse function
+
+    @since version 2.0.0
+    */
+    json unflatten() const
+    {
+        return json_pointer::unflatten(*this);
+    }
+
+    /// @}
+
+    //////////////////////////
+    // JSON Patch functions //
+    //////////////////////////
+
+    /// @name JSON Patch functions
+    /// @{
+
+    /*!
+    @brief applies a JSON patch
+
+    [JSON Patch](http://jsonpatch.com) defines a JSON document structure for
+    expressing a sequence of operations to apply to a JSON) document. With
+    this function, a JSON Patch is applied to the current JSON value by
+    executing all operations from the patch.
+
+    @param[in] json_patch  JSON patch document
+    @return patched document
+
+    @note The application of a patch is atomic: Either all operations succeed
+          and the patched document is returned or an exception is thrown. In
+          any case, the original value is not changed: the patch is applied
+          to a copy of the value.
+
+    @throw parse_error.104 if the JSON patch does not consist of an array of
+    objects
+
+    @throw parse_error.105 if the JSON patch is malformed (e.g., mandatory
+    attributes are missing); example: `"operation add must have member path"`
+
+    @throw out_of_range.401 if an array index is out of range.
+
+    @throw out_of_range.403 if a JSON pointer inside the patch could not be
+    resolved successfully in the current JSON value; example: `"key baz not
+    found"`
+
+    @throw out_of_range.405 if JSON pointer has no parent ("add", "remove",
+    "move")
+
+    @throw other_error.501 if "test" operation was unsuccessful
+
+    @complexity Linear in the size of the JSON value and the length of the
+    JSON patch. As usually only a fraction of the JSON value is affected by
+    the patch, the complexity can usually be neglected.
+
+    @liveexample{The following code shows how a JSON patch is applied to a
+    value.,patch}
+
+    @sa @ref diff -- create a JSON patch by comparing two JSON values
+
+    @sa [RFC 6902 (JSON Patch)](https://tools.ietf.org/html/rfc6902)
+    @sa [RFC 6901 (JSON Pointer)](https://tools.ietf.org/html/rfc6901)
+
+    @since version 2.0.0
+    */
+    json patch(const json& json_patch) const;
+
+    /*!
+    @brief creates a diff as a JSON patch
+
+    Creates a [JSON Patch](http://jsonpatch.com) so that value @a source can
+    be changed into the value @a target by calling @ref patch function.
+
+    @invariant For two JSON values @a source and @a target, the following code
+    yields always `true`:
+    @code {.cpp}
+    source.patch(diff(source, target)) == target;
+    @endcode
+
+    @note Currently, only `remove`, `add`, and `replace` operations are
+          generated.
+
+    @param[in] source  JSON value to compare from
+    @param[in] target  JSON value to compare against
+    @param[in] path    helper value to create JSON pointers
+
+    @return a JSON patch to convert the @a source to @a target
+
+    @complexity Linear in the lengths of @a source and @a target.
+
+    @liveexample{The following code shows how a JSON patch is created as a
+    diff for two JSON values.,diff}
+
+    @sa @ref patch -- apply a JSON patch
+    @sa @ref merge_patch -- apply a JSON Merge Patch
+
+    @sa [RFC 6902 (JSON Patch)](https://tools.ietf.org/html/rfc6902)
+
+    @since version 2.0.0
+    */
+    static json diff(const json& source, const json& target,
+                           const std::string& path = "");
+
+    /// @}
+
+    ////////////////////////////////
+    // JSON Merge Patch functions //
+    ////////////////////////////////
+
+    /// @name JSON Merge Patch functions
+    /// @{
+
+    /*!
+    @brief applies a JSON Merge Patch
+
+    The merge patch format is primarily intended for use with the HTTP PATCH
+    method as a means of describing a set of modifications to a target
+    resource's content. This function applies a merge patch to the current
+    JSON value.
+
+    The function implements the following algorithm from Section 2 of
+    [RFC 7396 (JSON Merge Patch)](https://tools.ietf.org/html/rfc7396):
+
+    ```
+    define MergePatch(Target, Patch):
+      if Patch is an Object:
+        if Target is not an Object:
+          Target = {} // Ignore the contents and set it to an empty Object
+        for each Name/Value pair in Patch:
+          if Value is null:
+            if Name exists in Target:
+              remove the Name/Value pair from Target
+          else:
+            Target[Name] = MergePatch(Target[Name], Value)
+        return Target
+      else:
+        return Patch
+    ```
+
+    Thereby, `Target` is the current object; that is, the patch is applied to
+    the current value.
+
+    @param[in] patch  the patch to apply
+
+    @complexity Linear in the lengths of @a patch.
+
+    @liveexample{The following code shows how a JSON Merge Patch is applied to
+    a JSON document.,merge_patch}
+
+    @sa @ref patch -- apply a JSON patch
+    @sa [RFC 7396 (JSON Merge Patch)](https://tools.ietf.org/html/rfc7396)
+
+    @since version 3.0.0
+    */
+    void merge_patch(const json& patch);
+
+    /// @}
+};
+} // namespace wpi
+
+///////////////////////
+// nonmember support //
+///////////////////////
+
+// specialization of std::swap, and std::hash
+namespace std
+{
+/*!
+@brief exchanges the values of two JSON objects
+
+@since version 1.0.0
+*/
+template<>
+inline void swap(wpi::json& j1,
+                 wpi::json& j2) noexcept(
+                     is_nothrow_move_constructible<wpi::json>::value and
+                     is_nothrow_move_assignable<wpi::json>::value
+                 )
+{
+    j1.swap(j2);
+}
+
+/// hash value for JSON objects
+template<>
+struct hash<wpi::json>
+{
+    /*!
+    @brief return a hash value for a JSON object
+
+    @since version 1.0.0
+    */
+    std::size_t operator()(const wpi::json& j) const
+    {
+        // a naive hashing via the string representation
+        const auto& h = hash<std::string>();
+        return h(j.dump());
+    }
+};
+
+/// specialization for std::less<value_t>
+/// @note: do not remove the space after '<',
+///        see https://github.com/nlohmann/json/pull/679
+template<>
+struct less< ::wpi::detail::value_t>
+{
+    /*!
+    @brief compare two value_t enum values
+    @since version 3.0.0
+    */
+    bool operator()(wpi::detail::value_t lhs,
+                    wpi::detail::value_t rhs) const noexcept
+    {
+        return wpi::detail::operator<(lhs, rhs);
+    }
+};
+
+} // namespace std
+
+/*!
+@brief user-defined string literal for JSON values
+
+This operator implements a user-defined string literal for JSON objects. It
+can be used by adding `"_json"` to a string literal and returns a JSON object
+if no parse error occurred.
+
+@param[in] s  a string representation of a JSON object
+@param[in] n  the length of string @a s
+@return a JSON object
+
+@since version 1.0.0
+*/
+inline wpi::json operator "" _json(const char* s, std::size_t n)
+{
+    return wpi::json::parse(wpi::StringRef(s, n));
+}
+
+/*!
+@brief user-defined string literal for JSON pointer
+
+This operator implements a user-defined string literal for JSON Pointers. It
+can be used by adding `"_json_pointer"` to a string literal and returns a JSON pointer
+object if no parse error occurred.
+
+@param[in] s  a string representation of a JSON Pointer
+@param[in] n  the length of string @a s
+@return a JSON pointer object
+
+@since version 2.0.0
+*/
+inline wpi::json::json_pointer operator "" _json_pointer(const char* s, std::size_t n)
+{
+    return wpi::json::json_pointer(wpi::StringRef(s, n));
+}
+
+#ifndef WPI_JSON_IMPLEMENTATION
+
+// restore GCC/clang diagnostic settings
+#if defined(__clang__) || defined(__GNUC__) || defined(__GNUG__)
+    #pragma GCC diagnostic pop
+#endif
+#if defined(__clang__)
+    #pragma GCC diagnostic pop
+#endif
+
+// clean up
+#undef JSON_CATCH
+#undef JSON_THROW
+#undef JSON_TRY
+#undef JSON_LIKELY
+#undef JSON_UNLIKELY
+#undef JSON_HAS_CPP_14
+#undef JSON_HAS_CPP_17
+#undef NLOHMANN_BASIC_JSON_TPL_DECLARATION
+#undef NLOHMANN_BASIC_JSON_TPL
+#undef NLOHMANN_JSON_HAS_HELPER
+
+#endif  // WPI_JSON_IMPLEMENTATION
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/leb128.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/leb128.h
new file mode 100644
index 0000000..c70f471
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/leb128.h
@@ -0,0 +1,68 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_LEB128_H_
+#define WPIUTIL_WPI_LEB128_H_
+
+#include <cstddef>
+
+#include "wpi/SmallVector.h"
+
+namespace wpi {
+
+class raw_istream;
+
+/**
+ * Get size of unsigned LEB128 data
+ * @val: value
+ *
+ * Determine the number of bytes required to encode an unsigned LEB128 datum.
+ * The algorithm is taken from Appendix C of the DWARF 3 spec. For information
+ * on the encodings refer to section "7.6 - Variable Length Data". Return
+ * the number of bytes required.
+ */
+uint64_t SizeUleb128(uint64_t val);
+
+/**
+ * Write unsigned LEB128 data
+ * @addr: the address where the ULEB128 data is to be stored
+ * @val: value to be stored
+ *
+ * Encode an unsigned LEB128 encoded datum. The algorithm is taken
+ * from Appendix C of the DWARF 3 spec. For information on the
+ * encodings refer to section "7.6 - Variable Length Data". Return
+ * the number of bytes written.
+ */
+uint64_t WriteUleb128(SmallVectorImpl<char>& dest, uint64_t val);
+
+/**
+ * Read unsigned LEB128 data
+ * @addr: the address where the ULEB128 data is stored
+ * @ret: address to store the result
+ *
+ * Decode an unsigned LEB128 encoded datum. The algorithm is taken
+ * from Appendix C of the DWARF 3 spec. For information on the
+ * encodings refer to section "7.6 - Variable Length Data". Return
+ * the number of bytes read.
+ */
+uint64_t ReadUleb128(const char* addr, uint64_t* ret);
+
+/**
+ * Read unsigned LEB128 data from a stream
+ * @is: the input stream where the ULEB128 data is to be read from
+ * @ret: address to store the result
+ *
+ * Decode an unsigned LEB128 encoded datum. The algorithm is taken
+ * from Appendix C of the DWARF 3 spec. For information on the
+ * encodings refer to section "7.6 - Variable Length Data". Return
+ * false on stream error, true on success.
+ */
+bool ReadUleb128(raw_istream& is, uint64_t* ret);
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_LEB128_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/memory.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/memory.h
new file mode 100644
index 0000000..325b5d7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/memory.h
@@ -0,0 +1,40 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_MEMORY_H_
+#define WPIUTIL_WPI_MEMORY_H_
+
+#include <cstdlib>
+
+namespace wpi {
+
+/**
+ * Wrapper around std::calloc that calls std::terminate on out of memory.
+ * @param num number of objects to allocate
+ * @param size number of bytes per object to allocate
+ * @return Pointer to beginning of newly allocated memory.
+ */
+void* CheckedCalloc(size_t num, size_t size);
+
+/**
+ * Wrapper around std::malloc that calls std::terminate on out of memory.
+ * @param size number of bytes to allocate
+ * @return Pointer to beginning of newly allocated memory.
+ */
+void* CheckedMalloc(size_t size);
+
+/**
+ * Wrapper around std::realloc that calls std::terminate on out of memory.
+ * @param ptr memory previously allocated
+ * @param size number of bytes to allocate
+ * @return Pointer to beginning of newly allocated memory.
+ */
+void* CheckedRealloc(void* ptr, size_t size);
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_MEMORY_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/mutex.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/mutex.h
new file mode 100644
index 0000000..0ce3a51
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/mutex.h
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <mutex>
+
+#include "priority_mutex.h"
+
+namespace wpi {
+
+#ifdef WPI_HAVE_PRIORITY_MUTEX
+using mutex = priority_mutex;
+using recursive_mutex = priority_recursive_mutex;
+#else
+using mutex = ::std::mutex;
+using recursive_mutex = ::std::recursive_mutex;
+#endif
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/optional.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/optional.h
new file mode 100644
index 0000000..ed14b45
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/optional.h
@@ -0,0 +1,913 @@
+// Copyright (C) 2011 - 2012 Andrzej Krzemienski.
+//
+// Use, modification, and distribution is subject to the Boost Software
+// License, Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at
+// http://www.boost.org/LICENSE_1_0.txt)
+//
+// The idea and interface is based on Boost.Optional library
+// authored by Fernando Luis Cacciola Carballal
+
+# ifndef WPIUTIL_WPI_OPTIONAL_H
+# define WPIUTIL_WPI_OPTIONAL_H
+
+# include <utility>
+# include <type_traits>
+# include <initializer_list>
+# include <cassert>
+# include <functional>
+# include <string>
+# include <stdexcept>
+
+# define TR2_OPTIONAL_REQUIRES(...) typename std::enable_if<__VA_ARGS__::value, bool>::type = false
+
+# if defined __GNUC__ || (defined _MSC_VER) && (_MSC_VER >= 1910)
+#   define OPTIONAL_HAS_CONSTEXPR_INIT_LIST 1
+#   define OPTIONAL_CONSTEXPR_INIT_LIST constexpr
+# else
+#   define OPTIONAL_HAS_CONSTEXPR_INIT_LIST 0
+#   define OPTIONAL_CONSTEXPR_INIT_LIST
+# endif
+
+# if defined __clang__ && (defined __cplusplus) && (__cplusplus != 201103L)
+#   define OPTIONAL_HAS_MOVE_ACCESSORS 1
+# else
+#   define OPTIONAL_HAS_MOVE_ACCESSORS 0
+# endif
+
+namespace wpi{
+
+// 20.5.4, optional for object types
+template <class T> class optional;
+
+// 20.5.5, optional for lvalue reference types
+template <class T> class optional<T&>;
+
+
+// workaround: std utility functions aren't constexpr yet
+template <class T> inline constexpr T&& constexpr_forward(typename std::remove_reference<T>::type& t) noexcept
+{
+  return static_cast<T&&>(t);
+}
+
+template <class T> inline constexpr T&& constexpr_forward(typename std::remove_reference<T>::type&& t) noexcept
+{
+    static_assert(!std::is_lvalue_reference<T>::value, "!!");
+    return static_cast<T&&>(t);
+}
+
+template <class T> inline constexpr typename std::remove_reference<T>::type&& constexpr_move(T&& t) noexcept
+{
+    return static_cast<typename std::remove_reference<T>::type&&>(t);
+}
+
+
+#if defined NDEBUG
+# define TR2_OPTIONAL_ASSERTED_EXPRESSION(CHECK, EXPR) (EXPR)
+#else
+# define TR2_OPTIONAL_ASSERTED_EXPRESSION(CHECK, EXPR) ((CHECK) ? (EXPR) : ([]{assert(!#CHECK);}(), (EXPR)))
+#endif
+
+
+namespace detail_
+{
+
+// static_addressof: a constexpr version of addressof
+template <typename T>
+struct has_overloaded_addressof
+{
+  template <class X>
+  constexpr static bool has_overload(...) { return false; }
+  
+  template <class X, size_t S = sizeof(std::declval<X&>().operator&()) >
+  constexpr static bool has_overload(bool) { return true; }
+
+  constexpr static bool value = has_overload<T>(true);
+};
+
+template <typename T, TR2_OPTIONAL_REQUIRES(!has_overloaded_addressof<T>)>
+constexpr T* static_addressof(T& ref)
+{
+  return &ref;
+}
+
+template <typename T, TR2_OPTIONAL_REQUIRES(has_overloaded_addressof<T>)>
+T* static_addressof(T& ref)
+{
+  return std::addressof(ref);
+}
+
+
+// the call to convert<A>(b) has return type A and converts b to type A iff b decltype(b) is implicitly convertible to A  
+template <class U>
+constexpr U convert(U v) { return v; }
+  
+
+namespace swap_ns
+{
+  using std::swap;
+    
+  template <class T>
+  void adl_swap(T& t, T& u) noexcept(noexcept(swap(t, u)))
+  {
+    swap(t, u);
+  }
+
+} // namespace swap_ns
+
+} // namespace detail
+
+
+constexpr struct trivial_init_t{} trivial_init{};
+
+
+// 20.5.6, In-place construction
+constexpr struct in_place_t{} in_place{};
+
+
+// 20.5.7, Disengaged state indicator
+struct nullopt_t
+{
+  struct init{};
+  constexpr explicit nullopt_t(init){}
+};
+constexpr nullopt_t nullopt{nullopt_t::init()};
+
+
+// 20.5.8, class bad_optional_access
+class bad_optional_access : public std::logic_error {
+public:
+  explicit bad_optional_access(const std::string& what_arg) : logic_error{what_arg} {}
+  explicit bad_optional_access(const char* what_arg) : logic_error{what_arg} {}
+};
+
+
+template <class T>
+union storage_t
+{
+  unsigned char dummy_;
+  T value_;
+
+  constexpr storage_t( trivial_init_t ) noexcept : dummy_() {};
+
+  template <class... Args>
+  constexpr storage_t( Args&&... args ) : value_(constexpr_forward<Args>(args)...) {}
+
+  ~storage_t(){}
+};
+
+
+template <class T>
+union constexpr_storage_t
+{
+    unsigned char dummy_;
+    T value_;
+
+    constexpr constexpr_storage_t( trivial_init_t ) noexcept : dummy_() {};
+
+    template <class... Args>
+    constexpr constexpr_storage_t( Args&&... args ) : value_(constexpr_forward<Args>(args)...) {}
+
+    ~constexpr_storage_t() = default;
+};
+
+
+template <class T>
+struct optional_base
+{
+    bool init_;
+    storage_t<T> storage_;
+
+    constexpr optional_base() noexcept : init_(false), storage_(trivial_init) {};
+
+    explicit constexpr optional_base(const T& v) : init_(true), storage_(v) {}
+
+    explicit constexpr optional_base(T&& v) : init_(true), storage_(constexpr_move(v)) {}
+
+    template <class... Args> explicit optional_base(in_place_t, Args&&... args)
+        : init_(true), storage_(constexpr_forward<Args>(args)...) {}
+
+    template <class U, class... Args, TR2_OPTIONAL_REQUIRES(std::is_constructible<T, std::initializer_list<U>>)>
+    explicit optional_base(in_place_t, std::initializer_list<U> il, Args&&... args)
+        : init_(true), storage_(il, std::forward<Args>(args)...) {}
+
+    ~optional_base() { if (init_) storage_.value_.T::~T(); }
+};
+
+
+template <class T>
+struct constexpr_optional_base
+{
+    bool init_;
+    constexpr_storage_t<T> storage_;
+
+    constexpr constexpr_optional_base() noexcept : init_(false), storage_(trivial_init) {};
+
+    explicit constexpr constexpr_optional_base(const T& v) : init_(true), storage_(v) {}
+
+    explicit constexpr constexpr_optional_base(T&& v) : init_(true), storage_(constexpr_move(v)) {}
+
+    template <class... Args> explicit constexpr constexpr_optional_base(in_place_t, Args&&... args)
+      : init_(true), storage_(constexpr_forward<Args>(args)...) {}
+
+    template <class U, class... Args, TR2_OPTIONAL_REQUIRES(std::is_constructible<T, std::initializer_list<U>>)>
+    OPTIONAL_CONSTEXPR_INIT_LIST explicit constexpr_optional_base(in_place_t, std::initializer_list<U> il, Args&&... args)
+      : init_(true), storage_(il, std::forward<Args>(args)...) {}
+
+    ~constexpr_optional_base() = default;
+};
+
+template <class T>
+using OptionalBase = typename std::conditional<
+    std::is_trivially_destructible<T>::value,                          // if possible
+    constexpr_optional_base<typename std::remove_const<T>::type>, // use base with trivial destructor
+    optional_base<typename std::remove_const<T>::type>
+>::type;
+
+
+
+template <class T>
+class optional : private OptionalBase<T>
+{
+  static_assert( !std::is_same<typename std::decay<T>::type, nullopt_t>::value, "bad T" );
+  static_assert( !std::is_same<typename std::decay<T>::type, in_place_t>::value, "bad T" );
+  
+
+  constexpr bool initialized() const noexcept { return OptionalBase<T>::init_; }
+  typename std::remove_const<T>::type* dataptr() {  return std::addressof(OptionalBase<T>::storage_.value_); }
+  constexpr const T* dataptr() const { return detail_::static_addressof(OptionalBase<T>::storage_.value_); }
+  
+  constexpr const T& contained_val() const& { return OptionalBase<T>::storage_.value_; }
+#   if OPTIONAL_HAS_MOVE_ACCESSORS == 1
+  constexpr T&& contained_val() && { return std::move(OptionalBase<T>::storage_.value_); }
+  constexpr T& contained_val() & { return OptionalBase<T>::storage_.value_; }
+#   else
+  T& contained_val() & { return OptionalBase<T>::storage_.value_; }
+  T&& contained_val() && { return std::move(OptionalBase<T>::storage_.value_); }
+#   endif
+
+  void clear() noexcept {
+    if (initialized()) dataptr()->T::~T();
+    OptionalBase<T>::init_ = false;
+  }
+  
+  template <class... Args>
+  void initialize(Args&&... args) noexcept(noexcept(T(std::forward<Args>(args)...)))
+  {
+    assert(!OptionalBase<T>::init_);
+    ::new (static_cast<void*>(dataptr())) T(std::forward<Args>(args)...);
+    OptionalBase<T>::init_ = true;
+  }
+
+  template <class U, class... Args>
+  void initialize(std::initializer_list<U> il, Args&&... args) noexcept(noexcept(T(il, std::forward<Args>(args)...)))
+  {
+    assert(!OptionalBase<T>::init_);
+    ::new (static_cast<void*>(dataptr())) T(il, std::forward<Args>(args)...);
+    OptionalBase<T>::init_ = true;
+  }
+
+public:
+  typedef T value_type;
+
+  // 20.5.5.1, constructors
+  constexpr optional() noexcept : OptionalBase<T>()  {};
+  constexpr optional(nullopt_t) noexcept : OptionalBase<T>() {};
+
+  optional(const optional& rhs)
+  : OptionalBase<T>()
+  {
+    if (rhs.initialized()) {
+        ::new (static_cast<void*>(dataptr())) T(*rhs);
+        OptionalBase<T>::init_ = true;
+    }
+  }
+
+  optional(optional&& rhs) noexcept(std::is_nothrow_move_constructible<T>::value)
+  : OptionalBase<T>()
+  {
+    if (rhs.initialized()) {
+        ::new (static_cast<void*>(dataptr())) T(std::move(*rhs));
+        OptionalBase<T>::init_ = true;
+    }
+  }
+
+  constexpr optional(const T& v) : OptionalBase<T>(v) {}
+
+  constexpr optional(T&& v) : OptionalBase<T>(constexpr_move(v)) {}
+
+  template <class... Args>
+  explicit constexpr optional(in_place_t, Args&&... args)
+  : OptionalBase<T>(in_place_t{}, constexpr_forward<Args>(args)...) {}
+
+  template <class U, class... Args, TR2_OPTIONAL_REQUIRES(std::is_constructible<T, std::initializer_list<U>>)>
+  OPTIONAL_CONSTEXPR_INIT_LIST explicit optional(in_place_t, std::initializer_list<U> il, Args&&... args)
+  : OptionalBase<T>(in_place_t{}, il, constexpr_forward<Args>(args)...) {}
+
+  // 20.5.4.2, Destructor
+  ~optional() = default;
+
+  // 20.5.4.3, assignment
+  optional& operator=(nullopt_t) noexcept
+  {
+    clear();
+    return *this;
+  }
+  
+  optional& operator=(const optional& rhs)
+  {
+    if      (initialized() == true  && rhs.initialized() == false) clear();
+    else if (initialized() == false && rhs.initialized() == true)  initialize(*rhs);
+    else if (initialized() == true  && rhs.initialized() == true)  contained_val() = *rhs;
+    return *this;
+  }
+  
+  optional& operator=(optional&& rhs)
+  noexcept(std::is_nothrow_move_assignable<T>::value && std::is_nothrow_move_constructible<T>::value)
+  {
+    if      (initialized() == true  && rhs.initialized() == false) clear();
+    else if (initialized() == false && rhs.initialized() == true)  initialize(std::move(*rhs));
+    else if (initialized() == true  && rhs.initialized() == true)  contained_val() = std::move(*rhs);
+    return *this;
+  }
+
+  template <class U>
+  auto operator=(U&& v)
+  -> typename std::enable_if
+  <
+    std::is_same<typename std::decay<U>::type, T>::value,
+    optional&
+  >::type
+  {
+    if (initialized()) { contained_val() = std::forward<U>(v); }
+    else               { initialize(std::forward<U>(v));  }
+    return *this;
+  }
+  
+  
+  template <class... Args>
+  void emplace(Args&&... args)
+  {
+    clear();
+    initialize(std::forward<Args>(args)...);
+  }
+  
+  template <class U, class... Args>
+  void emplace(std::initializer_list<U> il, Args&&... args)
+  {
+    clear();
+    initialize<U, Args...>(il, std::forward<Args>(args)...);
+  }
+  
+  // 20.5.4.4, Swap
+  void swap(optional<T>& rhs) noexcept(std::is_nothrow_move_constructible<T>::value
+                                       && noexcept(detail_::swap_ns::adl_swap(std::declval<T&>(), std::declval<T&>())))
+  {
+    if      (initialized() == true  && rhs.initialized() == false) { rhs.initialize(std::move(**this)); clear(); }
+    else if (initialized() == false && rhs.initialized() == true)  { initialize(std::move(*rhs)); rhs.clear(); }
+    else if (initialized() == true  && rhs.initialized() == true)  { using std::swap; swap(**this, *rhs); }
+  }
+
+  // 20.5.4.5, Observers
+  
+  explicit constexpr operator bool() const noexcept { return initialized(); }
+  constexpr bool has_value() const noexcept { return initialized(); }
+  
+  constexpr T const* operator ->() const {
+    return TR2_OPTIONAL_ASSERTED_EXPRESSION(initialized(), dataptr());
+  }
+  
+# if OPTIONAL_HAS_MOVE_ACCESSORS == 1
+
+  constexpr T* operator ->() {
+    assert (initialized());
+    return dataptr();
+  }
+  
+  constexpr T const& operator *() const& {
+    return TR2_OPTIONAL_ASSERTED_EXPRESSION(initialized(), contained_val());
+  }
+  
+  constexpr T& operator *() & {
+    assert (initialized());
+    return contained_val();
+  }
+  
+  constexpr T&& operator *() && {
+    assert (initialized());
+    return constexpr_move(contained_val());
+  }
+
+  constexpr T const& value() const& {
+    return initialized() ? contained_val() : (throw bad_optional_access("bad optional access"), contained_val());
+  }
+  
+  constexpr T& value() & {
+    return initialized() ? contained_val() : (throw bad_optional_access("bad optional access"), contained_val());
+  }
+  
+  constexpr T&& value() && {
+    if (!initialized()) throw bad_optional_access("bad optional access");
+	return std::move(contained_val());
+  }
+  
+# else
+
+  T* operator ->() {
+    assert (initialized());
+    return dataptr();
+  }
+  
+  constexpr T const& operator *() const {
+    return TR2_OPTIONAL_ASSERTED_EXPRESSION(initialized(), contained_val());
+  }
+  
+  T& operator *() {
+    assert (initialized());
+    return contained_val();
+  }
+  
+  constexpr T const& value() const {
+    return initialized() ? contained_val() : (throw bad_optional_access("bad optional access"), contained_val());
+  }
+  
+  T& value() {
+    return initialized() ? contained_val() : (throw bad_optional_access("bad optional access"), contained_val());
+  }
+  
+# endif
+  
+  template <class V>
+  constexpr T value_or(V&& v) const&
+  {
+    return *this ? **this : detail_::convert<T>(constexpr_forward<V>(v));
+  }
+  
+#   if OPTIONAL_HAS_MOVE_ACCESSORS == 1
+
+  template <class V>
+  constexpr T value_or(V&& v) &&
+  {
+    return *this ? constexpr_move(const_cast<optional<T>&>(*this).contained_val()) : detail_::convert<T>(constexpr_forward<V>(v));
+  }
+
+#   else
+ 
+  template <class V>
+  T value_or(V&& v) &&
+  {
+    return *this ? constexpr_move(const_cast<optional<T>&>(*this).contained_val()) : detail_::convert<T>(constexpr_forward<V>(v));
+  }
+  
+#   endif
+  
+  // 20.6.3.6, modifiers
+  void reset() noexcept { clear(); }
+};
+
+
+template <class T>
+class optional<T&>
+{
+  static_assert( !std::is_same<T, nullopt_t>::value, "bad T" );
+  static_assert( !std::is_same<T, in_place_t>::value, "bad T" );
+  T* ref;
+  
+public:
+
+  // 20.5.5.1, construction/destruction
+  constexpr optional() noexcept : ref(nullptr) {}
+  
+  constexpr optional(nullopt_t) noexcept : ref(nullptr) {}
+   
+  constexpr optional(T& v) noexcept : ref(detail_::static_addressof(v)) {}
+  
+  optional(T&&) = delete;
+  
+  constexpr optional(const optional& rhs) noexcept : ref(rhs.ref) {}
+  
+  explicit constexpr optional(in_place_t, T& v) noexcept : ref(detail_::static_addressof(v)) {}
+  
+  explicit optional(in_place_t, T&&) = delete;
+  
+  ~optional() = default;
+  
+  // 20.5.5.2, mutation
+  optional& operator=(nullopt_t) noexcept {
+    ref = nullptr;
+    return *this;
+  }
+  
+  // optional& operator=(const optional& rhs) noexcept {
+    // ref = rhs.ref;
+    // return *this;
+  // }
+  
+  // optional& operator=(optional&& rhs) noexcept {
+    // ref = rhs.ref;
+    // return *this;
+  // }
+  
+  template <typename U>
+  auto operator=(U&& rhs) noexcept
+  -> typename std::enable_if
+  <
+    std::is_same<typename std::decay<U>::type, optional<T&>>::value,
+    optional&
+  >::type
+  {
+    ref = rhs.ref;
+    return *this;
+  }
+  
+  template <typename U>
+  auto operator=(U&& rhs) noexcept
+  -> typename std::enable_if
+  <
+    !std::is_same<typename std::decay<U>::type, optional<T&>>::value,
+    optional&
+  >::type
+  = delete;
+  
+  void emplace(T& v) noexcept {
+    ref = detail_::static_addressof(v);
+  }
+  
+  void emplace(T&&) = delete;
+  
+  
+  void swap(optional<T&>& rhs) noexcept
+  {
+    std::swap(ref, rhs.ref);
+  }
+    
+  // 20.5.5.3, observers
+  constexpr T* operator->() const {
+    return TR2_OPTIONAL_ASSERTED_EXPRESSION(ref, ref);
+  }
+  
+  constexpr T& operator*() const {
+    return TR2_OPTIONAL_ASSERTED_EXPRESSION(ref, *ref);
+  }
+  
+  constexpr T& value() const {
+    return ref ? *ref : (throw bad_optional_access("bad optional access"), *ref);
+  }
+  
+  explicit constexpr operator bool() const noexcept {
+    return ref != nullptr;
+  }
+ 
+  constexpr bool has_value() const noexcept {
+    return ref != nullptr;
+  }
+  
+  template <class V>
+  constexpr typename std::decay<T>::type value_or(V&& v) const
+  {
+    return *this ? **this : detail_::convert<typename std::decay<T>::type>(constexpr_forward<V>(v));
+  }
+
+  // x.x.x.x, modifiers
+  void reset() noexcept { ref = nullptr; }
+};
+
+
+template <class T>
+class optional<T&&>
+{
+  static_assert( sizeof(T) == 0, "optional rvalue references disallowed" );
+};
+
+
+// 20.5.8, Relational operators
+template <class T> constexpr bool operator==(const optional<T>& x, const optional<T>& y)
+{
+  return bool(x) != bool(y) ? false : bool(x) == false ? true : *x == *y;
+}
+
+template <class T> constexpr bool operator!=(const optional<T>& x, const optional<T>& y)
+{
+  return !(x == y);
+}
+
+template <class T> constexpr bool operator<(const optional<T>& x, const optional<T>& y)
+{
+  return (!y) ? false : (!x) ? true : *x < *y;
+}
+
+template <class T> constexpr bool operator>(const optional<T>& x, const optional<T>& y)
+{
+  return (y < x);
+}
+
+template <class T> constexpr bool operator<=(const optional<T>& x, const optional<T>& y)
+{
+  return !(y < x);
+}
+
+template <class T> constexpr bool operator>=(const optional<T>& x, const optional<T>& y)
+{
+  return !(x < y);
+}
+
+
+// 20.5.9, Comparison with nullopt
+template <class T> constexpr bool operator==(const optional<T>& x, nullopt_t) noexcept
+{
+  return (!x);
+}
+
+template <class T> constexpr bool operator==(nullopt_t, const optional<T>& x) noexcept
+{
+  return (!x);
+}
+
+template <class T> constexpr bool operator!=(const optional<T>& x, nullopt_t) noexcept
+{
+  return bool(x);
+}
+
+template <class T> constexpr bool operator!=(nullopt_t, const optional<T>& x) noexcept
+{
+  return bool(x);
+}
+
+template <class T> constexpr bool operator<(const optional<T>&, nullopt_t) noexcept
+{
+  return false;
+}
+
+template <class T> constexpr bool operator<(nullopt_t, const optional<T>& x) noexcept
+{
+  return bool(x);
+}
+
+template <class T> constexpr bool operator<=(const optional<T>& x, nullopt_t) noexcept
+{
+  return (!x);
+}
+
+template <class T> constexpr bool operator<=(nullopt_t, const optional<T>&) noexcept
+{
+  return true;
+}
+
+template <class T> constexpr bool operator>(const optional<T>& x, nullopt_t) noexcept
+{
+  return bool(x);
+}
+
+template <class T> constexpr bool operator>(nullopt_t, const optional<T>&) noexcept
+{
+  return false;
+}
+
+template <class T> constexpr bool operator>=(const optional<T>&, nullopt_t) noexcept
+{
+  return true;
+}
+
+template <class T> constexpr bool operator>=(nullopt_t, const optional<T>& x) noexcept
+{
+  return (!x);
+}
+
+
+
+// 20.5.10, Comparison with T
+template <class T> constexpr bool operator==(const optional<T>& x, const T& v)
+{
+  return bool(x) ? *x == v : false;
+}
+
+template <class T> constexpr bool operator==(const T& v, const optional<T>& x)
+{
+  return bool(x) ? v == *x : false;
+}
+
+template <class T> constexpr bool operator!=(const optional<T>& x, const T& v)
+{
+  return bool(x) ? *x != v : true;
+}
+
+template <class T> constexpr bool operator!=(const T& v, const optional<T>& x)
+{
+  return bool(x) ? v != *x : true;
+}
+
+template <class T> constexpr bool operator<(const optional<T>& x, const T& v)
+{
+  return bool(x) ? *x < v : true;
+}
+
+template <class T> constexpr bool operator>(const T& v, const optional<T>& x)
+{
+  return bool(x) ? v > *x : true;
+}
+
+template <class T> constexpr bool operator>(const optional<T>& x, const T& v)
+{
+  return bool(x) ? *x > v : false;
+}
+
+template <class T> constexpr bool operator<(const T& v, const optional<T>& x)
+{
+  return bool(x) ? v < *x : false;
+}
+
+template <class T> constexpr bool operator>=(const optional<T>& x, const T& v)
+{
+  return bool(x) ? *x >= v : false;
+}
+
+template <class T> constexpr bool operator<=(const T& v, const optional<T>& x)
+{
+  return bool(x) ? v <= *x : false;
+}
+
+template <class T> constexpr bool operator<=(const optional<T>& x, const T& v)
+{
+  return bool(x) ? *x <= v : true;
+}
+
+template <class T> constexpr bool operator>=(const T& v, const optional<T>& x)
+{
+  return bool(x) ? v >= *x : true;
+}
+
+
+// Comparison of optional<T&> with T
+template <class T> constexpr bool operator==(const optional<T&>& x, const T& v)
+{
+  return bool(x) ? *x == v : false;
+}
+
+template <class T> constexpr bool operator==(const T& v, const optional<T&>& x)
+{
+  return bool(x) ? v == *x : false;
+}
+
+template <class T> constexpr bool operator!=(const optional<T&>& x, const T& v)
+{
+  return bool(x) ? *x != v : true;
+}
+
+template <class T> constexpr bool operator!=(const T& v, const optional<T&>& x)
+{
+  return bool(x) ? v != *x : true;
+}
+
+template <class T> constexpr bool operator<(const optional<T&>& x, const T& v)
+{
+  return bool(x) ? *x < v : true;
+}
+
+template <class T> constexpr bool operator>(const T& v, const optional<T&>& x)
+{
+  return bool(x) ? v > *x : true;
+}
+
+template <class T> constexpr bool operator>(const optional<T&>& x, const T& v)
+{
+  return bool(x) ? *x > v : false;
+}
+
+template <class T> constexpr bool operator<(const T& v, const optional<T&>& x)
+{
+  return bool(x) ? v < *x : false;
+}
+
+template <class T> constexpr bool operator>=(const optional<T&>& x, const T& v)
+{
+  return bool(x) ? *x >= v : false;
+}
+
+template <class T> constexpr bool operator<=(const T& v, const optional<T&>& x)
+{
+  return bool(x) ? v <= *x : false;
+}
+
+template <class T> constexpr bool operator<=(const optional<T&>& x, const T& v)
+{
+  return bool(x) ? *x <= v : true;
+}
+
+template <class T> constexpr bool operator>=(const T& v, const optional<T&>& x)
+{
+  return bool(x) ? v >= *x : true;
+}
+
+// Comparison of optional<T const&> with T
+template <class T> constexpr bool operator==(const optional<const T&>& x, const T& v)
+{
+  return bool(x) ? *x == v : false;
+}
+
+template <class T> constexpr bool operator==(const T& v, const optional<const T&>& x)
+{
+  return bool(x) ? v == *x : false;
+}
+
+template <class T> constexpr bool operator!=(const optional<const T&>& x, const T& v)
+{
+  return bool(x) ? *x != v : true;
+}
+
+template <class T> constexpr bool operator!=(const T& v, const optional<const T&>& x)
+{
+  return bool(x) ? v != *x : true;
+}
+
+template <class T> constexpr bool operator<(const optional<const T&>& x, const T& v)
+{
+  return bool(x) ? *x < v : true;
+}
+
+template <class T> constexpr bool operator>(const T& v, const optional<const T&>& x)
+{
+  return bool(x) ? v > *x : true;
+}
+
+template <class T> constexpr bool operator>(const optional<const T&>& x, const T& v)
+{
+  return bool(x) ? *x > v : false;
+}
+
+template <class T> constexpr bool operator<(const T& v, const optional<const T&>& x)
+{
+  return bool(x) ? v < *x : false;
+}
+
+template <class T> constexpr bool operator>=(const optional<const T&>& x, const T& v)
+{
+  return bool(x) ? *x >= v : false;
+}
+
+template <class T> constexpr bool operator<=(const T& v, const optional<const T&>& x)
+{
+  return bool(x) ? v <= *x : false;
+}
+
+template <class T> constexpr bool operator<=(const optional<const T&>& x, const T& v)
+{
+  return bool(x) ? *x <= v : true;
+}
+
+template <class T> constexpr bool operator>=(const T& v, const optional<const T&>& x)
+{
+  return bool(x) ? v >= *x : true;
+}
+
+
+// 20.5.12, Specialized algorithms
+template <class T>
+void swap(optional<T>& x, optional<T>& y) noexcept(noexcept(x.swap(y)))
+{
+  x.swap(y);
+}
+
+
+template <class T>
+constexpr optional<typename std::decay<T>::type> make_optional(T&& v)
+{
+  return optional<typename std::decay<T>::type>(constexpr_forward<T>(v));
+}
+
+template <class X>
+constexpr optional<X&> make_optional(std::reference_wrapper<X> v)
+{
+  return optional<X&>(v.get());
+}
+
+
+} // namespace wpi
+
+namespace std
+{
+  template <typename T>
+  struct hash<wpi::optional<T>>
+  {
+    typedef typename hash<T>::result_type result_type;
+    typedef wpi::optional<T> argument_type;
+    
+    constexpr result_type operator()(argument_type const& arg) const {
+      return arg ? std::hash<T>{}(*arg) : result_type{};
+    }
+  };
+  
+  template <typename T>
+  struct hash<wpi::optional<T&>>
+  {
+    typedef typename hash<T>::result_type result_type;
+    typedef wpi::optional<T&> argument_type;
+    
+    constexpr result_type operator()(argument_type const& arg) const {
+      return arg ? std::hash<T>{}(*arg) : result_type{};
+    }
+  };
+}
+
+# undef TR2_OPTIONAL_REQUIRES
+# undef TR2_OPTIONAL_ASSERTED_EXPRESSION
+
+# endif //WPIUTIL_WPI_OPTIONAL_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/priority_mutex.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/priority_mutex.h
new file mode 100644
index 0000000..4e23fac
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/priority_mutex.h
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+// Allows usage with std::lock_guard without including <mutex> separately
+#ifdef __linux__
+#include <pthread.h>
+#endif
+
+#include <mutex>
+
+namespace wpi {
+
+#if defined(__FRC_ROBORIO__) && !defined(WPI_USE_PRIORITY_MUTEX)
+#define WPI_USE_PRIORITY_MUTEX
+#endif
+
+#if defined(WPI_USE_PRIORITY_MUTEX) && defined(__linux__)
+
+#define WPI_HAVE_PRIORITY_MUTEX 1
+
+class priority_recursive_mutex {
+ public:
+  using native_handle_type = pthread_mutex_t*;
+
+  constexpr priority_recursive_mutex() noexcept = default;
+  priority_recursive_mutex(const priority_recursive_mutex&) = delete;
+  priority_recursive_mutex& operator=(const priority_recursive_mutex&) = delete;
+
+  // Lock the mutex, blocking until it's available.
+  void lock() { pthread_mutex_lock(&m_mutex); }
+
+  // Unlock the mutex.
+  void unlock() { pthread_mutex_unlock(&m_mutex); }
+
+  // Tries to lock the mutex.
+  bool try_lock() noexcept { return !pthread_mutex_trylock(&m_mutex); }
+
+  pthread_mutex_t* native_handle() { return &m_mutex; }
+
+ private:
+// Do the equivalent of setting PTHREAD_PRIO_INHERIT and
+// PTHREAD_MUTEX_RECURSIVE_NP.
+#ifdef __PTHREAD_MUTEX_HAVE_PREV
+  pthread_mutex_t m_mutex = {
+      {0, 0, 0, 0, 0x20 | PTHREAD_MUTEX_RECURSIVE_NP, __PTHREAD_SPINS, {0, 0}}};
+#else
+  pthread_mutex_t m_mutex = {
+      {0, 0, 0, 0x20 | PTHREAD_MUTEX_RECURSIVE_NP, 0, {__PTHREAD_SPINS}}};
+#endif
+};
+
+class priority_mutex {
+ public:
+  using native_handle_type = pthread_mutex_t*;
+
+  constexpr priority_mutex() noexcept = default;
+  priority_mutex(const priority_mutex&) = delete;
+  priority_mutex& operator=(const priority_mutex&) = delete;
+
+  // Lock the mutex, blocking until it's available.
+  void lock() { pthread_mutex_lock(&m_mutex); }
+
+  // Unlock the mutex.
+  void unlock() { pthread_mutex_unlock(&m_mutex); }
+
+  // Tries to lock the mutex.
+  bool try_lock() noexcept { return !pthread_mutex_trylock(&m_mutex); }
+
+  pthread_mutex_t* native_handle() { return &m_mutex; }
+
+ private:
+// Do the equivalent of setting PTHREAD_PRIO_INHERIT.
+#ifdef __PTHREAD_MUTEX_HAVE_PREV
+  pthread_mutex_t m_mutex = {{0, 0, 0, 0, 0x20, __PTHREAD_SPINS, {0, 0}}};
+#else
+  pthread_mutex_t m_mutex = {{0, 0, 0, 0x20, 0, {__PTHREAD_SPINS}}};
+#endif
+};
+
+#endif  // defined(WPI_USE_PRIORITY_MUTEX) && defined(__linux__)
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_istream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_istream.h
new file mode 100644
index 0000000..1e6faf9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_istream.h
@@ -0,0 +1,178 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_RAW_ISTREAM_H_
+#define WPIUTIL_WPI_RAW_ISTREAM_H_
+
+#include <stdint.h>
+
+#include <algorithm>
+#include <cstddef>
+#include <string>
+#include <system_error>
+#include <vector>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include "wpi/Twine.h"
+
+namespace wpi {
+
+class raw_istream {
+ public:
+  raw_istream() = default;
+  virtual ~raw_istream() = default;
+
+  raw_istream& read(char& c) {
+    read_impl(&c, 1);
+    return *this;
+  }
+
+  raw_istream& read(unsigned char& c) {
+    read_impl(&c, 1);
+    return *this;
+  }
+
+  raw_istream& read(signed char& c) {
+    read_impl(&c, 1);
+    return *this;
+  }
+
+  raw_istream& read(void* data, size_t len) {
+    read_impl(data, len);
+    return *this;
+  }
+
+  size_t readsome(void* data, size_t len) {
+    size_t readlen = std::min(in_avail(), len);
+    if (readlen == 0) return 0;
+    read_impl(data, readlen);
+    return m_read_count;
+  }
+
+  raw_istream& readinto(SmallVectorImpl<char>& buf, size_t len) {
+    size_t old_size = buf.size();
+    buf.append(len, 0);
+    read_impl(&buf[old_size], len);
+    buf.resize(old_size + m_read_count);
+    return *this;
+  }
+
+  raw_istream& readinto(SmallVectorImpl<uint8_t>& buf, size_t len) {
+    size_t old_size = buf.size();
+    buf.append(len, 0);
+    read_impl(&buf[old_size], len);
+    buf.resize(old_size + m_read_count);
+    return *this;
+  }
+
+  raw_istream& readinto(std::vector<char>& buf, size_t len) {
+    size_t old_size = buf.size();
+    buf.insert(buf.end(), len, 0);
+    read_impl(&buf[old_size], len);
+    buf.resize(old_size + m_read_count);
+    return *this;
+  }
+
+  raw_istream& readinto(std::vector<uint8_t>& buf, size_t len) {
+    size_t old_size = buf.size();
+    buf.insert(buf.end(), len, 0);
+    read_impl(&buf[old_size], len);
+    buf.resize(old_size + m_read_count);
+    return *this;
+  }
+
+  raw_istream& readinto(std::string& buf, size_t len) {
+    size_t old_size = buf.size();
+    buf.insert(buf.end(), len, 0);
+    read_impl(&buf[old_size], len);
+    buf.resize(old_size + m_read_count);
+    return *this;
+  }
+
+  // Read a line from an input stream (up to a maximum length).
+  // The returned buffer will contain the trailing \n (unless the maximum length
+  // was reached).  \r's are stripped from the buffer.
+  // @param buf Buffer for output
+  // @param maxLen Maximum length
+  // @return Line
+  StringRef getline(SmallVectorImpl<char>& buf, int maxLen);
+
+  virtual void close() = 0;
+
+  // Number of bytes available to read without potentially blocking.
+  // Note this can return zero even if there are bytes actually available to
+  // read.
+  virtual size_t in_avail() const = 0;
+
+  // Return the number of bytes read by the last read operation.
+  size_t read_count() const { return m_read_count; }
+
+  bool has_error() const { return m_error; }
+  void clear_error() { m_error = false; }
+
+  raw_istream(const raw_istream&) = delete;
+  raw_istream& operator=(const raw_istream&) = delete;
+
+ protected:
+  void error_detected() { m_error = true; }
+  void set_read_count(size_t count) { m_read_count = count; }
+
+ private:
+  virtual void read_impl(void* data, size_t len) = 0;
+
+  bool m_error = false;
+  size_t m_read_count = 0;
+};
+
+class raw_mem_istream : public raw_istream {
+ public:
+  // not const as we don't want to allow temporaries
+  explicit raw_mem_istream(std::string& str)
+      : raw_mem_istream(str.data(), str.size()) {}
+  explicit raw_mem_istream(ArrayRef<char> mem)
+      : raw_mem_istream(mem.data(), mem.size()) {}
+  explicit raw_mem_istream(ArrayRef<uint8_t> mem)
+      : raw_mem_istream(reinterpret_cast<const char*>(mem.data()), mem.size()) {
+  }
+  explicit raw_mem_istream(const char* str)
+      : m_cur(str), m_left(std::strlen(str)) {}
+  raw_mem_istream(const char* mem, size_t len) : m_cur(mem), m_left(len) {}
+  void close() override;
+  size_t in_avail() const override;
+
+ private:
+  void read_impl(void* data, size_t len) override;
+
+  const char* m_cur;
+  size_t m_left;
+};
+
+class raw_fd_istream : public raw_istream {
+ public:
+  raw_fd_istream(const Twine& filename, std::error_code& ec,
+                 size_t bufSize = 4096);
+  raw_fd_istream(int fd, bool shouldClose, size_t bufSize = 4096);
+  ~raw_fd_istream() override;
+  void close() override;
+  size_t in_avail() const override;
+
+ private:
+  void read_impl(void* data, size_t len) override;
+
+  char* m_buf;
+  char* m_cur;
+  char* m_end;
+  size_t m_bufSize;
+  int m_fd;
+  bool m_shouldClose;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_RAW_ISTREAM_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_os_ostream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_os_ostream.h
new file mode 100644
index 0000000..4335e02
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_os_ostream.h
@@ -0,0 +1,42 @@
+//===- raw_os_ostream.h - std::ostream adaptor for raw_ostream --*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+//  This file defines the raw_os_ostream class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_RAW_OS_OSTREAM_H
+#define WPIUTIL_WPI_RAW_OS_OSTREAM_H
+
+#include "wpi/raw_ostream.h"
+#include <iosfwd>
+
+namespace wpi {
+
+/// raw_os_ostream - A raw_ostream that writes to an std::ostream.  This is a
+/// simple adaptor class.  It does not check for output errors; clients should
+/// use the underlying stream to detect errors.
+class raw_os_ostream : public raw_ostream {
+  std::ostream &OS;
+
+  /// write_impl - See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  /// current_pos - Return the current position within the stream, not
+  /// counting the bytes currently in the buffer.
+  uint64_t current_pos() const override;
+
+public:
+  raw_os_ostream(std::ostream &O) : OS(O) {}
+  ~raw_os_ostream() override;
+};
+
+} // end wpi namespace
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_ostream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_ostream.h
new file mode 100644
index 0000000..9e14d6d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_ostream.h
@@ -0,0 +1,663 @@
+//===--- raw_ostream.h - Raw output stream ----------------------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+//  This file defines the raw_ostream class.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_RAW_OSTREAM_H
+#define WPIUTIL_WPI_RAW_OSTREAM_H
+
+#include "wpi/ArrayRef.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+#include <cassert>
+#include <cstddef>
+#include <cstdint>
+#include <cstring>
+#include <string>
+#include <vector>
+#include <system_error>
+
+namespace wpi {
+
+class format_object_base;
+class FormattedString;
+class FormattedNumber;
+class FormattedBytes;
+
+namespace sys {
+namespace fs {
+enum OpenFlags : unsigned;
+} // end namespace fs
+} // end namespace sys
+
+/// This class implements an extremely fast bulk output stream that can *only*
+/// output to a stream.  It does not support seeking, reopening, rewinding, line
+/// buffered disciplines etc. It is a simple buffer that outputs
+/// a chunk at a time.
+class raw_ostream {
+private:
+  /// The buffer is handled in such a way that the buffer is
+  /// uninitialized, unbuffered, or out of space when OutBufCur >=
+  /// OutBufEnd. Thus a single comparison suffices to determine if we
+  /// need to take the slow path to write a single character.
+  ///
+  /// The buffer is in one of three states:
+  ///  1. Unbuffered (BufferMode == Unbuffered)
+  ///  1. Uninitialized (BufferMode != Unbuffered && OutBufStart == 0).
+  ///  2. Buffered (BufferMode != Unbuffered && OutBufStart != 0 &&
+  ///               OutBufEnd - OutBufStart >= 1).
+  ///
+  /// If buffered, then the raw_ostream owns the buffer if (BufferMode ==
+  /// InternalBuffer); otherwise the buffer has been set via SetBuffer and is
+  /// managed by the subclass.
+  ///
+  /// If a subclass installs an external buffer using SetBuffer then it can wait
+  /// for a \see write_impl() call to handle the data which has been put into
+  /// this buffer.
+  char *OutBufStart, *OutBufEnd, *OutBufCur;
+
+  enum BufferKind {
+    Unbuffered = 0,
+    InternalBuffer,
+    ExternalBuffer
+  } BufferMode;
+
+public:
+  // color order matches ANSI escape sequence, don't change
+  enum Colors {
+    BLACK = 0,
+    RED,
+    GREEN,
+    YELLOW,
+    BLUE,
+    MAGENTA,
+    CYAN,
+    WHITE,
+    SAVEDCOLOR
+  };
+
+  explicit raw_ostream(bool unbuffered = false)
+      : BufferMode(unbuffered ? Unbuffered : InternalBuffer) {
+    // Start out ready to flush.
+    OutBufStart = OutBufEnd = OutBufCur = nullptr;
+  }
+
+  raw_ostream(const raw_ostream &) = delete;
+  void operator=(const raw_ostream &) = delete;
+
+  virtual ~raw_ostream();
+
+  /// tell - Return the current offset with the file.
+  uint64_t tell() const { return current_pos() + GetNumBytesInBuffer(); }
+
+  //===--------------------------------------------------------------------===//
+  // Configuration Interface
+  //===--------------------------------------------------------------------===//
+
+  /// Set the stream to be buffered, with an automatically determined buffer
+  /// size.
+  void SetBuffered();
+
+  /// Set the stream to be buffered, using the specified buffer size.
+  void SetBufferSize(size_t Size) {
+    flush();
+    SetBufferAndMode(new char[Size], Size, InternalBuffer);
+  }
+
+  size_t GetBufferSize() const {
+    // If we're supposed to be buffered but haven't actually gotten around
+    // to allocating the buffer yet, return the value that would be used.
+    if (BufferMode != Unbuffered && OutBufStart == nullptr)
+      return preferred_buffer_size();
+
+    // Otherwise just return the size of the allocated buffer.
+    return OutBufEnd - OutBufStart;
+  }
+
+  /// Set the stream to be unbuffered. When unbuffered, the stream will flush
+  /// after every write. This routine will also flush the buffer immediately
+  /// when the stream is being set to unbuffered.
+  void SetUnbuffered() {
+    flush();
+    SetBufferAndMode(nullptr, 0, Unbuffered);
+  }
+
+  size_t GetNumBytesInBuffer() const {
+    return OutBufCur - OutBufStart;
+  }
+
+  //===--------------------------------------------------------------------===//
+  // Data Output Interface
+  //===--------------------------------------------------------------------===//
+
+  void flush() {
+    if (OutBufCur != OutBufStart)
+      flush_nonempty();
+  }
+
+  raw_ostream &operator<<(char C) {
+    if (OutBufCur >= OutBufEnd)
+      return write(C);
+    *OutBufCur++ = C;
+    return *this;
+  }
+
+  raw_ostream &operator<<(unsigned char C) {
+    if (OutBufCur >= OutBufEnd)
+      return write(C);
+    *OutBufCur++ = C;
+    return *this;
+  }
+
+  raw_ostream &operator<<(signed char C) {
+    if (OutBufCur >= OutBufEnd)
+      return write(C);
+    *OutBufCur++ = C;
+    return *this;
+  }
+
+  raw_ostream &operator<<(ArrayRef<uint8_t> Arr) {
+    // Inline fast path, particularly for arrays with a known length.
+    size_t Size = Arr.size();
+
+    // Make sure we can use the fast path.
+    if (Size > (size_t)(OutBufEnd - OutBufCur))
+      return write(Arr.data(), Size);
+
+    if (Size) {
+      memcpy(OutBufCur, Arr.data(), Size);
+      OutBufCur += Size;
+    }
+    return *this;
+  }
+
+  raw_ostream &operator<<(StringRef Str) {
+    // Inline fast path, particularly for strings with a known length.
+    size_t Size = Str.size();
+
+    // Make sure we can use the fast path.
+    if (Size > (size_t)(OutBufEnd - OutBufCur))
+      return write(Str.data(), Size);
+
+    if (Size) {
+      memcpy(OutBufCur, Str.data(), Size);
+      OutBufCur += Size;
+    }
+    return *this;
+  }
+
+  raw_ostream &operator<<(const char *Str) {
+    // Inline fast path, particularly for constant strings where a sufficiently
+    // smart compiler will simplify strlen.
+
+    return this->operator<<(StringRef(Str));
+  }
+
+  raw_ostream &operator<<(const std::string &Str) {
+    // Avoid the fast path, it would only increase code size for a marginal win.
+    return write(Str.data(), Str.length());
+  }
+
+  raw_ostream &operator<<(const SmallVectorImpl<char> &Str) {
+    return write(Str.data(), Str.size());
+  }
+
+  raw_ostream &operator<<(const std::vector<uint8_t> &Arr) {
+    // Avoid the fast path, it would only increase code size for a marginal win.
+    return write(Arr.data(), Arr.size());
+  }
+
+  raw_ostream &operator<<(const SmallVectorImpl<uint8_t> &Arr) {
+    return write(Arr.data(), Arr.size());
+  }
+
+  raw_ostream &operator<<(unsigned long N);
+  raw_ostream &operator<<(long N);
+  raw_ostream &operator<<(unsigned long long N);
+  raw_ostream &operator<<(long long N);
+  raw_ostream &operator<<(const void *P);
+
+  raw_ostream &operator<<(unsigned int N) {
+    return this->operator<<(static_cast<unsigned long>(N));
+  }
+
+  raw_ostream &operator<<(int N) {
+    return this->operator<<(static_cast<long>(N));
+  }
+
+  raw_ostream &operator<<(double N);
+
+  /// Output \p N in hexadecimal, without any prefix or padding.
+  raw_ostream &write_hex(unsigned long long N);
+
+  /// Output \p Str, turning '\\', '\t', '\n', '"', and anything that doesn't
+  /// satisfy std::isprint into an escape sequence.
+  raw_ostream &write_escaped(StringRef Str, bool UseHexEscapes = false);
+
+  raw_ostream &write(unsigned char C);
+  raw_ostream &write(const char *Ptr, size_t Size);
+  raw_ostream &write(const uint8_t *Ptr, size_t Size) {
+    return write(reinterpret_cast<const char *>(Ptr), Size);
+  }
+
+  // Formatted output, see the format() function in Support/Format.h.
+  raw_ostream &operator<<(const format_object_base &Fmt);
+
+  // Formatted output, see the leftJustify() function in Support/Format.h.
+  raw_ostream &operator<<(const FormattedString &);
+
+  // Formatted output, see the formatHex() function in Support/Format.h.
+  raw_ostream &operator<<(const FormattedNumber &);
+
+  // Formatted output, see the format_bytes() function in Support/Format.h.
+  raw_ostream &operator<<(const FormattedBytes &);
+
+  /// indent - Insert 'NumSpaces' spaces.
+  raw_ostream &indent(unsigned NumSpaces);
+
+  /// write_zeros - Insert 'NumZeros' nulls.
+  raw_ostream &write_zeros(unsigned NumZeros);
+
+  /// Changes the foreground color of text that will be output from this point
+  /// forward.
+  /// @param Color ANSI color to use, the special SAVEDCOLOR can be used to
+  /// change only the bold attribute, and keep colors untouched
+  /// @param Bold bold/brighter text, default false
+  /// @param BG if true change the background, default: change foreground
+  /// @returns itself so it can be used within << invocations
+  virtual raw_ostream &changeColor(enum Colors Color,
+                                   bool Bold = false,
+                                   bool BG = false) {
+    (void)Color;
+    (void)Bold;
+    (void)BG;
+    return *this;
+  }
+
+  /// Resets the colors to terminal defaults. Call this when you are done
+  /// outputting colored text, or before program exit.
+  virtual raw_ostream &resetColor() { return *this; }
+
+  /// Reverses the foreground and background colors.
+  virtual raw_ostream &reverseColor() { return *this; }
+
+  /// This function determines if this stream is connected to a "tty" or
+  /// "console" window. That is, the output would be displayed to the user
+  /// rather than being put on a pipe or stored in a file.
+  virtual bool is_displayed() const { return false; }
+
+  /// This function determines if this stream is displayed and supports colors.
+  virtual bool has_colors() const { return is_displayed(); }
+
+  //===--------------------------------------------------------------------===//
+  // Subclass Interface
+  //===--------------------------------------------------------------------===//
+
+private:
+  /// The is the piece of the class that is implemented by subclasses.  This
+  /// writes the \p Size bytes starting at
+  /// \p Ptr to the underlying stream.
+  ///
+  /// This function is guaranteed to only be called at a point at which it is
+  /// safe for the subclass to install a new buffer via SetBuffer.
+  ///
+  /// \param Ptr The start of the data to be written. For buffered streams this
+  /// is guaranteed to be the start of the buffer.
+  ///
+  /// \param Size The number of bytes to be written.
+  ///
+  /// \invariant { Size > 0 }
+  virtual void write_impl(const char *Ptr, size_t Size) = 0;
+
+  // An out of line virtual method to provide a home for the class vtable.
+  virtual void handle();
+
+  /// Return the current position within the stream, not counting the bytes
+  /// currently in the buffer.
+  virtual uint64_t current_pos() const = 0;
+
+protected:
+  /// Use the provided buffer as the raw_ostream buffer. This is intended for
+  /// use only by subclasses which can arrange for the output to go directly
+  /// into the desired output buffer, instead of being copied on each flush.
+  void SetBuffer(char *BufferStart, size_t Size) {
+    SetBufferAndMode(BufferStart, Size, ExternalBuffer);
+  }
+
+  /// Return an efficient buffer size for the underlying output mechanism.
+  virtual size_t preferred_buffer_size() const;
+
+  /// Return the beginning of the current stream buffer, or 0 if the stream is
+  /// unbuffered.
+  const char *getBufferStart() const { return OutBufStart; }
+
+  //===--------------------------------------------------------------------===//
+  // Private Interface
+  //===--------------------------------------------------------------------===//
+private:
+  /// Install the given buffer and mode.
+  void SetBufferAndMode(char *BufferStart, size_t Size, BufferKind Mode);
+
+  /// Flush the current buffer, which is known to be non-empty. This outputs the
+  /// currently buffered data and resets the buffer to empty.
+  void flush_nonempty();
+
+  /// Copy data into the buffer. Size must not be greater than the number of
+  /// unused bytes in the buffer.
+  void copy_to_buffer(const char *Ptr, size_t Size);
+
+  virtual void anchor();
+};
+
+/// An abstract base class for streams implementations that also support a
+/// pwrite operation. This is useful for code that can mostly stream out data,
+/// but needs to patch in a header that needs to know the output size.
+class raw_pwrite_stream : public raw_ostream {
+  virtual void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) = 0;
+  void anchor() override;
+
+public:
+  explicit raw_pwrite_stream(bool Unbuffered = false)
+      : raw_ostream(Unbuffered) {}
+  void pwrite(const char *Ptr, size_t Size, uint64_t Offset) {
+#ifndef NDBEBUG
+    uint64_t Pos = tell();
+    // /dev/null always reports a pos of 0, so we cannot perform this check
+    // in that case.
+    if (Pos)
+      assert(Size + Offset <= Pos && "We don't support extending the stream");
+#endif
+    pwrite_impl(Ptr, Size, Offset);
+  }
+};
+
+//===----------------------------------------------------------------------===//
+// File Output Streams
+//===----------------------------------------------------------------------===//
+
+/// A raw_ostream that writes to a file descriptor.
+///
+class raw_fd_ostream : public raw_pwrite_stream {
+  int FD;
+  bool ShouldClose;
+
+  std::error_code EC;
+
+  uint64_t pos;
+
+  bool SupportsSeeking;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream, not counting the bytes
+  /// currently in the buffer.
+  uint64_t current_pos() const override { return pos; }
+
+  /// Determine an efficient buffer size.
+  size_t preferred_buffer_size() const override;
+
+  /// Set the flag indicating that an output error has been encountered.
+  void error_detected(std::error_code EC) { this->EC = EC; }
+
+  void anchor() override;
+
+public:
+  /// Open the specified file for writing. If an error occurs, information
+  /// about the error is put into EC, and the stream should be immediately
+  /// destroyed;
+  /// \p Flags allows optional flags to control how the file will be opened.
+  ///
+  /// As a special case, if Filename is "-", then the stream will use
+  /// STDOUT_FILENO instead of opening a file. Note that it will still consider
+  /// itself to own the file descriptor. In particular, it will close the
+  /// file descriptor when it is done (this is necessary to detect
+  /// output errors).
+  raw_fd_ostream(StringRef Filename, std::error_code &EC,
+                 sys::fs::OpenFlags Flags);
+
+  /// FD is the file descriptor that this writes to.  If ShouldClose is true,
+  /// this closes the file when the stream is destroyed.
+  raw_fd_ostream(int fd, bool shouldClose, bool unbuffered=false);
+
+  ~raw_fd_ostream() override;
+
+  /// Manually flush the stream and close the file. Note that this does not call
+  /// fsync.
+  void close();
+
+  bool supportsSeeking() { return SupportsSeeking; }
+
+  /// Flushes the stream and repositions the underlying file descriptor position
+  /// to the offset specified from the beginning of the file.
+  uint64_t seek(uint64_t off);
+
+  std::error_code error() const { return EC; }
+
+  /// Return the value of the flag in this raw_fd_ostream indicating whether an
+  /// output error has been encountered.
+  /// This doesn't implicitly flush any pending output.  Also, it doesn't
+  /// guarantee to detect all errors unless the stream has been closed.
+  bool has_error() const { return bool(EC); }
+
+  /// Set the flag read by has_error() to false. If the error flag is set at the
+  /// time when this raw_ostream's destructor is called, report_fatal_error is
+  /// called to report the error. Use clear_error() after handling the error to
+  /// avoid this behavior.
+  ///
+  ///   "Errors should never pass silently.
+  ///    Unless explicitly silenced."
+  ///      - from The Zen of Python, by Tim Peters
+  ///
+  void clear_error() { EC = std::error_code(); }
+};
+
+/// This returns a reference to a raw_ostream for standard output. Use it like:
+/// outs() << "foo" << "bar";
+raw_ostream &outs();
+
+/// This returns a reference to a raw_ostream for standard error. Use it like:
+/// errs() << "foo" << "bar";
+raw_ostream &errs();
+
+/// This returns a reference to a raw_ostream which simply discards output.
+raw_ostream &nulls();
+
+//===----------------------------------------------------------------------===//
+// Output Stream Adaptors
+//===----------------------------------------------------------------------===//
+
+/// A raw_ostream that writes to an std::string.  This is a simple adaptor
+/// class. This class does not encounter output errors.
+class raw_string_ostream : public raw_ostream {
+  std::string &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  /// Return the current position within the stream, not counting the bytes
+  /// currently in the buffer.
+  uint64_t current_pos() const override { return OS.size(); }
+
+public:
+  explicit raw_string_ostream(std::string &O) : OS(O) {}
+  ~raw_string_ostream() override;
+
+  /// Flushes the stream contents to the target string and returns  the string's
+  /// reference.
+  std::string& str() {
+    flush();
+    return OS;
+  }
+};
+
+/// A raw_ostream that writes to an SmallVector or SmallString.  This is a
+/// simple adaptor class. This class does not encounter output errors.
+/// raw_svector_ostream operates without a buffer, delegating all memory
+/// management to the SmallString. Thus the SmallString is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_svector_ostream : public raw_pwrite_stream {
+  SmallVectorImpl<char> &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream.
+  uint64_t current_pos() const override;
+
+public:
+  /// Construct a new raw_svector_ostream.
+  ///
+  /// \param O The vector to write to; this should generally have at least 128
+  /// bytes free to avoid any extraneous memory overhead.
+  explicit raw_svector_ostream(SmallVectorImpl<char> &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  ~raw_svector_ostream() override = default;
+
+  void flush() = delete;
+
+  /// Return a StringRef for the vector contents.
+  StringRef str() { return StringRef(OS.data(), OS.size()); }
+};
+
+/// A raw_ostream that writes to a vector.  This is a
+/// simple adaptor class. This class does not encounter output errors.
+/// raw_vector_ostream operates without a buffer, delegating all memory
+/// management to the vector. Thus the vector is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_vector_ostream : public raw_pwrite_stream {
+  std::vector<char> &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream.
+  uint64_t current_pos() const override;
+
+public:
+  /// Construct a new raw_svector_ostream.
+  ///
+  /// \param O The vector to write to; this should generally have at least 128
+  /// bytes free to avoid any extraneous memory overhead.
+  explicit raw_vector_ostream(std::vector<char> &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  ~raw_vector_ostream() override = default;
+
+  void flush() = delete;
+
+  /// Return a StringRef for the vector contents.
+  StringRef str() { return StringRef(OS.data(), OS.size()); }
+};
+
+/// A raw_ostream that writes to an SmallVector or SmallString.  This is a
+/// simple adaptor class. This class does not encounter output errors.
+/// raw_svector_ostream operates without a buffer, delegating all memory
+/// management to the SmallString. Thus the SmallString is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_usvector_ostream : public raw_pwrite_stream {
+  SmallVectorImpl<uint8_t> &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream.
+  uint64_t current_pos() const override;
+
+public:
+  /// Construct a new raw_svector_ostream.
+  ///
+  /// \param O The vector to write to; this should generally have at least 128
+  /// bytes free to avoid any extraneous memory overhead.
+  explicit raw_usvector_ostream(SmallVectorImpl<uint8_t> &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  ~raw_usvector_ostream() override = default;
+
+  void flush() = delete;
+
+  /// Return an ArrayRef for the vector contents.
+  ArrayRef<uint8_t> array() { return ArrayRef<uint8_t>(OS.data(), OS.size()); }
+};
+
+/// A raw_ostream that writes to a vector.  This is a
+/// simple adaptor class. This class does not encounter output errors.
+/// raw_vector_ostream operates without a buffer, delegating all memory
+/// management to the vector. Thus the vector is always up-to-date,
+/// may be used directly and there is no need to call flush().
+class raw_uvector_ostream : public raw_pwrite_stream {
+  std::vector<uint8_t> &OS;
+
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t Size) override;
+
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream.
+  uint64_t current_pos() const override;
+
+public:
+  /// Construct a new raw_svector_ostream.
+  ///
+  /// \param O The vector to write to; this should generally have at least 128
+  /// bytes free to avoid any extraneous memory overhead.
+  explicit raw_uvector_ostream(std::vector<uint8_t> &O) : OS(O) {
+    SetUnbuffered();
+  }
+
+  ~raw_uvector_ostream() override = default;
+
+  void flush() = delete;
+
+  /// Return a StringRef for the vector contents.
+  ArrayRef<uint8_t> array() { return ArrayRef<uint8_t>(OS.data(), OS.size()); }
+};
+
+
+/// A raw_ostream that discards all output.
+class raw_null_ostream : public raw_pwrite_stream {
+  /// See raw_ostream::write_impl.
+  void write_impl(const char *Ptr, size_t size) override;
+  void pwrite_impl(const char *Ptr, size_t Size, uint64_t Offset) override;
+
+  /// Return the current position within the stream, not counting the bytes
+  /// currently in the buffer.
+  uint64_t current_pos() const override;
+
+public:
+  explicit raw_null_ostream() = default;
+  ~raw_null_ostream() override;
+};
+
+class buffer_ostream : public raw_svector_ostream {
+  raw_ostream &OS;
+  SmallVector<char, 0> Buffer;
+
+public:
+  buffer_ostream(raw_ostream &OS) : raw_svector_ostream(Buffer), OS(OS) {}
+  ~buffer_ostream() override { OS << str(); }
+};
+
+} // end namespace wpi
+
+#endif // LLVM_SUPPORT_RAW_OSTREAM_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_socket_istream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_socket_istream.h
new file mode 100644
index 0000000..4ff8022
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_socket_istream.h
@@ -0,0 +1,34 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_RAW_SOCKET_ISTREAM_H_
+#define WPIUTIL_WPI_RAW_SOCKET_ISTREAM_H_
+
+#include "wpi/raw_istream.h"
+
+namespace wpi {
+
+class NetworkStream;
+
+class raw_socket_istream : public raw_istream {
+ public:
+  explicit raw_socket_istream(NetworkStream& stream, int timeout = 0)
+      : m_stream(stream), m_timeout(timeout) {}
+
+  void close() override;
+  size_t in_avail() const override;
+
+ private:
+  void read_impl(void* data, size_t len) override;
+
+  NetworkStream& m_stream;
+  int m_timeout;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_RAW_SOCKET_ISTREAM_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_socket_ostream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_socket_ostream.h
new file mode 100644
index 0000000..151af46
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_socket_ostream.h
@@ -0,0 +1,42 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_RAW_SOCKET_OSTREAM_H_
+#define WPIUTIL_WPI_RAW_SOCKET_OSTREAM_H_
+
+#include "wpi/raw_ostream.h"
+
+namespace wpi {
+
+class NetworkStream;
+
+class raw_socket_ostream : public raw_ostream {
+ public:
+  raw_socket_ostream(NetworkStream& stream, bool shouldClose)
+      : m_stream(stream), m_shouldClose(shouldClose) {}
+  ~raw_socket_ostream();
+
+  void close();
+
+  bool has_error() const { return m_error; }
+  void clear_error() { m_error = false; }
+
+ protected:
+  void error_detected() { m_error = true; }
+
+ private:
+  void write_impl(const char* data, size_t len) override;
+  uint64_t current_pos() const override;
+
+  NetworkStream& m_stream;
+  bool m_error = false;
+  bool m_shouldClose;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_RAW_SOCKET_OSTREAM_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_uv_ostream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_uv_ostream.h
new file mode 100644
index 0000000..e35b4a8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/raw_uv_ostream.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_RAW_UV_OSTREAM_H_
+#define WPIUTIL_WPI_RAW_UV_OSTREAM_H_
+
+#include "wpi/ArrayRef.h"
+#include "wpi/SmallVector.h"
+#include "wpi/raw_ostream.h"
+#include "wpi/uv/Buffer.h"
+
+namespace wpi {
+
+/**
+ * raw_ostream style output to a SmallVector of uv::Buffer buffers.  Fixed-size
+ * buffers are allocated and appended as necessary to fit the data being output.
+ * The SmallVector need not be empty at start.
+ */
+class raw_uv_ostream : public raw_ostream {
+ public:
+  /**
+   * Construct a new raw_uv_ostream.
+   * @param bufs Buffers vector.  NOT cleared on construction.
+   * @param allocSize Size to allocate for each buffer; allocation will be
+   *                  performed using Buffer::Allocate().
+   */
+  raw_uv_ostream(SmallVectorImpl<uv::Buffer>& bufs, size_t allocSize)
+      : m_bufs(bufs),
+        m_alloc([=]() { return uv::Buffer::Allocate(allocSize); }) {
+    SetUnbuffered();
+  }
+
+  /**
+   * Construct a new raw_uv_ostream.
+   * @param bufs Buffers vector.  NOT cleared on construction.
+   * @param alloc Allocator.
+   */
+  raw_uv_ostream(SmallVectorImpl<uv::Buffer>& bufs,
+                 std::function<uv::Buffer()> alloc)
+      : m_bufs(bufs), m_alloc(alloc) {
+    SetUnbuffered();
+  }
+
+  ~raw_uv_ostream() override = default;
+
+  /**
+   * Returns an ArrayRef to the buffers.
+   */
+  ArrayRef<uv::Buffer> bufs() { return m_bufs; }
+
+  void flush() = delete;
+
+ private:
+  void write_impl(const char* data, size_t len) override;
+  uint64_t current_pos() const override;
+
+  SmallVectorImpl<uv::Buffer>& m_bufs;
+  std::function<uv::Buffer()> m_alloc;
+
+  // How much allocated space is left in the current buffer.
+  size_t m_left = 0;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_RAW_UV_OSTREAM_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/sha1.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/sha1.h
new file mode 100644
index 0000000..6a0817f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/sha1.h
@@ -0,0 +1,53 @@
+/*
+    sha1.hpp - header of
+
+    ============
+    SHA-1 in C++
+    ============
+
+    100% Public Domain.
+
+    Original C Code
+        -- Steve Reid <steve@edmweb.com>
+    Small changes to fit into bglibs
+        -- Bruce Guenter <bruce@untroubled.org>
+    Translation to simpler C++ Code
+        -- Volker Grabsch <vog@notjusthosting.com>
+    Safety fixes
+        -- Eugene Hopkinson <slowriot at voxelstorm dot com>
+*/
+
+#ifndef WPIUTIL_WPI_SHA1_H_
+#define WPIUTIL_WPI_SHA1_H_
+
+#include <stdint.h>
+
+#include <string>
+
+#include "wpi/StringRef.h"
+
+namespace wpi {
+template <typename T>
+class SmallVectorImpl;
+class raw_istream;
+
+class SHA1 {
+ public:
+  SHA1();
+  void Update(StringRef s);
+  void Update(raw_istream& is);
+  std::string Final();
+  StringRef Final(SmallVectorImpl<char>& buf);
+  StringRef RawFinal(SmallVectorImpl<char>& buf);
+  static std::string FromFile(StringRef filename);
+
+ private:
+  uint32_t digest[5];
+  unsigned char buffer[64];
+  size_t buf_size;
+  uint64_t transforms;
+};
+
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_SHA1_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/spinlock.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/spinlock.h
new file mode 100644
index 0000000..73137f1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/spinlock.h
@@ -0,0 +1,134 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <atomic>
+#include <cassert>
+#include <mutex>
+#include <thread>
+
+#include "Compiler.h"
+
+namespace wpi {
+
+/**
+ * A spinlock mutex.  Wraps std::atomic_flag in a std::mutex compatible way.
+ */
+class spinlock {
+  std::atomic_flag lock_flag;
+
+ public:
+  spinlock() noexcept { lock_flag.clear(); }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  bool try_lock() { return !lock_flag.test_and_set(std::memory_order_acquire); }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  void lock() {
+    for (unsigned int i = 1; !try_lock(); ++i)
+      if ((i & 0xff) == 0) std::this_thread::yield();
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  void unlock() { lock_flag.clear(std::memory_order_release); }
+};
+
+/**
+ * A recursive spinlock mutex.  This version uses std::atomic_flag for spin,
+ * then checks the thread id for recursion.  It is generally faster on desktop
+ * platforms compared to recursive_spinlock2.
+ */
+class recursive_spinlock1 {
+  std::atomic<std::thread::id> owner_thread_id{std::thread::id{}};
+  int32_t recursive_counter{0};
+  std::atomic_flag lock_flag;
+
+ public:
+  recursive_spinlock1() noexcept { lock_flag.clear(); }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  bool try_lock() {
+    if (!lock_flag.test_and_set(std::memory_order_acquire)) {
+      owner_thread_id.store(std::this_thread::get_id(),
+                            std::memory_order_release);
+    } else {
+      if (owner_thread_id.load(std::memory_order_acquire) !=
+          std::this_thread::get_id())
+        return false;
+    }
+    ++recursive_counter;
+    return true;
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  void lock() {
+    for (unsigned int i = 1; !try_lock(); ++i)
+      if ((i & 0xffff) == 0) std::this_thread::yield();
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  void unlock() {
+    assert(owner_thread_id.load(std::memory_order_acquire) ==
+           std::this_thread::get_id());
+    assert(recursive_counter > 0);
+
+    if (--recursive_counter == 0) {
+      owner_thread_id.store(std::thread::id{}, std::memory_order_release);
+      lock_flag.clear(std::memory_order_release);
+    }
+  }
+};
+
+/**
+ * A recursive spinlock mutex.  This version spins directly on the std::atomic
+ * of the thread id.  It is generally faster on embedded ARM platforms such
+ * as the RoboRIO and Raspberry Pi, compared to recursive_spinlock1.
+ */
+class recursive_spinlock2 {
+  std::atomic<std::thread::id> owner_thread_id{std::thread::id{}};
+  int32_t recursive_counter{0};
+
+ public:
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  bool try_lock() {
+    auto owner = std::thread::id{};
+    auto us = std::this_thread::get_id();
+    if (!owner_thread_id.compare_exchange_weak(owner, us,
+                                               std::memory_order_acquire)) {
+      if (owner != us) return false;
+    }
+    ++recursive_counter;
+    return true;
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  void lock() {
+    for (unsigned int i = 1; !try_lock(); ++i)
+      if ((i & 0xffff) == 0) std::this_thread::yield();
+  }
+
+  LLVM_ATTRIBUTE_ALWAYS_INLINE
+  void unlock() {
+    assert(owner_thread_id.load(std::memory_order_acquire) ==
+           std::this_thread::get_id());
+    assert(recursive_counter > 0);
+
+    if (--recursive_counter == 0)
+      owner_thread_id.store(std::thread::id{}, std::memory_order_release);
+  }
+};
+
+#ifdef __arm__
+// benchmarking has shown this version to be faster on ARM, but slower on
+// windows, mac, and linux
+using recursive_spinlock = recursive_spinlock2;
+#else
+using recursive_spinlock = recursive_spinlock1;
+#endif
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/timestamp.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/timestamp.h
new file mode 100644
index 0000000..aefcd56
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/timestamp.h
@@ -0,0 +1,71 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_TIMESTAMP_H_
+#define WPIUTIL_WPI_TIMESTAMP_H_
+
+#include <stdint.h>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+/**
+ * The default implementation used for Now().
+ * In general this is the time returned by the operating system.
+ * @return Time in microseconds.
+ */
+uint64_t WPI_NowDefault(void);
+
+/**
+ * Set the implementation used by WPI_Now().
+ * The implementation must return monotonic time in microseconds to maintain
+ * the contract of WPI_Now().
+ * @param func Function called by WPI_Now() to return the time.
+ */
+void WPI_SetNowImpl(uint64_t (*func)(void));
+
+/**
+ * Return a value representing the current time in microseconds.
+ * The epoch is not defined.
+ * @return Time in microseconds.
+ */
+uint64_t WPI_Now(void);
+
+#ifdef __cplusplus
+}  // extern "C"
+#endif
+
+#ifdef __cplusplus
+namespace wpi {
+
+/**
+ * The default implementation used for Now().
+ * In general this is the time returned by the operating system.
+ * @return Time in microseconds.
+ */
+uint64_t NowDefault(void);
+
+/**
+ * Set the implementation used by Now().
+ * The implementation must return monotonic time in microseconds to maintain
+ * the contract of Now().
+ * @param func Function called by Now() to return the time.
+ */
+void SetNowImpl(uint64_t (*func)());
+
+/**
+ * Return a value representing the current time in microseconds.
+ * This is a monotonic clock with an undefined epoch.
+ * @return Time in microseconds.
+ */
+uint64_t Now(void);
+
+}  // namespace wpi
+#endif
+
+#endif  // WPIUTIL_WPI_TIMESTAMP_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/type_traits.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/type_traits.h
new file mode 100644
index 0000000..5d35ee1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/type_traits.h
@@ -0,0 +1,125 @@
+//===- llvm/Support/type_traits.h - Simplfied type traits -------*- C++ -*-===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+//
+// This file provides useful additions to the standard type_traits library.
+//
+//===----------------------------------------------------------------------===//
+
+#ifndef WPIUTIL_WPI_TYPE_TRAITS_H
+#define WPIUTIL_WPI_TYPE_TRAITS_H
+
+#include "wpi/Compiler.h"
+#include <type_traits>
+#include <utility>
+
+#ifndef __has_feature
+#define WPI_DEFINED_HAS_FEATURE
+#define __has_feature(x) 0
+#endif
+
+namespace wpi {
+
+/// isPodLike - This is a type trait that is used to determine whether a given
+/// type can be copied around with memcpy instead of running ctors etc.
+template <typename T>
+struct isPodLike {
+  // std::is_trivially_copyable is available in libc++ with clang, libstdc++
+  // that comes with GCC 5.
+#if (__has_feature(is_trivially_copyable) && defined(_LIBCPP_VERSION)) ||      \
+    (defined(__GNUC__) && __GNUC__ >= 5)
+  // If the compiler supports the is_trivially_copyable trait use it, as it
+  // matches the definition of isPodLike closely.
+  static const bool value = std::is_trivially_copyable<T>::value;
+#elif __has_feature(is_trivially_copyable)
+  // Use the internal name if the compiler supports is_trivially_copyable but we
+  // don't know if the standard library does. This is the case for clang in
+  // conjunction with libstdc++ from GCC 4.x.
+  static const bool value = __is_trivially_copyable(T);
+#else
+  // If we don't know anything else, we can (at least) assume that all non-class
+  // types are PODs.
+  static const bool value = !std::is_class<T>::value;
+#endif
+};
+
+// std::pair's are pod-like if their elements are.
+template<typename T, typename U>
+struct isPodLike<std::pair<T, U>> {
+  static const bool value = isPodLike<T>::value && isPodLike<U>::value;
+};
+
+/// Metafunction that determines whether the given type is either an
+/// integral type or an enumeration type, including enum classes.
+///
+/// Note that this accepts potentially more integral types than is_integral
+/// because it is based on being implicitly convertible to an integral type.
+/// Also note that enum classes aren't implicitly convertible to integral types,
+/// the value may therefore need to be explicitly converted before being used.
+template <typename T> class is_integral_or_enum {
+  using UnderlyingT = typename std::remove_reference<T>::type;
+
+public:
+  static const bool value =
+      !std::is_class<UnderlyingT>::value && // Filter conversion operators.
+      !std::is_pointer<UnderlyingT>::value &&
+      !std::is_floating_point<UnderlyingT>::value &&
+      (std::is_enum<UnderlyingT>::value ||
+       std::is_convertible<UnderlyingT, unsigned long long>::value);
+};
+
+/// If T is a pointer, just return it. If it is not, return T&.
+template<typename T, typename Enable = void>
+struct add_lvalue_reference_if_not_pointer { using type = T &; };
+
+template <typename T>
+struct add_lvalue_reference_if_not_pointer<
+    T, typename std::enable_if<std::is_pointer<T>::value>::type> {
+  using type = T;
+};
+
+/// If T is a pointer to X, return a pointer to const X. If it is not,
+/// return const T.
+template<typename T, typename Enable = void>
+struct add_const_past_pointer { using type = const T; };
+
+template <typename T>
+struct add_const_past_pointer<
+    T, typename std::enable_if<std::is_pointer<T>::value>::type> {
+  using type = const typename std::remove_pointer<T>::type *;
+};
+
+template <typename T, typename Enable = void>
+struct const_pointer_or_const_ref {
+  using type = const T &;
+};
+template <typename T>
+struct const_pointer_or_const_ref<
+    T, typename std::enable_if<std::is_pointer<T>::value>::type> {
+  using type = typename add_const_past_pointer<T>::type;
+};
+
+} // namespace wpi
+
+// If the compiler supports detecting whether a class is final, define
+// an LLVM_IS_FINAL macro. If it cannot be defined properly, this
+// macro will be left undefined.
+#ifndef LLVM_IS_FINAL
+#if __cplusplus >= 201402L || defined(_MSC_VER)
+#define LLVM_IS_FINAL(Ty) std::is_final<Ty>()
+#elif __has_feature(is_final) || LLVM_GNUC_PREREQ(4, 7, 0)
+#define LLVM_IS_FINAL(Ty) __is_final(Ty)
+#endif
+#endif
+
+#ifdef WPI_DEFINED_HAS_FEATURE
+#undef __has_feature
+#undef WPI_DEFINED_HAS_FEATURE
+#endif
+
+#endif // LLVM_SUPPORT_TYPE_TRAITS_H
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Async.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Async.h
new file mode 100644
index 0000000..3ea3e5d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Async.h
@@ -0,0 +1,168 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_ASYNC_H_
+#define WPIUTIL_WPI_UV_ASYNC_H_
+
+#include <uv.h>
+
+#include <memory>
+#include <thread>
+#include <tuple>
+#include <utility>
+#include <vector>
+
+#include "wpi/STLExtras.h"
+#include "wpi/Signal.h"
+#include "wpi/mutex.h"
+#include "wpi/uv/Handle.h"
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+/**
+ * Async handle.
+ * Async handles allow the user to "wakeup" the event loop and have a signal
+ * generated from another thread.
+ *
+ * Data may be passed into the callback called on the event loop by using
+ * template parameters.  If data parameters are used, the async callback will
+ * be called once for every call to Send().  If no data parameters are used,
+ * the async callback may or may not be called for every call to Send() (e.g.
+ * the calls may be coaleasced).
+ */
+template <typename... T>
+class Async final : public HandleImpl<Async<T...>, uv_async_t> {
+  struct private_init {};
+
+ public:
+  Async(const std::shared_ptr<Loop>& loop, const private_init&)
+      : m_loop{loop} {}
+  ~Async() noexcept override {
+    if (auto loop = m_loop.lock())
+      this->Close();
+    else
+      this->ForceClosed();
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Async> Create(Loop& loop) {
+    return Create(loop.shared_from_this());
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Async> Create(const std::shared_ptr<Loop>& loop) {
+    auto h = std::make_shared<Async>(loop, private_init{});
+    int err =
+        uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
+          auto& h = *static_cast<Async*>(handle->data);
+          std::lock_guard<wpi::mutex> lock(h.m_mutex);
+          for (auto&& v : h.m_data) apply_tuple(h.wakeup, v);
+          h.m_data.clear();
+        });
+    if (err < 0) {
+      loop->ReportError(err);
+      return nullptr;
+    }
+    h->Keep();
+    return h;
+  }
+
+  /**
+   * Wakeup the event loop and emit the event.
+   *
+   * It’s safe to call this function from any thread including the loop thread.
+   * An async event will be emitted on the loop thread.
+   */
+  template <typename... U>
+  void Send(U&&... u) {
+    auto loop = m_loop.lock();
+    if (loop && loop->GetThreadId() == std::this_thread::get_id()) {
+      // called from within the loop, just call the function directly
+      wakeup(std::forward<U>(u)...);
+      return;
+    }
+
+    {
+      std::lock_guard<wpi::mutex> lock(m_mutex);
+      m_data.emplace_back(std::forward_as_tuple(std::forward<U>(u)...));
+    }
+    if (loop) this->Invoke(&uv_async_send, this->GetRaw());
+  }
+
+  /**
+   * Signal generated (on event loop thread) when the async event occurs.
+   */
+  sig::Signal<T...> wakeup;
+
+ private:
+  wpi::mutex m_mutex;
+  std::vector<std::tuple<T...>> m_data;
+  std::weak_ptr<Loop> m_loop;
+};
+
+/**
+ * Async specialization for no data parameters.  The async callback may or may
+ * not be called for every call to Send() (e.g. the calls may be coaleasced).
+ */
+template <>
+class Async<> final : public HandleImpl<Async<>, uv_async_t> {
+  struct private_init {};
+
+ public:
+  Async(const std::shared_ptr<Loop>& loop, const private_init&)
+      : m_loop(loop) {}
+  ~Async() noexcept override;
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Async> Create(Loop& loop) {
+    return Create(loop.shared_from_this());
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Async> Create(const std::shared_ptr<Loop>& loop);
+
+  /**
+   * Wakeup the event loop and emit the event.
+   *
+   * It’s safe to call this function from any thread.
+   * An async event will be emitted on the loop thread.
+   */
+  void Send() {
+    if (auto loop = m_loop.lock()) Invoke(&uv_async_send, GetRaw());
+  }
+
+  /**
+   * Signal generated (on event loop thread) when the async event occurs.
+   */
+  sig::Signal<> wakeup;
+
+ private:
+  std::weak_ptr<Loop> m_loop;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_ASYNC_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/AsyncFunction.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/AsyncFunction.h
new file mode 100644
index 0000000..6430856
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/AsyncFunction.h
@@ -0,0 +1,169 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_ASYNCFUNCTION_H_
+#define WPIUTIL_WPI_UV_ASYNCFUNCTION_H_
+
+#include <stdint.h>
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <thread>
+#include <tuple>
+#include <utility>
+#include <vector>
+
+#include "wpi/STLExtras.h"
+#include "wpi/future.h"
+#include "wpi/mutex.h"
+#include "wpi/uv/Handle.h"
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+template <typename T>
+class AsyncFunction;
+
+/**
+ * Function async handle.
+ * Async handles allow the user to "wakeup" the event loop and have a function
+ * called from another thread that returns a result to the calling thread.
+ */
+template <typename R, typename... T>
+class AsyncFunction<R(T...)> final
+    : public HandleImpl<AsyncFunction<R(T...)>, uv_async_t> {
+  struct private_init {};
+
+ public:
+  AsyncFunction(const std::shared_ptr<Loop>& loop,
+                std::function<void(promise<R>, T...)> func, const private_init&)
+      : wakeup{func}, m_loop{loop} {}
+  ~AsyncFunction() noexcept override {
+    if (auto loop = m_loop.lock())
+      this->Close();
+    else
+      this->ForceClosed();
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param func wakeup function to be called (sets wakeup value); the function
+   *             needs to return void, and its first parameter is the promise
+   *             for the result.  If no value is set on the promise by the
+   *             wakeup function, a default-constructed value is "returned".
+   */
+  static std::shared_ptr<AsyncFunction> Create(
+      Loop& loop, std::function<void(promise<R>, T...)> func = nullptr) {
+    return Create(loop.shared_from_this(), std::move(func));
+  }
+
+  /**
+   * Create an async handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param func wakeup function to be called (sets wakeup value); the function
+   *             needs to return void, and its first parameter is the promise
+   *             for the result.  If no value is set on the promise by the
+   *             wakeup function, a default-constructed value is "returned".
+   */
+  static std::shared_ptr<AsyncFunction> Create(
+      const std::shared_ptr<Loop>& loop,
+      std::function<void(promise<R>, T...)> func = nullptr) {
+    auto h =
+        std::make_shared<AsyncFunction>(loop, std::move(func), private_init{});
+    int err =
+        uv_async_init(loop->GetRaw(), h->GetRaw(), [](uv_async_t* handle) {
+          auto& h = *static_cast<AsyncFunction*>(handle->data);
+          std::unique_lock<wpi::mutex> lock(h.m_mutex);
+
+          if (!h.m_params.empty()) {
+            // for each set of parameters in the input queue, call the wakeup
+            // function and put the result in the output queue if the caller is
+            // waiting for it
+            for (auto&& v : h.m_params) {
+              auto p = h.m_promises.CreatePromise(v.first);
+              if (h.wakeup)
+                apply_tuple(h.wakeup,
+                            std::tuple_cat(std::make_tuple(std::move(p)),
+                                           std::move(v.second)));
+            }
+            h.m_params.clear();
+            // wake up any threads that might be waiting for the result
+            lock.unlock();
+            h.m_promises.Notify();
+          }
+        });
+    if (err < 0) {
+      loop->ReportError(err);
+      return nullptr;
+    }
+    h->Keep();
+    return h;
+  }
+
+  /**
+   * Wakeup the event loop, call the async function, and return a future for
+   * the result.
+   *
+   * It’s safe to call this function from any thread including the loop thread.
+   * The async function will be called on the loop thread.
+   *
+   * The future will return a default-constructed result if this handle is
+   * destroyed while waiting for a result.
+   */
+  template <typename... U>
+  future<R> Call(U&&... u) {
+    // create the future
+    uint64_t req = m_promises.CreateRequest();
+
+    auto loop = m_loop.lock();
+    if (loop && loop->GetThreadId() == std::this_thread::get_id()) {
+      // called from within the loop, just call the function directly
+      wakeup(m_promises.CreatePromise(req), std::forward<U>(u)...);
+      return m_promises.CreateFuture(req);
+    }
+
+    // add the parameters to the input queue
+    {
+      std::lock_guard<wpi::mutex> lock(m_mutex);
+      m_params.emplace_back(std::piecewise_construct,
+                            std::forward_as_tuple(req),
+                            std::forward_as_tuple(std::forward<U>(u)...));
+    }
+
+    // signal the loop
+    if (loop) this->Invoke(&uv_async_send, this->GetRaw());
+
+    // return future
+    return m_promises.CreateFuture(req);
+  }
+
+  template <typename... U>
+  future<R> operator()(U&&... u) {
+    return Call(std::forward<U>(u)...);
+  }
+
+  /**
+   * Function called (on event loop thread) when the async is called.
+   */
+  std::function<void(promise<R>, T...)> wakeup;
+
+ private:
+  wpi::mutex m_mutex;
+  std::vector<std::pair<uint64_t, std::tuple<T...>>> m_params;
+  PromiseFactory<R> m_promises;
+  std::weak_ptr<Loop> m_loop;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_ASYNCFUNCTION_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Buffer.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Buffer.h
new file mode 100644
index 0000000..b500c0f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Buffer.h
@@ -0,0 +1,158 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_BUFFER_H_
+#define WPIUTIL_WPI_UV_BUFFER_H_
+
+#include <uv.h>
+
+#include <cstring>
+#include <initializer_list>
+#include <utility>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/SmallVector.h"
+#include "wpi/StringRef.h"
+
+namespace wpi {
+namespace uv {
+
+/**
+ * Data buffer.  Convenience wrapper around uv_buf_t.
+ */
+class Buffer : public uv_buf_t {
+ public:
+  Buffer() {
+    base = nullptr;
+    len = 0;
+  }
+  /*implicit*/ Buffer(const uv_buf_t& oth) {  // NOLINT(runtime/explicit)
+    base = oth.base;
+    len = oth.len;
+  }
+  /*implicit*/ Buffer(StringRef str)  // NOLINT(runtime/explicit)
+      : Buffer{str.data(), str.size()} {}
+  /*implicit*/ Buffer(ArrayRef<uint8_t> arr)  // NOLINT(runtime/explicit)
+      : Buffer{reinterpret_cast<const char*>(arr.data()), arr.size()} {}
+  Buffer(char* base_, size_t len_) {
+    base = base_;
+    len = len_;
+  }
+  Buffer(const char* base_, size_t len_) {
+    base = const_cast<char*>(base_);
+    len = len_;
+  }
+
+  ArrayRef<char> data() const { return ArrayRef<char>{base, len}; }
+  MutableArrayRef<char> data() { return MutableArrayRef<char>{base, len}; }
+
+  operator ArrayRef<char>() const { return data(); }
+  operator MutableArrayRef<char>() { return data(); }
+
+  static Buffer Allocate(size_t size) { return Buffer{new char[size], size}; }
+
+  static Buffer Dup(StringRef in) {
+    Buffer buf = Allocate(in.size());
+    std::memcpy(buf.base, in.data(), in.size());
+    return buf;
+  }
+
+  static Buffer Dup(ArrayRef<uint8_t> in) {
+    Buffer buf = Allocate(in.size());
+    std::memcpy(buf.base, in.begin(), in.size());
+    return buf;
+  }
+
+  Buffer Dup() const {
+    Buffer buf = Allocate(len);
+    std::memcpy(buf.base, base, len);
+    return buf;
+  }
+
+  void Deallocate() {
+    delete[] base;
+    base = nullptr;
+    len = 0;
+  }
+
+  Buffer Move() {
+    Buffer buf = *this;
+    base = nullptr;
+    len = 0;
+    return buf;
+  }
+
+  friend void swap(Buffer& a, Buffer& b) {
+    using std::swap;
+    swap(a.base, b.base);
+    swap(a.len, b.len);
+  }
+};
+
+/**
+ * A simple pool allocator for Buffers.
+ * Buffers are allocated individually but are reused rather than returned
+ * to the heap.
+ * @tparam DEPTH depth of pool
+ */
+template <size_t DEPTH = 4>
+class SimpleBufferPool {
+ public:
+  /**
+   * Constructor.
+   * @param size Size of each buffer to allocate.
+   */
+  explicit SimpleBufferPool(size_t size = 4096) : m_size{size} {}
+
+  /**
+   * Allocate a buffer.
+   */
+  Buffer Allocate() {
+    if (m_pool.empty()) return Buffer::Allocate(m_size);
+    auto buf = m_pool.back();
+    m_pool.pop_back();
+    buf.len = m_size;
+    return buf;
+  }
+
+  /**
+   * Allocate a buffer.
+   */
+  Buffer operator()() { return Allocate(); }
+
+  /**
+   * Release allocated buffers back into the pool.
+   * This is NOT safe to use with arbitrary buffers unless they were
+   * allocated with the same size as the buffer pool allocation size.
+   */
+  void Release(MutableArrayRef<Buffer> bufs) {
+    for (auto& buf : bufs) m_pool.emplace_back(buf.Move());
+  }
+
+  /**
+   * Clear the pool, releasing all buffers.
+   */
+  void Clear() {
+    for (auto& buf : m_pool) buf.Deallocate();
+    m_pool.clear();
+  }
+
+  /**
+   * Get number of buffers left in the pool before a new buffer will be
+   * allocated from the heap.
+   */
+  size_t Remaining() const { return m_pool.size(); }
+
+ private:
+  SmallVector<Buffer, DEPTH> m_pool;
+  size_t m_size;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_BUFFER_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Check.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Check.h
new file mode 100644
index 0000000..e64a9f0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Check.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_CHECK_H_
+#define WPIUTIL_WPI_UV_CHECK_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Handle.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * Check handle.
+ * Check handles will generate a signal once per loop iteration, right
+ * after polling for I/O.
+ */
+class Check final : public HandleImpl<Check, uv_check_t> {
+  struct private_init {};
+
+ public:
+  explicit Check(const private_init&) {}
+  ~Check() noexcept override = default;
+
+  /**
+   * Create a check handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Check> Create(Loop& loop);
+
+  /**
+   * Create a check handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Check> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start the handle.
+   */
+  void Start();
+
+  /**
+   * Stop the handle.  The signal will no longer be generated.
+   */
+  void Stop() { Invoke(&uv_check_stop, GetRaw()); }
+
+  /**
+   * Signal generated once per loop iteration after polling for I/O.
+   */
+  sig::Signal<> check;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_CHECK_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Error.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Error.h
new file mode 100644
index 0000000..07a0ab8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Error.h
@@ -0,0 +1,51 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_ERROR_H_
+#define WPIUTIL_WPI_UV_ERROR_H_
+
+#include <uv.h>
+
+namespace wpi {
+namespace uv {
+
+/**
+ * Error code.
+ */
+class Error {
+ public:
+  Error() : m_err(UV_UNKNOWN) {}
+  explicit Error(int err) : m_err(err) {}
+
+  /**
+   * Boolean conversion.  Returns true if error, false if ok.
+   */
+  explicit operator bool() const { return m_err < 0; }
+
+  /**
+   * Returns the error code.
+   */
+  int code() const { return m_err; }
+
+  /**
+   * Returns the error message.
+   */
+  const char* str() const { return uv_strerror(m_err); }
+
+  /**
+   * Returns the error name.
+   */
+  const char* name() const { return uv_err_name(m_err); }
+
+ private:
+  int m_err;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_ERROR_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/FsEvent.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/FsEvent.h
new file mode 100644
index 0000000..cf91848
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/FsEvent.h
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_FSEVENT_H_
+#define WPIUTIL_WPI_UV_FSEVENT_H_
+
+#include <uv.h>
+
+#include <memory>
+#include <string>
+
+#include "wpi/Signal.h"
+#include "wpi/Twine.h"
+#include "wpi/uv/Handle.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * Filesystem Event handle.
+ */
+class FsEvent final : public HandleImpl<FsEvent, uv_fs_event_t> {
+  struct private_init {};
+
+ public:
+  explicit FsEvent(const private_init&) {}
+  ~FsEvent() noexcept override = default;
+
+  /**
+   * Create a filesystem event handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<FsEvent> Create(Loop& loop);
+
+  /**
+   * Create a filesystem event handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<FsEvent> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start watching the specified path for changes.
+   *
+   * @param path Path to watch for changes
+   * @param events Bitmask of event flags.  Only UV_FS_EVENT_RECURSIVE is
+   *               supported (and only on OSX and Windows).
+   */
+  void Start(const Twine& path, unsigned int flags = 0);
+
+  /**
+   * Stop watching for changes.
+   */
+  void Stop() { Invoke(&uv_fs_event_stop, GetRaw()); }
+
+  /**
+   * Get the path being monitored.  Signals error and returns empty string if
+   * an error occurs.
+   * @return Monitored path.
+   */
+  std::string GetPath();
+
+  /**
+   * Signal generated when a filesystem change occurs.  The first parameter
+   * is the filename (if a directory was passed to Start(), the filename is
+   * relative to that directory).  The second parameter is an ORed mask of
+   * UV_RENAME and UV_CHANGE.
+   */
+  sig::Signal<const char*, int> fsEvent;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_FSEVENT_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/GetAddrInfo.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/GetAddrInfo.h
new file mode 100644
index 0000000..deb4a24
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/GetAddrInfo.h
@@ -0,0 +1,125 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_GETADDRINFO_H_
+#define WPIUTIL_WPI_UV_GETADDRINFO_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/Twine.h"
+#include "wpi/uv/Request.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * GetAddrInfo request.
+ * For use with `GetAddrInfo()` function family.
+ */
+class GetAddrInfoReq : public RequestImpl<GetAddrInfoReq, uv_getaddrinfo_t> {
+ public:
+  GetAddrInfoReq();
+
+  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
+
+  /**
+   * Resolved lookup signal.
+   * Parameter is resolved address info.
+   */
+  sig::Signal<const addrinfo&> resolved;
+};
+
+/**
+ * Asynchronous getaddrinfo(3).  HandleResolvedAddress() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * Either node or service may be null (`Twine::createNull()`) but not both.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param node Either a numerical network address or a network hostname.
+ * @param service Either a service name or a port number as a string.
+ * @param hints Optional `addrinfo` data structure with additional address
+ *              type constraints.
+ */
+void GetAddrInfo(Loop& loop, const std::shared_ptr<GetAddrInfoReq>& req,
+                 const Twine& node, const Twine& service = Twine::createNull(),
+                 const addrinfo* hints = nullptr);
+
+/**
+ * Asynchronous getaddrinfo(3).  HandleResolvedAddress() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * Either node or service may be null (`Twine::createNull()`) but not both.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param node Either a numerical network address or a network hostname.
+ * @param service Either a service name or a port number as a string.
+ * @param hints Optional `addrinfo` data structure with additional address
+ *              type constraints.
+ */
+inline void GetAddrInfo(const std::shared_ptr<Loop>& loop,
+                        const std::shared_ptr<GetAddrInfoReq>& req,
+                        const Twine& node,
+                        const Twine& service = Twine::createNull(),
+                        const addrinfo* hints = nullptr) {
+  GetAddrInfo(*loop, req, node, service, hints);
+}
+
+/**
+ * Asynchronous getaddrinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * Either node or service may be null (`Twine::createNull()`) but not both.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param node Either a numerical network address or a network hostname.
+ * @param service Either a service name or a port number as a string.
+ * @param hints Optional `addrinfo` data structure with additional address
+ *              type constraints.
+ */
+void GetAddrInfo(Loop& loop, std::function<void(const addrinfo&)> callback,
+                 const Twine& node, const Twine& service = Twine::createNull(),
+                 const addrinfo* hints = nullptr);
+
+/**
+ * Asynchronous getaddrinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * Either node or service may be null (`Twine::createNull()`) but not both.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param node Either a numerical network address or a network hostname.
+ * @param service Either a service name or a port number as a string.
+ * @param hints Optional `addrinfo` data structure with additional address
+ *              type constraints.
+ */
+inline void GetAddrInfo(const std::shared_ptr<Loop>& loop,
+                        std::function<void(const addrinfo&)> callback,
+                        const Twine& node,
+                        const Twine& service = Twine::createNull(),
+                        const addrinfo* hints = nullptr) {
+  GetAddrInfo(*loop, callback, node, service, hints);
+}
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_GETADDRINFO_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/GetNameInfo.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/GetNameInfo.h
new file mode 100644
index 0000000..d6f4d62
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/GetNameInfo.h
@@ -0,0 +1,228 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_GETNAMEINFO_H_
+#define WPIUTIL_WPI_UV_GETNAMEINFO_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/Twine.h"
+#include "wpi/uv/Request.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * GetNameInfo request.
+ * For use with `GetNameInfo()` function family.
+ */
+class GetNameInfoReq : public RequestImpl<GetNameInfoReq, uv_getnameinfo_t> {
+ public:
+  GetNameInfoReq();
+
+  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
+
+  /**
+   * Resolved lookup signal.
+   * Parameters are hostname and service.
+   */
+  sig::Signal<const char*, const char*> resolved;
+};
+
+/**
+ * Asynchronous getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                 const sockaddr& addr, int flags = 0);
+
+/**
+ * Asynchronous getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo(const std::shared_ptr<Loop>& loop,
+                        const std::shared_ptr<GetNameInfoReq>& req,
+                        const sockaddr& addr, int flags = 0) {
+  GetNameInfo(*loop, req, addr, flags);
+}
+
+/**
+ * Asynchronous getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo(Loop& loop,
+                 std::function<void(const char*, const char*)> callback,
+                 const sockaddr& addr, int flags = 0);
+
+/**
+ * Asynchronous getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ * @return Connection object for the callback
+ */
+inline void GetNameInfo(const std::shared_ptr<Loop>& loop,
+                        std::function<void(const char*, const char*)> callback,
+                        const sockaddr& addr, int flags = 0) {
+  GetNameInfo(*loop, callback, addr, flags);
+}
+
+/**
+ * Asynchronous IPv4 getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param ip A valid IPv4 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo4(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                  const Twine& ip, unsigned int port, int flags = 0);
+
+/**
+ * Asynchronous IPv4 getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param ip A valid IPv4 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo4(const std::shared_ptr<Loop>& loop,
+                         const std::shared_ptr<GetNameInfoReq>& req,
+                         const Twine& ip, unsigned int port, int flags = 0) {
+  return GetNameInfo4(*loop, req, ip, port, flags);
+}
+
+/**
+ * Asynchronous IPv4 getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param ip A valid IPv4 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo4(Loop& loop,
+                  std::function<void(const char*, const char*)> callback,
+                  const Twine& ip, unsigned int port, int flags = 0);
+
+/**
+ * Asynchronous IPv4 getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * @param loop Event loop
+ * @param ip A valid IPv4 address
+ * @param port A valid port number
+ * @param callback Callback function to call when resolution completes
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo4(const std::shared_ptr<Loop>& loop,
+                         std::function<void(const char*, const char*)> callback,
+                         const Twine& ip, unsigned int port, int flags = 0) {
+  return GetNameInfo4(*loop, callback, ip, port, flags);
+}
+
+/**
+ * Asynchronous IPv6 getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param ip A valid IPv6 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo6(Loop& loop, const std::shared_ptr<GetNameInfoReq>& req,
+                  const Twine& ip, unsigned int port, int flags = 0);
+
+/**
+ * Asynchronous IPv6 getnameinfo(3).  HandleResolvedName() is called on the
+ * request when the resolution completes.  HandleError() is called on the
+ * request if any errors occur.
+ *
+ * @param loop Event loop
+ * @param req request
+ * @param ip A valid IPv6 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo6(const std::shared_ptr<Loop>& loop,
+                         const std::shared_ptr<GetNameInfoReq>& req,
+                         const Twine& ip, unsigned int port, int flags = 0) {
+  GetNameInfo6(*loop, req, ip, port, flags);
+}
+
+/**
+ * Asynchronous IPv6 getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param ip A valid IPv6 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+void GetNameInfo6(Loop& loop,
+                  std::function<void(const char*, const char*)> callback,
+                  const Twine& ip, unsigned int port, int flags = 0);
+
+/**
+ * Asynchronous IPv6 getnameinfo(3).  The callback is called when the resolution
+ * completes, and errors are forwarded to the loop.  This is a convenience
+ * wrapper.
+ *
+ * @param loop Event loop
+ * @param callback Callback function to call when resolution completes
+ * @param ip A valid IPv6 address
+ * @param port A valid port number
+ * @param flags Optional flags to modify the behavior of `getnameinfo`.
+ */
+inline void GetNameInfo6(const std::shared_ptr<Loop>& loop,
+                         std::function<void(const char*, const char*)> callback,
+                         const Twine& ip, unsigned int port, int flags = 0) {
+  return GetNameInfo6(*loop, callback, ip, port, flags);
+}
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_GETNAMEINFO_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Handle.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Handle.h
new file mode 100644
index 0000000..046c155
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Handle.h
@@ -0,0 +1,275 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_HANDLE_H_
+#define WPIUTIL_WPI_UV_HANDLE_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <utility>
+
+#include "wpi/Signal.h"
+#include "wpi/StringRef.h"
+#include "wpi/uv/Buffer.h"
+#include "wpi/uv/Error.h"
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+/**
+ * Handle.
+ * Handles are not moveable or copyable and cannot be directly constructed.
+ * This class provides shared_ptr ownership and shared_from_this.
+ * Use the specific handle type Create() functions to create handles.
+ */
+class Handle : public std::enable_shared_from_this<Handle> {
+ public:
+  using Type = uv_handle_type;
+
+  Handle(const Handle&) = delete;
+  Handle(Handle&&) = delete;
+  Handle& operator=(const Handle&) = delete;
+  Handle& operator=(Handle&&) = delete;
+  virtual ~Handle() noexcept;
+
+  /**
+   * Get the type of the handle.
+   *
+   * A base handle offers no functionality to promote it to the actual handle
+   * type. By means of this function, the type of the underlying handle as
+   * specified by Type is made available.
+   *
+   * @return The actual type of the handle.
+   */
+  Type GetType() const noexcept { return m_uv_handle->type; }
+
+  /**
+   * Get the name of the type of the handle.  E.g. "pipe" for pipe handles.
+   */
+  StringRef GetTypeName() const noexcept {
+    return uv_handle_type_name(m_uv_handle->type);
+  }
+
+  /**
+   * Get the loop where this handle runs.
+   *
+   * @return The loop.
+   */
+  std::shared_ptr<Loop> GetLoop() const noexcept {
+    return GetLoopRef().shared_from_this();
+  }
+
+  /**
+   * Get the loop where this handle runs.
+   *
+   * @return The loop.
+   */
+  Loop& GetLoopRef() const noexcept {
+    return *static_cast<Loop*>(m_uv_handle->loop->data);
+  }
+
+  /**
+   * Check if the handle is active.
+   *
+   * What _active_ means depends on the type of handle:
+   *
+   * * An AsyncHandle handle is always active and cannot be deactivated,
+   * except by closing it with uv_close().
+   * * A PipeHandle, TcpHandle, UDPHandle, etc. handle - basically any handle
+   * that deals with I/O - is active when it is doing something that involves
+   * I/O, like reading, writing, connecting, accepting new connections, etc.
+   * * A CheckHandle, IdleHandle, TimerHandle, etc. handle is active when it
+   * has been started with a call to `Start()`.
+   *
+   * Rule of thumb: if a handle of type `FooHandle` has a `Start()` member
+   * method, then it’s active from the moment that method is called. Likewise,
+   * `Stop()` deactivates the handle again.
+   *
+   * @return True if the handle is active, false otherwise.
+   */
+  bool IsActive() const noexcept { return uv_is_active(m_uv_handle) != 0; }
+
+  /**
+   * Check if a handle is closing or closed.
+   *
+   * This function should only be used between the initialization of the
+   * handle and the arrival of the close callback.
+   *
+   * @return True if the handle is closing or closed, false otherwise.
+   */
+  bool IsClosing() const noexcept {
+    return m_closed || uv_is_closing(m_uv_handle) != 0;
+  }
+
+  /**
+   * Request handle to be closed.
+   *
+   * This **must** be called on each handle before memory is released.
+   * In-progress requests are cancelled and this can result in error() being
+   * emitted.
+   *
+   * The handle will emit closed() when finished.
+   */
+  void Close() noexcept;
+
+  /**
+   * Reference the given handle.
+   *
+   * References are idempotent, that is, if a handle is already referenced
+   * calling this function again will have no effect.
+   */
+  void Reference() noexcept { uv_ref(m_uv_handle); }
+
+  /**
+   * Unreference the given handle.
+   *
+   * References are idempotent, that is, if a handle is not referenced calling
+   * this function again will have no effect.
+   */
+  void Unreference() noexcept { uv_unref(m_uv_handle); }
+
+  /**
+   * Check if the given handle is referenced.
+   * @return True if the handle is referenced, false otherwise.
+   */
+  bool HasReference() const noexcept { return uv_has_ref(m_uv_handle) != 0; }
+
+  /**
+   * Return the size of the underlying handle type.
+   * @return The size of the underlying handle type.
+   */
+  size_t RawSize() const noexcept { return uv_handle_size(m_uv_handle->type); }
+
+  /**
+   * Get the underlying handle data structure.
+   *
+   * @return The underlying handle data structure.
+   */
+  uv_handle_t* GetRawHandle() const noexcept { return m_uv_handle; }
+
+  /**
+   * Set the functions used for allocating and releasing buffers.  The size
+   * passed to the allocator function is a "suggested" size--it's just an
+   * indication, not related in any way to the pending data to be read.  The
+   * user is free to allocate the amount of memory they decide.  For example,
+   * applications with custom allocation schemes may decide to use a different
+   * size which matches the memory chunks they already have for other purposes.
+   *
+   * @warning Be very careful changing the allocator after the loop has started
+   * running; there are no interlocks between this and buffers currently in
+   * flight.
+   *
+   * @param alloc Allocation function
+   * @param dealloc Deallocation function
+   */
+  void SetBufferAllocator(std::function<Buffer(size_t)> alloc,
+                          std::function<void(Buffer&)> dealloc) {
+    m_allocBuf = alloc;
+    m_freeBuf = dealloc;
+  }
+
+  /**
+   * Free a buffer.  Uses the function provided to SetBufFree() or
+   * Buffer::Deallocate by default.
+   *
+   * @param buf The buffer
+   */
+  void FreeBuf(Buffer& buf) const noexcept { m_freeBuf(buf); }
+
+  /**
+   * Gets user-defined data.
+   * @return User-defined data if any, nullptr otherwise.
+   */
+  template <typename T = void>
+  std::shared_ptr<T> GetData() const {
+    return std::static_pointer_cast<T>(m_data);
+  }
+
+  /**
+   * Sets user-defined data.
+   * @param data User-defined arbitrary data.
+   */
+  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
+
+  /**
+   * Error signal
+   */
+  sig::Signal<Error> error;
+
+  /**
+   * Closed signal
+   */
+  sig::Signal<> closed;
+
+  /**
+   * Report an error.
+   * @param err Error code
+   */
+  void ReportError(int err) { error(Error(err)); }
+
+ protected:
+  explicit Handle(uv_handle_t* uv_handle) : m_uv_handle{uv_handle} {
+    m_uv_handle->data = this;
+  }
+
+  void Keep() noexcept { m_self = shared_from_this(); }
+  void Release() noexcept { m_self.reset(); }
+  void ForceClosed() noexcept { m_closed = true; }
+
+  static void AllocBuf(uv_handle_t* handle, size_t size, uv_buf_t* buf);
+  static void DefaultFreeBuf(Buffer& buf);
+
+  template <typename F, typename... Args>
+  bool Invoke(F&& f, Args&&... args) {
+    auto err = std::forward<F>(f)(std::forward<Args>(args)...);
+    if (err < 0) ReportError(err);
+    return err == 0;
+  }
+
+ private:
+  std::shared_ptr<Handle> m_self;
+  uv_handle_t* m_uv_handle;
+  bool m_closed = false;
+  std::function<Buffer(size_t)> m_allocBuf{&Buffer::Allocate};
+  std::function<void(Buffer&)> m_freeBuf{&DefaultFreeBuf};
+  std::shared_ptr<void> m_data;
+};
+
+/**
+ * Handle.
+ */
+template <typename T, typename U>
+class HandleImpl : public Handle {
+ public:
+  std::shared_ptr<T> shared_from_this() {
+    return std::static_pointer_cast<T>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const T> shared_from_this() const {
+    return std::static_pointer_cast<const T>(Handle::shared_from_this());
+  }
+
+  /**
+   * Get the underlying handle data structure.
+   *
+   * @return The underlying handle data structure.
+   */
+  U* GetRaw() const noexcept {
+    return reinterpret_cast<U*>(this->GetRawHandle());
+  }
+
+ protected:
+  HandleImpl() : Handle{reinterpret_cast<uv_handle_t*>(new U)} {}
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_HANDLE_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Idle.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Idle.h
new file mode 100644
index 0000000..e8278b2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Idle.h
@@ -0,0 +1,79 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_IDLE_H_
+#define WPIUTIL_WPI_UV_IDLE_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Handle.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * Idle handle.
+ *
+ * Idle handles will generate a signal once per loop iteration, right
+ * before the Prepare handles.
+ *
+ * The notable difference with Prepare handles is that when there are active
+ * idle handles, the loop will perform a zero timeout poll instead of blocking
+ * for I/O.
+ *
+ * @warning Despite the name, idle handles will signal every loop iteration,
+ * not when the loop is actually "idle".  This also means they can easly become
+ * CPU hogs.
+ */
+class Idle final : public HandleImpl<Idle, uv_idle_t> {
+  struct private_init {};
+
+ public:
+  explicit Idle(const private_init&) {}
+  ~Idle() noexcept override = default;
+
+  /**
+   * Create an idle handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Idle> Create(Loop& loop);
+
+  /**
+   * Create an idle handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Idle> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start the handle.
+   */
+  void Start();
+
+  /**
+   * Stop the handle.  The signal will no longer be generated.
+   */
+  void Stop() { Invoke(&uv_idle_stop, GetRaw()); }
+
+  /**
+   * Signal generated once per loop iteration prior to Prepare signals.
+   */
+  sig::Signal<> idle;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_IDLE_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Loop.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Loop.h
new file mode 100644
index 0000000..2b3b27f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Loop.h
@@ -0,0 +1,257 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_LOOP_H_
+#define WPIUTIL_WPI_UV_LOOP_H_
+
+#include <uv.h>
+
+#include <atomic>
+#include <chrono>
+#include <functional>
+#include <memory>
+#include <thread>
+#include <utility>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Error.h"
+
+namespace wpi {
+namespace uv {
+
+class Handle;
+
+/**
+ * Event loop.
+ *
+ * The event loop is the central part of uv functionality.  It takes care of
+ * polling for I/O and scheduling signals to be generated based on different
+ * sources of events.
+ *
+ * The event loop is not moveable, copyable, or directly constructible.  Use
+ * Create() to create an event loop, or GetDefault() to get the default loop
+ * if you know your program will only have a single one.
+ */
+class Loop final : public std::enable_shared_from_this<Loop> {
+  struct private_init {};
+
+ public:
+  using Time = std::chrono::duration<uint64_t, std::milli>;
+
+  enum Mode {
+    kDefault = UV_RUN_DEFAULT,
+    kOnce = UV_RUN_ONCE,
+    kNoWait = UV_RUN_NOWAIT
+  };
+
+  explicit Loop(const private_init&) noexcept;
+
+  Loop(const Loop&) = delete;
+  Loop& operator=(const Loop&) = delete;
+  Loop(Loop&& oth) = delete;
+  Loop& operator=(Loop&& oth) = delete;
+
+  ~Loop() noexcept;
+
+  /**
+   * Create a new event loop.  The created loop is not the default event loop.
+   *
+   * @return The newly created loop.  May return nullptr if a failure occurs.
+   */
+  static std::shared_ptr<Loop> Create();
+
+  /**
+   * Create the default event loop.  Only use this event loop if a single loop
+   * is needed for the entire application.
+   *
+   * @return The newly created loop.  May return nullptr if a failure occurs.
+   */
+  static std::shared_ptr<Loop> GetDefault();
+
+  /**
+   * Release all internal loop resources.
+   *
+   * Call this function only when the loop has finished executing and all open
+   * handles and requests have been closed, or the loop will emit an error.
+   *
+   * error() will be emitted in case of errors.
+   */
+  void Close();
+
+  /**
+   * Run the event loop.
+   *
+   * Available modes are:
+   *
+   * * `Loop::kDefault`: Run the event loop until there are no
+   *                     active and referenced handles or requests.
+   * * `Loop::kOnce`: Run a single event loop iteration. Note that this
+   *                  function blocksif there are no pending callbacks.
+   * * `Loop::kNoWait`: Run a single event loop iteration, but don't block
+   *                    if there are no pending callbacks.
+   *
+   * @return True when done, false in all other cases.
+   */
+  bool Run(Mode mode = kDefault) {
+    m_tid = std::this_thread::get_id();
+    int rv = uv_run(m_loop, static_cast<uv_run_mode>(static_cast<int>(mode)));
+    m_tid = std::thread::id{};
+    return rv == 0;
+  }
+
+  /**
+   * Check if there are active resources.
+   *
+   * @return True if there are active resources in the loop.
+   */
+  bool IsAlive() const noexcept { return uv_loop_alive(m_loop) != 0; }
+
+  /**
+   * Stop the event loop.
+   *
+   * This will cause Run() to end as soon as possible.
+   * This will happen not sooner than the next loop iteration.
+   * If this function was called before blocking for I/O, the loop won’t block
+   * for I/O on this iteration.
+   */
+  void Stop() noexcept { uv_stop(m_loop); }
+
+  /**
+   * Get backend file descriptor.
+   *
+   * Only kqueue, epoll and event ports are supported.
+   * This can be used in conjunction with `run(Loop::kNoWait)` to poll
+   * in one thread and run the event loop’s callbacks in another.
+   *
+   * @return The backend file descriptor.
+   */
+  int GetDescriptor() const noexcept { return uv_backend_fd(m_loop); }
+
+  /**
+   * Get the poll timeout.
+   *
+   * @return A `std::pair` composed of a boolean value that is true in case of
+   * valid timeout, false otherwise, and the timeout
+   * (`std::chrono::duration<uint64_t, std::milli>`).
+   */
+  std::pair<bool, Time> GetTimeout() const noexcept {
+    auto to = uv_backend_timeout(m_loop);
+    return std::make_pair(to == -1, Time{to});
+  }
+
+  /**
+   * Return the current timestamp in milliseconds.
+   *
+   * The timestamp is cached at the start of the event loop tick.
+   * The timestamp increases monotonically from some arbitrary point in
+   * time.
+   * Don’t make assumptions about the starting point, you will only get
+   * disappointed.
+   *
+   * @return The current timestamp in milliseconds (actual type is
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  Time Now() const noexcept { return Time{uv_now(m_loop)}; }
+
+  /**
+   * Update the event loop’s concept of _now_.
+   *
+   * The current time is cached at the start of the event loop tick in order
+   * to reduce the number of time-related system calls.
+   * You won’t normally need to call this function unless you have callbacks
+   * that block the event loop for longer periods of time, where _longer_ is
+   * somewhat subjective but probably on the order of a millisecond or more.
+   */
+  void UpdateTime() noexcept { uv_update_time(m_loop); }
+
+  /**
+   * Walk the list of handles.
+   *
+   * The callback will be executed once for each handle that is still active.
+   *
+   * @param callback A function to be invoked once for each active handle.
+   */
+  void Walk(std::function<void(Handle&)> callback);
+
+  /**
+   * Reinitialize any kernel state necessary in the child process after
+   * a fork(2) system call.
+   *
+   * Previously started watchers will continue to be started in the child
+   * process.
+   *
+   * It is necessary to explicitly call this function on every event loop
+   * created in the parent process that you plan to continue to use in the
+   * child, including the default loop (even if you don’t continue to use it
+   * in the parent). This function must be called before calling any API
+   * function using the loop in the child. Failure to do so will result in
+   * undefined behaviour, possibly including duplicate events delivered to
+   * both parent and child or aborting the child process.
+   *
+   * When possible, it is preferred to create a new loop in the child process
+   * instead of reusing a loop created in the parent. New loops created in the
+   * child process after the fork should not use this function.
+   *
+   * Note that this function is not implemented on Windows.
+   * Note also that this function is experimental in `libuv`. It may contain
+   * bugs, and is subject to change or removal. API and ABI stability is not
+   * guaranteed.
+   *
+   * error() will be emitted in case of errors.
+   */
+  void Fork();
+
+  /**
+   * Get the underlying event loop data structure.
+   *
+   * @return The underlying event loop data structure.
+   */
+  uv_loop_t* GetRaw() const noexcept { return m_loop; }
+
+  /**
+   * Gets user-defined data.
+   * @return User-defined data if any, nullptr otherwise.
+   */
+  template <typename T = void>
+  std::shared_ptr<T> GetData() const {
+    return std::static_pointer_cast<T>(m_data);
+  }
+
+  /**
+   * Sets user-defined data.
+   * @param data User-defined arbitrary data.
+   */
+  void SetData(std::shared_ptr<void> data) { m_data = std::move(data); }
+
+  /**
+   * Get the thread id of the loop thread.  If the loop is not currently
+   * running, returns default-constructed thread id.
+   */
+  std::thread::id GetThreadId() const { return m_tid; }
+
+  /**
+   * Error signal
+   */
+  sig::Signal<Error> error;
+
+  /**
+   * Reports error.
+   * @param err Error code
+   */
+  void ReportError(int err) { error(Error(err)); }
+
+ private:
+  std::shared_ptr<void> m_data;
+  uv_loop_t* m_loop;
+  uv_loop_t m_loopStruct;
+  std::atomic<std::thread::id> m_tid;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_LOOP_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/NetworkStream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/NetworkStream.h
new file mode 100644
index 0000000..05c1c92
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/NetworkStream.h
@@ -0,0 +1,156 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_NETWORKSTREAM_H_
+#define WPIUTIL_WPI_UV_NETWORKSTREAM_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Stream.h"
+
+namespace wpi {
+namespace uv {
+
+class NetworkStream;
+
+/**
+ * Connection request.
+ */
+class ConnectReq : public RequestImpl<ConnectReq, uv_connect_t> {
+ public:
+  ConnectReq();
+
+  NetworkStream& GetStream() const {
+    return *static_cast<NetworkStream*>(GetRaw()->handle->data);
+  }
+
+  /**
+   * Connection completed signal.
+   */
+  sig::Signal<> connected;
+};
+
+/**
+ * Network stream handle.
+ * This is an abstract type; there are two network stream implementations (Tcp
+ * and Pipe).
+ */
+class NetworkStream : public Stream {
+ public:
+  static constexpr int kDefaultBacklog = 128;
+
+  std::shared_ptr<NetworkStream> shared_from_this() {
+    return std::static_pointer_cast<NetworkStream>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const NetworkStream> shared_from_this() const {
+    return std::static_pointer_cast<const NetworkStream>(
+        Handle::shared_from_this());
+  }
+
+  /**
+   * Start listening for incoming connections.  When a new incoming connection
+   * is received the connection signal is generated.
+   * @param backlog the number of connections the kernel might queue, same as
+   *        listen(2).
+   */
+  void Listen(int backlog = kDefaultBacklog);
+
+  /**
+   * Start listening for incoming connections.  This is a convenience wrapper
+   * around `Listen(int)` that also connects a callback to the connection
+   * signal.  When a new incoming connection is received the connection signal
+   * is generated (and the callback is called).
+   * @param callback the callback to call when a connection is received.
+   *        `Accept()` should be called from this callback.
+   * @param backlog the number of connections the kernel might queue, same as
+   *        listen(2).
+   */
+  void Listen(std::function<void()> callback, int backlog = kDefaultBacklog);
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a ListenEvent event to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @return The stream handle for the accepted connection, or nullptr on error.
+   */
+  std::shared_ptr<NetworkStream> Accept() {
+    return DoAccept()->shared_from_this();
+  }
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a connection signal to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @param client Client stream object.
+   * @return False on error.
+   */
+  bool Accept(const std::shared_ptr<NetworkStream>& client) {
+    return Invoke(&uv_accept, GetRawStream(), client->GetRawStream());
+  }
+
+  /**
+   * Signal generated when an incoming connection is received.
+   */
+  sig::Signal<> connection;
+
+ protected:
+  explicit NetworkStream(uv_stream_t* uv_stream) : Stream{uv_stream} {}
+
+  virtual NetworkStream* DoAccept() = 0;
+};
+
+template <typename T, typename U>
+class NetworkStreamImpl : public NetworkStream {
+ public:
+  std::shared_ptr<T> shared_from_this() {
+    return std::static_pointer_cast<T>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const T> shared_from_this() const {
+    return std::static_pointer_cast<const T>(Handle::shared_from_this());
+  }
+
+  /**
+   * Get the underlying handle data structure.
+   *
+   * @return The underlying handle data structure.
+   */
+  U* GetRaw() const noexcept {
+    return reinterpret_cast<U*>(this->GetRawHandle());
+  }
+
+ protected:
+  NetworkStreamImpl() : NetworkStream{reinterpret_cast<uv_stream_t*>(new U)} {}
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_NETWORKSTREAM_H_
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
new file mode 100644
index 0000000..b4d8af2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Pipe.h
@@ -0,0 +1,194 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_PIPE_H_
+#define WPIUTIL_WPI_UV_PIPE_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+#include <string>
+
+#include "wpi/Twine.h"
+#include "wpi/uv/NetworkStream.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+class PipeConnectReq;
+
+/**
+ * Pipe handle.
+ * Pipe handles provide an abstraction over local domain sockets on Unix and
+ * named pipes on Windows.
+ */
+class Pipe final : public NetworkStreamImpl<Pipe, uv_pipe_t> {
+  struct private_init {};
+
+ public:
+  explicit Pipe(const private_init&) {}
+  ~Pipe() noexcept override = default;
+
+  /**
+   * Create a pipe handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param ipc Indicates if this pipe will be used for handle passing between
+   *            processes.
+   */
+  static std::shared_ptr<Pipe> Create(Loop& loop, bool ipc = false);
+
+  /**
+   * Create a pipe handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param ipc Indicates if this pipe will be used for handle passing between
+   *            processes.
+   */
+  static std::shared_ptr<Pipe> Create(const std::shared_ptr<Loop>& loop,
+                                      bool ipc = false) {
+    return Create(*loop, ipc);
+  }
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a ListenEvent event to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @return The stream handle for the accepted connection, or nullptr on error.
+   */
+  std::shared_ptr<Pipe> Accept();
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a connection signal to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @param client Client stream object.
+   * @return False on error.
+   */
+  bool Accept(const std::shared_ptr<Pipe>& client) {
+    return NetworkStream::Accept(client);
+  }
+
+  /**
+   * Open an existing file descriptor or HANDLE as a pipe.
+   *
+   * @note The passed file descriptor or HANDLE is not checked for its type, but
+   * it's required that it represents a valid pipe.
+   *
+   * @param file A valid file handle (either a file descriptor or a HANDLE).
+   */
+  void Open(uv_file file) { Invoke(&uv_pipe_open, GetRaw(), file); }
+
+  /**
+   * Bind the pipe to a file path (Unix) or a name (Windows).
+   *
+   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
+   * typically between 92 and 108 bytes.
+   *
+   * @param name File path (Unix) or name (Windows).
+   */
+  void Bind(const Twine& name);
+
+  /**
+   * Connect to the Unix domain socket or the named pipe.
+   *
+   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
+   * typically between 92 and 108 bytes.
+   *
+   * HandleConnected() is called on the request when the connection has been
+   * established.
+   * HandleError() is called on the request in case of errors during the
+   * connection.
+   *
+   * @param name File path (Unix) or name (Windows).
+   * @param req connection request
+   */
+  void Connect(const Twine& name, const std::shared_ptr<PipeConnectReq>& req);
+
+  /**
+   * Connect to the Unix domain socket or the named pipe.
+   *
+   * @note Paths on Unix get truncated to `sizeof(sockaddr_un.sun_path)` bytes,
+   * typically between 92 and 108 bytes.
+   *
+   * The callback is called when the connection has been established.  Errors
+   * are reported to the stream error handler.
+   *
+   * @param name File path (Unix) or name (Windows).
+   * @param callback Callback function to call when connection established
+   */
+  void Connect(const Twine& name, std::function<void()> callback);
+
+  /**
+   * Get the name of the Unix domain socket or the named pipe.
+   * @return The name (will be empty if an error occurred).
+   */
+  std::string GetSock();
+
+  /**
+   * Get the name of the Unix domain socket or the named pipe to which the
+   * handle is connected.
+   * @return The name (will be empty if an error occurred).
+   */
+  std::string GetPeer();
+
+  /**
+   * Set the number of pending pipe instance handles when the pipe server is
+   * waiting for connections.
+   * @note This setting applies to Windows only.
+   * @param count Number of pending handles.
+   */
+  void SetPendingInstances(int count) {
+    uv_pipe_pending_instances(GetRaw(), count);
+  }
+
+  /**
+   * Alters pipe permissions, allowing it to be accessed from processes run
+   * by different users.  Makes the pipe writable or readable by all users.
+   * Mode can be UV_WRITABLE, UV_READABLE, or both.  This function is blocking.
+   * @param flags chmod flags
+   */
+  void Chmod(int flags) { Invoke(&uv_pipe_chmod, GetRaw(), flags); }
+
+ private:
+  Pipe* DoAccept() override;
+};
+
+/**
+ * Pipe connection request.
+ */
+class PipeConnectReq : public ConnectReq {
+ public:
+  Pipe& GetStream() const {
+    return *static_cast<Pipe*>(&ConnectReq::GetStream());
+  }
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_PIPE_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Poll.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Poll.h
new file mode 100644
index 0000000..fad00e4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Poll.h
@@ -0,0 +1,126 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_POLL_H_
+#define WPIUTIL_WPI_UV_POLL_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Handle.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * Poll handle.
+ */
+class Poll final : public HandleImpl<Poll, uv_poll_t> {
+  struct private_init {};
+
+ public:
+  explicit Poll(const private_init&) {}
+  ~Poll() noexcept override = default;
+
+  /**
+   * Create a poll handle using a file descriptor.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param fd File descriptor.
+   */
+  static std::shared_ptr<Poll> Create(Loop& loop, int fd);
+
+  /**
+   * Create a poll handle using a file descriptor.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param fd File descriptor.
+   */
+  static std::shared_ptr<Poll> Create(const std::shared_ptr<Loop>& loop,
+                                      int fd) {
+    return Create(*loop, fd);
+  }
+
+  /**
+   * Create a poll handle using a socket descriptor.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param sock Socket descriptor.
+   */
+  static std::shared_ptr<Poll> CreateSocket(Loop& loop, uv_os_sock_t sock);
+
+  /**
+   * Create a poll handle using a socket descriptor.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param sock Socket descriptor.
+   */
+  static std::shared_ptr<Poll> CreateSocket(const std::shared_ptr<Loop>& loop,
+                                            uv_os_sock_t sock) {
+    return CreateSocket(*loop, sock);
+  }
+
+  /**
+   * 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 fd File descriptor
+   * @param callback Callback
+   */
+  void Reuse(int fd, std::function<void()> callback);
+
+  /**
+   * Reuse this handle.  This closes the handle, and after the close completes,
+   * reinitializes it (identically to CreateSocket) 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 sock Socket descriptor.
+   * @param callback Callback
+   */
+  void ReuseSocket(uv_os_sock_t sock, std::function<void()> callback);
+
+  /**
+   * Start polling the file descriptor.
+   *
+   * @param events Bitmask of events (UV_READABLE, UV_WRITEABLE, UV_PRIORITIZED,
+   *               and UV_DISCONNECT).
+   */
+  void Start(int events);
+
+  /**
+   * Stop polling the file descriptor.
+   */
+  void Stop() { Invoke(&uv_poll_stop, GetRaw()); }
+
+  /**
+   * Signal generated when a poll event occurs.
+   */
+  sig::Signal<int> pollEvent;
+
+ private:
+  struct ReuseData {
+    std::function<void()> callback;
+    bool isSocket;
+    int fd;
+    uv_os_sock_t sock;
+  };
+  std::unique_ptr<ReuseData> m_reuseData;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_POLL_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Prepare.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Prepare.h
new file mode 100644
index 0000000..600922f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Prepare.h
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_PREPARE_H_
+#define WPIUTIL_WPI_UV_PREPARE_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Handle.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * Prepare handle.
+ * Prepare handles will generate a signal once per loop iteration, right
+ * before polling for I/O.
+ */
+class Prepare final : public HandleImpl<Prepare, uv_prepare_t> {
+  struct private_init {};
+
+ public:
+  explicit Prepare(const private_init&) {}
+  ~Prepare() noexcept override = default;
+
+  /**
+   * Create a prepare handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Prepare> Create(Loop& loop);
+
+  /**
+   * Create a prepare handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Prepare> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start the handle.
+   */
+  void Start();
+
+  /**
+   * Stop the handle.  The signal will no longer be generated.
+   */
+  void Stop() { Invoke(&uv_prepare_stop, GetRaw()); }
+
+  /**
+   * Signal generated once per loop iteration prior to polling for I/O.
+   */
+  sig::Signal<> prepare;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_PREPARE_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Process.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Process.h
new file mode 100644
index 0000000..e3a2ec3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Process.h
@@ -0,0 +1,308 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_PROCESS_H_
+#define WPIUTIL_WPI_UV_PROCESS_H_
+
+#include <uv.h>
+
+#include <memory>
+#include <string>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/Signal.h"
+#include "wpi/SmallVector.h"
+#include "wpi/Twine.h"
+#include "wpi/uv/Handle.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+class Pipe;
+
+/**
+ * Process handle.
+ * Process handles will spawn a new process and allow the user to control it
+ * and establish communication channels with it using streams.
+ */
+class Process final : public HandleImpl<Process, uv_process_t> {
+  struct private_init {};
+
+ public:
+  explicit Process(const private_init&) {}
+  ~Process() noexcept override = default;
+
+  /**
+   * Structure for Spawn() option temporaries.  This is a reference type
+   * similar to StringRef, so if this value is stored outside of a temporary,
+   * be careful about overwriting what it points to.
+   */
+  struct Option {
+    enum Type {
+      kNone,
+      kArg,
+      kEnv,
+      kCwd,
+      kUid,
+      kGid,
+      kSetFlags,
+      kClearFlags,
+      kStdioIgnore,
+      kStdioInheritFd,
+      kStdioInheritPipe,
+      kStdioCreatePipe
+    };
+
+    Option() : m_type(kNone) {}
+
+    /*implicit*/ Option(const char* arg) {  // NOLINT(runtime/explicit)
+      m_data.str = arg;
+    }
+
+    /*implicit*/ Option(const std::string& arg) {  // NOLINT(runtime/explicit)
+      m_data.str = arg.data();
+    }
+
+    /*implicit*/ Option(StringRef arg)  // NOLINT(runtime/explicit)
+        : m_strData(arg) {
+      m_data.str = m_strData.c_str();
+    }
+
+    /*implicit*/ Option(
+        const SmallVectorImpl<char>& arg)  // NOLINT(runtime/explicit)
+        : m_strData(arg.data(), arg.size()) {
+      m_data.str = m_strData.c_str();
+    }
+
+    /*implicit*/ Option(const Twine& arg)  // NOLINT(runtime/explicit)
+        : m_strData(arg.str()) {
+      m_data.str = m_strData.c_str();
+    }
+
+    explicit Option(Type type) : m_type(type) {}
+
+    Type m_type = kArg;
+    std::string m_strData;
+    union {
+      const char* str;
+      uv_uid_t uid;
+      uv_gid_t gid;
+      unsigned int flags;
+      struct {
+        size_t index;
+        union {
+          int fd;
+          Pipe* pipe;
+        };
+        unsigned int flags;
+      } stdio;
+    } m_data;
+  };
+
+  /**
+   * Set environment variable for the subprocess.  If not set, the parent's
+   * environment is used.
+   * @param env environment variable
+   */
+  static Option Env(const Twine& env) {
+    Option o(Option::kEnv);
+    o.m_strData = env.str();
+    o.m_data.str = o.m_strData.c_str();
+    return o;
+  }
+
+  /**
+   * Set the current working directory for the subprocess.
+   * @param cwd current working directory
+   */
+  static Option Cwd(const Twine& cwd) {
+    Option o(Option::kCwd);
+    o.m_strData = cwd.str();
+    o.m_data.str = o.m_strData.c_str();
+    return o;
+  }
+
+  /**
+   * Set the child process' user id.
+   * @param uid user id
+   */
+  static Option Uid(uv_uid_t uid) {
+    Option o(Option::kUid);
+    o.m_data.uid = uid;
+    return o;
+  }
+
+  /**
+   * Set the child process' group id.
+   * @param gid group id
+   */
+  static Option Gid(uv_gid_t gid) {
+    Option o(Option::kGid);
+    o.m_data.gid = gid;
+    return o;
+  }
+
+  /**
+   * Set spawn flags.
+   * @param flags Bitmask values from uv_process_flags.
+   */
+  static Option SetFlags(unsigned int flags) {
+    Option o(Option::kSetFlags);
+    o.m_data.flags = flags;
+    return o;
+  }
+
+  /**
+   * Clear spawn flags.
+   * @param flags Bitmask values from uv_process_flags.
+   */
+  static Option ClearFlags(unsigned int flags) {
+    Option o(Option::kClearFlags);
+    o.m_data.flags = flags;
+    return o;
+  }
+
+  /**
+   * Explicitly ignore a stdio.
+   * @param index stdio index
+   */
+  static Option StdioIgnore(size_t index) {
+    Option o(Option::kStdioIgnore);
+    o.m_data.stdio.index = index;
+    return o;
+  }
+
+  /**
+   * Inherit a file descriptor from the parent process.
+   * @param index stdio index
+   * @param fd parent file descriptor
+   */
+  static Option StdioInherit(size_t index, int fd) {
+    Option o(Option::kStdioInheritFd);
+    o.m_data.stdio.index = index;
+    o.m_data.stdio.fd = fd;
+    return o;
+  }
+
+  /**
+   * Inherit a pipe from the parent process.
+   * @param index stdio index
+   * @param pipe pipe
+   */
+  static Option StdioInherit(size_t index, Pipe& pipe) {
+    Option o(Option::kStdioInheritPipe);
+    o.m_data.stdio.index = index;
+    o.m_data.stdio.pipe = &pipe;
+    return o;
+  }
+
+  /**
+   * Create a pipe between the child and the parent.
+   * @param index stdio index
+   * @param pipe pipe
+   * @param flags Some combination of UV_READABLE_PIPE, UV_WRITABLE_PIPE, and
+   *              UV_OVERLAPPED_PIPE (Windows only, ignored on Unix).
+   */
+  static Option StdioCreatePipe(size_t index, Pipe& pipe, unsigned int flags) {
+    Option o(Option::kStdioCreatePipe);
+    o.m_data.stdio.index = index;
+    o.m_data.stdio.pipe = &pipe;
+    o.m_data.stdio.flags = flags;
+    return o;
+  }
+
+  /**
+   * Disables inheritance for file descriptors / handles that this process
+   * inherited from its parent.  The effect is that child processes spawned
+   * by this process don't accidentally inherit these handles.
+   *
+   * It is recommended to call this function as early in your program as
+   * possible, before the inherited file descriptors can be closed or
+   * duplicated.
+   */
+  static void DisableStdioInheritance() { uv_disable_stdio_inheritance(); }
+
+  /**
+   * Starts a process.  If the process is not successfully spawned, an error
+   * is generated on the loop and this function returns nullptr.
+   *
+   * Possible reasons for failing to spawn would include (but not be limited to)
+   * the file to execute not existing, not having permissions to use the setuid
+   * or setgid specified, or not having enough memory to allocate for the new
+   * process.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param file Path pointing to the program to be executed
+   * @param options Process options
+   */
+  static std::shared_ptr<Process> SpawnArray(Loop& loop, const Twine& file,
+                                             ArrayRef<Option> options);
+
+  template <typename... Args>
+  static std::shared_ptr<Process> Spawn(Loop& loop, const Twine& file,
+                                        const Args&... options) {
+    return SpawnArray(loop, file, {options...});
+  }
+
+  /**
+   * Starts a process.  If the process is not successfully spawned, an error
+   * is generated on the loop and this function returns nullptr.
+   *
+   * Possible reasons for failing to spawn would include (but not be limited to)
+   * the file to execute not existing, not having permissions to use the setuid
+   * or setgid specified, or not having enough memory to allocate for the new
+   * process.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param file Path pointing to the program to be executed
+   * @param options Process options
+   */
+  static std::shared_ptr<Process> SpawnArray(const std::shared_ptr<Loop>& loop,
+                                             const Twine& file,
+                                             ArrayRef<Option> options) {
+    return SpawnArray(*loop, file, options);
+  }
+
+  template <typename... Args>
+  static std::shared_ptr<Process> Spawn(const std::shared_ptr<Loop>& loop,
+                                        const Twine& file,
+                                        const Args&... options) {
+    return SpawnArray(*loop, file, {options...});
+  }
+
+  /**
+   * Sends the specified signal to the process.
+   * @param signum signal number
+   */
+  void Kill(int signum) { Invoke(&uv_process_kill, GetRaw(), signum); }
+
+  /**
+   * Sends the specified signal to the given PID.
+   * @param pid process ID
+   * @param signum signal number
+   * @return 0 on success, otherwise error code.
+   */
+  static int Kill(int pid, int signum) noexcept { return uv_kill(pid, signum); }
+
+  /**
+   * Get the process ID.
+   * @return Process ID.
+   */
+  uv_pid_t GetPid() const noexcept { return GetRaw()->pid; }
+
+  /**
+   * Signal generated when the process exits.  The parameters are the exit
+   * status and the signal that caused the process to terminate, if any.
+   */
+  sig::Signal<int64_t, int> exited;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_PROCESS_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Request.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Request.h
new file mode 100644
index 0000000..c33ca83
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Request.h
@@ -0,0 +1,171 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_REQUEST_H_
+#define WPIUTIL_WPI_UV_REQUEST_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+
+#include "wpi/uv/Error.h"
+
+namespace wpi {
+namespace uv {
+
+/**
+ * Request.  Requests are not moveable or copyable.
+ * This class provides shared_ptr ownership and shared_from_this.
+ */
+class Request : public std::enable_shared_from_this<Request> {
+ public:
+  using Type = uv_req_type;
+
+  Request(const Request&) = delete;
+  Request(Request&&) = delete;
+  Request& operator=(const Request&) = delete;
+  Request& operator=(Request&&) = delete;
+  virtual ~Request() noexcept = default;
+
+  /**
+   * Get the type of the request.
+   *
+   * A base request offers no functionality to promote it to the actual request
+   * type. By means of this function, the type of the underlying request as
+   * specified by Type is made available.
+   *
+   * @return The actual type of the request.
+   */
+  Type GetType() const noexcept { return m_uv_req->type; }
+
+  /**
+   * Get the name of the type of the request.  E.g. "connect" for connect.
+   */
+  const char* GetTypeName() const noexcept {
+    return uv_req_type_name(m_uv_req->type);
+  }
+
+  /**
+   * Cancel a pending request.
+   *
+   * This method fails if the request is executing or has finished
+   * executing.
+   * It can emit an error signal in case of errors.
+   *
+   * @return True in case of success, false otherwise.
+   */
+  bool Cancel() { return uv_cancel(m_uv_req) == 0; }
+
+  /**
+   * Return the size of the underlying request type.
+   * @return The size of the underlying request type.
+   */
+  size_t RawSize() const noexcept { return uv_req_size(m_uv_req->type); }
+
+  /**
+   * Get the underlying request data structure.
+   *
+   * @return The underlying request data structure.
+   */
+  uv_req_t* GetRawReq() noexcept { return m_uv_req; }
+
+  /**
+   * Get the underlying request data structure.
+   *
+   * @return The underlying request data structure.
+   */
+  const uv_req_t* GetRawReq() const noexcept { return m_uv_req; }
+
+  /**
+   * Keep this request in memory even if no outside shared_ptr references
+   * remain.  To release call Release().
+   *
+   * Derived classes can override this method for different memory management
+   * approaches (e.g. pooled storage of requests).
+   */
+  virtual void Keep() noexcept { m_self = shared_from_this(); }
+
+  /**
+   * No longer force holding this request in memory.  Does not immediately
+   * destroy the object unless no outside shared_ptr references remain.
+   *
+   * Derived classes can override this method for different memory management
+   * approaches (e.g. pooled storage of requests).
+   */
+  virtual void Release() noexcept { m_self.reset(); }
+
+  /**
+   * Error callback.  By default, this is set up to report errors to the handle
+   * that created this request.
+   * @param err error code
+   */
+  std::function<void(Error)> error;
+
+  /**
+   * Report an error.
+   * @param err Error code
+   */
+  void ReportError(int err) { error(Error(err)); }
+
+ protected:
+  /**
+   * Constructor.
+   */
+  explicit Request(uv_req_t* uv_req) : m_uv_req{uv_req} {
+    m_uv_req->data = this;
+  }
+
+ private:
+  std::shared_ptr<Request> m_self;
+  uv_req_t* m_uv_req;
+};
+
+/**
+ * Request.  Requests are not moveable or copyable.
+ * @tparam T CRTP derived class
+ * @tparam U underlying libuv request type
+ */
+template <typename T, typename U>
+class RequestImpl : public Request {
+ public:
+  std::shared_ptr<T> shared_from_this() {
+    return std::static_pointer_cast<T>(this->shared_from_this());
+  }
+
+  std::shared_ptr<const T> shared_from_this() const {
+    return std::static_pointer_cast<const T>(this->shared_from_this());
+  }
+
+  /**
+   * Get the underlying request data structure.
+   *
+   * @return The underlying request data structure.
+   */
+  U* GetRaw() noexcept { return &m_uv_req; }
+
+  /**
+   * Get the underlying request data structure.
+   *
+   * @return The underlying request data structure.
+   */
+  const U* GetRaw() const noexcept { return &m_uv_req; }
+
+ protected:
+  /**
+   * Constructor.
+   */
+  RequestImpl() : Request{reinterpret_cast<uv_req_t*>(&m_uv_req)} {}
+
+ private:
+  U m_uv_req;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_REQUEST_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Signal.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Signal.h
new file mode 100644
index 0000000..5fe34c6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Signal.h
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_SIGNAL_H_
+#define WPIUTIL_WPI_UV_SIGNAL_H_
+
+#include <uv.h>
+
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Handle.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * Signal handle.
+ */
+class Signal final : public HandleImpl<Signal, uv_signal_t> {
+  struct private_init {};
+
+ public:
+  explicit Signal(const private_init&) {}
+  ~Signal() noexcept override = default;
+
+  /**
+   * Create a signal handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Signal> Create(Loop& loop);
+
+  /**
+   * Create a signal handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Signal> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Start watching for the given signal.
+   *
+   * @param signum Signal to watch for.
+   */
+  void Start(int signum);
+
+  /**
+   * Start watching for the given signal.  Same as Start() but the signal
+   * handler is reset the moment the signal is received.
+   *
+   * @param signum Signal to watch for.
+   */
+  void StartOneshot(int signum);
+
+  /**
+   * Stop watching for the signal.
+   */
+  void Stop() { Invoke(&uv_signal_stop, GetRaw()); }
+
+  /**
+   * Get the signal being monitored.
+   * @return Signal number.
+   */
+  int GetSignal() const { return GetRaw()->signum; }
+
+  /**
+   * Signal generated when a signal occurs.
+   */
+  sig::Signal<int> signal;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_SIGNAL_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Stream.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Stream.h
new file mode 100644
index 0000000..28e2ef7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Stream.h
@@ -0,0 +1,251 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_STREAM_H_
+#define WPIUTIL_WPI_UV_STREAM_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/Signal.h"
+#include "wpi/uv/Buffer.h"
+#include "wpi/uv/Handle.h"
+#include "wpi/uv/Request.h"
+
+namespace wpi {
+namespace uv {
+
+class Stream;
+
+/**
+ * Shutdown request.
+ */
+class ShutdownReq : public RequestImpl<ShutdownReq, uv_shutdown_t> {
+ public:
+  ShutdownReq();
+
+  Stream& GetStream() const {
+    return *static_cast<Stream*>(GetRaw()->handle->data);
+  }
+
+  /**
+   * Shutdown completed signal.
+   */
+  sig::Signal<> complete;
+};
+
+/**
+ * Write request.
+ */
+class WriteReq : public RequestImpl<WriteReq, uv_write_t> {
+ public:
+  WriteReq();
+
+  Stream& GetStream() const {
+    return *static_cast<Stream*>(GetRaw()->handle->data);
+  }
+
+  /**
+   * Write completed signal.  This is called even if an error occurred.
+   * @param err error value
+   */
+  sig::Signal<Error> finish;
+};
+
+/**
+ * Stream handle.
+ * Stream handles provide an abstraction of a duplex communication channel.
+ * This is an abstract type; there are three stream implementations (Tcp,
+ * Pipe, and Tty).
+ */
+class Stream : public Handle {
+ public:
+  std::shared_ptr<Stream> shared_from_this() {
+    return std::static_pointer_cast<Stream>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const Stream> shared_from_this() const {
+    return std::static_pointer_cast<const Stream>(Handle::shared_from_this());
+  }
+
+  /**
+   * Shutdown the outgoing (write) side of a duplex stream. It waits for pending
+   * write requests to complete.  HandleShutdownComplete() is called on the
+   * request after shutdown is complete.
+   *
+   * @param req shutdown request
+   */
+  void Shutdown(const std::shared_ptr<ShutdownReq>& req);
+
+  /**
+   * Shutdown the outgoing (write) side of a duplex stream. It waits for pending
+   * write requests to complete.  The callback is called after shutdown is
+   * complete.  Errors will be reported to the stream error handler.
+   *
+   * @param callback Callback function to call when shutdown completes
+   * @return Connection object for the callback
+   */
+  void Shutdown(std::function<void()> callback = nullptr);
+
+  /**
+   * Start reading data from an incoming stream.
+   *
+   * This will only succeed after a connection has been established.
+   *
+   * A data signal will be emitted several times until there is no more
+   * data to read or `StopRead()` is called.
+   * An end signal will be emitted when there is no more data to read.
+   */
+  void StartRead();
+
+  /**
+   * Stop reading data from the stream.
+   *
+   * This function is idempotent and may be safely called on a stopped stream.
+   */
+  void StopRead() { Invoke(&uv_read_stop, GetRawStream()); }
+
+  /**
+   * Write data to the stream.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the write request.
+   * An easy way to ensure this is to have the write request keep track of
+   * the data and use either its Complete() function or destructor to free the
+   * data.
+   *
+   * The finish signal will be emitted on the request object when the data
+   * has been written (or if an error occurs).
+   * The error signal will be emitted on the request object in case of errors.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param req write request
+   */
+  void Write(ArrayRef<Buffer> bufs, const std::shared_ptr<WriteReq>& req);
+
+  /**
+   * Write data to the stream.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the write request.
+   * The callback can be used to free data after the request completes.
+   *
+   * The callback will be called when the data has been written (even if an
+   * error occurred).  Errors will be reported to the stream error handler.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @param callback Callback function to call when the write completes
+   */
+  void Write(ArrayRef<Buffer> bufs,
+             std::function<void(MutableArrayRef<Buffer>, Error)> callback);
+
+  /**
+   * Queue a write request if it can be completed immediately.
+   *
+   * Same as `Write()`, but won’t queue a write request if it can’t be
+   * completed immediately.
+   * An error signal will be emitted in case of errors.
+   *
+   * @param bufs The buffers to be written to the stream.
+   * @return Number of bytes written.
+   */
+  int TryWrite(ArrayRef<Buffer> bufs);
+
+  /**
+   * Check if the stream is readable.
+   * @return True if the stream is readable, false otherwise.
+   */
+  bool IsReadable() const noexcept {
+    return uv_is_readable(GetRawStream()) == 1;
+  }
+
+  /**
+   * @brief Checks if the stream is writable.
+   * @return True if the stream is writable, false otherwise.
+   */
+  bool IsWritable() const noexcept {
+    return uv_is_writable(GetRawStream()) == 1;
+  }
+
+  /**
+   * Enable or disable blocking mode for a stream.
+   *
+   * When blocking mode is enabled all writes complete synchronously. The
+   * interface remains unchanged otherwise, e.g. completion or failure of the
+   * operation will still be reported through events which are emitted
+   * asynchronously.
+   *
+   * @param enable True to enable blocking mode, false otherwise.
+   * @return True in case of success, false otherwise.
+   */
+  bool SetBlocking(bool enable) noexcept {
+    return uv_stream_set_blocking(GetRawStream(), enable) == 0;
+  }
+
+  /**
+   * Gets the amount of queued bytes waiting to be sent.
+   * @return Amount of queued bytes waiting to be sent.
+   */
+  size_t GetWriteQueueSize() const noexcept {
+    return GetRawStream()->write_queue_size;
+  }
+
+  /**
+   * Get the underlying stream data structure.
+   *
+   * @return The underlying stream data structure.
+   */
+  uv_stream_t* GetRawStream() const noexcept {
+    return reinterpret_cast<uv_stream_t*>(GetRawHandle());
+  }
+
+  /**
+   * Signal generated when data was read on a stream.
+   */
+  sig::Signal<Buffer&, size_t> data;
+
+  /**
+   * Signal generated when no more read data is available.
+   */
+  sig::Signal<> end;
+
+ protected:
+  explicit Stream(uv_stream_t* uv_stream)
+      : Handle{reinterpret_cast<uv_handle_t*>(uv_stream)} {}
+};
+
+template <typename T, typename U>
+class StreamImpl : public Stream {
+ public:
+  std::shared_ptr<T> shared_from_this() {
+    return std::static_pointer_cast<T>(Handle::shared_from_this());
+  }
+
+  std::shared_ptr<const T> shared_from_this() const {
+    return std::static_pointer_cast<const T>(Handle::shared_from_this());
+  }
+
+  /**
+   * Get the underlying handle data structure.
+   *
+   * @return The underlying handle data structure.
+   */
+  U* GetRaw() const noexcept {
+    return reinterpret_cast<U*>(this->GetRawHandle());
+  }
+
+ protected:
+  StreamImpl() : Stream{reinterpret_cast<uv_stream_t*>(new U)} {}
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_STREAM_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Tcp.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Tcp.h
new file mode 100644
index 0000000..067c0fd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Tcp.h
@@ -0,0 +1,366 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_TCP_H_
+#define WPIUTIL_WPI_UV_TCP_H_
+
+#include <uv.h>
+
+#include <chrono>
+#include <functional>
+#include <memory>
+
+#include "wpi/Twine.h"
+#include "wpi/uv/NetworkStream.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+class TcpConnectReq;
+
+/**
+ * TCP handle.
+ * TCP handles are used to represent both TCP streams and servers.
+ */
+class Tcp final : public NetworkStreamImpl<Tcp, uv_tcp_t> {
+  struct private_init {};
+
+ public:
+  using Time = std::chrono::duration<uint64_t, std::milli>;
+
+  explicit Tcp(const private_init&) {}
+  ~Tcp() noexcept override = default;
+
+  /**
+   * Create a TCP handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param flags Flags
+   */
+  static std::shared_ptr<Tcp> Create(Loop& loop,
+                                     unsigned int flags = AF_UNSPEC);
+
+  /**
+   * Create a TCP handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param flags Flags
+   */
+  static std::shared_ptr<Tcp> Create(const std::shared_ptr<Loop>& loop,
+                                     unsigned int flags = AF_UNSPEC) {
+    return Create(*loop, flags);
+  }
+
+  /**
+   * 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 flags Flags
+   * @param callback Callback
+   */
+  void Reuse(std::function<void()> callback, unsigned int flags = AF_UNSPEC);
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a ListenEvent event to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @return The stream handle for the accepted connection, or nullptr on error.
+   */
+  std::shared_ptr<Tcp> Accept();
+
+  /**
+   * Accept incoming connection.
+   *
+   * This call is used in conjunction with `Listen()` to accept incoming
+   * connections. Call this function after receiving a connection signal to
+   * accept the connection.
+   * An error signal will be emitted in case of errors.
+   *
+   * When the connection signal is emitted it is guaranteed that this
+   * function will complete successfully the first time. If you attempt to use
+   * it more than once, it may fail.
+   * It is suggested to only call this function once per connection signal.
+   *
+   * @param client Client stream object.
+   * @return False on error.
+   */
+  bool Accept(const std::shared_ptr<Tcp>& client) {
+    return NetworkStream::Accept(client);
+  }
+
+  /**
+   * Open an existing file descriptor or SOCKET as a TCP handle.
+   *
+   * @note The passed file descriptor or SOCKET is not checked for its type, but
+   * it's required that it represents a valid stream socket.
+   *
+   * @param sock A valid socket handle (either a file descriptor or a SOCKET).
+   */
+  void Open(uv_os_sock_t sock) { Invoke(&uv_tcp_open, GetRaw(), sock); }
+
+  /**
+   * Enable/Disable Nagle's algorithm.
+   * @param enable True to enable it, false otherwise.
+   * @return True in case of success, false otherwise.
+   */
+  bool SetNoDelay(bool enable) { return uv_tcp_nodelay(GetRaw(), enable) == 0; }
+
+  /**
+   * Enable/Disable TCP keep-alive.
+   * @param enable True to enable it, false otherwise.
+   * @param time Initial delay in seconds (use
+   * `std::chrono::duration<unsigned int>`).
+   * @return True in case of success, false otherwise.
+   */
+  bool SetKeepAlive(bool enable, Time time = Time{0}) {
+    return uv_tcp_keepalive(GetRaw(), enable, time.count()) == 0;
+  }
+
+  /**
+   * Enable/Disable simultaneous asynchronous accept requests.
+   *
+   * Enable/Disable simultaneous asynchronous accept requests that are
+   * queued by the operating system when listening for new TCP
+   * connections.
+   * This setting is used to tune a TCP server for the desired performance.
+   * Having simultaneous accepts can significantly improve the rate of
+   * accepting connections (which is why it is enabled by default) but may
+   * lead to uneven load distribution in multi-process setups.
+   *
+   * @param enable True to enable it, false otherwise.
+   * @return True in case of success, false otherwise.
+   */
+  bool SetSimultaneousAccepts(bool enable) {
+    return uv_tcp_simultaneous_accepts(GetRaw(), enable) == 0;
+  }
+
+  /**
+   * Bind the handle to an IPv4 or IPv6 address and port.
+   *
+   * A successful call to this function does not guarantee that the call to
+   * `Listen()` or `Connect()` will work properly.
+   * An error signal can be emitted because of either this function or the
+   * ones mentioned above.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   * @param flags Optional additional flags.
+   */
+  void Bind(const sockaddr& addr, unsigned int flags = 0) {
+    Invoke(&uv_tcp_bind, GetRaw(), &addr, flags);
+  }
+
+  void Bind(const sockaddr_in& addr, unsigned int flags = 0) {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+
+  void Bind(const sockaddr_in6& addr, unsigned int flags = 0) {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+
+  /**
+   * Bind the handle to an IPv4 address and port.
+   *
+   * A successful call to this function does not guarantee that the call to
+   * `Listen()` or `Connect()` will work properly.
+   * An error signal can be emitted because of either this function or the
+   * ones mentioned above.
+   *
+   * Available flags are:
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Bind(const Twine& ip, unsigned int port, unsigned int flags = 0);
+
+  /**
+   * Bind the handle to an IPv6 address and port.
+   *
+   * A successful call to this function does not guarantee that the call to
+   * `Listen()` or `Connect()` will work properly.
+   * An error signal can be emitted because of either this function or the
+   * ones mentioned above.
+   *
+   * Available flags are:
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Bind6(const Twine& ip, unsigned int port, unsigned int flags = 0);
+
+  /**
+   * Get the current address to which the handle is bound.
+   * @return The address (will be zeroed if an error occurred).
+   */
+  sockaddr_storage GetSock();
+
+  /**
+   * Get the address of the peer connected to the handle.
+   * @return The address (will be zeroed if an error occurred).
+   */
+  sockaddr_storage GetPeer();
+
+  /**
+   * Establish an IPv4 or IPv6 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The connected signal is emitted on the request when the connection has been
+   * established.
+   * The error signal is emitted on the request in case of errors during the
+   * connection.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   * @param req connection request
+   */
+  void Connect(const sockaddr& addr, const std::shared_ptr<TcpConnectReq>& req);
+
+  void Connect(const sockaddr_in& addr,
+               const std::shared_ptr<TcpConnectReq>& req) {
+    Connect(reinterpret_cast<const sockaddr&>(addr), req);
+  }
+
+  void Connect(const sockaddr_in6& addr,
+               const std::shared_ptr<TcpConnectReq>& req) {
+    Connect(reinterpret_cast<const sockaddr&>(addr), req);
+  }
+
+  /**
+   * Establish an IPv4 or IPv6 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The callback is called when the connection has been established.  Errors
+   * are reported to the stream error handler.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   * @param callback Callback function to call when connection established
+   */
+  void Connect(const sockaddr& addr, std::function<void()> callback);
+
+  void Connect(const sockaddr_in& addr, std::function<void()> callback) {
+    Connect(reinterpret_cast<const sockaddr&>(addr), callback);
+  }
+
+  void Connect(const sockaddr_in6& addr, std::function<void()> callback) {
+    Connect(reinterpret_cast<const sockaddr&>(addr), callback);
+  }
+
+  /**
+   * Establish an IPv4 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The connected signal is emitted on the request when the connection has been
+   * established.
+   * The error signal is emitted on the request in case of errors during the
+   * connection.
+   *
+   * @param ip The address to which to connect to.
+   * @param port The port to which to connect to.
+   * @param req connection request
+   */
+  void Connect(const Twine& ip, unsigned int port,
+               const std::shared_ptr<TcpConnectReq>& req);
+
+  /**
+   * Establish an IPv4 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The callback is called when the connection has been established.  Errors
+   * are reported to the stream error handler.
+   *
+   * @param ip The address to which to connect to.
+   * @param port The port to which to connect to.
+   * @param callback Callback function to call when connection established
+   */
+  void Connect(const Twine& ip, unsigned int port,
+               std::function<void()> callback);
+
+  /**
+   * Establish an IPv6 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The connected signal is emitted on the request when the connection has been
+   * established.
+   * The error signal is emitted on the request in case of errors during the
+   * connection.
+   *
+   * @param ip The address to which to connect to.
+   * @param port The port to which to connect to.
+   * @param req connection request
+   */
+  void Connect6(const Twine& ip, unsigned int port,
+                const std::shared_ptr<TcpConnectReq>& req);
+
+  /**
+   * Establish an IPv6 TCP connection.
+   *
+   * On Windows if the addr is initialized to point to an unspecified address
+   * (`0.0.0.0` or `::`) it will be changed to point to localhost. This is
+   * done to match the behavior of Linux systems.
+   *
+   * The callback is called when the connection has been established.  Errors
+   * are reported to the stream error handler.
+   *
+   * @param ip The address to which to connect to.
+   * @param port The port to which to connect to.
+   * @param callback Callback function to call when connection established
+   */
+  void Connect6(const Twine& ip, unsigned int port,
+                std::function<void()> callback);
+
+ private:
+  Tcp* DoAccept() override;
+
+  struct ReuseData {
+    std::function<void()> callback;
+    unsigned int flags;
+  };
+  std::unique_ptr<ReuseData> m_reuseData;
+};
+
+/**
+ * TCP connection request.
+ */
+class TcpConnectReq : public ConnectReq {
+ public:
+  Tcp& GetStream() const {
+    return *static_cast<Tcp*>(&ConnectReq::GetStream());
+  }
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_TCP_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Timer.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Timer.h
new file mode 100644
index 0000000..bdafee3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Timer.h
@@ -0,0 +1,139 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_TIMER_H_
+#define WPIUTIL_WPI_UV_TIMER_H_
+
+#include <uv.h>
+
+#include <chrono>
+#include <functional>
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Handle.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * Timer handle.
+ * Timer handles are used to schedule signals to be called in the future.
+ */
+class Timer final : public HandleImpl<Timer, uv_timer_t> {
+  struct private_init {};
+
+ public:
+  using Time = std::chrono::duration<uint64_t, std::milli>;
+
+  explicit Timer(const private_init&) {}
+  ~Timer() noexcept override = default;
+
+  /**
+   * Create a timer handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Timer> Create(Loop& loop);
+
+  /**
+   * Create a timer handle.
+   *
+   * @param loop Loop object where this handle runs.
+   */
+  static std::shared_ptr<Timer> Create(const std::shared_ptr<Loop>& loop) {
+    return Create(*loop);
+  }
+
+  /**
+   * Create a timer that calls a functor after a given time interval.
+   *
+   * @param loop Loop object where the timer should run.
+   * @param timeout Time interval
+   * @param func Functor
+   */
+  static void SingleShot(Loop& loop, Time timeout, std::function<void()> func);
+
+  /**
+   * Create a timer that calls a functor after a given time interval.
+   *
+   * @param loop Loop object where the timer should run.
+   * @param timeout Time interval
+   * @param func Functor
+   */
+  static void SingleShot(const std::shared_ptr<Loop>& loop, Time timeout,
+                         std::function<void()> func) {
+    return SingleShot(*loop, timeout, func);
+  }
+
+  /**
+   * Start the timer.
+   *
+   * If timeout is zero, an event is emitted on the next event loop
+   * iteration. If repeat is non-zero, an event is emitted first
+   * after timeout milliseconds and then repeatedly after repeat milliseconds.
+   *
+   * @param timeout Milliseconds before to emit an event (use
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   * @param repeat Milliseconds between successive events (use
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  void Start(Time timeout, Time repeat = Time{0});
+
+  /**
+   * Stop the timer.
+   */
+  void Stop() { Invoke(&uv_timer_stop, GetRaw()); }
+
+  /**
+   * Stop the timer and restart it if it was repeating.
+   *
+   * Stop the timer, and if it is repeating restart it using the repeat value
+   * as the timeout.
+   * If the timer has never been started before it emits sigError.
+   */
+  void Again() { Invoke(&uv_timer_again, GetRaw()); }
+
+  /**
+   * Set the repeat interval value.
+   *
+   * The timer will be scheduled to run on the given interval and will follow
+   * normal timer semantics in the case of a time-slice overrun.
+   * For example, if a 50ms repeating timer first runs for 17ms, it will be
+   * scheduled to run again 33ms later. If other tasks consume more than the
+   * 33ms following the first timer event, then another event will be emitted
+   * as soon as possible.
+   *
+   * If the repeat value is set from a listener bound to an event, it does
+   * not immediately take effect. If the timer was non-repeating before, it
+   * will have been stopped. If it was repeating, then the old repeat value
+   * will have been used to schedule the next timeout.
+   *
+   * @param repeat Repeat interval in milliseconds (use
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  void SetRepeat(Time repeat) { uv_timer_set_repeat(GetRaw(), repeat.count()); }
+
+  /**
+   * Get the timer repeat value.
+   * @return Timer repeat value in milliseconds (as a
+   * `std::chrono::duration<uint64_t, std::milli>`).
+   */
+  Time GetRepeat() const { return Time{uv_timer_get_repeat(GetRaw())}; }
+
+  /**
+   * Signal generated when the timeout event occurs.
+   */
+  sig::Signal<> timeout;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_TIMER_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Tty.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Tty.h
new file mode 100644
index 0000000..a15d8eb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Tty.h
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_TTY_H_
+#define WPIUTIL_WPI_UV_TTY_H_
+
+#include <uv.h>
+
+#include <memory>
+#include <utility>
+
+#include "wpi/uv/Stream.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+class Tty;
+
+/**
+ * TTY handle.
+ * TTY handles represent a stream for the console.
+ */
+class Tty final : public StreamImpl<Tty, uv_tty_t> {
+  struct private_init {};
+
+ public:
+  explicit Tty(const private_init&) {}
+  ~Tty() noexcept override = default;
+
+  /**
+   * Create a TTY handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param fd File descriptor, usually 0=stdin, 1=stdout, 2=stderr
+   * @param readable Specifies if you plan on calling StartRead().  stdin is
+   *                 readable, stdout is not.
+   */
+  static std::shared_ptr<Tty> Create(Loop& loop, uv_file fd, bool readable);
+
+  /**
+   * Create a TTY handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param fd File descriptor, usually 0=stdin, 1=stdout, 2=stderr
+   * @param readable Specifies if you plan on calling StartRead().  stdin is
+   *                 readable, stdout is not.
+   */
+  static std::shared_ptr<Tty> Create(const std::shared_ptr<Loop>& loop,
+                                     uv_file fd, bool readable) {
+    return Create(*loop, fd, readable);
+  }
+
+  /**
+   * Set the TTY using the specified terminal mode.
+   *
+   * @param mode terminal mode
+   */
+  void SetMode(uv_tty_mode_t mode) {
+    int err = uv_tty_set_mode(GetRaw(), mode);
+    if (err < 0) ReportError(err);
+  }
+
+  /**
+   * Reset TTY settings to default values for the next process to take over.
+   * Typically called when the program exits.
+   */
+  void ResetMode() { Invoke(&uv_tty_reset_mode); }
+
+  /**
+   * Gets the current window size.
+   * @return Window size (pair of width and height).
+   */
+  std::pair<int, int> GetWindowSize() {
+    int width = 0, height = 0;
+    Invoke(&uv_tty_get_winsize, GetRaw(), &width, &height);
+    return std::make_pair(width, height);
+  }
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_TTY_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Udp.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Udp.h
new file mode 100644
index 0000000..7ceb0bb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Udp.h
@@ -0,0 +1,302 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_UDP_H_
+#define WPIUTIL_WPI_UV_UDP_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+
+#include "wpi/ArrayRef.h"
+#include "wpi/Signal.h"
+#include "wpi/Twine.h"
+#include "wpi/uv/Handle.h"
+#include "wpi/uv/Request.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+class Udp;
+
+/**
+ * UDP send request.
+ */
+class UdpSendReq : public RequestImpl<UdpSendReq, uv_udp_send_t> {
+ public:
+  UdpSendReq();
+
+  Udp& GetUdp() const { return *static_cast<Udp*>(GetRaw()->handle->data); }
+
+  /**
+   * Send completed signal.  This is called even if an error occurred.
+   * @param err error value
+   */
+  sig::Signal<Error> complete;
+};
+
+/**
+ * UDP handle.
+ * UDP handles encapsulate UDP communication for both clients and servers.
+ */
+class Udp final : public HandleImpl<Udp, uv_udp_t> {
+  struct private_init {};
+
+ public:
+  explicit Udp(const private_init&) {}
+  ~Udp() noexcept override = default;
+
+  /**
+   * Create a UDP handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param flags Flags
+   */
+  static std::shared_ptr<Udp> Create(Loop& loop,
+                                     unsigned int flags = AF_UNSPEC);
+
+  /**
+   * Create a UDP handle.
+   *
+   * @param loop Loop object where this handle runs.
+   * @param flags Flags
+   */
+  static std::shared_ptr<Udp> Create(const std::shared_ptr<Loop>& loop,
+                                     unsigned int flags = AF_UNSPEC) {
+    return Create(*loop, flags);
+  }
+
+  /**
+   * Open an existing file descriptor or SOCKET as a UDP handle.
+   *
+   * @param sock A valid socket handle (either a file descriptor or a SOCKET).
+   */
+  void Open(uv_os_sock_t sock) { Invoke(&uv_udp_open, GetRaw(), sock); }
+
+  /**
+   * Bind the handle to an IPv4 or IPv6 address and port.
+   *
+   * @param addr Initialized `sockaddr_in` or `sockaddr_in6` data structure.
+   * @param flags Optional additional flags.
+   */
+  void Bind(const sockaddr& addr, unsigned int flags = 0) {
+    Invoke(&uv_udp_bind, GetRaw(), &addr, flags);
+  }
+
+  void Bind(const sockaddr_in& addr, unsigned int flags = 0) {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+
+  void Bind(const sockaddr_in6& addr, unsigned int flags = 0) {
+    Bind(reinterpret_cast<const sockaddr&>(addr), flags);
+  }
+
+  /**
+   * Bind the handle to an IPv4 address and port.
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Bind(const Twine& ip, unsigned int port, unsigned int flags = 0);
+
+  /**
+   * Bind the handle to an IPv6 address and port.
+   *
+   * @param ip The address to which to bind.
+   * @param port The port to which to bind.
+   * @param flags Optional additional flags.
+   */
+  void Bind6(const Twine& ip, unsigned int port, unsigned int flags = 0);
+
+  /**
+   * Get the current address to which the handle is bound.
+   * @return The address (will be zeroed if an error occurred).
+   */
+  sockaddr_storage GetSock();
+
+  /**
+   * Set membership for a multicast address.
+   *
+   * @param multicastAddr Multicast address to set membership for
+   * @param interfaceAddr Interface address
+   * @param membership Should be UV_JOIN_GROUP or UV_LEAVE_GROUP
+   */
+  void SetMembership(const Twine& multicastAddr, const Twine& interfaceAddr,
+                     uv_membership membership);
+
+  /**
+   * Set IP multicast loop flag.  Makes multicast packets loop back to local
+   * sockets.
+   *
+   * @param enabled True for enabled, false for disabled
+   */
+  void SetMulticastLoop(bool enabled) {
+    Invoke(&uv_udp_set_multicast_loop, GetRaw(), enabled ? 1 : 0);
+  }
+
+  /**
+   * Set the multicast TTL.
+   *
+   * @param ttl Time to live (1-255)
+   */
+  void SetMulticastTtl(int ttl) {
+    Invoke(&uv_udp_set_multicast_ttl, GetRaw(), ttl);
+  }
+
+  /**
+   * Set the multicast interface to send or receive data on.
+   *
+   * @param interfaceAddr Interface address
+   */
+  void SetMulticastInterface(const Twine& interfaceAddr);
+
+  /**
+   * Set broadcast on or off.
+   *
+   * @param enabled True for enabled, false for disabled
+   */
+  void SetBroadcast(bool enabled) {
+    Invoke(&uv_udp_set_broadcast, GetRaw(), enabled ? 1 : 0);
+  }
+
+  /**
+   * Set the time to live (TTL).
+   *
+   * @param ttl Time to live (1-255)
+   */
+  void SetTtl(int ttl) { Invoke(&uv_udp_set_ttl, GetRaw(), ttl); }
+
+  /**
+   * Send data over the UDP socket.  If the socket has not previously been bound
+   * with Bind() it will be bound to 0.0.0.0 (the "all interfaces" IPv4 address)
+   * and a random port number.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the send request.
+   * The callback can be used to free data after the request completes.
+   *
+   * HandleSendComplete() will be called on the request object when the data
+   * has been written.  HandleSendComplete() is called even if an error occurs.
+   * HandleError() will be called on the request object in case of errors.
+   *
+   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
+   *             remote peer.
+   * @param bufs The buffers to be written to the stream.
+   * @param req write request
+   */
+  void Send(const sockaddr& addr, ArrayRef<Buffer> bufs,
+            const std::shared_ptr<UdpSendReq>& req);
+
+  void Send(const sockaddr_in& addr, ArrayRef<Buffer> bufs,
+            const std::shared_ptr<UdpSendReq>& req) {
+    Send(reinterpret_cast<const sockaddr&>(addr), bufs, req);
+  }
+
+  void Send(const sockaddr_in6& addr, ArrayRef<Buffer> bufs,
+            const std::shared_ptr<UdpSendReq>& req) {
+    Send(reinterpret_cast<const sockaddr&>(addr), bufs, req);
+  }
+
+  /**
+   * Send data over the UDP socket.  If the socket has not previously been bound
+   * with Bind() it will be bound to 0.0.0.0 (the "all interfaces" IPv4 address)
+   * and a random port number.
+   *
+   * Data are written in order. The lifetime of the data pointers passed in
+   * the `bufs` parameter must exceed the lifetime of the send request.
+   * The callback can be used to free data after the request completes.
+   *
+   * The callback will be called when the data has been sent.  Errors will
+   * be reported via the error signal.
+   *
+   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
+   *             remote peer.
+   * @param bufs The buffers to be sent.
+   * @param callback Callback function to call when the data has been sent.
+   */
+  void Send(const sockaddr& addr, ArrayRef<Buffer> bufs,
+            std::function<void(MutableArrayRef<Buffer>, Error)> callback);
+
+  void Send(const sockaddr_in& addr, ArrayRef<Buffer> bufs,
+            std::function<void(MutableArrayRef<Buffer>, Error)> callback) {
+    Send(reinterpret_cast<const sockaddr&>(addr), bufs, callback);
+  }
+
+  void Send(const sockaddr_in6& addr, ArrayRef<Buffer> bufs,
+            std::function<void(MutableArrayRef<Buffer>, Error)> callback) {
+    Send(reinterpret_cast<const sockaddr&>(addr), bufs, callback);
+  }
+
+  /**
+   * Same as Send(), but won't queue a send request if it can't be completed
+   * immediately.
+   *
+   * @param addr sockaddr_in or sockaddr_in6 with the address and port of the
+   *             remote peer.
+   * @param bufs The buffers to be send.
+   * @return Number of bytes sent.
+   */
+  int TrySend(const sockaddr& addr, ArrayRef<Buffer> bufs) {
+    int val = uv_udp_try_send(GetRaw(), bufs.data(), bufs.size(), &addr);
+    if (val < 0) {
+      this->ReportError(val);
+      return 0;
+    }
+    return val;
+  }
+
+  int TrySend(const sockaddr_in& addr, ArrayRef<Buffer> bufs) {
+    return TrySend(reinterpret_cast<const sockaddr&>(addr), bufs);
+  }
+
+  int TrySend(const sockaddr_in6& addr, ArrayRef<Buffer> bufs) {
+    return TrySend(reinterpret_cast<const sockaddr&>(addr), bufs);
+  }
+
+  /**
+   * Prepare for receiving data.  If the socket has not previously been bound
+   * with Bind() it is bound to 0.0.0.0 (the "all interfaces" IPv4 address) and
+   * a random port number.
+   *
+   * A received signal will be emitted for each received data packet until
+   * `StopRecv()` is called.
+   */
+  void StartRecv();
+
+  /**
+   * Stop listening for incoming datagrams.
+   */
+  void StopRecv() { Invoke(&uv_udp_recv_stop, GetRaw()); }
+
+  /**
+   * Gets the amount of queued bytes waiting to be sent.
+   * @return Amount of queued bytes waiting to be sent.
+   */
+  size_t GetSendQueueSize() const noexcept { return GetRaw()->send_queue_size; }
+
+  /**
+   * Gets the amount of queued packets waiting to be sent.
+   * @return Amount of queued packets waiting to be sent.
+   */
+  size_t GetSendQueueCount() const noexcept {
+    return GetRaw()->send_queue_count;
+  }
+
+  /**
+   * Signal generated for each incoming datagram.  Parameters are the buffer,
+   * the number of bytes received, the address of the sender, and flags.
+   */
+  sig::Signal<Buffer&, size_t, const sockaddr&, unsigned> received;
+};
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_UDP_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Work.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Work.h
new file mode 100644
index 0000000..bf061fb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/Work.h
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_WORK_H_
+#define WPIUTIL_WPI_UV_WORK_H_
+
+#include <uv.h>
+
+#include <functional>
+#include <memory>
+
+#include "wpi/Signal.h"
+#include "wpi/uv/Request.h"
+
+namespace wpi {
+namespace uv {
+
+class Loop;
+
+/**
+ * Work request.
+ * For use with `QueueWork()` function family.
+ */
+class WorkReq : public RequestImpl<WorkReq, uv_work_t> {
+ public:
+  WorkReq();
+
+  Loop& GetLoop() const { return *static_cast<Loop*>(GetRaw()->loop->data); }
+
+  /**
+   * Function(s) that will be run on the thread pool.
+   */
+  sig::Signal<> work;
+
+  /**
+   * Function(s) that will be run on the loop thread after the work on the
+   * thread pool has been completed by the work callback.
+   */
+  sig::Signal<> afterWork;
+};
+
+/**
+ * Initializes a work request which will run on the thread pool.
+ *
+ * @param loop Event loop
+ * @param req request
+ */
+void QueueWork(Loop& loop, const std::shared_ptr<WorkReq>& req);
+
+/**
+ * Initializes a work request which will run on the thread pool.
+ *
+ * @param loop Event loop
+ * @param req request
+ */
+inline void QueueWork(const std::shared_ptr<Loop>& loop,
+                      const std::shared_ptr<WorkReq>& req) {
+  QueueWork(*loop, req);
+}
+
+/**
+ * Initializes a work request which will run on the thread pool.  The work
+ * callback will be run on a thread from the thread pool, and the afterWork
+ * callback will be called on the loop thread after the work completes.  Any
+ * errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param work Work callback (called from separate thread)
+ * @param afterWork After work callback (called on loop thread)
+ */
+void QueueWork(Loop& loop, std::function<void()> work,
+               std::function<void()> afterWork);
+
+/**
+ * Initializes a work request which will run on the thread pool.  The work
+ * callback will be run on a thread from the thread pool, and the afterWork
+ * callback will be called on the loop thread after the work completes.  Any
+ * errors are forwarded to the loop.
+ *
+ * @param loop Event loop
+ * @param work Work callback (called from separate thread)
+ * @param afterWork After work callback (called on loop thread)
+ */
+inline void QueueWork(const std::shared_ptr<Loop>& loop,
+                      std::function<void()> work,
+                      std::function<void()> afterWork) {
+  QueueWork(*loop, work, afterWork);
+}
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_WORK_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/util.h b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/util.h
new file mode 100644
index 0000000..3795aa8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/include/wpi/uv/util.h
@@ -0,0 +1,131 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifndef WPIUTIL_WPI_UV_UTIL_H_
+#define WPIUTIL_WPI_UV_UTIL_H_
+
+#include <uv.h>
+
+#include <cstring>
+
+#include "wpi/Twine.h"
+
+namespace wpi {
+namespace uv {
+
+/**
+ * Convert a binary structure containing an IPv4 address to a string.
+ * @param addr Binary structure
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @param port Output port number
+ * @return Error (same as `uv_ip4_name()`).
+ */
+template <typename T>
+int AddrToName(const sockaddr_in& addr, T* ip, unsigned int* port) {
+  char name[128];
+  int err = uv_ip4_name(&addr, name, 128);
+  if (err == 0) {
+    ip->assign(name, name + std::strlen(name));
+    *port = ntohs(addr.sin_port);
+  } else {
+    ip->assign(name, name);
+  }
+  return err;
+}
+
+/**
+ * Convert a binary structure containing an IPv6 address to a string.
+ * @param addr Binary structure
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @param port Output port number
+ * @return Error (same as `uv_ip6_name()`).
+ */
+template <typename T>
+int AddrToName(const sockaddr_in6& addr, T* ip, unsigned int* port) {
+  char name[128];
+  int err = uv_ip6_name(&addr, name, 128);
+  if (err == 0) {
+    ip->assign(name, name + std::strlen(name));
+    *port = ntohs(addr.sin6_port);
+  } else {
+    ip->assign(name, name);
+  }
+  return err;
+}
+
+/**
+ * Convert a binary IPv4 address to a string.
+ * @param addr Binary address
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @return Error (same as `uv_inet_ntop()`).
+ */
+template <typename T>
+int AddrToName(const in_addr& addr, T* ip) {
+  char name[128];
+  int err = uv_inet_ntop(AF_INET, &addr, name, 128);
+  if (err == 0)
+    ip->assign(name, name + std::strlen(name));
+  else
+    ip->assign(name, name);
+  return err;
+}
+
+/**
+ * Convert a binary IPv6 address to a string.
+ * @param addr Binary address
+ * @param ip Output string (any type that has `assign(char*, char*)`)
+ * @return Error (same as `uv_inet_ntop()`).
+ */
+template <typename T>
+int AddrToName(const in6_addr& addr, T* ip) {
+  char name[128];
+  int err = uv_inet_ntop(AF_INET6, &addr, name, 128);
+  if (err == 0)
+    ip->assign(name, name + std::strlen(name));
+  else
+    ip->assign(name, name);
+  return err;
+}
+
+/**
+ * Convert a string containing an IPv4 address to a binary structure.
+ * @param ip IPv4 address string
+ * @param port Port number
+ * @param addr Output binary structure
+ * @return Error (same as `uv_ip4_addr()`).
+ */
+int NameToAddr(const Twine& ip, unsigned int port, sockaddr_in* addr);
+
+/**
+ * Convert a string containing an IPv6 address to a binary structure.
+ * @param ip IPv6 address string
+ * @param port Port number
+ * @param addr Output binary structure
+ * @return Error (same as `uv_ip6_addr()`).
+ */
+int NameToAddr(const Twine& ip, unsigned int port, sockaddr_in6* addr);
+
+/**
+ * Convert a string containing an IPv4 address to binary format.
+ * @param ip IPv4 address string
+ * @param addr Output binary
+ * @return Error (same as `uv_inet_pton()`).
+ */
+int NameToAddr(const Twine& ip, in_addr* addr);
+
+/**
+ * Convert a string containing an IPv6 address to binary format.
+ * @param ip IPv6 address string
+ * @param addr Output binary
+ * @return Error (same as `uv_inet_pton()`).
+ */
+int NameToAddr(const Twine& ip, in6_addr* addr);
+
+}  // namespace uv
+}  // namespace wpi
+
+#endif  // WPIUTIL_WPI_UV_UTIL_H_
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/fs-poll.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/fs-poll.cpp
new file mode 100644
index 0000000..61cc737
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/fs-poll.cpp
@@ -0,0 +1,256 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv-common.h"
+
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+
+struct poll_ctx {
+  uv_fs_poll_t* parent_handle; /* NULL if parent has been stopped or closed */
+  int busy_polling;
+  unsigned int interval;
+  uint64_t start_time;
+  uv_loop_t* loop;
+  uv_fs_poll_cb poll_cb;
+  uv_timer_t timer_handle;
+  uv_fs_t fs_req; /* TODO(bnoordhuis) mark fs_req internal */
+  uv_stat_t statbuf;
+  char path[1]; /* variable length */
+};
+
+static int statbuf_eq(const uv_stat_t* a, const uv_stat_t* b);
+static void poll_cb(uv_fs_t* req);
+static void timer_cb(uv_timer_t* timer);
+static void timer_close_cb(uv_handle_t* handle);
+
+static uv_stat_t zero_statbuf;
+
+
+int uv_fs_poll_init(uv_loop_t* loop, uv_fs_poll_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_POLL);
+  return 0;
+}
+
+
+int uv_fs_poll_start(uv_fs_poll_t* handle,
+                     uv_fs_poll_cb cb,
+                     const char* path,
+                     unsigned int interval) {
+  struct poll_ctx* ctx;
+  uv_loop_t* loop;
+  size_t len;
+  int err;
+
+  if (uv__is_active(handle))
+    return 0;
+
+  loop = handle->loop;
+  len = strlen(path);
+  ctx = (struct poll_ctx*)uv__calloc(1, sizeof(*ctx) + len);
+
+  if (ctx == NULL)
+    return UV_ENOMEM;
+
+  ctx->loop = loop;
+  ctx->poll_cb = cb;
+  ctx->interval = interval ? interval : 1;
+  ctx->start_time = uv_now(loop);
+  ctx->parent_handle = handle;
+  memcpy(ctx->path, path, len + 1);
+
+  err = uv_timer_init(loop, &ctx->timer_handle);
+  if (err < 0)
+    goto error;
+
+  ctx->timer_handle.flags |= UV__HANDLE_INTERNAL;
+  uv__handle_unref(&ctx->timer_handle);
+
+  err = uv_fs_stat(loop, &ctx->fs_req, ctx->path, poll_cb);
+  if (err < 0)
+    goto error;
+
+  handle->poll_ctx = ctx;
+  uv__handle_start(handle);
+
+  return 0;
+
+error:
+  uv__free(ctx);
+  return err;
+}
+
+
+int uv_fs_poll_stop(uv_fs_poll_t* handle) {
+  struct poll_ctx* ctx;
+
+  if (!uv__is_active(handle))
+    return 0;
+
+  ctx = (struct poll_ctx*)handle->poll_ctx;
+  assert(ctx != NULL);
+  assert(ctx->parent_handle != NULL);
+  ctx->parent_handle = NULL;
+  handle->poll_ctx = NULL;
+
+  /* Close the timer if it's active. If it's inactive, there's a stat request
+   * in progress and poll_cb will take care of the cleanup.
+   */
+  if (uv__is_active(&ctx->timer_handle))
+    uv_close((uv_handle_t*)&ctx->timer_handle, timer_close_cb);
+
+  uv__handle_stop(handle);
+
+  return 0;
+}
+
+
+int uv_fs_poll_getpath(uv_fs_poll_t* handle, char* buffer, size_t* size) {
+  struct poll_ctx* ctx;
+  size_t required_len;
+
+  if (!uv__is_active(handle)) {
+    *size = 0;
+    return UV_EINVAL;
+  }
+
+  ctx = (struct poll_ctx*)handle->poll_ctx;
+  assert(ctx != NULL);
+
+  required_len = strlen(ctx->path);
+  if (required_len >= *size) {
+    *size = required_len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, ctx->path, required_len);
+  *size = required_len;
+  buffer[required_len] = '\0';
+
+  return 0;
+}
+
+
+void uv__fs_poll_close(uv_fs_poll_t* handle) {
+  uv_fs_poll_stop(handle);
+}
+
+
+static void timer_cb(uv_timer_t* timer) {
+  struct poll_ctx* ctx;
+
+  ctx = container_of(timer, struct poll_ctx, timer_handle);
+  assert(ctx->parent_handle != NULL);
+  assert(ctx->parent_handle->poll_ctx == ctx);
+  ctx->start_time = uv_now(ctx->loop);
+
+  if (uv_fs_stat(ctx->loop, &ctx->fs_req, ctx->path, poll_cb))
+    abort();
+}
+
+
+static void poll_cb(uv_fs_t* req) {
+  uv_stat_t* statbuf;
+  struct poll_ctx* ctx;
+  uint64_t interval;
+
+  ctx = container_of(req, struct poll_ctx, fs_req);
+
+  if (ctx->parent_handle == NULL) { /* handle has been stopped or closed */
+    uv_close((uv_handle_t*)&ctx->timer_handle, timer_close_cb);
+    uv_fs_req_cleanup(req);
+    return;
+  }
+
+  if (req->result != 0) {
+    if (ctx->busy_polling != req->result) {
+      ctx->poll_cb(ctx->parent_handle,
+                   req->result,
+                   &ctx->statbuf,
+                   &zero_statbuf);
+      ctx->busy_polling = req->result;
+    }
+    goto out;
+  }
+
+  statbuf = &req->statbuf;
+
+  if (ctx->busy_polling != 0)
+    if (ctx->busy_polling < 0 || !statbuf_eq(&ctx->statbuf, statbuf))
+      ctx->poll_cb(ctx->parent_handle, 0, &ctx->statbuf, statbuf);
+
+  ctx->statbuf = *statbuf;
+  ctx->busy_polling = 1;
+
+out:
+  uv_fs_req_cleanup(req);
+
+  if (ctx->parent_handle == NULL) { /* handle has been stopped by callback */
+    uv_close((uv_handle_t*)&ctx->timer_handle, timer_close_cb);
+    return;
+  }
+
+  /* Reschedule timer, subtract the delay from doing the stat(). */
+  interval = ctx->interval;
+  interval -= (uv_now(ctx->loop) - ctx->start_time) % interval;
+
+  if (uv_timer_start(&ctx->timer_handle, timer_cb, interval, 0))
+    abort();
+}
+
+
+static void timer_close_cb(uv_handle_t* handle) {
+  uv__free(container_of(handle, struct poll_ctx, timer_handle));
+}
+
+
+static int statbuf_eq(const uv_stat_t* a, const uv_stat_t* b) {
+  return a->st_ctim.tv_nsec == b->st_ctim.tv_nsec
+      && a->st_mtim.tv_nsec == b->st_mtim.tv_nsec
+      && a->st_birthtim.tv_nsec == b->st_birthtim.tv_nsec
+      && a->st_ctim.tv_sec == b->st_ctim.tv_sec
+      && a->st_mtim.tv_sec == b->st_mtim.tv_sec
+      && a->st_birthtim.tv_sec == b->st_birthtim.tv_sec
+      && a->st_size == b->st_size
+      && a->st_mode == b->st_mode
+      && a->st_uid == b->st_uid
+      && a->st_gid == b->st_gid
+      && a->st_ino == b->st_ino
+      && a->st_dev == b->st_dev
+      && a->st_flags == b->st_flags
+      && a->st_gen == b->st_gen;
+}
+
+
+#if defined(_WIN32)
+
+#include "win/internal.h"
+#include "win/handle-inl.h"
+
+void uv__fs_poll_endgame(uv_loop_t* loop, uv_fs_poll_t* handle) {
+  assert(handle->flags & UV__HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+  uv__handle_close(handle);
+}
+
+#endif /* _WIN32 */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/heap-inl.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/heap-inl.h
new file mode 100644
index 0000000..1e2ed60
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/heap-inl.h
@@ -0,0 +1,245 @@
+/* Copyright (c) 2013, Ben Noordhuis <info@bnoordhuis.nl>
+ *
+ * Permission to use, copy, modify, and/or distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#ifndef UV_SRC_HEAP_H_
+#define UV_SRC_HEAP_H_
+
+#include <stddef.h>  /* NULL */
+
+#if defined(__GNUC__)
+# define HEAP_EXPORT(declaration) __attribute__((unused)) static declaration
+#else
+# define HEAP_EXPORT(declaration) static declaration
+#endif
+
+struct heap_node {
+  struct heap_node* left;
+  struct heap_node* right;
+  struct heap_node* parent;
+};
+
+/* A binary min heap.  The usual properties hold: the root is the lowest
+ * element in the set, the height of the tree is at most log2(nodes) and
+ * it's always a complete binary tree.
+ *
+ * The heap function try hard to detect corrupted tree nodes at the cost
+ * of a minor reduction in performance.  Compile with -DNDEBUG to disable.
+ */
+struct heap {
+  struct heap_node* min;
+  unsigned int nelts;
+};
+
+/* Return non-zero if a < b. */
+typedef int (*heap_compare_fn)(const struct heap_node* a,
+                               const struct heap_node* b);
+
+/* Public functions. */
+HEAP_EXPORT(void heap_init(struct heap* heap));
+HEAP_EXPORT(struct heap_node* heap_min(const struct heap* heap));
+HEAP_EXPORT(void heap_insert(struct heap* heap,
+                             struct heap_node* newnode,
+                             heap_compare_fn less_than));
+HEAP_EXPORT(void heap_remove(struct heap* heap,
+                             struct heap_node* node,
+                             heap_compare_fn less_than));
+HEAP_EXPORT(void heap_dequeue(struct heap* heap, heap_compare_fn less_than));
+
+/* Implementation follows. */
+
+HEAP_EXPORT(void heap_init(struct heap* heap)) {
+  heap->min = NULL;
+  heap->nelts = 0;
+}
+
+HEAP_EXPORT(struct heap_node* heap_min(const struct heap* heap)) {
+  return heap->min;
+}
+
+/* Swap parent with child. Child moves closer to the root, parent moves away. */
+static void heap_node_swap(struct heap* heap,
+                           struct heap_node* parent,
+                           struct heap_node* child) {
+  struct heap_node* sibling;
+  struct heap_node t;
+
+  t = *parent;
+  *parent = *child;
+  *child = t;
+
+  parent->parent = child;
+  if (child->left == child) {
+    child->left = parent;
+    sibling = child->right;
+  } else {
+    child->right = parent;
+    sibling = child->left;
+  }
+  if (sibling != NULL)
+    sibling->parent = child;
+
+  if (parent->left != NULL)
+    parent->left->parent = parent;
+  if (parent->right != NULL)
+    parent->right->parent = parent;
+
+  if (child->parent == NULL)
+    heap->min = child;
+  else if (child->parent->left == parent)
+    child->parent->left = child;
+  else
+    child->parent->right = child;
+}
+
+HEAP_EXPORT(void heap_insert(struct heap* heap,
+                             struct heap_node* newnode,
+                             heap_compare_fn less_than)) {
+  struct heap_node** parent;
+  struct heap_node** child;
+  unsigned int path;
+  unsigned int n;
+  unsigned int k;
+
+  newnode->left = NULL;
+  newnode->right = NULL;
+  newnode->parent = NULL;
+
+  /* Calculate the path from the root to the insertion point.  This is a min
+   * heap so we always insert at the left-most free node of the bottom row.
+   */
+  path = 0;
+  for (k = 0, n = 1 + heap->nelts; n >= 2; k += 1, n /= 2)
+    path = (path << 1) | (n & 1);
+
+  /* Now traverse the heap using the path we calculated in the previous step. */
+  parent = child = &heap->min;
+  while (k > 0) {
+    parent = child;
+    if (path & 1)
+      child = &(*child)->right;
+    else
+      child = &(*child)->left;
+    path >>= 1;
+    k -= 1;
+  }
+
+  /* Insert the new node. */
+  newnode->parent = *parent;
+  *child = newnode;
+  heap->nelts += 1;
+
+  /* Walk up the tree and check at each node if the heap property holds.
+   * It's a min heap so parent < child must be true.
+   */
+  while (newnode->parent != NULL && less_than(newnode, newnode->parent))
+    heap_node_swap(heap, newnode->parent, newnode);
+}
+
+HEAP_EXPORT(void heap_remove(struct heap* heap,
+                             struct heap_node* node,
+                             heap_compare_fn less_than)) {
+  struct heap_node* smallest;
+  struct heap_node** max;
+  struct heap_node* child;
+  unsigned int path;
+  unsigned int k;
+  unsigned int n;
+
+  if (heap->nelts == 0)
+    return;
+
+  /* Calculate the path from the min (the root) to the max, the left-most node
+   * of the bottom row.
+   */
+  path = 0;
+  for (k = 0, n = heap->nelts; n >= 2; k += 1, n /= 2)
+    path = (path << 1) | (n & 1);
+
+  /* Now traverse the heap using the path we calculated in the previous step. */
+  max = &heap->min;
+  while (k > 0) {
+    if (path & 1)
+      max = &(*max)->right;
+    else
+      max = &(*max)->left;
+    path >>= 1;
+    k -= 1;
+  }
+
+  heap->nelts -= 1;
+
+  /* Unlink the max node. */
+  child = *max;
+  *max = NULL;
+
+  if (child == node) {
+    /* We're removing either the max or the last node in the tree. */
+    if (child == heap->min) {
+      heap->min = NULL;
+    }
+    return;
+  }
+
+  /* Replace the to be deleted node with the max node. */
+  child->left = node->left;
+  child->right = node->right;
+  child->parent = node->parent;
+
+  if (child->left != NULL) {
+    child->left->parent = child;
+  }
+
+  if (child->right != NULL) {
+    child->right->parent = child;
+  }
+
+  if (node->parent == NULL) {
+    heap->min = child;
+  } else if (node->parent->left == node) {
+    node->parent->left = child;
+  } else {
+    node->parent->right = child;
+  }
+
+  /* Walk down the subtree and check at each node if the heap property holds.
+   * It's a min heap so parent < child must be true.  If the parent is bigger,
+   * swap it with the smallest child.
+   */
+  for (;;) {
+    smallest = child;
+    if (child->left != NULL && less_than(child->left, smallest))
+      smallest = child->left;
+    if (child->right != NULL && less_than(child->right, smallest))
+      smallest = child->right;
+    if (smallest == child)
+      break;
+    heap_node_swap(heap, child, smallest);
+  }
+
+  /* Walk up the subtree and check that each parent is less than the node
+   * this is required, because `max` node is not guaranteed to be the
+   * actual maximum in tree
+   */
+  while (child->parent != NULL && less_than(child, child->parent))
+    heap_node_swap(heap, child->parent, child);
+}
+
+HEAP_EXPORT(void heap_dequeue(struct heap* heap, heap_compare_fn less_than)) {
+  heap_remove(heap, heap->min, less_than);
+}
+
+#undef HEAP_EXPORT
+
+#endif  /* UV_SRC_HEAP_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/inet.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/inet.cpp
new file mode 100644
index 0000000..79d6232
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/inet.cpp
@@ -0,0 +1,310 @@
+/*
+ * Copyright (c) 2004 by Internet Systems Consortium, Inc. ("ISC")
+ * Copyright (c) 1996-1999 by Internet Software Consortium.
+ *
+ * Permission to use, copy, modify, and distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND ISC DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS.  IN NO EVENT SHALL ISC BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT
+ * OF OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#include <stdio.h>
+#include <string.h>
+
+#if defined(_MSC_VER) && _MSC_VER < 1600
+# include "uv/stdint-msvc2008.h"
+#else
+# include <stdint.h>
+#endif
+
+#include "uv.h"
+#include "uv-common.h"
+
+#define UV__INET_ADDRSTRLEN         16
+#define UV__INET6_ADDRSTRLEN        46
+
+
+static int inet_ntop4(const unsigned char *src, char *dst, size_t size);
+static int inet_ntop6(const unsigned char *src, char *dst, size_t size);
+static int inet_pton4(const char *src, unsigned char *dst);
+static int inet_pton6(const char *src, unsigned char *dst);
+
+
+int uv_inet_ntop(int af, const void* src, char* dst, size_t size) {
+  switch (af) {
+  case AF_INET:
+    return (inet_ntop4((const unsigned char*)src, dst, size));
+  case AF_INET6:
+    return (inet_ntop6((const unsigned char*)src, dst, size));
+  default:
+    return UV_EAFNOSUPPORT;
+  }
+  /* NOTREACHED */
+}
+
+
+static int inet_ntop4(const unsigned char *src, char *dst, size_t size) {
+  static const char fmt[] = "%u.%u.%u.%u";
+  char tmp[UV__INET_ADDRSTRLEN];
+  int l;
+
+  l = snprintf(tmp, sizeof(tmp), fmt, src[0], src[1], src[2], src[3]);
+  if (l <= 0 || (size_t) l >= size) {
+    return UV_ENOSPC;
+  }
+  strncpy(dst, tmp, size);
+  dst[size - 1] = '\0';
+  return 0;
+}
+
+
+static int inet_ntop6(const unsigned char *src, char *dst, size_t size) {
+  /*
+   * Note that int32_t and int16_t need only be "at least" large enough
+   * to contain a value of the specified size.  On some systems, like
+   * Crays, there is no such thing as an integer variable with 16 bits.
+   * Keep this in mind if you think this function should have been coded
+   * to use pointer overlays.  All the world's not a VAX.
+   */
+  char tmp[UV__INET6_ADDRSTRLEN], *tp;
+  struct { int base, len; } best, cur;
+  unsigned int words[sizeof(struct in6_addr) / sizeof(uint16_t)];
+  int i;
+
+  /*
+   * Preprocess:
+   *  Copy the input (bytewise) array into a wordwise array.
+   *  Find the longest run of 0x00's in src[] for :: shorthanding.
+   */
+  memset(words, '\0', sizeof words);
+  for (i = 0; i < (int) sizeof(struct in6_addr); i++)
+    words[i / 2] |= (src[i] << ((1 - (i % 2)) << 3));
+  best.base = -1;
+  best.len = 0;
+  cur.base = -1;
+  cur.len = 0;
+  for (i = 0; i < (int) ARRAY_SIZE(words); i++) {
+    if (words[i] == 0) {
+      if (cur.base == -1)
+        cur.base = i, cur.len = 1;
+      else
+        cur.len++;
+    } else {
+      if (cur.base != -1) {
+        if (best.base == -1 || cur.len > best.len)
+          best = cur;
+        cur.base = -1;
+      }
+    }
+  }
+  if (cur.base != -1) {
+    if (best.base == -1 || cur.len > best.len)
+      best = cur;
+  }
+  if (best.base != -1 && best.len < 2)
+    best.base = -1;
+
+  /*
+   * Format the result.
+   */
+  tp = tmp;
+  for (i = 0; i < (int) ARRAY_SIZE(words); i++) {
+    /* Are we inside the best run of 0x00's? */
+    if (best.base != -1 && i >= best.base &&
+        i < (best.base + best.len)) {
+      if (i == best.base)
+        *tp++ = ':';
+      continue;
+    }
+    /* Are we following an initial run of 0x00s or any real hex? */
+    if (i != 0)
+      *tp++ = ':';
+    /* Is this address an encapsulated IPv4? */
+    if (i == 6 && best.base == 0 && (best.len == 6 ||
+        (best.len == 7 && words[7] != 0x0001) ||
+        (best.len == 5 && words[5] == 0xffff))) {
+      int err = inet_ntop4(src+12, tp, sizeof tmp - (tp - tmp));
+      if (err)
+        return err;
+      tp += strlen(tp);
+      break;
+    }
+    tp += sprintf(tp, "%x", words[i]);
+  }
+  /* Was it a trailing run of 0x00's? */
+  if (best.base != -1 && (best.base + best.len) == ARRAY_SIZE(words))
+    *tp++ = ':';
+  *tp++ = '\0';
+
+  /*
+   * Check for overflow, copy, and we're done.
+   */
+  if ((size_t)(tp - tmp) > size) {
+    return UV_ENOSPC;
+  }
+  strcpy(dst, tmp);
+  return 0;
+}
+
+
+int uv_inet_pton(int af, const char* src, void* dst) {
+  if (src == NULL || dst == NULL)
+    return UV_EINVAL;
+
+  switch (af) {
+  case AF_INET:
+    return (inet_pton4(src, (unsigned char*)dst));
+  case AF_INET6: {
+    int len;
+    char tmp[UV__INET6_ADDRSTRLEN], *s;
+    const char *p;
+    s = (char*) src;
+    p = strchr(src, '%');
+    if (p != NULL) {
+      s = tmp;
+      len = p - src;
+      if (len > UV__INET6_ADDRSTRLEN-1)
+        return UV_EINVAL;
+      memcpy(s, src, len);
+      s[len] = '\0';
+    }
+    return inet_pton6(s, (unsigned char*)dst);
+  }
+  default:
+    return UV_EAFNOSUPPORT;
+  }
+  /* NOTREACHED */
+}
+
+
+static int inet_pton4(const char *src, unsigned char *dst) {
+  static const char digits[] = "0123456789";
+  int saw_digit, octets, ch;
+  unsigned char tmp[sizeof(struct in_addr)], *tp;
+
+  saw_digit = 0;
+  octets = 0;
+  *(tp = tmp) = 0;
+  while ((ch = *src++) != '\0') {
+    const char *pch;
+
+    if ((pch = strchr(digits, ch)) != NULL) {
+      unsigned int nw = *tp * 10 + (pch - digits);
+
+      if (saw_digit && *tp == 0)
+        return UV_EINVAL;
+      if (nw > 255)
+        return UV_EINVAL;
+      *tp = nw;
+      if (!saw_digit) {
+        if (++octets > 4)
+          return UV_EINVAL;
+        saw_digit = 1;
+      }
+    } else if (ch == '.' && saw_digit) {
+      if (octets == 4)
+        return UV_EINVAL;
+      *++tp = 0;
+      saw_digit = 0;
+    } else
+      return UV_EINVAL;
+  }
+  if (octets < 4)
+    return UV_EINVAL;
+  memcpy(dst, tmp, sizeof(struct in_addr));
+  return 0;
+}
+
+
+static int inet_pton6(const char *src, unsigned char *dst) {
+  static const char xdigits_l[] = "0123456789abcdef",
+                    xdigits_u[] = "0123456789ABCDEF";
+  unsigned char tmp[sizeof(struct in6_addr)], *tp, *endp, *colonp;
+  const char *xdigits, *curtok;
+  int ch, seen_xdigits;
+  unsigned int val;
+
+  memset((tp = tmp), '\0', sizeof tmp);
+  endp = tp + sizeof tmp;
+  colonp = NULL;
+  /* Leading :: requires some special handling. */
+  if (*src == ':')
+    if (*++src != ':')
+      return UV_EINVAL;
+  curtok = src;
+  seen_xdigits = 0;
+  val = 0;
+  while ((ch = *src++) != '\0') {
+    const char *pch;
+
+    if ((pch = strchr((xdigits = xdigits_l), ch)) == NULL)
+      pch = strchr((xdigits = xdigits_u), ch);
+    if (pch != NULL) {
+      val <<= 4;
+      val |= (pch - xdigits);
+      if (++seen_xdigits > 4)
+        return UV_EINVAL;
+      continue;
+    }
+    if (ch == ':') {
+      curtok = src;
+      if (!seen_xdigits) {
+        if (colonp)
+          return UV_EINVAL;
+        colonp = tp;
+        continue;
+      } else if (*src == '\0') {
+        return UV_EINVAL;
+      }
+      if (tp + sizeof(uint16_t) > endp)
+        return UV_EINVAL;
+      *tp++ = (unsigned char) (val >> 8) & 0xff;
+      *tp++ = (unsigned char) val & 0xff;
+      seen_xdigits = 0;
+      val = 0;
+      continue;
+    }
+    if (ch == '.' && ((tp + sizeof(struct in_addr)) <= endp)) {
+      int err = inet_pton4(curtok, tp);
+      if (err == 0) {
+        tp += sizeof(struct in_addr);
+        seen_xdigits = 0;
+        break;  /*%< '\\0' was seen by inet_pton4(). */
+      }
+    }
+    return UV_EINVAL;
+  }
+  if (seen_xdigits) {
+    if (tp + sizeof(uint16_t) > endp)
+      return UV_EINVAL;
+    *tp++ = (unsigned char) (val >> 8) & 0xff;
+    *tp++ = (unsigned char) val & 0xff;
+  }
+  if (colonp != NULL) {
+    /*
+     * Since some memmove()'s erroneously fail to handle
+     * overlapping regions, we'll do the shift by hand.
+     */
+    const int n = tp - colonp;
+    int i;
+
+    if (tp == endp)
+      return UV_EINVAL;
+    for (i = 1; i <= n; i++) {
+      endp[- i] = colonp[n - i];
+      colonp[n - i] = 0;
+    }
+    tp = endp;
+  }
+  if (tp != endp)
+    return UV_EINVAL;
+  memcpy(dst, tmp, sizeof tmp);
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/queue.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/queue.h
new file mode 100644
index 0000000..ff3540a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/queue.h
@@ -0,0 +1,108 @@
+/* Copyright (c) 2013, Ben Noordhuis <info@bnoordhuis.nl>
+ *
+ * Permission to use, copy, modify, and/or distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#ifndef QUEUE_H_
+#define QUEUE_H_
+
+#include <stddef.h>
+
+typedef void *QUEUE[2];
+
+/* Private macros. */
+#define QUEUE_NEXT(q)       (*(QUEUE **) &((*(q))[0]))
+#define QUEUE_PREV(q)       (*(QUEUE **) &((*(q))[1]))
+#define QUEUE_PREV_NEXT(q)  (QUEUE_NEXT(QUEUE_PREV(q)))
+#define QUEUE_NEXT_PREV(q)  (QUEUE_PREV(QUEUE_NEXT(q)))
+
+/* Public macros. */
+#define QUEUE_DATA(ptr, type, field)                                          \
+  ((type *) ((char *) (ptr) - offsetof(type, field)))
+
+/* Important note: mutating the list while QUEUE_FOREACH is
+ * iterating over its elements results in undefined behavior.
+ */
+#define QUEUE_FOREACH(q, h)                                                   \
+  for ((q) = QUEUE_NEXT(h); (q) != (h); (q) = QUEUE_NEXT(q))
+
+#define QUEUE_EMPTY(q)                                                        \
+  ((const QUEUE *) (q) == (const QUEUE *) QUEUE_NEXT(q))
+
+#define QUEUE_HEAD(q)                                                         \
+  (QUEUE_NEXT(q))
+
+#define QUEUE_INIT(q)                                                         \
+  do {                                                                        \
+    QUEUE_NEXT(q) = (q);                                                      \
+    QUEUE_PREV(q) = (q);                                                      \
+  }                                                                           \
+  while (0)
+
+#define QUEUE_ADD(h, n)                                                       \
+  do {                                                                        \
+    QUEUE_PREV_NEXT(h) = QUEUE_NEXT(n);                                       \
+    QUEUE_NEXT_PREV(n) = QUEUE_PREV(h);                                       \
+    QUEUE_PREV(h) = QUEUE_PREV(n);                                            \
+    QUEUE_PREV_NEXT(h) = (h);                                                 \
+  }                                                                           \
+  while (0)
+
+#define QUEUE_SPLIT(h, q, n)                                                  \
+  do {                                                                        \
+    QUEUE_PREV(n) = QUEUE_PREV(h);                                            \
+    QUEUE_PREV_NEXT(n) = (n);                                                 \
+    QUEUE_NEXT(n) = (q);                                                      \
+    QUEUE_PREV(h) = QUEUE_PREV(q);                                            \
+    QUEUE_PREV_NEXT(h) = (h);                                                 \
+    QUEUE_PREV(q) = (n);                                                      \
+  }                                                                           \
+  while (0)
+
+#define QUEUE_MOVE(h, n)                                                      \
+  do {                                                                        \
+    if (QUEUE_EMPTY(h))                                                       \
+      QUEUE_INIT(n);                                                          \
+    else {                                                                    \
+      QUEUE* q = QUEUE_HEAD(h);                                               \
+      QUEUE_SPLIT(h, q, n);                                                   \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+#define QUEUE_INSERT_HEAD(h, q)                                               \
+  do {                                                                        \
+    QUEUE_NEXT(q) = QUEUE_NEXT(h);                                            \
+    QUEUE_PREV(q) = (h);                                                      \
+    QUEUE_NEXT_PREV(q) = (q);                                                 \
+    QUEUE_NEXT(h) = (q);                                                      \
+  }                                                                           \
+  while (0)
+
+#define QUEUE_INSERT_TAIL(h, q)                                               \
+  do {                                                                        \
+    QUEUE_NEXT(q) = (h);                                                      \
+    QUEUE_PREV(q) = QUEUE_PREV(h);                                            \
+    QUEUE_PREV_NEXT(q) = (q);                                                 \
+    QUEUE_PREV(h) = (q);                                                      \
+  }                                                                           \
+  while (0)
+
+#define QUEUE_REMOVE(q)                                                       \
+  do {                                                                        \
+    QUEUE_PREV_NEXT(q) = QUEUE_NEXT(q);                                       \
+    QUEUE_NEXT_PREV(q) = QUEUE_PREV(q);                                       \
+  }                                                                           \
+  while (0)
+
+#endif /* QUEUE_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/threadpool.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/threadpool.cpp
new file mode 100644
index 0000000..3b4b7cf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/threadpool.cpp
@@ -0,0 +1,318 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv-common.h"
+
+#if !defined(_WIN32)
+# include "unix/internal.h"
+#endif
+
+#include <stdlib.h>
+
+#define MAX_THREADPOOL_SIZE 128
+
+static uv_once_t once = UV_ONCE_INIT;
+static uv_cond_t cond;
+static uv_mutex_t mutex;
+static unsigned int idle_threads;
+static unsigned int nthreads;
+static uv_thread_t* threads;
+static uv_thread_t default_threads[4];
+static QUEUE exit_message;
+static QUEUE wq;
+
+
+static void uv__cancelled(struct uv__work* w) {
+  abort();
+}
+
+
+/* To avoid deadlock with uv_cancel() it's crucial that the worker
+ * never holds the global mutex and the loop-local mutex at the same time.
+ */
+static void worker(void* arg) {
+  struct uv__work* w;
+  QUEUE* q;
+
+  uv_sem_post((uv_sem_t*) arg);
+  arg = NULL;
+
+  for (;;) {
+    uv_mutex_lock(&mutex);
+
+    while (QUEUE_EMPTY(&wq)) {
+      idle_threads += 1;
+      uv_cond_wait(&cond, &mutex);
+      idle_threads -= 1;
+    }
+
+    q = QUEUE_HEAD(&wq);
+
+    if (q == &exit_message)
+      uv_cond_signal(&cond);
+    else {
+      QUEUE_REMOVE(q);
+      QUEUE_INIT(q);  /* Signal uv_cancel() that the work req is
+                             executing. */
+    }
+
+    uv_mutex_unlock(&mutex);
+
+    if (q == &exit_message)
+      break;
+
+    w = QUEUE_DATA(q, struct uv__work, wq);
+    w->work(w);
+
+    uv_mutex_lock(&w->loop->wq_mutex);
+    w->work = NULL;  /* Signal uv_cancel() that the work req is done
+                        executing. */
+    QUEUE_INSERT_TAIL(&w->loop->wq, &w->wq);
+    uv_async_send(&w->loop->wq_async);
+    uv_mutex_unlock(&w->loop->wq_mutex);
+  }
+}
+
+
+static void post(QUEUE* q) {
+  uv_mutex_lock(&mutex);
+  QUEUE_INSERT_TAIL(&wq, q);
+  if (idle_threads > 0)
+    uv_cond_signal(&cond);
+  uv_mutex_unlock(&mutex);
+}
+
+
+#ifndef _WIN32
+UV_DESTRUCTOR(static void cleanup(void)) {
+  unsigned int i;
+
+  if (nthreads == 0)
+    return;
+
+  post(&exit_message);
+
+  for (i = 0; i < nthreads; i++)
+    if (uv_thread_join(threads + i))
+      abort();
+
+  if (threads != default_threads)
+    uv__free(threads);
+
+  uv_mutex_destroy(&mutex);
+  uv_cond_destroy(&cond);
+
+  threads = NULL;
+  nthreads = 0;
+}
+#endif
+
+
+static void init_threads(void) {
+  unsigned int i;
+  const char* val;
+  uv_sem_t sem;
+
+  nthreads = ARRAY_SIZE(default_threads);
+  val = getenv("UV_THREADPOOL_SIZE");
+  if (val != NULL)
+    nthreads = atoi(val);
+  if (nthreads == 0)
+    nthreads = 1;
+  if (nthreads > MAX_THREADPOOL_SIZE)
+    nthreads = MAX_THREADPOOL_SIZE;
+
+  threads = default_threads;
+  if (nthreads > ARRAY_SIZE(default_threads)) {
+    threads = (uv_thread_t*)uv__malloc(nthreads * sizeof(threads[0]));
+    if (threads == NULL) {
+      nthreads = ARRAY_SIZE(default_threads);
+      threads = default_threads;
+    }
+  }
+
+  if (uv_cond_init(&cond))
+    abort();
+
+  if (uv_mutex_init(&mutex))
+    abort();
+
+  QUEUE_INIT(&wq);
+
+  if (uv_sem_init(&sem, 0))
+    abort();
+
+  for (i = 0; i < nthreads; i++)
+    if (uv_thread_create(threads + i, worker, &sem))
+      abort();
+
+  for (i = 0; i < nthreads; i++)
+    uv_sem_wait(&sem);
+
+  uv_sem_destroy(&sem);
+}
+
+
+#ifndef _WIN32
+static void reset_once(void) {
+  uv_once_t child_once = UV_ONCE_INIT;
+  memcpy(&once, &child_once, sizeof(child_once));
+}
+#endif
+
+
+static void init_once(void) {
+#ifndef _WIN32
+  /* Re-initialize the threadpool after fork.
+   * Note that this discards the global mutex and condition as well
+   * as the work queue.
+   */
+  if (pthread_atfork(NULL, NULL, &reset_once))
+    abort();
+#endif
+  init_threads();
+}
+
+
+void uv__work_submit(uv_loop_t* loop,
+                     struct uv__work* w,
+                     void (*work)(struct uv__work* w),
+                     void (*done)(struct uv__work* w, int status)) {
+  uv_once(&once, init_once);
+  w->loop = loop;
+  w->work = work;
+  w->done = done;
+  post(&w->wq);
+}
+
+
+static int uv__work_cancel(uv_loop_t* loop, uv_req_t* req, struct uv__work* w) {
+  int cancelled;
+
+  uv_mutex_lock(&mutex);
+  uv_mutex_lock(&w->loop->wq_mutex);
+
+  cancelled = !QUEUE_EMPTY(&w->wq) && w->work != NULL;
+  if (cancelled)
+    QUEUE_REMOVE(&w->wq);
+
+  uv_mutex_unlock(&w->loop->wq_mutex);
+  uv_mutex_unlock(&mutex);
+
+  if (!cancelled)
+    return UV_EBUSY;
+
+  w->work = uv__cancelled;
+  uv_mutex_lock(&loop->wq_mutex);
+  QUEUE_INSERT_TAIL(&loop->wq, &w->wq);
+  uv_async_send(&loop->wq_async);
+  uv_mutex_unlock(&loop->wq_mutex);
+
+  return 0;
+}
+
+
+void uv__work_done(uv_async_t* handle) {
+  struct uv__work* w;
+  uv_loop_t* loop;
+  QUEUE* q;
+  QUEUE wq;
+  int err;
+
+  loop = container_of(handle, uv_loop_t, wq_async);
+  uv_mutex_lock(&loop->wq_mutex);
+  QUEUE_MOVE(&loop->wq, &wq);
+  uv_mutex_unlock(&loop->wq_mutex);
+
+  while (!QUEUE_EMPTY(&wq)) {
+    q = QUEUE_HEAD(&wq);
+    QUEUE_REMOVE(q);
+
+    w = container_of(q, struct uv__work, wq);
+    err = (w->work == uv__cancelled) ? UV_ECANCELED : 0;
+    w->done(w, err);
+  }
+}
+
+
+static void uv__queue_work(struct uv__work* w) {
+  uv_work_t* req = container_of(w, uv_work_t, work_req);
+
+  req->work_cb(req);
+}
+
+
+static void uv__queue_done(struct uv__work* w, int err) {
+  uv_work_t* req;
+
+  req = container_of(w, uv_work_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  if (req->after_work_cb == NULL)
+    return;
+
+  req->after_work_cb(req, err);
+}
+
+
+int uv_queue_work(uv_loop_t* loop,
+                  uv_work_t* req,
+                  uv_work_cb work_cb,
+                  uv_after_work_cb after_work_cb) {
+  if (work_cb == NULL)
+    return UV_EINVAL;
+
+  uv__req_init(loop, req, UV_WORK);
+  req->loop = loop;
+  req->work_cb = work_cb;
+  req->after_work_cb = after_work_cb;
+  uv__work_submit(loop, &req->work_req, uv__queue_work, uv__queue_done);
+  return 0;
+}
+
+
+int uv_cancel(uv_req_t* req) {
+  struct uv__work* wreq;
+  uv_loop_t* loop;
+
+  switch (req->type) {
+  case UV_FS:
+    loop =  ((uv_fs_t*) req)->loop;
+    wreq = &((uv_fs_t*) req)->work_req;
+    break;
+  case UV_GETADDRINFO:
+    loop =  ((uv_getaddrinfo_t*) req)->loop;
+    wreq = &((uv_getaddrinfo_t*) req)->work_req;
+    break;
+  case UV_GETNAMEINFO:
+    loop = ((uv_getnameinfo_t*) req)->loop;
+    wreq = &((uv_getnameinfo_t*) req)->work_req;
+    break;
+  case UV_WORK:
+    loop =  ((uv_work_t*) req)->loop;
+    wreq = &((uv_work_t*) req)->work_req;
+    break;
+  default:
+    return UV_EINVAL;
+  }
+
+  return uv__work_cancel(loop, req, wreq);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/android-ifaddrs.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/android-ifaddrs.cpp
new file mode 100644
index 0000000..ab6b029
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/android-ifaddrs.cpp
@@ -0,0 +1,710 @@
+/*
+Copyright (c) 2013, Kenneth MacKay
+Copyright (c) 2014, Emergya (Cloud4all, FP7/2007-2013 grant agreement #289016)
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without modification,
+are permitted provided that the following conditions are met:
+ * Redistributions of source code must retain the above copyright notice, this
+   list of conditions and the following disclaimer.
+ * Redistributions in binary form must reproduce the above copyright notice,
+   this list of conditions and the following disclaimer in the documentation
+   and/or other materials provided with the distribution.
+
+THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
+ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
+WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
+DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR
+ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
+(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
+LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON
+ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
+SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+#include "uv/android-ifaddrs.h"
+#include "uv-common.h"
+
+#include <string.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <unistd.h>
+#include <sys/socket.h>
+#include <net/if_arp.h>
+#include <netinet/in.h>
+#include <linux/netlink.h>
+#include <linux/rtnetlink.h>
+
+typedef struct NetlinkList
+{
+    struct NetlinkList *m_next;
+    struct nlmsghdr *m_data;
+    unsigned int m_size;
+} NetlinkList;
+
+static int netlink_socket(pid_t *p_pid)
+{
+    struct sockaddr_nl l_addr;
+    socklen_t l_len;
+
+    int l_socket = socket(PF_NETLINK, SOCK_RAW, NETLINK_ROUTE);
+    if(l_socket < 0)
+    {
+        return -1;
+    }
+
+    memset(&l_addr, 0, sizeof(l_addr));
+    l_addr.nl_family = AF_NETLINK;
+    if(bind(l_socket, (struct sockaddr *)&l_addr, sizeof(l_addr)) < 0)
+    {
+        close(l_socket);
+        return -1;
+    }
+
+    l_len = sizeof(l_addr);
+    if(getsockname(l_socket, (struct sockaddr *)&l_addr, &l_len) < 0)
+    {
+        close(l_socket);
+        return -1;
+    }
+    *p_pid = l_addr.nl_pid;
+
+    return l_socket;
+}
+
+static int netlink_send(int p_socket, int p_request)
+{
+    char l_buffer[NLMSG_ALIGN(sizeof(struct nlmsghdr)) + NLMSG_ALIGN(sizeof(struct rtgenmsg))];
+
+    struct nlmsghdr *l_hdr;
+    struct rtgenmsg *l_msg;
+    struct sockaddr_nl l_addr;
+
+    memset(l_buffer, 0, sizeof(l_buffer));
+
+    l_hdr = (struct nlmsghdr *)l_buffer;
+    l_msg = (struct rtgenmsg *)NLMSG_DATA(l_hdr);
+
+    l_hdr->nlmsg_len = NLMSG_LENGTH(sizeof(*l_msg));
+    l_hdr->nlmsg_type = p_request;
+    l_hdr->nlmsg_flags = NLM_F_ROOT | NLM_F_MATCH | NLM_F_REQUEST;
+    l_hdr->nlmsg_pid = 0;
+    l_hdr->nlmsg_seq = p_socket;
+    l_msg->rtgen_family = AF_UNSPEC;
+
+    memset(&l_addr, 0, sizeof(l_addr));
+    l_addr.nl_family = AF_NETLINK;
+    return (sendto(p_socket, l_hdr, l_hdr->nlmsg_len, 0, (struct sockaddr *)&l_addr, sizeof(l_addr)));
+}
+
+static int netlink_recv(int p_socket, void *p_buffer, size_t p_len)
+{
+    struct sockaddr_nl l_addr;
+    struct msghdr l_msg;
+
+    struct iovec l_iov;
+    l_iov.iov_base = p_buffer;
+    l_iov.iov_len = p_len;
+
+    for(;;)
+    {
+        int l_result;
+        l_msg.msg_name = (void *)&l_addr;
+        l_msg.msg_namelen = sizeof(l_addr);
+        l_msg.msg_iov = &l_iov;
+        l_msg.msg_iovlen = 1;
+        l_msg.msg_control = NULL;
+        l_msg.msg_controllen = 0;
+        l_msg.msg_flags = 0;
+        l_result = recvmsg(p_socket, &l_msg, 0);
+
+        if(l_result < 0)
+        {
+            if(errno == EINTR)
+            {
+                continue;
+            }
+            return -2;
+        }
+
+        /* Buffer was too small */
+        if(l_msg.msg_flags & MSG_TRUNC)
+        {
+            return -1;
+        }
+        return l_result;
+    }
+}
+
+static struct nlmsghdr *getNetlinkResponse(int p_socket, pid_t p_pid, int *p_size, int *p_done)
+{
+    size_t l_size = 4096;
+    void *l_buffer = NULL;
+
+    for(;;)
+    {
+        int l_read;
+
+        uv__free(l_buffer);
+        l_buffer = uv__malloc(l_size);
+        if (l_buffer == NULL)
+        {
+            return NULL;
+        }
+
+        l_read = netlink_recv(p_socket, l_buffer, l_size);
+        *p_size = l_read;
+        if(l_read == -2)
+        {
+            uv__free(l_buffer);
+            return NULL;
+        }
+        if(l_read >= 0)
+        {
+            struct nlmsghdr *l_hdr;
+            for(l_hdr = (struct nlmsghdr *)l_buffer; NLMSG_OK(l_hdr, (unsigned int)l_read); l_hdr = (struct nlmsghdr *)NLMSG_NEXT(l_hdr, l_read))
+            {
+                if((pid_t)l_hdr->nlmsg_pid != p_pid || (int)l_hdr->nlmsg_seq != p_socket)
+                {
+                    continue;
+                }
+
+                if(l_hdr->nlmsg_type == NLMSG_DONE)
+                {
+                    *p_done = 1;
+                    break;
+                }
+
+                if(l_hdr->nlmsg_type == NLMSG_ERROR)
+                {
+                    uv__free(l_buffer);
+                    return NULL;
+                }
+            }
+            return l_buffer;
+        }
+
+        l_size *= 2;
+    }
+}
+
+static NetlinkList *newListItem(struct nlmsghdr *p_data, unsigned int p_size)
+{
+    NetlinkList *l_item = (NetlinkList*)uv__malloc(sizeof(NetlinkList));
+    if (l_item == NULL)
+    {
+        return NULL;
+    }
+
+    l_item->m_next = NULL;
+    l_item->m_data = p_data;
+    l_item->m_size = p_size;
+    return l_item;
+}
+
+static void freeResultList(NetlinkList *p_list)
+{
+    NetlinkList *l_cur;
+    while(p_list)
+    {
+        l_cur = p_list;
+        p_list = p_list->m_next;
+        uv__free(l_cur->m_data);
+        uv__free(l_cur);
+    }
+}
+
+static NetlinkList *getResultList(int p_socket, int p_request, pid_t p_pid)
+{
+    int l_size;
+    int l_done;
+    NetlinkList *l_list;
+    NetlinkList *l_end;
+
+    if(netlink_send(p_socket, p_request) < 0)
+    {
+        return NULL;
+    }
+
+    l_list = NULL;
+    l_end = NULL;
+
+    l_done = 0;
+    while(!l_done)
+    {
+        NetlinkList *l_item;
+
+        struct nlmsghdr *l_hdr = getNetlinkResponse(p_socket, p_pid, &l_size, &l_done);
+        /* Error */
+        if(!l_hdr)
+        {
+            freeResultList(l_list);
+            return NULL;
+        }
+
+        l_item = newListItem(l_hdr, l_size);
+        if (!l_item)
+        {
+            freeResultList(l_list);
+            return NULL;
+        }
+        if(!l_list)
+        {
+            l_list = l_item;
+        }
+        else
+        {
+            l_end->m_next = l_item;
+        }
+        l_end = l_item;
+    }
+    return l_list;
+}
+
+static size_t maxSize(size_t a, size_t b)
+{
+    return (a > b ? a : b);
+}
+
+static size_t calcAddrLen(sa_family_t p_family, int p_dataSize)
+{
+    switch(p_family)
+    {
+        case AF_INET:
+            return sizeof(struct sockaddr_in);
+        case AF_INET6:
+            return sizeof(struct sockaddr_in6);
+        case AF_PACKET:
+            return maxSize(sizeof(struct sockaddr_ll), offsetof(struct sockaddr_ll, sll_addr) + p_dataSize);
+        default:
+            return maxSize(sizeof(struct sockaddr), offsetof(struct sockaddr, sa_data) + p_dataSize);
+    }
+}
+
+static void makeSockaddr(sa_family_t p_family, struct sockaddr *p_dest, void *p_data, size_t p_size)
+{
+    switch(p_family)
+    {
+        case AF_INET:
+            memcpy(&((struct sockaddr_in*)p_dest)->sin_addr, p_data, p_size);
+            break;
+        case AF_INET6:
+            memcpy(&((struct sockaddr_in6*)p_dest)->sin6_addr, p_data, p_size);
+            break;
+        case AF_PACKET:
+            memcpy(((struct sockaddr_ll*)p_dest)->sll_addr, p_data, p_size);
+            ((struct sockaddr_ll*)p_dest)->sll_halen = p_size;
+            break;
+        default:
+            memcpy(p_dest->sa_data, p_data, p_size);
+            break;
+    }
+    p_dest->sa_family = p_family;
+}
+
+static void addToEnd(struct ifaddrs **p_resultList, struct ifaddrs *p_entry)
+{
+    if(!*p_resultList)
+    {
+        *p_resultList = p_entry;
+    }
+    else
+    {
+        struct ifaddrs *l_cur = *p_resultList;
+        while(l_cur->ifa_next)
+        {
+            l_cur = l_cur->ifa_next;
+        }
+        l_cur->ifa_next = p_entry;
+    }
+}
+
+static int interpretLink(struct nlmsghdr *p_hdr, struct ifaddrs **p_resultList)
+{
+    struct ifaddrs *l_entry;
+
+    char *l_index;
+    char *l_name;
+    char *l_addr;
+    char *l_data;
+
+    struct ifinfomsg *l_info = (struct ifinfomsg *)NLMSG_DATA(p_hdr);
+
+    size_t l_nameSize = 0;
+    size_t l_addrSize = 0;
+    size_t l_dataSize = 0;
+
+    size_t l_rtaSize = NLMSG_PAYLOAD(p_hdr, sizeof(struct ifinfomsg));
+    struct rtattr *l_rta;
+    for(l_rta = IFLA_RTA(l_info); RTA_OK(l_rta, l_rtaSize); l_rta = RTA_NEXT(l_rta, l_rtaSize))
+    {
+        size_t l_rtaDataSize = RTA_PAYLOAD(l_rta);
+        switch(l_rta->rta_type)
+        {
+            case IFLA_ADDRESS:
+            case IFLA_BROADCAST:
+                l_addrSize += NLMSG_ALIGN(calcAddrLen(AF_PACKET, l_rtaDataSize));
+                break;
+            case IFLA_IFNAME:
+                l_nameSize += NLMSG_ALIGN(l_rtaSize + 1);
+                break;
+            case IFLA_STATS:
+                l_dataSize += NLMSG_ALIGN(l_rtaSize);
+                break;
+            default:
+                break;
+        }
+    }
+
+    l_entry = (struct ifaddrs*)uv__malloc(sizeof(struct ifaddrs) + sizeof(int) + l_nameSize + l_addrSize + l_dataSize);
+    if (l_entry == NULL)
+    {
+        return -1;
+    }
+    memset(l_entry, 0, sizeof(struct ifaddrs));
+    l_entry->ifa_name = "";
+
+    l_index = ((char *)l_entry) + sizeof(struct ifaddrs);
+    l_name = l_index + sizeof(int);
+    l_addr = l_name + l_nameSize;
+    l_data = l_addr + l_addrSize;
+
+    /* Save the interface index so we can look it up when handling the
+     * addresses.
+     */
+    memcpy(l_index, &l_info->ifi_index, sizeof(int));
+
+    l_entry->ifa_flags = l_info->ifi_flags;
+
+    l_rtaSize = NLMSG_PAYLOAD(p_hdr, sizeof(struct ifinfomsg));
+    for(l_rta = IFLA_RTA(l_info); RTA_OK(l_rta, l_rtaSize); l_rta = RTA_NEXT(l_rta, l_rtaSize))
+    {
+        void *l_rtaData = RTA_DATA(l_rta);
+        size_t l_rtaDataSize = RTA_PAYLOAD(l_rta);
+        switch(l_rta->rta_type)
+        {
+            case IFLA_ADDRESS:
+            case IFLA_BROADCAST:
+            {
+                size_t l_addrLen = calcAddrLen(AF_PACKET, l_rtaDataSize);
+                makeSockaddr(AF_PACKET, (struct sockaddr *)l_addr, l_rtaData, l_rtaDataSize);
+                ((struct sockaddr_ll *)l_addr)->sll_ifindex = l_info->ifi_index;
+                ((struct sockaddr_ll *)l_addr)->sll_hatype = l_info->ifi_type;
+                if(l_rta->rta_type == IFLA_ADDRESS)
+                {
+                    l_entry->ifa_addr = (struct sockaddr *)l_addr;
+                }
+                else
+                {
+                    l_entry->ifa_broadaddr = (struct sockaddr *)l_addr;
+                }
+                l_addr += NLMSG_ALIGN(l_addrLen);
+                break;
+            }
+            case IFLA_IFNAME:
+                strncpy(l_name, l_rtaData, l_rtaDataSize);
+                l_name[l_rtaDataSize] = '\0';
+                l_entry->ifa_name = l_name;
+                break;
+            case IFLA_STATS:
+                memcpy(l_data, l_rtaData, l_rtaDataSize);
+                l_entry->ifa_data = l_data;
+                break;
+            default:
+                break;
+        }
+    }
+
+    addToEnd(p_resultList, l_entry);
+    return 0;
+}
+
+static struct ifaddrs *findInterface(int p_index, struct ifaddrs **p_links, int p_numLinks)
+{
+    int l_num = 0;
+    struct ifaddrs *l_cur = *p_links;
+    while(l_cur && l_num < p_numLinks)
+    {
+        char *l_indexPtr = ((char *)l_cur) + sizeof(struct ifaddrs);
+        int l_index;
+        memcpy(&l_index, l_indexPtr, sizeof(int));
+        if(l_index == p_index)
+        {
+            return l_cur;
+        }
+
+        l_cur = l_cur->ifa_next;
+        ++l_num;
+    }
+    return NULL;
+}
+
+static int interpretAddr(struct nlmsghdr *p_hdr, struct ifaddrs **p_resultList, int p_numLinks)
+{
+    struct ifaddrmsg *l_info = (struct ifaddrmsg *)NLMSG_DATA(p_hdr);
+    struct ifaddrs *l_interface = findInterface(l_info->ifa_index, p_resultList, p_numLinks);
+
+    size_t l_nameSize = 0;
+    size_t l_addrSize = 0;
+
+    int l_addedNetmask = 0;
+
+    size_t l_rtaSize = NLMSG_PAYLOAD(p_hdr, sizeof(struct ifaddrmsg));
+    struct rtattr *l_rta;
+    struct ifaddrs *l_entry;
+
+    char *l_name;
+    char *l_addr;
+
+    for(l_rta = IFA_RTA(l_info); RTA_OK(l_rta, l_rtaSize); l_rta = RTA_NEXT(l_rta, l_rtaSize))
+    {
+        size_t l_rtaDataSize = RTA_PAYLOAD(l_rta);
+        if(l_info->ifa_family == AF_PACKET)
+        {
+            continue;
+        }
+
+        switch(l_rta->rta_type)
+        {
+            case IFA_ADDRESS:
+            case IFA_LOCAL:
+                if((l_info->ifa_family == AF_INET || l_info->ifa_family == AF_INET6) && !l_addedNetmask)
+                {
+                    /* Make room for netmask */
+                    l_addrSize += NLMSG_ALIGN(calcAddrLen(l_info->ifa_family, l_rtaDataSize));
+                    l_addedNetmask = 1;
+                }
+            case IFA_BROADCAST:
+                l_addrSize += NLMSG_ALIGN(calcAddrLen(l_info->ifa_family, l_rtaDataSize));
+                break;
+            case IFA_LABEL:
+                l_nameSize += NLMSG_ALIGN(l_rtaDataSize + 1);
+                break;
+            default:
+                break;
+        }
+    }
+
+    l_entry = (struct ifaddrs*)uv__malloc(sizeof(struct ifaddrs) + l_nameSize + l_addrSize);
+    if (l_entry == NULL)
+    {
+        return -1;
+    }
+    memset(l_entry, 0, sizeof(struct ifaddrs));
+    l_entry->ifa_name = (l_interface ? l_interface->ifa_name : "");
+
+    l_name = ((char *)l_entry) + sizeof(struct ifaddrs);
+    l_addr = l_name + l_nameSize;
+
+    l_entry->ifa_flags = l_info->ifa_flags;
+    if(l_interface)
+    {
+        l_entry->ifa_flags |= l_interface->ifa_flags;
+    }
+
+    l_rtaSize = NLMSG_PAYLOAD(p_hdr, sizeof(struct ifaddrmsg));
+    for(l_rta = IFA_RTA(l_info); RTA_OK(l_rta, l_rtaSize); l_rta = RTA_NEXT(l_rta, l_rtaSize))
+    {
+        void *l_rtaData = RTA_DATA(l_rta);
+        size_t l_rtaDataSize = RTA_PAYLOAD(l_rta);
+        switch(l_rta->rta_type)
+        {
+            case IFA_ADDRESS:
+            case IFA_BROADCAST:
+            case IFA_LOCAL:
+            {
+                size_t l_addrLen = calcAddrLen(l_info->ifa_family, l_rtaDataSize);
+                makeSockaddr(l_info->ifa_family, (struct sockaddr *)l_addr, l_rtaData, l_rtaDataSize);
+                if(l_info->ifa_family == AF_INET6)
+                {
+                    if(IN6_IS_ADDR_LINKLOCAL((struct in6_addr *)l_rtaData) || IN6_IS_ADDR_MC_LINKLOCAL((struct in6_addr *)l_rtaData))
+                    {
+                        ((struct sockaddr_in6 *)l_addr)->sin6_scope_id = l_info->ifa_index;
+                    }
+                }
+
+                /* Apparently in a point-to-point network IFA_ADDRESS contains
+                 * the dest address and IFA_LOCAL contains the local address
+                 */
+                if(l_rta->rta_type == IFA_ADDRESS)
+                {
+                    if(l_entry->ifa_addr)
+                    {
+                        l_entry->ifa_dstaddr = (struct sockaddr *)l_addr;
+                    }
+                    else
+                    {
+                        l_entry->ifa_addr = (struct sockaddr *)l_addr;
+                    }
+                }
+                else if(l_rta->rta_type == IFA_LOCAL)
+                {
+                    if(l_entry->ifa_addr)
+                    {
+                        l_entry->ifa_dstaddr = l_entry->ifa_addr;
+                    }
+                    l_entry->ifa_addr = (struct sockaddr *)l_addr;
+                }
+                else
+                {
+                    l_entry->ifa_broadaddr = (struct sockaddr *)l_addr;
+                }
+                l_addr += NLMSG_ALIGN(l_addrLen);
+                break;
+            }
+            case IFA_LABEL:
+                strncpy(l_name, l_rtaData, l_rtaDataSize);
+                l_name[l_rtaDataSize] = '\0';
+                l_entry->ifa_name = l_name;
+                break;
+            default:
+                break;
+        }
+    }
+
+    if(l_entry->ifa_addr && (l_entry->ifa_addr->sa_family == AF_INET || l_entry->ifa_addr->sa_family == AF_INET6))
+    {
+        unsigned l_maxPrefix = (l_entry->ifa_addr->sa_family == AF_INET ? 32 : 128);
+        unsigned l_prefix = (l_info->ifa_prefixlen > l_maxPrefix ? l_maxPrefix : l_info->ifa_prefixlen);
+        unsigned char l_mask[16] = {0};
+        unsigned i;
+        for(i=0; i<(l_prefix/8); ++i)
+        {
+            l_mask[i] = 0xff;
+        }
+        if(l_prefix % 8)
+        {
+            l_mask[i] = 0xff << (8 - (l_prefix % 8));
+        }
+
+        makeSockaddr(l_entry->ifa_addr->sa_family, (struct sockaddr *)l_addr, l_mask, l_maxPrefix / 8);
+        l_entry->ifa_netmask = (struct sockaddr *)l_addr;
+    }
+
+    addToEnd(p_resultList, l_entry);
+    return 0;
+}
+
+static int interpretLinks(int p_socket, pid_t p_pid, NetlinkList *p_netlinkList, struct ifaddrs **p_resultList)
+{
+
+    int l_numLinks = 0;
+    for(; p_netlinkList; p_netlinkList = p_netlinkList->m_next)
+    {
+        unsigned int l_nlsize = p_netlinkList->m_size;
+        struct nlmsghdr *l_hdr;
+        for(l_hdr = p_netlinkList->m_data; NLMSG_OK(l_hdr, l_nlsize); l_hdr = NLMSG_NEXT(l_hdr, l_nlsize))
+        {
+            if((pid_t)l_hdr->nlmsg_pid != p_pid || (int)l_hdr->nlmsg_seq != p_socket)
+            {
+                continue;
+            }
+
+            if(l_hdr->nlmsg_type == NLMSG_DONE)
+            {
+                break;
+            }
+
+            if(l_hdr->nlmsg_type == RTM_NEWLINK)
+            {
+                if(interpretLink(l_hdr, p_resultList) == -1)
+                {
+                    return -1;
+                }
+                ++l_numLinks;
+            }
+        }
+    }
+    return l_numLinks;
+}
+
+static int interpretAddrs(int p_socket, pid_t p_pid, NetlinkList *p_netlinkList, struct ifaddrs **p_resultList, int p_numLinks)
+{
+    for(; p_netlinkList; p_netlinkList = p_netlinkList->m_next)
+    {
+        unsigned int l_nlsize = p_netlinkList->m_size;
+        struct nlmsghdr *l_hdr;
+        for(l_hdr = p_netlinkList->m_data; NLMSG_OK(l_hdr, l_nlsize); l_hdr = NLMSG_NEXT(l_hdr, l_nlsize))
+        {
+            if((pid_t)l_hdr->nlmsg_pid != p_pid || (int)l_hdr->nlmsg_seq != p_socket)
+            {
+                continue;
+            }
+
+            if(l_hdr->nlmsg_type == NLMSG_DONE)
+            {
+                break;
+            }
+
+            if(l_hdr->nlmsg_type == RTM_NEWADDR)
+            {
+                if (interpretAddr(l_hdr, p_resultList, p_numLinks) == -1)
+                {
+                    return -1;
+                }
+            }
+        }
+    }
+    return 0;
+}
+
+int getifaddrs(struct ifaddrs **ifap)
+{
+    int l_socket;
+    int l_result;
+    int l_numLinks;
+    pid_t l_pid;
+    NetlinkList *l_linkResults;
+    NetlinkList *l_addrResults;
+
+    if(!ifap)
+    {
+        return -1;
+    }
+    *ifap = NULL;
+
+    l_socket = netlink_socket(&l_pid);
+    if(l_socket < 0)
+    {
+        return -1;
+    }
+
+    l_linkResults = getResultList(l_socket, RTM_GETLINK, l_pid);
+    if(!l_linkResults)
+    {
+        close(l_socket);
+        return -1;
+    }
+
+    l_addrResults = getResultList(l_socket, RTM_GETADDR, l_pid);
+    if(!l_addrResults)
+    {
+        close(l_socket);
+        freeResultList(l_linkResults);
+        return -1;
+    }
+
+    l_result = 0;
+    l_numLinks = interpretLinks(l_socket, l_pid, l_linkResults, ifap);
+    if(l_numLinks == -1 || interpretAddrs(l_socket, l_pid, l_addrResults, ifap, l_numLinks) == -1)
+    {
+        l_result = -1;
+    }
+
+    freeResultList(l_linkResults);
+    freeResultList(l_addrResults);
+    close(l_socket);
+    return l_result;
+}
+
+void freeifaddrs(struct ifaddrs *ifa)
+{
+    struct ifaddrs *l_cur;
+    while(ifa)
+    {
+        l_cur = ifa;
+        ifa = ifa->ifa_next;
+        uv__free(l_cur);
+    }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/async.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/async.cpp
new file mode 100644
index 0000000..0b450ae
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/async.cpp
@@ -0,0 +1,269 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* This file contains both the uv__async internal infrastructure and the
+ * user-facing uv_async_t functions.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include "atomic-ops.h"
+
+#include <errno.h>
+#include <stdio.h>  /* snprintf() */
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+static void uv__async_send(uv_loop_t* loop);
+static int uv__async_start(uv_loop_t* loop);
+static int uv__async_eventfd(void);
+
+
+int uv_async_init(uv_loop_t* loop, uv_async_t* handle, uv_async_cb async_cb) {
+  int err;
+
+  err = uv__async_start(loop);
+  if (err)
+    return err;
+
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_ASYNC);
+  handle->async_cb = async_cb;
+  handle->pending = 0;
+
+  QUEUE_INSERT_TAIL(&loop->async_handles, &handle->queue);
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+int uv_async_send(uv_async_t* handle) {
+  /* Do a cheap read first. */
+  if (ACCESS_ONCE(int, handle->pending) != 0)
+    return 0;
+
+  if (cmpxchgi(&handle->pending, 0, 1) == 0)
+    uv__async_send(handle->loop);
+
+  return 0;
+}
+
+
+void uv__async_close(uv_async_t* handle) {
+  QUEUE_REMOVE(&handle->queue);
+  uv__handle_stop(handle);
+}
+
+
+static void uv__async_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  char buf[1024];
+  ssize_t r;
+  QUEUE queue;
+  QUEUE* q;
+  uv_async_t* h;
+
+  assert(w == &loop->async_io_watcher);
+
+  for (;;) {
+    r = read(w->fd, buf, sizeof(buf));
+
+    if (r == sizeof(buf))
+      continue;
+
+    if (r != -1)
+      break;
+
+    if (errno == EAGAIN || errno == EWOULDBLOCK)
+      break;
+
+    if (errno == EINTR)
+      continue;
+
+    abort();
+  }
+
+  QUEUE_MOVE(&loop->async_handles, &queue);
+  while (!QUEUE_EMPTY(&queue)) {
+    q = QUEUE_HEAD(&queue);
+    h = QUEUE_DATA(q, uv_async_t, queue);
+
+    QUEUE_REMOVE(q);
+    QUEUE_INSERT_TAIL(&loop->async_handles, q);
+
+    if (cmpxchgi(&h->pending, 1, 0) == 0)
+      continue;
+
+    if (h->async_cb == NULL)
+      continue;
+
+    h->async_cb(h);
+  }
+}
+
+
+static void uv__async_send(uv_loop_t* loop) {
+  const void* buf;
+  ssize_t len;
+  int fd;
+  int r;
+
+  buf = "";
+  len = 1;
+  fd = loop->async_wfd;
+
+#if defined(__linux__)
+  if (fd == -1) {
+    static const uint64_t val = 1;
+    buf = &val;
+    len = sizeof(val);
+    fd = loop->async_io_watcher.fd;  /* eventfd */
+  }
+#endif
+
+  do
+    r = write(fd, buf, len);
+  while (r == -1 && errno == EINTR);
+
+  if (r == len)
+    return;
+
+  if (r == -1)
+    if (errno == EAGAIN || errno == EWOULDBLOCK)
+      return;
+
+  abort();
+}
+
+
+static int uv__async_start(uv_loop_t* loop) {
+  int pipefd[2];
+  int err;
+
+  if (loop->async_io_watcher.fd != -1)
+    return 0;
+
+  err = uv__async_eventfd();
+  if (err >= 0) {
+    pipefd[0] = err;
+    pipefd[1] = -1;
+  }
+  else if (err == UV_ENOSYS) {
+    err = uv__make_pipe(pipefd, UV__F_NONBLOCK);
+#if defined(__linux__)
+    /* Save a file descriptor by opening one of the pipe descriptors as
+     * read/write through the procfs.  That file descriptor can then
+     * function as both ends of the pipe.
+     */
+    if (err == 0) {
+      char buf[32];
+      int fd;
+
+      snprintf(buf, sizeof(buf), "/proc/self/fd/%d", pipefd[0]);
+      fd = uv__open_cloexec(buf, O_RDWR);
+      if (fd >= 0) {
+        uv__close(pipefd[0]);
+        uv__close(pipefd[1]);
+        pipefd[0] = fd;
+        pipefd[1] = fd;
+      }
+    }
+#endif
+  }
+
+  if (err < 0)
+    return err;
+
+  uv__io_init(&loop->async_io_watcher, uv__async_io, pipefd[0]);
+  uv__io_start(loop, &loop->async_io_watcher, POLLIN);
+  loop->async_wfd = pipefd[1];
+
+  return 0;
+}
+
+
+int uv__async_fork(uv_loop_t* loop) {
+  if (loop->async_io_watcher.fd == -1) /* never started */
+    return 0;
+
+  uv__async_stop(loop);
+
+  return uv__async_start(loop);
+}
+
+
+void uv__async_stop(uv_loop_t* loop) {
+  if (loop->async_io_watcher.fd == -1)
+    return;
+
+  if (loop->async_wfd != -1) {
+    if (loop->async_wfd != loop->async_io_watcher.fd)
+      uv__close(loop->async_wfd);
+    loop->async_wfd = -1;
+  }
+
+  uv__io_stop(loop, &loop->async_io_watcher, POLLIN);
+  uv__close(loop->async_io_watcher.fd);
+  loop->async_io_watcher.fd = -1;
+}
+
+
+static int uv__async_eventfd(void) {
+#if defined(__linux__)
+  static int no_eventfd2;
+  static int no_eventfd;
+  int fd;
+
+  if (no_eventfd2)
+    goto skip_eventfd2;
+
+  fd = uv__eventfd2(0, UV__EFD_CLOEXEC | UV__EFD_NONBLOCK);
+  if (fd != -1)
+    return fd;
+
+  if (errno != ENOSYS)
+    return UV__ERR(errno);
+
+  no_eventfd2 = 1;
+
+skip_eventfd2:
+
+  if (no_eventfd)
+    goto skip_eventfd;
+
+  fd = uv__eventfd(0);
+  if (fd != -1) {
+    uv__cloexec(fd, 1);
+    uv__nonblock(fd, 1);
+    return fd;
+  }
+
+  if (errno != ENOSYS)
+    return UV__ERR(errno);
+
+  no_eventfd = 1;
+
+skip_eventfd:
+
+#endif
+
+  return UV_ENOSYS;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/atomic-ops.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/atomic-ops.h
new file mode 100644
index 0000000..7cac1f9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/atomic-ops.h
@@ -0,0 +1,100 @@
+/* Copyright (c) 2013, Ben Noordhuis <info@bnoordhuis.nl>
+ *
+ * Permission to use, copy, modify, and/or distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#ifndef UV_ATOMIC_OPS_H_
+#define UV_ATOMIC_OPS_H_
+
+#include "internal.h"  /* UV_UNUSED */
+
+#if defined(__SUNPRO_C) || defined(__SUNPRO_CC)
+#include <atomic.h>
+#endif
+
+UV_UNUSED(static int cmpxchgi(int* ptr, int oldval, int newval));
+UV_UNUSED(static long cmpxchgl(long* ptr, long oldval, long newval));
+UV_UNUSED(static void cpu_relax(void));
+
+/* Prefer hand-rolled assembly over the gcc builtins because the latter also
+ * issue full memory barriers.
+ */
+UV_UNUSED(static int cmpxchgi(int* ptr, int oldval, int newval)) {
+#if defined(__i386__) || defined(__x86_64__)
+  int out;
+  __asm__ __volatile__ ("lock; cmpxchg %2, %1;"
+                        : "=a" (out), "+m" (*(volatile int*) ptr)
+                        : "r" (newval), "0" (oldval)
+                        : "memory");
+  return out;
+#elif defined(_AIX) && defined(__xlC__)
+  const int out = (*(volatile int*) ptr);
+  __compare_and_swap(ptr, &oldval, newval);
+  return out;
+#elif defined(__MVS__)
+  unsigned int op4;
+  if (__plo_CSST(ptr, (unsigned int*) &oldval, newval,
+                (unsigned int*) ptr, *ptr, &op4))
+    return oldval;
+  else
+    return op4;
+#elif defined(__SUNPRO_C) || defined(__SUNPRO_CC)
+  return atomic_cas_uint(ptr, oldval, newval);
+#else
+  return __sync_val_compare_and_swap(ptr, oldval, newval);
+#endif
+}
+
+UV_UNUSED(static long cmpxchgl(long* ptr, long oldval, long newval)) {
+#if defined(__i386__) || defined(__x86_64__)
+  long out;
+  __asm__ __volatile__ ("lock; cmpxchg %2, %1;"
+                        : "=a" (out), "+m" (*(volatile long*) ptr)
+                        : "r" (newval), "0" (oldval)
+                        : "memory");
+  return out;
+#elif defined(_AIX) && defined(__xlC__)
+  const long out = (*(volatile int*) ptr);
+# if defined(__64BIT__)
+  __compare_and_swaplp(ptr, &oldval, newval);
+# else
+  __compare_and_swap(ptr, &oldval, newval);
+# endif /* if defined(__64BIT__) */
+  return out;
+#elif defined (__MVS__)
+#ifdef _LP64
+  unsigned long long op4;
+  if (__plo_CSSTGR(ptr, (unsigned long long*) &oldval, newval,
+                  (unsigned long long*) ptr, *ptr, &op4))
+#else
+  unsigned long op4;
+  if (__plo_CSST(ptr, (unsigned int*) &oldval, newval,
+                (unsigned int*) ptr, *ptr, &op4))
+#endif
+    return oldval;
+  else
+    return op4;
+#elif defined(__SUNPRO_C) || defined(__SUNPRO_CC)
+  return atomic_cas_ulong(ptr, oldval, newval);
+#else
+  return __sync_val_compare_and_swap(ptr, oldval, newval);
+#endif
+}
+
+UV_UNUSED(static void cpu_relax(void)) {
+#if defined(__i386__) || defined(__x86_64__)
+  __asm__ __volatile__ ("rep; nop");  /* a.k.a. PAUSE */
+#endif
+}
+
+#endif  /* UV_ATOMIC_OPS_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/bsd-ifaddrs.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/bsd-ifaddrs.cpp
new file mode 100644
index 0000000..3d885e1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/bsd-ifaddrs.cpp
@@ -0,0 +1,153 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+#include <stddef.h>
+
+#include <ifaddrs.h>
+#include <net/if.h>
+#if !defined(__CYGWIN__) && !defined(__MSYS__)
+#include <net/if_dl.h>
+#endif
+
+static int uv__ifaddr_exclude(struct ifaddrs *ent, int exclude_type) {
+  if (!((ent->ifa_flags & IFF_UP) && (ent->ifa_flags & IFF_RUNNING)))
+    return 1;
+  if (ent->ifa_addr == NULL)
+    return 1;
+#if !defined(__CYGWIN__) && !defined(__MSYS__)
+  /*
+   * If `exclude_type` is `UV__EXCLUDE_IFPHYS`, just see whether `sa_family`
+   * equals to `AF_LINK` or not. Otherwise, the result depends on the operation
+   * system with `AF_LINK` or `PF_INET`.
+   */
+  if (exclude_type == UV__EXCLUDE_IFPHYS)
+    return (ent->ifa_addr->sa_family != AF_LINK);
+#endif
+#if defined(__APPLE__) || defined(__FreeBSD__) || defined(__DragonFly__)
+  /*
+   * On BSD getifaddrs returns information related to the raw underlying
+   * devices.  We're not interested in this information.
+   */
+  if (ent->ifa_addr->sa_family == AF_LINK)
+    return 1;
+#elif defined(__NetBSD__)
+  if (ent->ifa_addr->sa_family != PF_INET &&
+      ent->ifa_addr->sa_family != PF_INET6)
+    return 1;
+#elif defined(__OpenBSD__)
+  if (ent->ifa_addr->sa_family != PF_INET)
+    return 1;
+#endif
+  return 0;
+}
+
+int uv_interface_addresses(uv_interface_address_t** addresses, int* count) {
+  struct ifaddrs* addrs;
+  struct ifaddrs* ent;
+  uv_interface_address_t* address;
+  int i;
+
+  if (getifaddrs(&addrs) != 0)
+    return UV__ERR(errno);
+
+  *count = 0;
+
+  /* Count the number of interfaces */
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
+      continue;
+    (*count)++;
+  }
+
+  *addresses =
+      (uv_interface_address_t*)uv__malloc(*count * sizeof(**addresses));
+
+  if (*addresses == NULL) {
+    freeifaddrs(addrs);
+    return UV_ENOMEM;
+  }
+
+  address = *addresses;
+
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
+      continue;
+
+    address->name = uv__strdup(ent->ifa_name);
+
+    if (ent->ifa_addr->sa_family == AF_INET6) {
+      address->address.address6 = *((struct sockaddr_in6*) ent->ifa_addr);
+    } else {
+      address->address.address4 = *((struct sockaddr_in*) ent->ifa_addr);
+    }
+
+    if (ent->ifa_netmask->sa_family == AF_INET6) {
+      address->netmask.netmask6 = *((struct sockaddr_in6*) ent->ifa_netmask);
+    } else {
+      address->netmask.netmask4 = *((struct sockaddr_in*) ent->ifa_netmask);
+    }
+
+    address->is_internal = !!(ent->ifa_flags & IFF_LOOPBACK);
+
+    address++;
+  }
+
+  /* Fill in physical addresses for each interface */
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFPHYS))
+      continue;
+
+    address = *addresses;
+
+    for (i = 0; i < *count; i++) {
+      if (strcmp(address->name, ent->ifa_name) == 0) {
+#if defined(__CYGWIN__) || defined(__MSYS__)
+        memset(address->phys_addr, 0, sizeof(address->phys_addr));
+#else
+        struct sockaddr_dl* sa_addr;
+        sa_addr = (struct sockaddr_dl*)(ent->ifa_addr);
+        memcpy(address->phys_addr, LLADDR(sa_addr), sizeof(address->phys_addr));
+#endif
+      }
+      address++;
+    }
+  }
+
+  freeifaddrs(addrs);
+
+  return 0;
+}
+
+
+void uv_free_interface_addresses(uv_interface_address_t* addresses,
+                                 int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(addresses[i].name);
+  }
+
+  uv__free(addresses);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/core.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/core.cpp
new file mode 100644
index 0000000..df36747
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/core.cpp
@@ -0,0 +1,1347 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stddef.h> /* NULL */
+#include <stdio.h> /* printf */
+#include <stdlib.h>
+#include <string.h> /* strerror */
+#include <errno.h>
+#include <assert.h>
+#include <unistd.h>
+#include <sys/types.h>
+#include <sys/stat.h>
+#include <fcntl.h>
+#include <sys/ioctl.h>
+#include <sys/socket.h>
+#include <sys/un.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#include <limits.h> /* INT_MAX, PATH_MAX, IOV_MAX */
+#include <sys/uio.h> /* writev */
+#include <sys/resource.h> /* getrusage */
+#include <pwd.h>
+
+#ifdef __sun
+# include <netdb.h> /* MAXHOSTNAMELEN on Solaris */
+# include <sys/filio.h>
+# include <sys/types.h>
+# include <sys/wait.h>
+#endif
+
+#ifdef __APPLE__
+# include <mach-o/dyld.h> /* _NSGetExecutablePath */
+# include <sys/filio.h>
+# if defined(O_CLOEXEC)
+#  define UV__O_CLOEXEC O_CLOEXEC
+# endif
+#endif
+
+#if defined(__DragonFly__)      || \
+    defined(__FreeBSD__)        || \
+    defined(__FreeBSD_kernel__) || \
+    defined(__NetBSD__)
+# include <sys/sysctl.h>
+# include <sys/filio.h>
+# include <sys/wait.h>
+# define UV__O_CLOEXEC O_CLOEXEC
+# if defined(__FreeBSD__) && __FreeBSD__ >= 10
+#  define uv__accept4 accept4
+# endif
+# if defined(__NetBSD__)
+#  define uv__accept4(a, b, c, d) paccept((a), (b), (c), NULL, (d))
+# endif
+# if (defined(__FreeBSD__) && __FreeBSD__ >= 10) || defined(__NetBSD__)
+#  define UV__SOCK_NONBLOCK SOCK_NONBLOCK
+#  define UV__SOCK_CLOEXEC  SOCK_CLOEXEC
+# endif
+# if !defined(F_DUP2FD_CLOEXEC) && defined(_F_DUP2FD_CLOEXEC)
+#  define F_DUP2FD_CLOEXEC  _F_DUP2FD_CLOEXEC
+# endif
+#endif
+
+#if defined(__ANDROID_API__) && __ANDROID_API__ < 21
+# include <dlfcn.h>  /* for dlsym */
+#endif
+
+#if defined(__MVS__)
+#include <sys/ioctl.h>
+#endif
+
+#if !defined(__MVS__)
+#include <sys/param.h> /* MAXHOSTNAMELEN on Linux and the BSDs */
+#endif
+
+/* Fallback for the maximum hostname length */
+#ifndef MAXHOSTNAMELEN
+# define MAXHOSTNAMELEN 256
+#endif
+
+static int uv__run_pending(uv_loop_t* loop);
+
+/* Verify that uv_buf_t is ABI-compatible with struct iovec. */
+STATIC_ASSERT(sizeof(uv_buf_t) == sizeof(struct iovec));
+STATIC_ASSERT(sizeof(&((uv_buf_t*) 0)->base) ==
+              sizeof(((struct iovec*) 0)->iov_base));
+STATIC_ASSERT(sizeof(&((uv_buf_t*) 0)->len) ==
+              sizeof(((struct iovec*) 0)->iov_len));
+STATIC_ASSERT(offsetof(uv_buf_t, base) == offsetof(struct iovec, iov_base));
+STATIC_ASSERT(offsetof(uv_buf_t, len) == offsetof(struct iovec, iov_len));
+
+
+uint64_t uv_hrtime(void) {
+  return uv__hrtime(UV_CLOCK_PRECISE);
+}
+
+
+void uv_close(uv_handle_t* handle, uv_close_cb close_cb) {
+  assert(!uv__is_closing(handle));
+
+  handle->flags |= UV_CLOSING;
+  handle->close_cb = close_cb;
+
+  switch (handle->type) {
+  case UV_NAMED_PIPE:
+    uv__pipe_close((uv_pipe_t*)handle);
+    break;
+
+  case UV_TTY:
+    uv__stream_close((uv_stream_t*)handle);
+    break;
+
+  case UV_TCP:
+    uv__tcp_close((uv_tcp_t*)handle);
+    break;
+
+  case UV_UDP:
+    uv__udp_close((uv_udp_t*)handle);
+    break;
+
+  case UV_PREPARE:
+    uv__prepare_close((uv_prepare_t*)handle);
+    break;
+
+  case UV_CHECK:
+    uv__check_close((uv_check_t*)handle);
+    break;
+
+  case UV_IDLE:
+    uv__idle_close((uv_idle_t*)handle);
+    break;
+
+  case UV_ASYNC:
+    uv__async_close((uv_async_t*)handle);
+    break;
+
+  case UV_TIMER:
+    uv__timer_close((uv_timer_t*)handle);
+    break;
+
+  case UV_PROCESS:
+    uv__process_close((uv_process_t*)handle);
+    break;
+
+  case UV_FS_EVENT:
+    uv__fs_event_close((uv_fs_event_t*)handle);
+    break;
+
+  case UV_POLL:
+    uv__poll_close((uv_poll_t*)handle);
+    break;
+
+  case UV_FS_POLL:
+    uv__fs_poll_close((uv_fs_poll_t*)handle);
+    break;
+
+  case UV_SIGNAL:
+    uv__signal_close((uv_signal_t*) handle);
+    /* Signal handles may not be closed immediately. The signal code will
+     * itself close uv__make_close_pending whenever appropriate. */
+    return;
+
+  default:
+    assert(0);
+  }
+
+  uv__make_close_pending(handle);
+}
+
+int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value) {
+  int r;
+  int fd;
+  socklen_t len;
+
+  if (handle == NULL || value == NULL)
+    return UV_EINVAL;
+
+  if (handle->type == UV_TCP || handle->type == UV_NAMED_PIPE)
+    fd = uv__stream_fd((uv_stream_t*) handle);
+  else if (handle->type == UV_UDP)
+    fd = ((uv_udp_t *) handle)->io_watcher.fd;
+  else
+    return UV_ENOTSUP;
+
+  len = sizeof(*value);
+
+  if (*value == 0)
+    r = getsockopt(fd, SOL_SOCKET, optname, value, &len);
+  else
+    r = setsockopt(fd, SOL_SOCKET, optname, (const void*) value, len);
+
+  if (r < 0)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+void uv__make_close_pending(uv_handle_t* handle) {
+  assert(handle->flags & UV_CLOSING);
+  assert(!(handle->flags & UV_CLOSED));
+  handle->next_closing = handle->loop->closing_handles;
+  handle->loop->closing_handles = handle;
+}
+
+int uv__getiovmax(void) {
+#if defined(IOV_MAX)
+  return IOV_MAX;
+#elif defined(_SC_IOV_MAX)
+  static int iovmax = -1;
+  if (iovmax == -1) {
+    iovmax = sysconf(_SC_IOV_MAX);
+    /* On some embedded devices (arm-linux-uclibc based ip camera),
+     * sysconf(_SC_IOV_MAX) can not get the correct value. The return
+     * value is -1 and the errno is EINPROGRESS. Degrade the value to 1.
+     */
+    if (iovmax == -1) iovmax = 1;
+  }
+  return iovmax;
+#else
+  return 1024;
+#endif
+}
+
+
+static void uv__finish_close(uv_handle_t* handle) {
+  /* Note: while the handle is in the UV_CLOSING state now, it's still possible
+   * for it to be active in the sense that uv__is_active() returns true.
+   * A good example is when the user calls uv_shutdown(), immediately followed
+   * by uv_close(). The handle is considered active at this point because the
+   * completion of the shutdown req is still pending.
+   */
+  assert(handle->flags & UV_CLOSING);
+  assert(!(handle->flags & UV_CLOSED));
+  handle->flags |= UV_CLOSED;
+
+  switch (handle->type) {
+    case UV_PREPARE:
+    case UV_CHECK:
+    case UV_IDLE:
+    case UV_ASYNC:
+    case UV_TIMER:
+    case UV_PROCESS:
+    case UV_FS_EVENT:
+    case UV_FS_POLL:
+    case UV_POLL:
+    case UV_SIGNAL:
+      break;
+
+    case UV_NAMED_PIPE:
+    case UV_TCP:
+    case UV_TTY:
+      uv__stream_destroy((uv_stream_t*)handle);
+      break;
+
+    case UV_UDP:
+      uv__udp_finish_close((uv_udp_t*)handle);
+      break;
+
+    default:
+      assert(0);
+      break;
+  }
+
+  uv__handle_unref(handle);
+  QUEUE_REMOVE(&handle->handle_queue);
+
+  if (handle->close_cb) {
+    handle->close_cb(handle);
+  }
+}
+
+
+static void uv__run_closing_handles(uv_loop_t* loop) {
+  uv_handle_t* p;
+  uv_handle_t* q;
+
+  p = loop->closing_handles;
+  loop->closing_handles = NULL;
+
+  while (p) {
+    q = p->next_closing;
+    uv__finish_close(p);
+    p = q;
+  }
+}
+
+
+int uv_is_closing(const uv_handle_t* handle) {
+  return uv__is_closing(handle);
+}
+
+
+int uv_backend_fd(const uv_loop_t* loop) {
+  return loop->backend_fd;
+}
+
+
+int uv_backend_timeout(const uv_loop_t* loop) {
+  if (loop->stop_flag != 0)
+    return 0;
+
+  if (!uv__has_active_handles(loop) && !uv__has_active_reqs(loop))
+    return 0;
+
+  if (!QUEUE_EMPTY(&loop->idle_handles))
+    return 0;
+
+  if (!QUEUE_EMPTY(&loop->pending_queue))
+    return 0;
+
+  if (loop->closing_handles)
+    return 0;
+
+  return uv__next_timeout(loop);
+}
+
+
+static int uv__loop_alive(const uv_loop_t* loop) {
+  return uv__has_active_handles(loop) ||
+         uv__has_active_reqs(loop) ||
+         loop->closing_handles != NULL;
+}
+
+
+int uv_loop_alive(const uv_loop_t* loop) {
+    return uv__loop_alive(loop);
+}
+
+
+int uv_run(uv_loop_t* loop, uv_run_mode mode) {
+  int timeout;
+  int r;
+  int ran_pending;
+
+  r = uv__loop_alive(loop);
+  if (!r)
+    uv__update_time(loop);
+
+  while (r != 0 && loop->stop_flag == 0) {
+    uv__update_time(loop);
+    uv__run_timers(loop);
+    ran_pending = uv__run_pending(loop);
+    uv__run_idle(loop);
+    uv__run_prepare(loop);
+
+    timeout = 0;
+    if ((mode == UV_RUN_ONCE && !ran_pending) || mode == UV_RUN_DEFAULT)
+      timeout = uv_backend_timeout(loop);
+
+    uv__io_poll(loop, timeout);
+    uv__run_check(loop);
+    uv__run_closing_handles(loop);
+
+    if (mode == UV_RUN_ONCE) {
+      /* UV_RUN_ONCE implies forward progress: at least one callback must have
+       * been invoked when it returns. uv__io_poll() can return without doing
+       * I/O (meaning: no callbacks) when its timeout expires - which means we
+       * have pending timers that satisfy the forward progress constraint.
+       *
+       * UV_RUN_NOWAIT makes no guarantees about progress so it's omitted from
+       * the check.
+       */
+      uv__update_time(loop);
+      uv__run_timers(loop);
+    }
+
+    r = uv__loop_alive(loop);
+    if (mode == UV_RUN_ONCE || mode == UV_RUN_NOWAIT)
+      break;
+  }
+
+  /* The if statement lets gcc compile it to a conditional store. Avoids
+   * dirtying a cache line.
+   */
+  if (loop->stop_flag != 0)
+    loop->stop_flag = 0;
+
+  return r;
+}
+
+
+void uv_update_time(uv_loop_t* loop) {
+  uv__update_time(loop);
+}
+
+
+int uv_is_active(const uv_handle_t* handle) {
+  return uv__is_active(handle);
+}
+
+
+/* Open a socket in non-blocking close-on-exec mode, atomically if possible. */
+int uv__socket(int domain, int type, int protocol) {
+  int sockfd;
+  int err;
+
+#if defined(SOCK_NONBLOCK) && defined(SOCK_CLOEXEC)
+  sockfd = socket(domain, type | SOCK_NONBLOCK | SOCK_CLOEXEC, protocol);
+  if (sockfd != -1)
+    return sockfd;
+
+  if (errno != EINVAL)
+    return UV__ERR(errno);
+#endif
+
+  sockfd = socket(domain, type, protocol);
+  if (sockfd == -1)
+    return UV__ERR(errno);
+
+  err = uv__nonblock(sockfd, 1);
+  if (err == 0)
+    err = uv__cloexec(sockfd, 1);
+
+  if (err) {
+    uv__close(sockfd);
+    return err;
+  }
+
+#if defined(SO_NOSIGPIPE)
+  {
+    int on = 1;
+    setsockopt(sockfd, SOL_SOCKET, SO_NOSIGPIPE, &on, sizeof(on));
+  }
+#endif
+
+  return sockfd;
+}
+
+/* get a file pointer to a file in read-only and close-on-exec mode */
+FILE* uv__open_file(const char* path) {
+  int fd;
+  FILE* fp;
+
+  fd = uv__open_cloexec(path, O_RDONLY);
+  if (fd < 0)
+    return NULL;
+
+   fp = fdopen(fd, "r");
+   if (fp == NULL)
+     uv__close(fd);
+
+   return fp;
+}
+
+
+int uv__accept(int sockfd) {
+  int peerfd;
+  int err;
+
+  assert(sockfd >= 0);
+
+  while (1) {
+#if defined(__linux__)                          || \
+    (defined(__FreeBSD__) && __FreeBSD__ >= 10) || \
+    defined(__NetBSD__)
+    static int no_accept4;
+
+    if (no_accept4)
+      goto skip;
+
+    peerfd = uv__accept4(sockfd,
+                         NULL,
+                         NULL,
+                         UV__SOCK_NONBLOCK|UV__SOCK_CLOEXEC);
+    if (peerfd != -1)
+      return peerfd;
+
+    if (errno == EINTR)
+      continue;
+
+    if (errno != ENOSYS)
+      return UV__ERR(errno);
+
+    no_accept4 = 1;
+skip:
+#endif
+
+    peerfd = accept(sockfd, NULL, NULL);
+    if (peerfd == -1) {
+      if (errno == EINTR)
+        continue;
+      return UV__ERR(errno);
+    }
+
+    err = uv__cloexec(peerfd, 1);
+    if (err == 0)
+      err = uv__nonblock(peerfd, 1);
+
+    if (err) {
+      uv__close(peerfd);
+      return err;
+    }
+
+    return peerfd;
+  }
+}
+
+
+int uv__close_nocheckstdio(int fd) {
+  int saved_errno;
+  int rc;
+
+  assert(fd > -1);  /* Catch uninitialized io_watcher.fd bugs. */
+
+  saved_errno = errno;
+  rc = close(fd);
+  if (rc == -1) {
+    rc = UV__ERR(errno);
+    if (rc == UV_EINTR || rc == UV__ERR(EINPROGRESS))
+      rc = 0;    /* The close is in progress, not an error. */
+    errno = saved_errno;
+  }
+
+  return rc;
+}
+
+
+int uv__close(int fd) {
+  assert(fd > STDERR_FILENO);  /* Catch stdio close bugs. */
+#if defined(__MVS__)
+  SAVE_ERRNO(epoll_file_close(fd));
+#endif
+  return uv__close_nocheckstdio(fd);
+}
+
+
+int uv__nonblock_ioctl(int fd, int set) {
+  int r;
+
+  do
+    r = ioctl(fd, FIONBIO, &set);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+#if !defined(__CYGWIN__) && !defined(__MSYS__)
+int uv__cloexec_ioctl(int fd, int set) {
+  int r;
+
+  do
+    r = ioctl(fd, set ? FIOCLEX : FIONCLEX);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+#endif
+
+
+int uv__nonblock_fcntl(int fd, int set) {
+  int flags;
+  int r;
+
+  do
+    r = fcntl(fd, F_GETFL);
+  while (r == -1 && errno == EINTR);
+
+  if (r == -1)
+    return UV__ERR(errno);
+
+  /* Bail out now if already set/clear. */
+  if (!!(r & O_NONBLOCK) == !!set)
+    return 0;
+
+  if (set)
+    flags = r | O_NONBLOCK;
+  else
+    flags = r & ~O_NONBLOCK;
+
+  do
+    r = fcntl(fd, F_SETFL, flags);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+int uv__cloexec_fcntl(int fd, int set) {
+  int flags;
+  int r;
+
+  do
+    r = fcntl(fd, F_GETFD);
+  while (r == -1 && errno == EINTR);
+
+  if (r == -1)
+    return UV__ERR(errno);
+
+  /* Bail out now if already set/clear. */
+  if (!!(r & FD_CLOEXEC) == !!set)
+    return 0;
+
+  if (set)
+    flags = r | FD_CLOEXEC;
+  else
+    flags = r & ~FD_CLOEXEC;
+
+  do
+    r = fcntl(fd, F_SETFD, flags);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+/* This function is not execve-safe, there is a race window
+ * between the call to dup() and fcntl(FD_CLOEXEC).
+ */
+int uv__dup(int fd) {
+  int err;
+
+  fd = dup(fd);
+
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  err = uv__cloexec(fd, 1);
+  if (err) {
+    uv__close(fd);
+    return err;
+  }
+
+  return fd;
+}
+
+
+ssize_t uv__recvmsg(int fd, struct msghdr* msg, int flags) {
+  struct cmsghdr* cmsg;
+  ssize_t rc;
+  int* pfd;
+  int* end;
+#if defined(__linux__)
+  static int no_msg_cmsg_cloexec;
+  if (no_msg_cmsg_cloexec == 0) {
+    rc = recvmsg(fd, msg, flags | 0x40000000);  /* MSG_CMSG_CLOEXEC */
+    if (rc != -1)
+      return rc;
+    if (errno != EINVAL)
+      return UV__ERR(errno);
+    rc = recvmsg(fd, msg, flags);
+    if (rc == -1)
+      return UV__ERR(errno);
+    no_msg_cmsg_cloexec = 1;
+  } else {
+    rc = recvmsg(fd, msg, flags);
+  }
+#else
+  rc = recvmsg(fd, msg, flags);
+#endif
+  if (rc == -1)
+    return UV__ERR(errno);
+  if (msg->msg_controllen == 0)
+    return rc;
+  for (cmsg = CMSG_FIRSTHDR(msg); cmsg != NULL; cmsg = CMSG_NXTHDR(msg, cmsg))
+    if (cmsg->cmsg_type == SCM_RIGHTS)
+      for (pfd = (int*) CMSG_DATA(cmsg),
+           end = (int*) ((char*) cmsg + cmsg->cmsg_len);
+           pfd < end;
+           pfd += 1)
+        uv__cloexec(*pfd, 1);
+  return rc;
+}
+
+
+int uv_cwd(char* buffer, size_t* size) {
+  if (buffer == NULL || size == NULL)
+    return UV_EINVAL;
+
+  if (getcwd(buffer, *size) == NULL)
+    return UV__ERR(errno);
+
+  *size = strlen(buffer);
+  if (*size > 1 && buffer[*size - 1] == '/') {
+    buffer[*size-1] = '\0';
+    (*size)--;
+  }
+
+  return 0;
+}
+
+
+int uv_chdir(const char* dir) {
+  if (chdir(dir))
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+void uv_disable_stdio_inheritance(void) {
+  int fd;
+
+  /* Set the CLOEXEC flag on all open descriptors. Unconditionally try the
+   * first 16 file descriptors. After that, bail out after the first error.
+   */
+  for (fd = 0; ; fd++)
+    if (uv__cloexec(fd, 1) && fd > 15)
+      break;
+}
+
+
+int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd) {
+  int fd_out;
+
+  switch (handle->type) {
+  case UV_TCP:
+  case UV_NAMED_PIPE:
+  case UV_TTY:
+    fd_out = uv__stream_fd((uv_stream_t*) handle);
+    break;
+
+  case UV_UDP:
+    fd_out = ((uv_udp_t *) handle)->io_watcher.fd;
+    break;
+
+  case UV_POLL:
+    fd_out = ((uv_poll_t *) handle)->io_watcher.fd;
+    break;
+
+  default:
+    return UV_EINVAL;
+  }
+
+  if (uv__is_closing(handle) || fd_out == -1)
+    return UV_EBADF;
+
+  *fd = fd_out;
+  return 0;
+}
+
+
+static int uv__run_pending(uv_loop_t* loop) {
+  QUEUE* q;
+  QUEUE pq;
+  uv__io_t* w;
+
+  if (QUEUE_EMPTY(&loop->pending_queue))
+    return 0;
+
+  QUEUE_MOVE(&loop->pending_queue, &pq);
+
+  while (!QUEUE_EMPTY(&pq)) {
+    q = QUEUE_HEAD(&pq);
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);
+    w = QUEUE_DATA(q, uv__io_t, pending_queue);
+    w->cb(loop, w, POLLOUT);
+  }
+
+  return 1;
+}
+
+
+static unsigned int next_power_of_two(unsigned int val) {
+  val -= 1;
+  val |= val >> 1;
+  val |= val >> 2;
+  val |= val >> 4;
+  val |= val >> 8;
+  val |= val >> 16;
+  val += 1;
+  return val;
+}
+
+static void maybe_resize(uv_loop_t* loop, unsigned int len) {
+  uv__io_t** watchers;
+  void* fake_watcher_list;
+  void* fake_watcher_count;
+  unsigned int nwatchers;
+  unsigned int i;
+
+  if (len <= loop->nwatchers)
+    return;
+
+  /* Preserve fake watcher list and count at the end of the watchers */
+  if (loop->watchers != NULL) {
+    fake_watcher_list = loop->watchers[loop->nwatchers];
+    fake_watcher_count = loop->watchers[loop->nwatchers + 1];
+  } else {
+    fake_watcher_list = NULL;
+    fake_watcher_count = NULL;
+  }
+
+  nwatchers = next_power_of_two(len + 2) - 2;
+  watchers = (uv__io_t**)
+      uv__realloc(loop->watchers, (nwatchers + 2) * sizeof(loop->watchers[0]));
+
+  if (watchers == NULL)
+    abort();
+  for (i = loop->nwatchers; i < nwatchers; i++)
+    watchers[i] = NULL;
+  watchers[nwatchers] = (uv__io_t*)fake_watcher_list;
+  watchers[nwatchers + 1] = (uv__io_t*)fake_watcher_count;
+
+  loop->watchers = watchers;
+  loop->nwatchers = nwatchers;
+}
+
+
+void uv__io_init(uv__io_t* w, uv__io_cb cb, int fd) {
+  assert(cb != NULL);
+  assert(fd >= -1);
+  QUEUE_INIT(&w->pending_queue);
+  QUEUE_INIT(&w->watcher_queue);
+  w->cb = cb;
+  w->fd = fd;
+  w->events = 0;
+  w->pevents = 0;
+
+#if defined(UV_HAVE_KQUEUE)
+  w->rcount = 0;
+  w->wcount = 0;
+#endif /* defined(UV_HAVE_KQUEUE) */
+}
+
+
+void uv__io_start(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
+  assert(0 != events);
+  assert(w->fd >= 0);
+  assert(w->fd < INT_MAX);
+
+  w->pevents |= events;
+  maybe_resize(loop, w->fd + 1);
+
+#if !defined(__sun)
+  /* The event ports backend needs to rearm all file descriptors on each and
+   * every tick of the event loop but the other backends allow us to
+   * short-circuit here if the event mask is unchanged.
+   */
+  if (w->events == w->pevents)
+    return;
+#endif
+
+  if (QUEUE_EMPTY(&w->watcher_queue))
+    QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
+
+  if (loop->watchers[w->fd] == NULL) {
+    loop->watchers[w->fd] = w;
+    loop->nfds++;
+  }
+}
+
+
+void uv__io_stop(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
+  assert(0 != events);
+
+  if (w->fd == -1)
+    return;
+
+  assert(w->fd >= 0);
+
+  /* Happens when uv__io_stop() is called on a handle that was never started. */
+  if ((unsigned) w->fd >= loop->nwatchers)
+    return;
+
+  w->pevents &= ~events;
+
+  if (w->pevents == 0) {
+    QUEUE_REMOVE(&w->watcher_queue);
+    QUEUE_INIT(&w->watcher_queue);
+
+    if (loop->watchers[w->fd] != NULL) {
+      assert(loop->watchers[w->fd] == w);
+      assert(loop->nfds > 0);
+      loop->watchers[w->fd] = NULL;
+      loop->nfds--;
+      w->events = 0;
+    }
+  }
+  else if (QUEUE_EMPTY(&w->watcher_queue))
+    QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
+}
+
+
+void uv__io_close(uv_loop_t* loop, uv__io_t* w) {
+  uv__io_stop(loop, w, POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
+  QUEUE_REMOVE(&w->pending_queue);
+
+  /* Remove stale events for this file descriptor */
+  uv__platform_invalidate_fd(loop, w->fd);
+}
+
+
+void uv__io_feed(uv_loop_t* loop, uv__io_t* w) {
+  if (QUEUE_EMPTY(&w->pending_queue))
+    QUEUE_INSERT_TAIL(&loop->pending_queue, &w->pending_queue);
+}
+
+
+int uv__io_active(const uv__io_t* w, unsigned int events) {
+  assert(0 == (events & ~(POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI)));
+  assert(0 != events);
+  return 0 != (w->pevents & events);
+}
+
+
+int uv__fd_exists(uv_loop_t* loop, int fd) {
+  return (unsigned) fd < loop->nwatchers && loop->watchers[fd] != NULL;
+}
+
+
+int uv_getrusage(uv_rusage_t* rusage) {
+  struct rusage usage;
+
+  if (getrusage(RUSAGE_SELF, &usage))
+    return UV__ERR(errno);
+
+  rusage->ru_utime.tv_sec = usage.ru_utime.tv_sec;
+  rusage->ru_utime.tv_usec = usage.ru_utime.tv_usec;
+
+  rusage->ru_stime.tv_sec = usage.ru_stime.tv_sec;
+  rusage->ru_stime.tv_usec = usage.ru_stime.tv_usec;
+
+#if !defined(__MVS__)
+  rusage->ru_maxrss = usage.ru_maxrss;
+  rusage->ru_ixrss = usage.ru_ixrss;
+  rusage->ru_idrss = usage.ru_idrss;
+  rusage->ru_isrss = usage.ru_isrss;
+  rusage->ru_minflt = usage.ru_minflt;
+  rusage->ru_majflt = usage.ru_majflt;
+  rusage->ru_nswap = usage.ru_nswap;
+  rusage->ru_inblock = usage.ru_inblock;
+  rusage->ru_oublock = usage.ru_oublock;
+  rusage->ru_msgsnd = usage.ru_msgsnd;
+  rusage->ru_msgrcv = usage.ru_msgrcv;
+  rusage->ru_nsignals = usage.ru_nsignals;
+  rusage->ru_nvcsw = usage.ru_nvcsw;
+  rusage->ru_nivcsw = usage.ru_nivcsw;
+#endif
+
+  return 0;
+}
+
+
+int uv__open_cloexec(const char* path, int flags) {
+  int err;
+  int fd;
+
+#if defined(UV__O_CLOEXEC)
+  static int no_cloexec;
+
+  if (!no_cloexec) {
+    fd = open(path, flags | UV__O_CLOEXEC);
+    if (fd != -1)
+      return fd;
+
+    if (errno != EINVAL)
+      return UV__ERR(errno);
+
+    /* O_CLOEXEC not supported. */
+    no_cloexec = 1;
+  }
+#endif
+
+  fd = open(path, flags);
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  err = uv__cloexec(fd, 1);
+  if (err) {
+    uv__close(fd);
+    return err;
+  }
+
+  return fd;
+}
+
+
+int uv__dup2_cloexec(int oldfd, int newfd) {
+  int r;
+#if (defined(__FreeBSD__) && __FreeBSD__ >= 10) || defined(__NetBSD__)
+  r = dup3(oldfd, newfd, O_CLOEXEC);
+  if (r == -1)
+    return UV__ERR(errno);
+  return r;
+#elif defined(__FreeBSD__) && defined(F_DUP2FD_CLOEXEC)
+  r = fcntl(oldfd, F_DUP2FD_CLOEXEC, newfd);
+  if (r != -1)
+    return r;
+  if (errno != EINVAL)
+    return UV__ERR(errno);
+  /* Fall through. */
+#elif defined(__linux__)
+  static int no_dup3;
+  if (!no_dup3) {
+    do
+      r = uv__dup3(oldfd, newfd, UV__O_CLOEXEC);
+    while (r == -1 && errno == EBUSY);
+    if (r != -1)
+      return r;
+    if (errno != ENOSYS)
+      return UV__ERR(errno);
+    /* Fall through. */
+    no_dup3 = 1;
+  }
+#endif
+  {
+    int err;
+    do
+      r = dup2(oldfd, newfd);
+#if defined(__linux__)
+    while (r == -1 && errno == EBUSY);
+#else
+    while (0);  /* Never retry. */
+#endif
+
+    if (r == -1)
+      return UV__ERR(errno);
+
+    err = uv__cloexec(newfd, 1);
+    if (err) {
+      uv__close(newfd);
+      return err;
+    }
+
+    return r;
+  }
+}
+
+
+int uv_os_homedir(char* buffer, size_t* size) {
+  uv_passwd_t pwd;
+  size_t len;
+  int r;
+
+  /* Check if the HOME environment variable is set first. The task of
+     performing input validation on buffer and size is taken care of by
+     uv_os_getenv(). */
+  r = uv_os_getenv("HOME", buffer, size);
+
+  if (r != UV_ENOENT)
+    return r;
+
+  /* HOME is not set, so call uv__getpwuid_r() */
+  r = uv__getpwuid_r(&pwd);
+
+  if (r != 0) {
+    return r;
+  }
+
+  len = strlen(pwd.homedir);
+
+  if (len >= *size) {
+    *size = len + 1;
+    uv_os_free_passwd(&pwd);
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, pwd.homedir, len + 1);
+  *size = len;
+  uv_os_free_passwd(&pwd);
+
+  return 0;
+}
+
+
+int uv_os_tmpdir(char* buffer, size_t* size) {
+  const char* buf;
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+#define CHECK_ENV_VAR(name)                                                   \
+  do {                                                                        \
+    buf = getenv(name);                                                       \
+    if (buf != NULL)                                                          \
+      goto return_buffer;                                                     \
+  }                                                                           \
+  while (0)
+
+  /* Check the TMPDIR, TMP, TEMP, and TEMPDIR environment variables in order */
+  CHECK_ENV_VAR("TMPDIR");
+  CHECK_ENV_VAR("TMP");
+  CHECK_ENV_VAR("TEMP");
+  CHECK_ENV_VAR("TEMPDIR");
+
+#undef CHECK_ENV_VAR
+
+  /* No temp environment variables defined */
+  #if defined(__ANDROID__)
+    buf = "/data/local/tmp";
+  #else
+    buf = "/tmp";
+  #endif
+
+return_buffer:
+  len = strlen(buf);
+
+  if (len >= *size) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  /* The returned directory should not have a trailing slash. */
+  if (len > 1 && buf[len - 1] == '/') {
+    len--;
+  }
+
+  memcpy(buffer, buf, len + 1);
+  buffer[len] = '\0';
+  *size = len;
+
+  return 0;
+}
+
+
+int uv__getpwuid_r(uv_passwd_t* pwd) {
+  struct passwd pw;
+  struct passwd* result;
+  char* buf;
+  uid_t uid;
+  size_t bufsize;
+  size_t name_size;
+  size_t homedir_size;
+  size_t shell_size;
+  long initsize;
+  int r;
+#if defined(__ANDROID_API__) && __ANDROID_API__ < 21
+  int (*getpwuid_r)(uid_t, struct passwd*, char*, size_t, struct passwd**);
+
+  getpwuid_r = dlsym(RTLD_DEFAULT, "getpwuid_r");
+  if (getpwuid_r == NULL)
+    return UV_ENOSYS;
+#endif
+
+  if (pwd == NULL)
+    return UV_EINVAL;
+
+  initsize = sysconf(_SC_GETPW_R_SIZE_MAX);
+
+  if (initsize <= 0)
+    bufsize = 4096;
+  else
+    bufsize = (size_t) initsize;
+
+  uid = geteuid();
+  buf = NULL;
+
+  for (;;) {
+    uv__free(buf);
+    buf = (char*)uv__malloc(bufsize);
+
+    if (buf == NULL)
+      return UV_ENOMEM;
+
+    r = getpwuid_r(uid, &pw, buf, bufsize, &result);
+
+    if (r != ERANGE)
+      break;
+
+    bufsize *= 2;
+  }
+
+  if (r != 0) {
+    uv__free(buf);
+    return -r;
+  }
+
+  if (result == NULL) {
+    uv__free(buf);
+    return UV_ENOENT;
+  }
+
+  /* Allocate memory for the username, shell, and home directory */
+  name_size = strlen(pw.pw_name) + 1;
+  homedir_size = strlen(pw.pw_dir) + 1;
+  shell_size = strlen(pw.pw_shell) + 1;
+  pwd->username = (char*)uv__malloc(name_size + homedir_size + shell_size);
+
+  if (pwd->username == NULL) {
+    uv__free(buf);
+    return UV_ENOMEM;
+  }
+
+  /* Copy the username */
+  memcpy(pwd->username, pw.pw_name, name_size);
+
+  /* Copy the home directory */
+  pwd->homedir = pwd->username + name_size;
+  memcpy(pwd->homedir, pw.pw_dir, homedir_size);
+
+  /* Copy the shell */
+  pwd->shell = pwd->homedir + homedir_size;
+  memcpy(pwd->shell, pw.pw_shell, shell_size);
+
+  /* Copy the uid and gid */
+  pwd->uid = pw.pw_uid;
+  pwd->gid = pw.pw_gid;
+
+  uv__free(buf);
+
+  return 0;
+}
+
+
+void uv_os_free_passwd(uv_passwd_t* pwd) {
+  if (pwd == NULL)
+    return;
+
+  /*
+    The memory for name, shell, and homedir are allocated in a single
+    uv__malloc() call. The base of the pointer is stored in pwd->username, so
+    that is the field that needs to be freed.
+  */
+  uv__free(pwd->username);
+  pwd->username = NULL;
+  pwd->shell = NULL;
+  pwd->homedir = NULL;
+}
+
+
+int uv_os_get_passwd(uv_passwd_t* pwd) {
+  return uv__getpwuid_r(pwd);
+}
+
+
+int uv_translate_sys_error(int sys_errno) {
+  /* If < 0 then it's already a libuv error. */
+  return sys_errno <= 0 ? sys_errno : -sys_errno;
+}
+
+
+int uv_os_getenv(const char* name, char* buffer, size_t* size) {
+  char* var;
+  size_t len;
+
+  if (name == NULL || buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  var = getenv(name);
+
+  if (var == NULL)
+    return UV_ENOENT;
+
+  len = strlen(var);
+
+  if (len >= *size) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, var, len + 1);
+  *size = len;
+
+  return 0;
+}
+
+
+int uv_os_setenv(const char* name, const char* value) {
+  if (name == NULL || value == NULL)
+    return UV_EINVAL;
+
+  if (setenv(name, value, 1) != 0)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+int uv_os_unsetenv(const char* name) {
+  if (name == NULL)
+    return UV_EINVAL;
+
+  if (unsetenv(name) != 0)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+int uv_os_gethostname(char* buffer, size_t* size) {
+  /*
+    On some platforms, if the input buffer is not large enough, gethostname()
+    succeeds, but truncates the result. libuv can detect this and return ENOBUFS
+    instead by creating a large enough buffer and comparing the hostname length
+    to the size input.
+  */
+  char buf[MAXHOSTNAMELEN + 1];
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  if (gethostname(buf, sizeof(buf)) != 0)
+    return UV__ERR(errno);
+
+  buf[sizeof(buf) - 1] = '\0'; /* Null terminate, just to be safe. */
+  len = strlen(buf);
+
+  if (len >= *size) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, buf, len + 1);
+  *size = len;
+  return 0;
+}
+
+
+uv_os_fd_t uv_get_osfhandle(int fd) {
+  return fd;
+}
+
+
+uv_pid_t uv_os_getpid(void) {
+  return getpid();
+}
+
+
+uv_pid_t uv_os_getppid(void) {
+  return getppid();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/cygwin.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/cygwin.cpp
new file mode 100644
index 0000000..9fe4093
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/cygwin.cpp
@@ -0,0 +1,54 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <sys/sysinfo.h>
+#include <unistd.h>
+
+int uv_uptime(double* uptime) {
+  struct sysinfo info;
+
+  if (sysinfo(&info) < 0)
+    return UV__ERR(errno);
+
+  *uptime = info.uptime;
+  return 0;
+}
+
+int uv_resident_set_memory(size_t* rss) {
+  /* FIXME: read /proc/meminfo? */
+  *rss = 0;
+  return UV_ENOSYS;
+}
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  /* FIXME: read /proc/stat? */
+  *cpu_infos = NULL;
+  *count = 0;
+  return UV_ENOSYS;
+}
+
+void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
+  (void)cpu_infos;
+  (void)count;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/darwin-proctitle.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/darwin-proctitle.cpp
new file mode 100644
index 0000000..8e43aee
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/darwin-proctitle.cpp
@@ -0,0 +1,210 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <dlfcn.h>
+#include <errno.h>
+#include <stdlib.h>
+#include <string.h>
+
+#include <TargetConditionals.h>
+
+#if !TARGET_OS_IPHONE
+# include <CoreFoundation/CoreFoundation.h>
+# include <ApplicationServices/ApplicationServices.h>
+#endif
+
+
+static int uv__pthread_setname_np(const char* name) {
+  int (*dynamic_pthread_setname_np)(const char* name);
+  char namebuf[64];  /* MAXTHREADNAMESIZE */
+  int err;
+
+  /* pthread_setname_np() first appeared in OS X 10.6 and iOS 3.2. */
+  *(void **)(&dynamic_pthread_setname_np) =
+      dlsym(RTLD_DEFAULT, "pthread_setname_np");
+
+  if (dynamic_pthread_setname_np == NULL)
+    return UV_ENOSYS;
+
+  strncpy(namebuf, name, sizeof(namebuf) - 1);
+  namebuf[sizeof(namebuf) - 1] = '\0';
+
+  err = dynamic_pthread_setname_np(namebuf);
+  if (err)
+    return UV__ERR(err);
+
+  return 0;
+}
+
+
+int uv__set_process_title(const char* title) {
+#if TARGET_OS_IPHONE
+  return uv__pthread_setname_np(title);
+#else
+  CFStringRef (*pCFStringCreateWithCString)(CFAllocatorRef,
+                                            const char*,
+                                            CFStringEncoding);
+  CFBundleRef (*pCFBundleGetBundleWithIdentifier)(CFStringRef);
+  void *(*pCFBundleGetDataPointerForName)(CFBundleRef, CFStringRef);
+  void *(*pCFBundleGetFunctionPointerForName)(CFBundleRef, CFStringRef);
+  CFTypeRef (*pLSGetCurrentApplicationASN)(void);
+  OSStatus (*pLSSetApplicationInformationItem)(int,
+                                               CFTypeRef,
+                                               CFStringRef,
+                                               CFStringRef,
+                                               CFDictionaryRef*);
+  void* application_services_handle;
+  void* core_foundation_handle;
+  CFBundleRef launch_services_bundle;
+  CFStringRef* display_name_key;
+  CFDictionaryRef (*pCFBundleGetInfoDictionary)(CFBundleRef);
+  CFBundleRef (*pCFBundleGetMainBundle)(void);
+  CFBundleRef hi_services_bundle;
+  OSStatus (*pSetApplicationIsDaemon)(int);
+  CFDictionaryRef (*pLSApplicationCheckIn)(int, CFDictionaryRef);
+  void (*pLSSetApplicationLaunchServicesServerConnectionStatus)(uint64_t,
+                                                                void*);
+  CFTypeRef asn;
+  int err;
+
+  err = UV_ENOENT;
+  application_services_handle = dlopen("/System/Library/Frameworks/"
+                                       "ApplicationServices.framework/"
+                                       "Versions/A/ApplicationServices",
+                                       RTLD_LAZY | RTLD_LOCAL);
+  core_foundation_handle = dlopen("/System/Library/Frameworks/"
+                                  "CoreFoundation.framework/"
+                                  "Versions/A/CoreFoundation",
+                                  RTLD_LAZY | RTLD_LOCAL);
+
+  if (application_services_handle == NULL || core_foundation_handle == NULL)
+    goto out;
+
+  *(void **)(&pCFStringCreateWithCString) =
+      dlsym(core_foundation_handle, "CFStringCreateWithCString");
+  *(void **)(&pCFBundleGetBundleWithIdentifier) =
+      dlsym(core_foundation_handle, "CFBundleGetBundleWithIdentifier");
+  *(void **)(&pCFBundleGetDataPointerForName) =
+      dlsym(core_foundation_handle, "CFBundleGetDataPointerForName");
+  *(void **)(&pCFBundleGetFunctionPointerForName) =
+      dlsym(core_foundation_handle, "CFBundleGetFunctionPointerForName");
+
+  if (pCFStringCreateWithCString == NULL ||
+      pCFBundleGetBundleWithIdentifier == NULL ||
+      pCFBundleGetDataPointerForName == NULL ||
+      pCFBundleGetFunctionPointerForName == NULL) {
+    goto out;
+  }
+
+#define S(s) pCFStringCreateWithCString(NULL, (s), kCFStringEncodingUTF8)
+
+  launch_services_bundle =
+      pCFBundleGetBundleWithIdentifier(S("com.apple.LaunchServices"));
+
+  if (launch_services_bundle == NULL)
+    goto out;
+
+  *(void **)(&pLSGetCurrentApplicationASN) =
+      pCFBundleGetFunctionPointerForName(launch_services_bundle,
+                                         S("_LSGetCurrentApplicationASN"));
+
+  if (pLSGetCurrentApplicationASN == NULL)
+    goto out;
+
+  *(void **)(&pLSSetApplicationInformationItem) =
+      pCFBundleGetFunctionPointerForName(launch_services_bundle,
+                                         S("_LSSetApplicationInformationItem"));
+
+  if (pLSSetApplicationInformationItem == NULL)
+    goto out;
+
+  display_name_key = (CFStringRef*)
+      pCFBundleGetDataPointerForName(launch_services_bundle,
+                                     S("_kLSDisplayNameKey"));
+
+  if (display_name_key == NULL || *display_name_key == NULL)
+    goto out;
+
+  *(void **)(&pCFBundleGetInfoDictionary) = dlsym(core_foundation_handle,
+                                     "CFBundleGetInfoDictionary");
+  *(void **)(&pCFBundleGetMainBundle) = dlsym(core_foundation_handle,
+                                 "CFBundleGetMainBundle");
+  if (pCFBundleGetInfoDictionary == NULL || pCFBundleGetMainBundle == NULL)
+    goto out;
+
+  /* Black 10.9 magic, to remove (Not responding) mark in Activity Monitor */
+  hi_services_bundle =
+      pCFBundleGetBundleWithIdentifier(S("com.apple.HIServices"));
+  err = UV_ENOENT;
+  if (hi_services_bundle == NULL)
+    goto out;
+
+  *(void **)(&pSetApplicationIsDaemon) = pCFBundleGetFunctionPointerForName(
+      hi_services_bundle,
+      S("SetApplicationIsDaemon"));
+  *(void **)(&pLSApplicationCheckIn) = pCFBundleGetFunctionPointerForName(
+      launch_services_bundle,
+      S("_LSApplicationCheckIn"));
+  *(void **)(&pLSSetApplicationLaunchServicesServerConnectionStatus) =
+      pCFBundleGetFunctionPointerForName(
+          launch_services_bundle,
+          S("_LSSetApplicationLaunchServicesServerConnectionStatus"));
+  if (pSetApplicationIsDaemon == NULL ||
+      pLSApplicationCheckIn == NULL ||
+      pLSSetApplicationLaunchServicesServerConnectionStatus == NULL) {
+    goto out;
+  }
+
+  if (pSetApplicationIsDaemon(1) != noErr)
+    goto out;
+
+  pLSSetApplicationLaunchServicesServerConnectionStatus(0, NULL);
+
+  /* Check into process manager?! */
+  pLSApplicationCheckIn(-2,
+                        pCFBundleGetInfoDictionary(pCFBundleGetMainBundle()));
+
+  asn = pLSGetCurrentApplicationASN();
+
+  err = UV_EINVAL;
+  if (pLSSetApplicationInformationItem(-2,  /* Magic value. */
+                                       asn,
+                                       *display_name_key,
+                                       S(title),
+                                       NULL) != noErr) {
+    goto out;
+  }
+
+  uv__pthread_setname_np(title);  /* Don't care if it fails. */
+  err = 0;
+
+out:
+  if (core_foundation_handle != NULL)
+    dlclose(core_foundation_handle);
+
+  if (application_services_handle != NULL)
+    dlclose(application_services_handle);
+
+  return err;
+#endif  /* !TARGET_OS_IPHONE */
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/darwin.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/darwin.cpp
new file mode 100644
index 0000000..9dc3d1b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/darwin.cpp
@@ -0,0 +1,231 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <stdint.h>
+#include <errno.h>
+
+#include <mach/mach.h>
+#include <mach/mach_time.h>
+#include <mach-o/dyld.h> /* _NSGetExecutablePath */
+#include <sys/resource.h>
+#include <sys/sysctl.h>
+#include <unistd.h>  /* sysconf */
+
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  loop->cf_state = NULL;
+
+  if (uv__kqueue_init(loop))
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+  uv__fsevents_loop_delete(loop);
+}
+
+
+uint64_t uv__hrtime(uv_clocktype_t type) {
+  static mach_timebase_info_data_t info;
+
+  if ((ACCESS_ONCE(uint32_t, info.numer) == 0 ||
+       ACCESS_ONCE(uint32_t, info.denom) == 0) &&
+      mach_timebase_info(&info) != KERN_SUCCESS)
+    abort();
+
+  return mach_absolute_time() * info.numer / info.denom;
+}
+
+
+int uv_exepath(char* buffer, size_t* size) {
+  /* realpath(exepath) may be > PATH_MAX so double it to be on the safe side. */
+  char abspath[PATH_MAX * 2 + 1];
+  char exepath[PATH_MAX + 1];
+  uint32_t exepath_size;
+  size_t abspath_size;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  exepath_size = sizeof(exepath);
+  if (_NSGetExecutablePath(exepath, &exepath_size))
+    return UV_EIO;
+
+  if (realpath(exepath, abspath) != abspath)
+    return UV__ERR(errno);
+
+  abspath_size = strlen(abspath);
+  if (abspath_size == 0)
+    return UV_EIO;
+
+  *size -= 1;
+  if (*size > abspath_size)
+    *size = abspath_size;
+
+  memcpy(buffer, abspath, *size);
+  buffer[*size] = '\0';
+
+  return 0;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  vm_statistics_data_t info;
+  mach_msg_type_number_t count = sizeof(info) / sizeof(integer_t);
+
+  if (host_statistics(mach_host_self(), HOST_VM_INFO,
+                      (host_info_t)&info, &count) != KERN_SUCCESS) {
+    return UV_EINVAL;  /* FIXME(bnoordhuis) Translate error. */
+  }
+
+  return (uint64_t) info.free_count * sysconf(_SC_PAGESIZE);
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  uint64_t info;
+  int which[] = {CTL_HW, HW_MEMSIZE};
+  size_t size = sizeof(info);
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info;
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct loadavg info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_LOADAVG};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0) < 0) return;
+
+  avg[0] = (double) info.ldavg[0] / info.fscale;
+  avg[1] = (double) info.ldavg[1] / info.fscale;
+  avg[2] = (double) info.ldavg[2] / info.fscale;
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  mach_msg_type_number_t count;
+  task_basic_info_data_t info;
+  kern_return_t err;
+
+  count = TASK_BASIC_INFO_COUNT;
+  err = task_info(mach_task_self(),
+                  TASK_BASIC_INFO,
+                  (task_info_t) &info,
+                  &count);
+  (void) &err;
+  /* task_info(TASK_BASIC_INFO) cannot really fail. Anything other than
+   * KERN_SUCCESS implies a libuv bug.
+   */
+  assert(err == KERN_SUCCESS);
+  *rss = info.resident_size;
+
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  time_t now;
+  struct timeval info;
+  size_t size = sizeof(info);
+  static int which[] = {CTL_KERN, KERN_BOOTTIME};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  now = time(NULL);
+  *uptime = now - info.tv_sec;
+
+  return 0;
+}
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
+               multiplier = ((uint64_t)1000L / ticks);
+  char model[512];
+  uint64_t cpuspeed;
+  size_t size;
+  unsigned int i;
+  natural_t numcpus;
+  mach_msg_type_number_t msg_type;
+  processor_cpu_load_info_data_t *info;
+  uv_cpu_info_t* cpu_info;
+
+  size = sizeof(model);
+  if (sysctlbyname("machdep.cpu.brand_string", &model, &size, NULL, 0) &&
+      sysctlbyname("hw.model", &model, &size, NULL, 0)) {
+    return UV__ERR(errno);
+  }
+
+  size = sizeof(cpuspeed);
+  if (sysctlbyname("hw.cpufrequency", &cpuspeed, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  if (host_processor_info(mach_host_self(), PROCESSOR_CPU_LOAD_INFO, &numcpus,
+                          (processor_info_array_t*)&info,
+                          &msg_type) != KERN_SUCCESS) {
+    return UV_EINVAL;  /* FIXME(bnoordhuis) Translate error. */
+  }
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+  if (!(*cpu_infos)) {
+    vm_deallocate(mach_task_self(), (vm_address_t)info, msg_type);
+    return UV_ENOMEM;
+  }
+
+  *count = numcpus;
+
+  for (i = 0; i < numcpus; i++) {
+    cpu_info = &(*cpu_infos)[i];
+
+    cpu_info->cpu_times.user = (uint64_t)(info[i].cpu_ticks[0]) * multiplier;
+    cpu_info->cpu_times.nice = (uint64_t)(info[i].cpu_ticks[3]) * multiplier;
+    cpu_info->cpu_times.sys = (uint64_t)(info[i].cpu_ticks[1]) * multiplier;
+    cpu_info->cpu_times.idle = (uint64_t)(info[i].cpu_ticks[2]) * multiplier;
+    cpu_info->cpu_times.irq = 0;
+
+    cpu_info->model = uv__strdup(model);
+    cpu_info->speed = cpuspeed/1000000;
+  }
+  vm_deallocate(mach_task_self(), (vm_address_t)info, msg_type);
+
+  return 0;
+}
+
+
+void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(cpu_infos[i].model);
+  }
+
+  uv__free(cpu_infos);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/dl.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/dl.cpp
new file mode 100644
index 0000000..fc1c052
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/dl.cpp
@@ -0,0 +1,80 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <dlfcn.h>
+#include <errno.h>
+#include <string.h>
+#include <locale.h>
+
+static int uv__dlerror(uv_lib_t* lib);
+
+
+int uv_dlopen(const char* filename, uv_lib_t* lib) {
+  dlerror(); /* Reset error status. */
+  lib->errmsg = NULL;
+  lib->handle = dlopen(filename, RTLD_LAZY);
+  return lib->handle ? 0 : uv__dlerror(lib);
+}
+
+
+void uv_dlclose(uv_lib_t* lib) {
+  uv__free(lib->errmsg);
+  lib->errmsg = NULL;
+
+  if (lib->handle) {
+    /* Ignore errors. No good way to signal them without leaking memory. */
+    dlclose(lib->handle);
+    lib->handle = NULL;
+  }
+}
+
+
+int uv_dlsym(uv_lib_t* lib, const char* name, void** ptr) {
+  dlerror(); /* Reset error status. */
+  *ptr = dlsym(lib->handle, name);
+  return uv__dlerror(lib);
+}
+
+
+const char* uv_dlerror(const uv_lib_t* lib) {
+  return lib->errmsg ? lib->errmsg : "no error";
+}
+
+
+static int uv__dlerror(uv_lib_t* lib) {
+  const char* errmsg;
+
+  uv__free(lib->errmsg);
+
+  errmsg = dlerror();
+
+  if (errmsg) {
+    lib->errmsg = uv__strdup(errmsg);
+    return -1;
+  }
+  else {
+    lib->errmsg = NULL;
+    return 0;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/freebsd.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/freebsd.cpp
new file mode 100644
index 0000000..789ee2c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/freebsd.cpp
@@ -0,0 +1,375 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+
+#include <paths.h>
+#include <sys/user.h>
+#include <sys/types.h>
+#include <sys/resource.h>
+#include <sys/sysctl.h>
+#include <vm/vm_param.h> /* VM_LOADAVG */
+#include <time.h>
+#include <stdlib.h>
+#include <unistd.h> /* sysconf */
+#include <fcntl.h>
+
+#ifndef CPUSTATES
+# define CPUSTATES 5U
+#endif
+#ifndef CP_USER
+# define CP_USER 0
+# define CP_NICE 1
+# define CP_SYS 2
+# define CP_IDLE 3
+# define CP_INTR 4
+#endif
+
+static uv_mutex_t process_title_mutex;
+static uv_once_t process_title_mutex_once = UV_ONCE_INIT;
+static char *process_title;
+
+
+static void init_process_title_mutex_once(void) {
+  uv_mutex_init(&process_title_mutex);
+}
+
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  return uv__kqueue_init(loop);
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+}
+
+
+#ifdef __DragonFly__
+int uv_exepath(char* buffer, size_t* size) {
+  char abspath[PATH_MAX * 2 + 1];
+  ssize_t abspath_size;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  abspath_size = readlink("/proc/curproc/file", abspath, sizeof(abspath));
+  if (abspath_size < 0)
+    return UV__ERR(errno);
+
+  assert(abspath_size > 0);
+  *size -= 1;
+
+  if (*size > abspath_size)
+    *size = abspath_size;
+
+  memcpy(buffer, abspath, *size);
+  buffer[*size] = '\0';
+
+  return 0;
+}
+#else
+int uv_exepath(char* buffer, size_t* size) {
+  char abspath[PATH_MAX * 2 + 1];
+  int mib[4];
+  size_t abspath_size;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  mib[0] = CTL_KERN;
+  mib[1] = KERN_PROC;
+  mib[2] = KERN_PROC_PATHNAME;
+  mib[3] = -1;
+
+  abspath_size = sizeof abspath;
+  if (sysctl(mib, 4, abspath, &abspath_size, NULL, 0))
+    return UV__ERR(errno);
+
+  assert(abspath_size > 0);
+  abspath_size -= 1;
+  *size -= 1;
+
+  if (*size > abspath_size)
+    *size = abspath_size;
+
+  memcpy(buffer, abspath, *size);
+  buffer[*size] = '\0';
+
+  return 0;
+}
+#endif
+
+uint64_t uv_get_free_memory(void) {
+  int freecount;
+  size_t size = sizeof(freecount);
+
+  if (sysctlbyname("vm.stats.vm.v_free_count", &freecount, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) freecount * sysconf(_SC_PAGESIZE);
+
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  unsigned long info;
+  int which[] = {CTL_HW, HW_PHYSMEM};
+
+  size_t size = sizeof(info);
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info;
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct loadavg info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_LOADAVG};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0) < 0) return;
+
+  avg[0] = (double) info.ldavg[0] / info.fscale;
+  avg[1] = (double) info.ldavg[1] / info.fscale;
+  avg[2] = (double) info.ldavg[2] / info.fscale;
+}
+
+
+char** uv_setup_args(int argc, char** argv) {
+  process_title = argc ? uv__strdup(argv[0]) : NULL;
+  return argv;
+}
+
+
+int uv_set_process_title(const char* title) {
+  int oid[4];
+  char* new_title;
+
+  new_title = uv__strdup(title);
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (process_title == NULL) {
+    uv_mutex_unlock(&process_title_mutex);
+    return UV_ENOMEM;
+  }
+
+  uv__free(process_title);
+  process_title = new_title;
+
+  oid[0] = CTL_KERN;
+  oid[1] = KERN_PROC;
+  oid[2] = KERN_PROC_ARGS;
+  oid[3] = getpid();
+
+  sysctl(oid,
+         ARRAY_SIZE(oid),
+         NULL,
+         NULL,
+         process_title,
+         strlen(process_title) + 1);
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  return 0;
+}
+
+
+int uv_get_process_title(char* buffer, size_t size) {
+  size_t len;
+
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (process_title) {
+    len = strlen(process_title) + 1;
+
+    if (size < len) {
+      uv_mutex_unlock(&process_title_mutex);
+      return UV_ENOBUFS;
+    }
+
+    memcpy(buffer, process_title, len);
+  } else {
+    len = 0;
+  }
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  buffer[len] = '\0';
+
+  return 0;
+}
+
+int uv_resident_set_memory(size_t* rss) {
+  struct kinfo_proc kinfo;
+  size_t page_size;
+  size_t kinfo_size;
+  int mib[4];
+
+  mib[0] = CTL_KERN;
+  mib[1] = KERN_PROC;
+  mib[2] = KERN_PROC_PID;
+  mib[3] = getpid();
+
+  kinfo_size = sizeof(kinfo);
+
+  if (sysctl(mib, 4, &kinfo, &kinfo_size, NULL, 0))
+    return UV__ERR(errno);
+
+  page_size = getpagesize();
+
+#ifdef __DragonFly__
+  *rss = kinfo.kp_vm_rssize * page_size;
+#else
+  *rss = kinfo.ki_rssize * page_size;
+#endif
+
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  int r;
+  struct timespec sp;
+  r = clock_gettime(CLOCK_MONOTONIC, &sp);
+  if (r)
+    return UV__ERR(errno);
+
+  *uptime = sp.tv_sec;
+  return 0;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
+               multiplier = ((uint64_t)1000L / ticks), cpuspeed, maxcpus,
+               cur = 0;
+  uv_cpu_info_t* cpu_info;
+  const char* maxcpus_key;
+  const char* cptimes_key;
+  const char* model_key;
+  char model[512];
+  long* cp_times;
+  int numcpus;
+  size_t size;
+  int i;
+
+#if defined(__DragonFly__)
+  /* This is not quite correct but DragonFlyBSD doesn't seem to have anything
+   * comparable to kern.smp.maxcpus or kern.cp_times (kern.cp_time is a total,
+   * not per CPU). At least this stops uv_cpu_info() from failing completely.
+   */
+  maxcpus_key = "hw.ncpu";
+  cptimes_key = "kern.cp_time";
+#else
+  maxcpus_key = "kern.smp.maxcpus";
+  cptimes_key = "kern.cp_times";
+#endif
+
+#if defined(__arm__) || defined(__aarch64__)
+  /* The key hw.model and hw.clockrate are not available on FreeBSD ARM. */
+  model_key = "hw.machine";
+  cpuspeed = 0;
+#else
+  model_key = "hw.model";
+
+  size = sizeof(cpuspeed);
+  if (sysctlbyname("hw.clockrate", &cpuspeed, &size, NULL, 0))
+    return -errno;
+#endif
+
+  size = sizeof(model);
+  if (sysctlbyname(model_key, &model, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  size = sizeof(numcpus);
+  if (sysctlbyname("hw.ncpu", &numcpus, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+  if (!(*cpu_infos))
+    return UV_ENOMEM;
+
+  *count = numcpus;
+
+  /* kern.cp_times on FreeBSD i386 gives an array up to maxcpus instead of
+   * ncpu.
+   */
+  size = sizeof(maxcpus);
+  if (sysctlbyname(maxcpus_key, &maxcpus, &size, NULL, 0)) {
+    uv__free(*cpu_infos);
+    return UV__ERR(errno);
+  }
+
+  size = maxcpus * CPUSTATES * sizeof(long);
+
+  cp_times = (long*)uv__malloc(size);
+  if (cp_times == NULL) {
+    uv__free(*cpu_infos);
+    return UV_ENOMEM;
+  }
+
+  if (sysctlbyname(cptimes_key, cp_times, &size, NULL, 0)) {
+    uv__free(cp_times);
+    uv__free(*cpu_infos);
+    return UV__ERR(errno);
+  }
+
+  for (i = 0; i < numcpus; i++) {
+    cpu_info = &(*cpu_infos)[i];
+
+    cpu_info->cpu_times.user = (uint64_t)(cp_times[CP_USER+cur]) * multiplier;
+    cpu_info->cpu_times.nice = (uint64_t)(cp_times[CP_NICE+cur]) * multiplier;
+    cpu_info->cpu_times.sys = (uint64_t)(cp_times[CP_SYS+cur]) * multiplier;
+    cpu_info->cpu_times.idle = (uint64_t)(cp_times[CP_IDLE+cur]) * multiplier;
+    cpu_info->cpu_times.irq = (uint64_t)(cp_times[CP_INTR+cur]) * multiplier;
+
+    cpu_info->model = uv__strdup(model);
+    cpu_info->speed = cpuspeed;
+
+    cur+=CPUSTATES;
+  }
+
+  uv__free(cp_times);
+  return 0;
+}
+
+
+void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(cpu_infos[i].model);
+  }
+
+  uv__free(cpu_infos);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/fs.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/fs.cpp
new file mode 100644
index 0000000..c958a83
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/fs.cpp
@@ -0,0 +1,1576 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* Caveat emptor: this file deviates from the libuv convention of returning
+ * negated errno codes. Most uv_fs_*() functions map directly to the system
+ * call of the same name. For more complex wrappers, it's easier to just
+ * return -1 with errno set. The dispatcher in uv__fs_work() takes care of
+ * getting the errno to the right place (req->result or as the return value.)
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <limits.h> /* PATH_MAX */
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/stat.h>
+#include <sys/time.h>
+#include <sys/uio.h>
+#include <pthread.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <utime.h>
+#include <poll.h>
+
+#if defined(__DragonFly__)        ||                                      \
+    defined(__FreeBSD__)          ||                                      \
+    defined(__FreeBSD_kernel_)    ||                                      \
+    defined(__OpenBSD__)          ||                                      \
+    defined(__NetBSD__)
+# define HAVE_PREADV 1
+#else
+# define HAVE_PREADV 0
+#endif
+
+#if defined(__linux__) || defined(__sun)
+# include <sys/sendfile.h>
+#endif
+
+#if defined(__APPLE__)
+# include <copyfile.h>
+#elif defined(__linux__) && !defined(FICLONE)
+# include <sys/ioctl.h>
+# define FICLONE _IOW(0x94, 9, int)
+#endif
+
+#define INIT(subtype)                                                         \
+  do {                                                                        \
+    if (req == NULL)                                                          \
+      return UV_EINVAL;                                                       \
+    UV_REQ_INIT(req, UV_FS);                                                  \
+    req->fs_type = UV_FS_ ## subtype;                                         \
+    req->result = 0;                                                          \
+    req->ptr = NULL;                                                          \
+    req->loop = loop;                                                         \
+    req->path = NULL;                                                         \
+    req->new_path = NULL;                                                     \
+    req->bufs = NULL;                                                         \
+    req->cb = cb;                                                             \
+  }                                                                           \
+  while (0)
+
+#define PATH                                                                  \
+  do {                                                                        \
+    assert(path != NULL);                                                     \
+    if (cb == NULL) {                                                         \
+      req->path = path;                                                       \
+    } else {                                                                  \
+      req->path = uv__strdup(path);                                           \
+      if (req->path == NULL)                                                  \
+        return UV_ENOMEM;                                                     \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+#define PATH2                                                                 \
+  do {                                                                        \
+    if (cb == NULL) {                                                         \
+      req->path = path;                                                       \
+      req->new_path = new_path;                                               \
+    } else {                                                                  \
+      size_t path_len;                                                        \
+      size_t new_path_len;                                                    \
+      path_len = strlen(path) + 1;                                            \
+      new_path_len = strlen(new_path) + 1;                                    \
+      req->path = (char*)uv__malloc(path_len + new_path_len);                 \
+      if (req->path == NULL)                                                  \
+        return UV_ENOMEM;                                                     \
+      req->new_path = req->path + path_len;                                   \
+      memcpy((void*) req->path, path, path_len);                              \
+      memcpy((void*) req->new_path, new_path, new_path_len);                  \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+#define POST                                                                  \
+  do {                                                                        \
+    if (cb != NULL) {                                                         \
+      uv__req_register(loop, req);                                            \
+      uv__work_submit(loop, &req->work_req, uv__fs_work, uv__fs_done);        \
+      return 0;                                                               \
+    }                                                                         \
+    else {                                                                    \
+      uv__fs_work(&req->work_req);                                            \
+      return req->result;                                                     \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+
+static ssize_t uv__fs_fsync(uv_fs_t* req) {
+#if defined(__APPLE__)
+  /* Apple's fdatasync and fsync explicitly do NOT flush the drive write cache
+   * to the drive platters. This is in contrast to Linux's fdatasync and fsync
+   * which do, according to recent man pages. F_FULLFSYNC is Apple's equivalent
+   * for flushing buffered data to permanent storage. If F_FULLFSYNC is not
+   * supported by the file system we should fall back to fsync(). This is the
+   * same approach taken by sqlite.
+   */
+  int r;
+
+  r = fcntl(req->file, F_FULLFSYNC);
+  if (r != 0 && errno == ENOTTY)
+    r = fsync(req->file);
+  return r;
+#else
+  return fsync(req->file);
+#endif
+}
+
+
+static ssize_t uv__fs_fdatasync(uv_fs_t* req) {
+#if defined(__linux__) || defined(__sun) || defined(__NetBSD__)
+  return fdatasync(req->file);
+#elif defined(__APPLE__)
+  /* See the comment in uv__fs_fsync. */
+  return uv__fs_fsync(req);
+#else
+  return fsync(req->file);
+#endif
+}
+
+
+static ssize_t uv__fs_futime(uv_fs_t* req) {
+#if defined(__linux__)
+  /* utimesat() has nanosecond resolution but we stick to microseconds
+   * for the sake of consistency with other platforms.
+   */
+  static int no_utimesat;
+  struct timespec ts[2];
+  struct timeval tv[2];
+  char path[sizeof("/proc/self/fd/") + 3 * sizeof(int)];
+  int r;
+
+  if (no_utimesat)
+    goto skip;
+
+  ts[0].tv_sec  = req->atime;
+  ts[0].tv_nsec = (uint64_t)(req->atime * 1000000) % 1000000 * 1000;
+  ts[1].tv_sec  = req->mtime;
+  ts[1].tv_nsec = (uint64_t)(req->mtime * 1000000) % 1000000 * 1000;
+
+  r = uv__utimesat(req->file, NULL, ts, 0);
+  if (r == 0)
+    return r;
+
+  if (errno != ENOSYS)
+    return r;
+
+  no_utimesat = 1;
+
+skip:
+
+  tv[0].tv_sec  = req->atime;
+  tv[0].tv_usec = (uint64_t)(req->atime * 1000000) % 1000000;
+  tv[1].tv_sec  = req->mtime;
+  tv[1].tv_usec = (uint64_t)(req->mtime * 1000000) % 1000000;
+  snprintf(path, sizeof(path), "/proc/self/fd/%d", (int) req->file);
+
+  r = utimes(path, tv);
+  if (r == 0)
+    return r;
+
+  switch (errno) {
+  case ENOENT:
+    if (fcntl(req->file, F_GETFL) == -1 && errno == EBADF)
+      break;
+    /* Fall through. */
+
+  case EACCES:
+  case ENOTDIR:
+    errno = ENOSYS;
+    break;
+  }
+
+  return r;
+
+#elif defined(__APPLE__)                                                      \
+    || defined(__DragonFly__)                                                 \
+    || defined(__FreeBSD__)                                                   \
+    || defined(__FreeBSD_kernel__)                                            \
+    || defined(__NetBSD__)                                                    \
+    || defined(__OpenBSD__)                                                   \
+    || defined(__sun)
+  struct timeval tv[2];
+  tv[0].tv_sec  = req->atime;
+  tv[0].tv_usec = (uint64_t)(req->atime * 1000000) % 1000000;
+  tv[1].tv_sec  = req->mtime;
+  tv[1].tv_usec = (uint64_t)(req->mtime * 1000000) % 1000000;
+# if defined(__sun)
+  return futimesat(req->file, NULL, tv);
+# else
+  return futimes(req->file, tv);
+# endif
+#elif defined(_AIX71)
+  struct timespec ts[2];
+  ts[0].tv_sec  = req->atime;
+  ts[0].tv_nsec = (uint64_t)(req->atime * 1000000) % 1000000 * 1000;
+  ts[1].tv_sec  = req->mtime;
+  ts[1].tv_nsec = (uint64_t)(req->mtime * 1000000) % 1000000 * 1000;
+  return futimens(req->file, ts);
+#elif defined(__MVS__)
+  attrib_t atr;
+  memset(&atr, 0, sizeof(atr));
+  atr.att_mtimechg = 1;
+  atr.att_atimechg = 1;
+  atr.att_mtime = req->mtime;
+  atr.att_atime = req->atime;
+  return __fchattr(req->file, &atr, sizeof(atr));
+#else
+  errno = ENOSYS;
+  return -1;
+#endif
+}
+
+
+static ssize_t uv__fs_mkdtemp(uv_fs_t* req) {
+  return mkdtemp((char*) req->path) ? 0 : -1;
+}
+
+
+static ssize_t uv__fs_open(uv_fs_t* req) {
+  static int no_cloexec_support;
+  int r;
+
+  /* Try O_CLOEXEC before entering locks */
+  if (no_cloexec_support == 0) {
+#ifdef O_CLOEXEC
+    r = open(req->path, req->flags | O_CLOEXEC, req->mode);
+    if (r >= 0)
+      return r;
+    if (errno != EINVAL)
+      return r;
+    no_cloexec_support = 1;
+#endif  /* O_CLOEXEC */
+  }
+
+  if (req->cb != NULL)
+    uv_rwlock_rdlock(&req->loop->cloexec_lock);
+
+  r = open(req->path, req->flags, req->mode);
+
+  /* In case of failure `uv__cloexec` will leave error in `errno`,
+   * so it is enough to just set `r` to `-1`.
+   */
+  if (r >= 0 && uv__cloexec(r, 1) != 0) {
+    r = uv__close(r);
+    if (r != 0)
+      abort();
+    r = -1;
+  }
+
+  if (req->cb != NULL)
+    uv_rwlock_rdunlock(&req->loop->cloexec_lock);
+
+  return r;
+}
+
+
+static ssize_t uv__fs_read(uv_fs_t* req) {
+#if defined(__linux__)
+  static int no_preadv;
+#endif
+  ssize_t result;
+
+#if defined(_AIX)
+  struct stat buf;
+  if(fstat(req->file, &buf))
+    return -1;
+  if(S_ISDIR(buf.st_mode)) {
+    errno = EISDIR;
+    return -1;
+  }
+#endif /* defined(_AIX) */
+  if (req->off < 0) {
+    if (req->nbufs == 1)
+      result = read(req->file, req->bufs[0].base, req->bufs[0].len);
+    else
+      result = readv(req->file, (struct iovec*) req->bufs, req->nbufs);
+  } else {
+    if (req->nbufs == 1) {
+      result = pread(req->file, req->bufs[0].base, req->bufs[0].len, req->off);
+      goto done;
+    }
+
+#if HAVE_PREADV
+    result = preadv(req->file, (struct iovec*) req->bufs, req->nbufs, req->off);
+#else
+# if defined(__linux__)
+    if (no_preadv) retry:
+# endif
+    {
+      off_t nread;
+      size_t index;
+
+      nread = 0;
+      index = 0;
+      result = 1;
+      do {
+        if (req->bufs[index].len > 0) {
+          result = pread(req->file,
+                         req->bufs[index].base,
+                         req->bufs[index].len,
+                         req->off + nread);
+          if (result > 0)
+            nread += result;
+        }
+        index++;
+      } while (index < req->nbufs && result > 0);
+      if (nread > 0)
+        result = nread;
+    }
+# if defined(__linux__)
+    else {
+      result = uv__preadv(req->file,
+                          (struct iovec*)req->bufs,
+                          req->nbufs,
+                          req->off);
+      if (result == -1 && errno == ENOSYS) {
+        no_preadv = 1;
+        goto retry;
+      }
+    }
+# endif
+#endif
+  }
+
+done:
+  return result;
+}
+
+
+#if defined(__APPLE__) && !defined(MAC_OS_X_VERSION_10_8)
+#define UV_CONST_DIRENT uv__dirent_t
+#else
+#define UV_CONST_DIRENT const uv__dirent_t
+#endif
+
+
+static int uv__fs_scandir_filter(UV_CONST_DIRENT* dent) {
+  return strcmp(dent->d_name, ".") != 0 && strcmp(dent->d_name, "..") != 0;
+}
+
+
+static int uv__fs_scandir_sort(UV_CONST_DIRENT** a, UV_CONST_DIRENT** b) {
+  return strcmp((*a)->d_name, (*b)->d_name);
+}
+
+
+static ssize_t uv__fs_scandir(uv_fs_t* req) {
+  uv__dirent_t **dents;
+  int n;
+
+  dents = NULL;
+  n = scandir(req->path, &dents, uv__fs_scandir_filter, uv__fs_scandir_sort);
+
+  /* NOTE: We will use nbufs as an index field */
+  req->nbufs = 0;
+
+  if (n == 0) {
+    /* OS X still needs to deallocate some memory.
+     * Memory was allocated using the system allocator, so use free() here.
+     */
+    free(dents);
+    dents = NULL;
+  } else if (n == -1) {
+    return n;
+  }
+
+  req->ptr = dents;
+
+  return n;
+}
+
+
+static ssize_t uv__fs_pathmax_size(const char* path) {
+  ssize_t pathmax;
+
+  pathmax = pathconf(path, _PC_PATH_MAX);
+
+  if (pathmax == -1) {
+#if defined(PATH_MAX)
+    return PATH_MAX;
+#else
+#error "PATH_MAX undefined in the current platform"
+#endif
+  }
+
+  return pathmax;
+}
+
+static ssize_t uv__fs_readlink(uv_fs_t* req) {
+  ssize_t len;
+  char* buf;
+
+  len = uv__fs_pathmax_size(req->path);
+  buf = (char*)uv__malloc(len + 1);
+
+  if (buf == NULL) {
+    errno = ENOMEM;
+    return -1;
+  }
+
+#if defined(__MVS__)
+  len = os390_readlink(req->path, buf, len);
+#else
+  len = readlink(req->path, buf, len);
+#endif
+
+
+  if (len == -1) {
+    uv__free(buf);
+    return -1;
+  }
+
+  buf[len] = '\0';
+  req->ptr = buf;
+
+  return 0;
+}
+
+static ssize_t uv__fs_realpath(uv_fs_t* req) {
+  ssize_t len;
+  char* buf;
+
+  len = uv__fs_pathmax_size(req->path);
+  buf = (char*)uv__malloc(len + 1);
+
+  if (buf == NULL) {
+    errno = ENOMEM;
+    return -1;
+  }
+
+  if (realpath(req->path, buf) == NULL) {
+    uv__free(buf);
+    return -1;
+  }
+
+  req->ptr = buf;
+
+  return 0;
+}
+
+static ssize_t uv__fs_sendfile_emul(uv_fs_t* req) {
+  struct pollfd pfd;
+  int use_pread;
+  off_t offset;
+  ssize_t nsent;
+  ssize_t nread;
+  ssize_t nwritten;
+  size_t buflen;
+  size_t len;
+  ssize_t n;
+  int in_fd;
+  int out_fd;
+  char buf[8192];
+
+  len = req->bufsml[0].len;
+  in_fd = req->flags;
+  out_fd = req->file;
+  offset = req->off;
+  use_pread = 1;
+
+  /* Here are the rules regarding errors:
+   *
+   * 1. Read errors are reported only if nsent==0, otherwise we return nsent.
+   *    The user needs to know that some data has already been sent, to stop
+   *    them from sending it twice.
+   *
+   * 2. Write errors are always reported. Write errors are bad because they
+   *    mean data loss: we've read data but now we can't write it out.
+   *
+   * We try to use pread() and fall back to regular read() if the source fd
+   * doesn't support positional reads, for example when it's a pipe fd.
+   *
+   * If we get EAGAIN when writing to the target fd, we poll() on it until
+   * it becomes writable again.
+   *
+   * FIXME: If we get a write error when use_pread==1, it should be safe to
+   *        return the number of sent bytes instead of an error because pread()
+   *        is, in theory, idempotent. However, special files in /dev or /proc
+   *        may support pread() but not necessarily return the same data on
+   *        successive reads.
+   *
+   * FIXME: There is no way now to signal that we managed to send *some* data
+   *        before a write error.
+   */
+  for (nsent = 0; (size_t) nsent < len; ) {
+    buflen = len - nsent;
+
+    if (buflen > sizeof(buf))
+      buflen = sizeof(buf);
+
+    do
+      if (use_pread)
+        nread = pread(in_fd, buf, buflen, offset);
+      else
+        nread = read(in_fd, buf, buflen);
+    while (nread == -1 && errno == EINTR);
+
+    if (nread == 0)
+      goto out;
+
+    if (nread == -1) {
+      if (use_pread && nsent == 0 && (errno == EIO || errno == ESPIPE)) {
+        use_pread = 0;
+        continue;
+      }
+
+      if (nsent == 0)
+        nsent = -1;
+
+      goto out;
+    }
+
+    for (nwritten = 0; nwritten < nread; ) {
+      do
+        n = write(out_fd, buf + nwritten, nread - nwritten);
+      while (n == -1 && errno == EINTR);
+
+      if (n != -1) {
+        nwritten += n;
+        continue;
+      }
+
+      if (errno != EAGAIN && errno != EWOULDBLOCK) {
+        nsent = -1;
+        goto out;
+      }
+
+      pfd.fd = out_fd;
+      pfd.events = POLLOUT;
+      pfd.revents = 0;
+
+      do
+        n = poll(&pfd, 1, -1);
+      while (n == -1 && errno == EINTR);
+
+      if (n == -1 || (pfd.revents & ~POLLOUT) != 0) {
+        errno = EIO;
+        nsent = -1;
+        goto out;
+      }
+    }
+
+    offset += nread;
+    nsent += nread;
+  }
+
+out:
+  if (nsent != -1)
+    req->off = offset;
+
+  return nsent;
+}
+
+
+static ssize_t uv__fs_sendfile(uv_fs_t* req) {
+  int in_fd;
+  int out_fd;
+
+  in_fd = req->flags;
+  out_fd = req->file;
+
+#if defined(__linux__) || defined(__sun)
+  {
+    off_t off;
+    ssize_t r;
+
+    off = req->off;
+    r = sendfile(out_fd, in_fd, &off, req->bufsml[0].len);
+
+    /* sendfile() on SunOS returns EINVAL if the target fd is not a socket but
+     * it still writes out data. Fortunately, we can detect it by checking if
+     * the offset has been updated.
+     */
+    if (r != -1 || off > req->off) {
+      r = off - req->off;
+      req->off = off;
+      return r;
+    }
+
+    if (errno == EINVAL ||
+        errno == EIO ||
+        errno == ENOTSOCK ||
+        errno == EXDEV) {
+      errno = 0;
+      return uv__fs_sendfile_emul(req);
+    }
+
+    return -1;
+  }
+#elif defined(__APPLE__)           || \
+      defined(__DragonFly__)       || \
+      defined(__FreeBSD__)         || \
+      defined(__FreeBSD_kernel__)
+  {
+    off_t len;
+    ssize_t r;
+
+    /* sendfile() on FreeBSD and Darwin returns EAGAIN if the target fd is in
+     * non-blocking mode and not all data could be written. If a non-zero
+     * number of bytes have been sent, we don't consider it an error.
+     */
+
+#if defined(__FreeBSD__) || defined(__DragonFly__)
+    len = 0;
+    r = sendfile(in_fd, out_fd, req->off, req->bufsml[0].len, NULL, &len, 0);
+#elif defined(__FreeBSD_kernel__)
+    len = 0;
+    r = bsd_sendfile(in_fd,
+                     out_fd,
+                     req->off,
+                     req->bufsml[0].len,
+                     NULL,
+                     &len,
+                     0);
+#else
+    /* The darwin sendfile takes len as an input for the length to send,
+     * so make sure to initialize it with the caller's value. */
+    len = req->bufsml[0].len;
+    r = sendfile(in_fd, out_fd, req->off, &len, NULL, 0);
+#endif
+
+     /*
+     * The man page for sendfile(2) on DragonFly states that `len` contains
+     * a meaningful value ONLY in case of EAGAIN and EINTR.
+     * Nothing is said about it's value in case of other errors, so better
+     * not depend on the potential wrong assumption that is was not modified
+     * by the syscall.
+     */
+    if (r == 0 || ((errno == EAGAIN || errno == EINTR) && len != 0)) {
+      req->off += len;
+      return (ssize_t) len;
+    }
+
+    if (errno == EINVAL ||
+        errno == EIO ||
+        errno == ENOTSOCK ||
+        errno == EXDEV) {
+      errno = 0;
+      return uv__fs_sendfile_emul(req);
+    }
+
+    return -1;
+  }
+#else
+  /* Squelch compiler warnings. */
+  (void) &in_fd;
+  (void) &out_fd;
+
+  return uv__fs_sendfile_emul(req);
+#endif
+}
+
+
+static ssize_t uv__fs_utime(uv_fs_t* req) {
+  struct utimbuf buf;
+  buf.actime = req->atime;
+  buf.modtime = req->mtime;
+  return utime(req->path, &buf); /* TODO use utimes() where available */
+}
+
+
+static ssize_t uv__fs_write(uv_fs_t* req) {
+#if defined(__linux__)
+  static int no_pwritev;
+#endif
+  ssize_t r;
+
+  /* Serialize writes on OS X, concurrent write() and pwrite() calls result in
+   * data loss. We can't use a per-file descriptor lock, the descriptor may be
+   * a dup().
+   */
+#if defined(__APPLE__)
+  static pthread_mutex_t lock = PTHREAD_MUTEX_INITIALIZER;
+
+  if (pthread_mutex_lock(&lock))
+    abort();
+#endif
+
+  if (req->off < 0) {
+    if (req->nbufs == 1)
+      r = write(req->file, req->bufs[0].base, req->bufs[0].len);
+    else
+      r = writev(req->file, (struct iovec*) req->bufs, req->nbufs);
+  } else {
+    if (req->nbufs == 1) {
+      r = pwrite(req->file, req->bufs[0].base, req->bufs[0].len, req->off);
+      goto done;
+    }
+#if HAVE_PREADV
+    r = pwritev(req->file, (struct iovec*) req->bufs, req->nbufs, req->off);
+#else
+# if defined(__linux__)
+    if (no_pwritev) retry:
+# endif
+    {
+      off_t written;
+      size_t index;
+
+      written = 0;
+      index = 0;
+      r = 0;
+      do {
+        if (req->bufs[index].len > 0) {
+          r = pwrite(req->file,
+                     req->bufs[index].base,
+                     req->bufs[index].len,
+                     req->off + written);
+          if (r > 0)
+            written += r;
+        }
+        index++;
+      } while (index < req->nbufs && r >= 0);
+      if (written > 0)
+        r = written;
+    }
+# if defined(__linux__)
+    else {
+      r = uv__pwritev(req->file,
+                      (struct iovec*) req->bufs,
+                      req->nbufs,
+                      req->off);
+      if (r == -1 && errno == ENOSYS) {
+        no_pwritev = 1;
+        goto retry;
+      }
+    }
+# endif
+#endif
+  }
+
+done:
+#if defined(__APPLE__)
+  if (pthread_mutex_unlock(&lock))
+    abort();
+#endif
+
+  return r;
+}
+
+static ssize_t uv__fs_copyfile(uv_fs_t* req) {
+#if defined(__APPLE__) && !TARGET_OS_IPHONE
+  /* On macOS, use the native copyfile(3). */
+  copyfile_flags_t flags;
+
+  flags = COPYFILE_ALL;
+
+  if (req->flags & UV_FS_COPYFILE_EXCL)
+    flags |= COPYFILE_EXCL;
+
+#ifdef COPYFILE_CLONE
+  if (req->flags & UV_FS_COPYFILE_FICLONE)
+    flags |= COPYFILE_CLONE;
+#endif
+
+  if (req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+#ifdef COPYFILE_CLONE_FORCE
+    flags |= COPYFILE_CLONE_FORCE;
+#else
+    return UV_ENOSYS;
+#endif
+  }
+
+  return copyfile(req->path, req->new_path, NULL, flags);
+#else
+  uv_fs_t fs_req;
+  uv_file srcfd;
+  uv_file dstfd;
+  struct stat statsbuf;
+  int dst_flags;
+  int result;
+  int err;
+  size_t bytes_to_send;
+  int64_t in_offset;
+
+  dstfd = -1;
+  err = 0;
+
+  /* Open the source file. */
+  srcfd = uv_fs_open(NULL, &fs_req, req->path, O_RDONLY, 0, NULL);
+  uv_fs_req_cleanup(&fs_req);
+
+  if (srcfd < 0)
+    return srcfd;
+
+  /* Get the source file's mode. */
+  if (fstat(srcfd, &statsbuf)) {
+    err = UV__ERR(errno);
+    goto out;
+  }
+
+  dst_flags = O_WRONLY | O_CREAT | O_TRUNC;
+
+  if (req->flags & UV_FS_COPYFILE_EXCL)
+    dst_flags |= O_EXCL;
+
+  /* Open the destination file. */
+  dstfd = uv_fs_open(NULL,
+                     &fs_req,
+                     req->new_path,
+                     dst_flags,
+                     statsbuf.st_mode,
+                     NULL);
+  uv_fs_req_cleanup(&fs_req);
+
+  if (dstfd < 0) {
+    err = dstfd;
+    goto out;
+  }
+
+  if (fchmod(dstfd, statsbuf.st_mode) == -1) {
+    err = UV__ERR(errno);
+    goto out;
+  }
+
+#ifdef FICLONE
+  if (req->flags & UV_FS_COPYFILE_FICLONE ||
+      req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+    if (ioctl(dstfd, FICLONE, srcfd) == -1) {
+      /* If an error occurred that the sendfile fallback also won't handle, or
+         this is a force clone then exit. Otherwise, fall through to try using
+         sendfile(). */
+      if (errno != ENOTTY && errno != EOPNOTSUPP && errno != EXDEV) {
+        err = UV__ERR(errno);
+        goto out;
+      } else if (req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+        err = UV_ENOTSUP;
+        goto out;
+      }
+    } else {
+      goto out;
+    }
+  }
+#else
+  if (req->flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+    err = UV_ENOSYS;
+    goto out;
+  }
+#endif
+
+  bytes_to_send = statsbuf.st_size;
+  in_offset = 0;
+  while (bytes_to_send != 0) {
+    err = uv_fs_sendfile(NULL,
+                         &fs_req,
+                         dstfd,
+                         srcfd,
+                         in_offset,
+                         bytes_to_send,
+                         NULL);
+    uv_fs_req_cleanup(&fs_req);
+    if (err < 0)
+      break;
+    bytes_to_send -= fs_req.result;
+    in_offset += fs_req.result;
+  }
+
+out:
+  if (err < 0)
+    result = err;
+  else
+    result = 0;
+
+  /* Close the source file. */
+  err = uv__close_nocheckstdio(srcfd);
+
+  /* Don't overwrite any existing errors. */
+  if (err != 0 && result == 0)
+    result = err;
+
+  /* Close the destination file if it is open. */
+  if (dstfd >= 0) {
+    err = uv__close_nocheckstdio(dstfd);
+
+    /* Don't overwrite any existing errors. */
+    if (err != 0 && result == 0)
+      result = err;
+
+    /* Remove the destination file if something went wrong. */
+    if (result != 0) {
+      uv_fs_unlink(NULL, &fs_req, req->new_path, NULL);
+      /* Ignore the unlink return value, as an error already happened. */
+      uv_fs_req_cleanup(&fs_req);
+    }
+  }
+
+  if (result == 0)
+    return 0;
+
+  errno = UV__ERR(result);
+  return -1;
+#endif
+}
+
+static void uv__to_stat(struct stat* src, uv_stat_t* dst) {
+  dst->st_dev = src->st_dev;
+  dst->st_mode = src->st_mode;
+  dst->st_nlink = src->st_nlink;
+  dst->st_uid = src->st_uid;
+  dst->st_gid = src->st_gid;
+  dst->st_rdev = src->st_rdev;
+  dst->st_ino = src->st_ino;
+  dst->st_size = src->st_size;
+  dst->st_blksize = src->st_blksize;
+  dst->st_blocks = src->st_blocks;
+
+#if defined(__APPLE__)
+  dst->st_atim.tv_sec = src->st_atimespec.tv_sec;
+  dst->st_atim.tv_nsec = src->st_atimespec.tv_nsec;
+  dst->st_mtim.tv_sec = src->st_mtimespec.tv_sec;
+  dst->st_mtim.tv_nsec = src->st_mtimespec.tv_nsec;
+  dst->st_ctim.tv_sec = src->st_ctimespec.tv_sec;
+  dst->st_ctim.tv_nsec = src->st_ctimespec.tv_nsec;
+  dst->st_birthtim.tv_sec = src->st_birthtimespec.tv_sec;
+  dst->st_birthtim.tv_nsec = src->st_birthtimespec.tv_nsec;
+  dst->st_flags = src->st_flags;
+  dst->st_gen = src->st_gen;
+#elif defined(__ANDROID__)
+  dst->st_atim.tv_sec = src->st_atime;
+  dst->st_atim.tv_nsec = src->st_atimensec;
+  dst->st_mtim.tv_sec = src->st_mtime;
+  dst->st_mtim.tv_nsec = src->st_mtimensec;
+  dst->st_ctim.tv_sec = src->st_ctime;
+  dst->st_ctim.tv_nsec = src->st_ctimensec;
+  dst->st_birthtim.tv_sec = src->st_ctime;
+  dst->st_birthtim.tv_nsec = src->st_ctimensec;
+  dst->st_flags = 0;
+  dst->st_gen = 0;
+#elif !defined(_AIX) && (       \
+    defined(__DragonFly__)   || \
+    defined(__FreeBSD__)     || \
+    defined(__OpenBSD__)     || \
+    defined(__NetBSD__)      || \
+    defined(_GNU_SOURCE)     || \
+    defined(_BSD_SOURCE)     || \
+    defined(_SVID_SOURCE)    || \
+    defined(_XOPEN_SOURCE)   || \
+    defined(_DEFAULT_SOURCE))
+  dst->st_atim.tv_sec = src->st_atim.tv_sec;
+  dst->st_atim.tv_nsec = src->st_atim.tv_nsec;
+  dst->st_mtim.tv_sec = src->st_mtim.tv_sec;
+  dst->st_mtim.tv_nsec = src->st_mtim.tv_nsec;
+  dst->st_ctim.tv_sec = src->st_ctim.tv_sec;
+  dst->st_ctim.tv_nsec = src->st_ctim.tv_nsec;
+# if defined(__FreeBSD__)    || \
+     defined(__NetBSD__)
+  dst->st_birthtim.tv_sec = src->st_birthtim.tv_sec;
+  dst->st_birthtim.tv_nsec = src->st_birthtim.tv_nsec;
+  dst->st_flags = src->st_flags;
+  dst->st_gen = src->st_gen;
+# else
+  dst->st_birthtim.tv_sec = src->st_ctim.tv_sec;
+  dst->st_birthtim.tv_nsec = src->st_ctim.tv_nsec;
+  dst->st_flags = 0;
+  dst->st_gen = 0;
+# endif
+#else
+  dst->st_atim.tv_sec = src->st_atime;
+  dst->st_atim.tv_nsec = 0;
+  dst->st_mtim.tv_sec = src->st_mtime;
+  dst->st_mtim.tv_nsec = 0;
+  dst->st_ctim.tv_sec = src->st_ctime;
+  dst->st_ctim.tv_nsec = 0;
+  dst->st_birthtim.tv_sec = src->st_ctime;
+  dst->st_birthtim.tv_nsec = 0;
+  dst->st_flags = 0;
+  dst->st_gen = 0;
+#endif
+}
+
+
+static int uv__fs_stat(const char *path, uv_stat_t *buf) {
+  struct stat pbuf;
+  int ret;
+
+  ret = stat(path, &pbuf);
+  if (ret == 0)
+    uv__to_stat(&pbuf, buf);
+
+  return ret;
+}
+
+
+static int uv__fs_lstat(const char *path, uv_stat_t *buf) {
+  struct stat pbuf;
+  int ret;
+
+  ret = lstat(path, &pbuf);
+  if (ret == 0)
+    uv__to_stat(&pbuf, buf);
+
+  return ret;
+}
+
+
+static int uv__fs_fstat(int fd, uv_stat_t *buf) {
+  struct stat pbuf;
+  int ret;
+
+  ret = fstat(fd, &pbuf);
+  if (ret == 0)
+    uv__to_stat(&pbuf, buf);
+
+  return ret;
+}
+
+
+typedef ssize_t (*uv__fs_buf_iter_processor)(uv_fs_t* req);
+static ssize_t uv__fs_buf_iter(uv_fs_t* req, uv__fs_buf_iter_processor process) {
+  unsigned int iovmax;
+  unsigned int nbufs;
+  uv_buf_t* bufs;
+  ssize_t total;
+  ssize_t result;
+
+  iovmax = uv__getiovmax();
+  nbufs = req->nbufs;
+  bufs = req->bufs;
+  total = 0;
+
+  while (nbufs > 0) {
+    req->nbufs = nbufs;
+    if (req->nbufs > iovmax)
+      req->nbufs = iovmax;
+
+    result = process(req);
+    if (result <= 0) {
+      if (total == 0)
+        total = result;
+      break;
+    }
+
+    if (req->off >= 0)
+      req->off += result;
+
+    req->bufs += req->nbufs;
+    nbufs -= req->nbufs;
+    total += result;
+  }
+
+  if (errno == EINTR && total == -1)
+    return total;
+
+  if (bufs != req->bufsml)
+    uv__free(bufs);
+
+  req->bufs = NULL;
+  req->nbufs = 0;
+
+  return total;
+}
+
+
+static void uv__fs_work(struct uv__work* w) {
+  int retry_on_eintr;
+  uv_fs_t* req;
+  ssize_t r;
+
+  req = container_of(w, uv_fs_t, work_req);
+  retry_on_eintr = !(req->fs_type == UV_FS_CLOSE);
+
+  do {
+    errno = 0;
+
+#define X(type, action)                                                       \
+  case UV_FS_ ## type:                                                        \
+    r = action;                                                               \
+    break;
+
+    switch (req->fs_type) {
+    X(ACCESS, access(req->path, req->flags));
+    X(CHMOD, chmod(req->path, req->mode));
+    X(CHOWN, chown(req->path, req->uid, req->gid));
+    X(CLOSE, close(req->file));
+    X(COPYFILE, uv__fs_copyfile(req));
+    X(FCHMOD, fchmod(req->file, req->mode));
+    X(FCHOWN, fchown(req->file, req->uid, req->gid));
+    X(LCHOWN, lchown(req->path, req->uid, req->gid));
+    X(FDATASYNC, uv__fs_fdatasync(req));
+    X(FSTAT, uv__fs_fstat(req->file, &req->statbuf));
+    X(FSYNC, uv__fs_fsync(req));
+    X(FTRUNCATE, ftruncate(req->file, req->off));
+    X(FUTIME, uv__fs_futime(req));
+    X(LSTAT, uv__fs_lstat(req->path, &req->statbuf));
+    X(LINK, link(req->path, req->new_path));
+    X(MKDIR, mkdir(req->path, req->mode));
+    X(MKDTEMP, uv__fs_mkdtemp(req));
+    X(OPEN, uv__fs_open(req));
+    X(READ, uv__fs_buf_iter(req, uv__fs_read));
+    X(SCANDIR, uv__fs_scandir(req));
+    X(READLINK, uv__fs_readlink(req));
+    X(REALPATH, uv__fs_realpath(req));
+    X(RENAME, rename(req->path, req->new_path));
+    X(RMDIR, rmdir(req->path));
+    X(SENDFILE, uv__fs_sendfile(req));
+    X(STAT, uv__fs_stat(req->path, &req->statbuf));
+    X(SYMLINK, symlink(req->path, req->new_path));
+    X(UNLINK, unlink(req->path));
+    X(UTIME, uv__fs_utime(req));
+    X(WRITE, uv__fs_buf_iter(req, uv__fs_write));
+    default: abort();
+    }
+#undef X
+  } while (r == -1 && errno == EINTR && retry_on_eintr);
+
+  if (r == -1)
+    req->result = UV__ERR(errno);
+  else
+    req->result = r;
+
+  if (r == 0 && (req->fs_type == UV_FS_STAT ||
+                 req->fs_type == UV_FS_FSTAT ||
+                 req->fs_type == UV_FS_LSTAT)) {
+    req->ptr = &req->statbuf;
+  }
+}
+
+
+static void uv__fs_done(struct uv__work* w, int status) {
+  uv_fs_t* req;
+
+  req = container_of(w, uv_fs_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  if (status == UV_ECANCELED) {
+    assert(req->result == 0);
+    req->result = UV_ECANCELED;
+  }
+
+  req->cb(req);
+}
+
+
+int uv_fs_access(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 int flags,
+                 uv_fs_cb cb) {
+  INIT(ACCESS);
+  PATH;
+  req->flags = flags;
+  POST;
+}
+
+
+int uv_fs_chmod(uv_loop_t* loop,
+                uv_fs_t* req,
+                const char* path,
+                int mode,
+                uv_fs_cb cb) {
+  INIT(CHMOD);
+  PATH;
+  req->mode = mode;
+  POST;
+}
+
+
+int uv_fs_chown(uv_loop_t* loop,
+                uv_fs_t* req,
+                const char* path,
+                uv_uid_t uid,
+                uv_gid_t gid,
+                uv_fs_cb cb) {
+  INIT(CHOWN);
+  PATH;
+  req->uid = uid;
+  req->gid = gid;
+  POST;
+}
+
+
+int uv_fs_close(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
+  INIT(CLOSE);
+  req->file = file;
+  POST;
+}
+
+
+int uv_fs_fchmod(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 uv_file file,
+                 int mode,
+                 uv_fs_cb cb) {
+  INIT(FCHMOD);
+  req->file = file;
+  req->mode = mode;
+  POST;
+}
+
+
+int uv_fs_fchown(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 uv_file file,
+                 uv_uid_t uid,
+                 uv_gid_t gid,
+                 uv_fs_cb cb) {
+  INIT(FCHOWN);
+  req->file = file;
+  req->uid = uid;
+  req->gid = gid;
+  POST;
+}
+
+
+int uv_fs_lchown(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 uv_uid_t uid,
+                 uv_gid_t gid,
+                 uv_fs_cb cb) {
+  INIT(LCHOWN);
+  PATH;
+  req->uid = uid;
+  req->gid = gid;
+  POST;
+}
+
+
+int uv_fs_fdatasync(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
+  INIT(FDATASYNC);
+  req->file = file;
+  POST;
+}
+
+
+int uv_fs_fstat(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
+  INIT(FSTAT);
+  req->file = file;
+  POST;
+}
+
+
+int uv_fs_fsync(uv_loop_t* loop, uv_fs_t* req, uv_file file, uv_fs_cb cb) {
+  INIT(FSYNC);
+  req->file = file;
+  POST;
+}
+
+
+int uv_fs_ftruncate(uv_loop_t* loop,
+                    uv_fs_t* req,
+                    uv_file file,
+                    int64_t off,
+                    uv_fs_cb cb) {
+  INIT(FTRUNCATE);
+  req->file = file;
+  req->off = off;
+  POST;
+}
+
+
+int uv_fs_futime(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 uv_file file,
+                 double atime,
+                 double mtime,
+                 uv_fs_cb cb) {
+  INIT(FUTIME);
+  req->file = file;
+  req->atime = atime;
+  req->mtime = mtime;
+  POST;
+}
+
+
+int uv_fs_lstat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  INIT(LSTAT);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_link(uv_loop_t* loop,
+               uv_fs_t* req,
+               const char* path,
+               const char* new_path,
+               uv_fs_cb cb) {
+  INIT(LINK);
+  PATH2;
+  POST;
+}
+
+
+int uv_fs_mkdir(uv_loop_t* loop,
+                uv_fs_t* req,
+                const char* path,
+                int mode,
+                uv_fs_cb cb) {
+  INIT(MKDIR);
+  PATH;
+  req->mode = mode;
+  POST;
+}
+
+
+int uv_fs_mkdtemp(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* tpl,
+                  uv_fs_cb cb) {
+  INIT(MKDTEMP);
+  req->path = uv__strdup(tpl);
+  if (req->path == NULL)
+    return UV_ENOMEM;
+  POST;
+}
+
+
+int uv_fs_open(uv_loop_t* loop,
+               uv_fs_t* req,
+               const char* path,
+               int flags,
+               int mode,
+               uv_fs_cb cb) {
+  INIT(OPEN);
+  PATH;
+  req->flags = flags;
+  req->mode = mode;
+  POST;
+}
+
+
+int uv_fs_read(uv_loop_t* loop, uv_fs_t* req,
+               uv_file file,
+               const uv_buf_t bufs[],
+               unsigned int nbufs,
+               int64_t off,
+               uv_fs_cb cb) {
+  INIT(READ);
+
+  if (bufs == NULL || nbufs == 0)
+    return UV_EINVAL;
+
+  req->file = file;
+
+  req->nbufs = nbufs;
+  req->bufs = req->bufsml;
+  if (nbufs > ARRAY_SIZE(req->bufsml))
+    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+
+  if (req->bufs == NULL)
+    return UV_ENOMEM;
+
+  memcpy(req->bufs, bufs, nbufs * sizeof(*bufs));
+
+  req->off = off;
+  POST;
+}
+
+
+int uv_fs_scandir(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* path,
+                  int flags,
+                  uv_fs_cb cb) {
+  INIT(SCANDIR);
+  PATH;
+  req->flags = flags;
+  POST;
+}
+
+
+int uv_fs_readlink(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   const char* path,
+                   uv_fs_cb cb) {
+  INIT(READLINK);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_realpath(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char * path,
+                  uv_fs_cb cb) {
+  INIT(REALPATH);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_rename(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 const char* new_path,
+                 uv_fs_cb cb) {
+  INIT(RENAME);
+  PATH2;
+  POST;
+}
+
+
+int uv_fs_rmdir(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  INIT(RMDIR);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_sendfile(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   uv_file out_fd,
+                   uv_file in_fd,
+                   int64_t off,
+                   size_t len,
+                   uv_fs_cb cb) {
+  INIT(SENDFILE);
+  req->flags = in_fd; /* hack */
+  req->file = out_fd;
+  req->off = off;
+  req->bufsml[0].len = len;
+  POST;
+}
+
+
+int uv_fs_stat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  INIT(STAT);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_symlink(uv_loop_t* loop,
+                  uv_fs_t* req,
+                  const char* path,
+                  const char* new_path,
+                  int flags,
+                  uv_fs_cb cb) {
+  INIT(SYMLINK);
+  PATH2;
+  req->flags = flags;
+  POST;
+}
+
+
+int uv_fs_unlink(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  INIT(UNLINK);
+  PATH;
+  POST;
+}
+
+
+int uv_fs_utime(uv_loop_t* loop,
+                uv_fs_t* req,
+                const char* path,
+                double atime,
+                double mtime,
+                uv_fs_cb cb) {
+  INIT(UTIME);
+  PATH;
+  req->atime = atime;
+  req->mtime = mtime;
+  POST;
+}
+
+
+int uv_fs_write(uv_loop_t* loop,
+                uv_fs_t* req,
+                uv_file file,
+                const uv_buf_t bufs[],
+                unsigned int nbufs,
+                int64_t off,
+                uv_fs_cb cb) {
+  INIT(WRITE);
+
+  if (bufs == NULL || nbufs == 0)
+    return UV_EINVAL;
+
+  req->file = file;
+
+  req->nbufs = nbufs;
+  req->bufs = req->bufsml;
+  if (nbufs > ARRAY_SIZE(req->bufsml))
+    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+
+  if (req->bufs == NULL)
+    return UV_ENOMEM;
+
+  memcpy(req->bufs, bufs, nbufs * sizeof(*bufs));
+
+  req->off = off;
+  POST;
+}
+
+
+void uv_fs_req_cleanup(uv_fs_t* req) {
+  if (req == NULL)
+    return;
+
+  /* Only necessary for asychronous requests, i.e., requests with a callback.
+   * Synchronous ones don't copy their arguments and have req->path and
+   * req->new_path pointing to user-owned memory.  UV_FS_MKDTEMP is the
+   * exception to the rule, it always allocates memory.
+   */
+  if (req->path != NULL && (req->cb != NULL || req->fs_type == UV_FS_MKDTEMP))
+    uv__free((void*) req->path);  /* Memory is shared with req->new_path. */
+
+  req->path = NULL;
+  req->new_path = NULL;
+
+  if (req->fs_type == UV_FS_SCANDIR && req->ptr != NULL)
+    uv__fs_scandir_cleanup(req);
+
+  if (req->bufs != req->bufsml)
+    uv__free(req->bufs);
+  req->bufs = NULL;
+
+  if (req->ptr != &req->statbuf)
+    uv__free(req->ptr);
+  req->ptr = NULL;
+}
+
+
+int uv_fs_copyfile(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   const char* path,
+                   const char* new_path,
+                   int flags,
+                   uv_fs_cb cb) {
+  INIT(COPYFILE);
+
+  if (flags & ~(UV_FS_COPYFILE_EXCL |
+                UV_FS_COPYFILE_FICLONE |
+                UV_FS_COPYFILE_FICLONE_FORCE)) {
+    return UV_EINVAL;
+  }
+
+  PATH2;
+  req->flags = flags;
+  POST;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/fsevents.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/fsevents.cpp
new file mode 100644
index 0000000..0515c73
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/fsevents.cpp
@@ -0,0 +1,919 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#if TARGET_OS_IPHONE
+
+/* iOS (currently) doesn't provide the FSEvents-API (nor CoreServices) */
+
+int uv__fsevents_init(uv_fs_event_t* handle) {
+  return 0;
+}
+
+
+int uv__fsevents_close(uv_fs_event_t* handle) {
+  return 0;
+}
+
+
+void uv__fsevents_loop_delete(uv_loop_t* loop) {
+}
+
+#else /* TARGET_OS_IPHONE */
+
+#include <dlfcn.h>
+#include <assert.h>
+#include <stdlib.h>
+#include <pthread.h>
+
+#include <CoreFoundation/CFRunLoop.h>
+#include <CoreServices/CoreServices.h>
+
+/* These are macros to avoid "initializer element is not constant" errors
+ * with old versions of gcc.
+ */
+#define kFSEventsModified (kFSEventStreamEventFlagItemFinderInfoMod |         \
+                           kFSEventStreamEventFlagItemModified |              \
+                           kFSEventStreamEventFlagItemInodeMetaMod |          \
+                           kFSEventStreamEventFlagItemChangeOwner |           \
+                           kFSEventStreamEventFlagItemXattrMod)
+
+#define kFSEventsRenamed  (kFSEventStreamEventFlagItemCreated |               \
+                           kFSEventStreamEventFlagItemRemoved |               \
+                           kFSEventStreamEventFlagItemRenamed)
+
+#define kFSEventsSystem   (kFSEventStreamEventFlagUserDropped |               \
+                           kFSEventStreamEventFlagKernelDropped |             \
+                           kFSEventStreamEventFlagEventIdsWrapped |           \
+                           kFSEventStreamEventFlagHistoryDone |               \
+                           kFSEventStreamEventFlagMount |                     \
+                           kFSEventStreamEventFlagUnmount |                   \
+                           kFSEventStreamEventFlagRootChanged)
+
+typedef struct uv__fsevents_event_s uv__fsevents_event_t;
+typedef struct uv__cf_loop_signal_s uv__cf_loop_signal_t;
+typedef struct uv__cf_loop_state_s uv__cf_loop_state_t;
+
+enum uv__cf_loop_signal_type_e {
+  kUVCFLoopSignalRegular,
+  kUVCFLoopSignalClosing
+};
+typedef enum uv__cf_loop_signal_type_e uv__cf_loop_signal_type_t;
+
+struct uv__cf_loop_signal_s {
+  QUEUE member;
+  uv_fs_event_t* handle;
+  uv__cf_loop_signal_type_t type;
+};
+
+struct uv__fsevents_event_s {
+  QUEUE member;
+  int events;
+  char path[1];
+};
+
+struct uv__cf_loop_state_s {
+  CFRunLoopRef loop;
+  CFRunLoopSourceRef signal_source;
+  int fsevent_need_reschedule;
+  FSEventStreamRef fsevent_stream;
+  uv_sem_t fsevent_sem;
+  uv_mutex_t fsevent_mutex;
+  void* fsevent_handles[2];
+  unsigned int fsevent_handle_count;
+};
+
+/* Forward declarations */
+static void uv__cf_loop_cb(void* arg);
+static void* uv__cf_loop_runner(void* arg);
+static int uv__cf_loop_signal(uv_loop_t* loop,
+                              uv_fs_event_t* handle,
+                              uv__cf_loop_signal_type_t type);
+
+/* Lazy-loaded by uv__fsevents_global_init(). */
+static CFArrayRef (*pCFArrayCreate)(CFAllocatorRef,
+                                    const void**,
+                                    CFIndex,
+                                    const CFArrayCallBacks*);
+static void (*pCFRelease)(CFTypeRef);
+static void (*pCFRunLoopAddSource)(CFRunLoopRef,
+                                   CFRunLoopSourceRef,
+                                   CFStringRef);
+static CFRunLoopRef (*pCFRunLoopGetCurrent)(void);
+static void (*pCFRunLoopRemoveSource)(CFRunLoopRef,
+                                      CFRunLoopSourceRef,
+                                      CFStringRef);
+static void (*pCFRunLoopRun)(void);
+static CFRunLoopSourceRef (*pCFRunLoopSourceCreate)(CFAllocatorRef,
+                                                    CFIndex,
+                                                    CFRunLoopSourceContext*);
+static void (*pCFRunLoopSourceSignal)(CFRunLoopSourceRef);
+static void (*pCFRunLoopStop)(CFRunLoopRef);
+static void (*pCFRunLoopWakeUp)(CFRunLoopRef);
+static CFStringRef (*pCFStringCreateWithFileSystemRepresentation)(
+    CFAllocatorRef,
+    const char*);
+static CFStringEncoding (*pCFStringGetSystemEncoding)(void);
+static CFStringRef (*pkCFRunLoopDefaultMode);
+static FSEventStreamRef (*pFSEventStreamCreate)(CFAllocatorRef,
+                                                FSEventStreamCallback,
+                                                FSEventStreamContext*,
+                                                CFArrayRef,
+                                                FSEventStreamEventId,
+                                                CFTimeInterval,
+                                                FSEventStreamCreateFlags);
+static void (*pFSEventStreamFlushSync)(FSEventStreamRef);
+static void (*pFSEventStreamInvalidate)(FSEventStreamRef);
+static void (*pFSEventStreamRelease)(FSEventStreamRef);
+static void (*pFSEventStreamScheduleWithRunLoop)(FSEventStreamRef,
+                                                 CFRunLoopRef,
+                                                 CFStringRef);
+static Boolean (*pFSEventStreamStart)(FSEventStreamRef);
+static void (*pFSEventStreamStop)(FSEventStreamRef);
+
+#define UV__FSEVENTS_PROCESS(handle, block)                                   \
+    do {                                                                      \
+      QUEUE events;                                                           \
+      QUEUE* q;                                                               \
+      uv__fsevents_event_t* event;                                            \
+      int err;                                                                \
+      uv_mutex_lock(&(handle)->cf_mutex);                                     \
+      /* Split-off all events and empty original queue */                     \
+      QUEUE_MOVE(&(handle)->cf_events, &events);                              \
+      /* Get error (if any) and zero original one */                          \
+      err = (handle)->cf_error;                                               \
+      (handle)->cf_error = 0;                                                 \
+      uv_mutex_unlock(&(handle)->cf_mutex);                                   \
+      /* Loop through events, deallocating each after processing */           \
+      while (!QUEUE_EMPTY(&events)) {                                         \
+        q = QUEUE_HEAD(&events);                                              \
+        event = QUEUE_DATA(q, uv__fsevents_event_t, member);                  \
+        QUEUE_REMOVE(q);                                                      \
+        /* NOTE: Checking uv__is_active() is required here, because handle    \
+         * callback may close handle and invoking it after it will lead to    \
+         * incorrect behaviour */                                             \
+        if (!uv__is_closing((handle)) && uv__is_active((handle)))             \
+          block                                                               \
+        /* Free allocated data */                                             \
+        uv__free(event);                                                      \
+      }                                                                       \
+      if (err != 0 && !uv__is_closing((handle)) && uv__is_active((handle)))   \
+        (handle)->cb((handle), NULL, 0, err);                                 \
+    } while (0)
+
+
+/* Runs in UV loop's thread, when there're events to report to handle */
+static void uv__fsevents_cb(uv_async_t* cb) {
+  uv_fs_event_t* handle;
+
+  handle = (uv_fs_event_t*)cb->data;
+
+  UV__FSEVENTS_PROCESS(handle, {
+    handle->cb(handle, event->path[0] ? event->path : NULL, event->events, 0);
+  });
+}
+
+
+/* Runs in CF thread, pushed event into handle's event list */
+static void uv__fsevents_push_event(uv_fs_event_t* handle,
+                                    QUEUE* events,
+                                    int err) {
+  assert(events != NULL || err != 0);
+  uv_mutex_lock(&handle->cf_mutex);
+
+  /* Concatenate two queues */
+  if (events != NULL)
+    QUEUE_ADD(&handle->cf_events, events);
+
+  /* Propagate error */
+  if (err != 0)
+    handle->cf_error = err;
+  uv_mutex_unlock(&handle->cf_mutex);
+
+  uv_async_send(handle->cf_cb);
+}
+
+
+/* Runs in CF thread, when there're events in FSEventStream */
+static void uv__fsevents_event_cb(ConstFSEventStreamRef streamRef,
+                                  void* info,
+                                  size_t numEvents,
+                                  void* eventPaths,
+                                  const FSEventStreamEventFlags eventFlags[],
+                                  const FSEventStreamEventId eventIds[]) {
+  size_t i;
+  int len;
+  char** paths;
+  char* path;
+  char* pos;
+  uv_fs_event_t* handle;
+  QUEUE* q;
+  uv_loop_t* loop;
+  uv__cf_loop_state_t* state;
+  uv__fsevents_event_t* event;
+  FSEventStreamEventFlags flags;
+  QUEUE head;
+
+  loop = (uv_loop_t*)info;
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  assert(state != NULL);
+  paths = (char**)eventPaths;
+
+  /* For each handle */
+  uv_mutex_lock(&state->fsevent_mutex);
+  QUEUE_FOREACH(q, &state->fsevent_handles) {
+    handle = QUEUE_DATA(q, uv_fs_event_t, cf_member);
+    QUEUE_INIT(&head);
+
+    /* Process and filter out events */
+    for (i = 0; i < numEvents; i++) {
+      flags = eventFlags[i];
+
+      /* Ignore system events */
+      if (flags & kFSEventsSystem)
+        continue;
+
+      path = paths[i];
+      len = strlen(path);
+
+      /* Filter out paths that are outside handle's request */
+      if (strncmp(path, handle->realpath, handle->realpath_len) != 0)
+        continue;
+
+      if (handle->realpath_len > 1 || *handle->realpath != '/') {
+        path += handle->realpath_len;
+        len -= handle->realpath_len;
+
+        /* Skip forward slash */
+        if (*path != '\0') {
+          path++;
+          len--;
+        }
+      }
+
+#ifdef MAC_OS_X_VERSION_10_7
+      /* Ignore events with path equal to directory itself */
+      if (len == 0)
+        continue;
+#else
+      if (len == 0 && (flags & kFSEventStreamEventFlagItemIsDir))
+        continue;
+#endif /* MAC_OS_X_VERSION_10_7 */
+
+      /* Do not emit events from subdirectories (without option set) */
+      if ((handle->cf_flags & UV_FS_EVENT_RECURSIVE) == 0 && *path != 0) {
+        pos = strchr(path + 1, '/');
+        if (pos != NULL)
+          continue;
+      }
+
+#ifndef MAC_OS_X_VERSION_10_7
+      path = "";
+      len = 0;
+#endif /* MAC_OS_X_VERSION_10_7 */
+
+      event = (uv__fsevents_event_t*)uv__malloc(sizeof(*event) + len);
+      if (event == NULL)
+        break;
+
+      memset(event, 0, sizeof(*event));
+      memcpy(event->path, path, len + 1);
+      event->events = UV_RENAME;
+
+#ifdef MAC_OS_X_VERSION_10_7
+      if (0 != (flags & kFSEventsModified) &&
+          0 == (flags & kFSEventsRenamed)) {
+        event->events = UV_CHANGE;
+      }
+#else
+      if (0 != (flags & kFSEventsModified) &&
+          0 != (flags & kFSEventStreamEventFlagItemIsDir) &&
+          0 == (flags & kFSEventStreamEventFlagItemRenamed)) {
+        event->events = UV_CHANGE;
+      }
+      if (0 == (flags & kFSEventStreamEventFlagItemIsDir) &&
+          0 == (flags & kFSEventStreamEventFlagItemRenamed)) {
+        event->events = UV_CHANGE;
+      }
+#endif /* MAC_OS_X_VERSION_10_7 */
+
+      QUEUE_INSERT_TAIL(&head, &event->member);
+    }
+
+    if (!QUEUE_EMPTY(&head))
+      uv__fsevents_push_event(handle, &head, 0);
+  }
+  uv_mutex_unlock(&state->fsevent_mutex);
+}
+
+
+/* Runs in CF thread */
+static int uv__fsevents_create_stream(uv_loop_t* loop, CFArrayRef paths) {
+  uv__cf_loop_state_t* state;
+  FSEventStreamContext ctx;
+  FSEventStreamRef ref;
+  CFAbsoluteTime latency;
+  FSEventStreamCreateFlags flags;
+
+  /* Initialize context */
+  ctx.version = 0;
+  ctx.info = loop;
+  ctx.retain = NULL;
+  ctx.release = NULL;
+  ctx.copyDescription = NULL;
+
+  latency = 0.05;
+
+  /* Explanation of selected flags:
+   * 1. NoDefer - without this flag, events that are happening continuously
+   *    (i.e. each event is happening after time interval less than `latency`,
+   *    counted from previous event), will be deferred and passed to callback
+   *    once they'll either fill whole OS buffer, or when this continuous stream
+   *    will stop (i.e. there'll be delay between events, bigger than
+   *    `latency`).
+   *    Specifying this flag will invoke callback after `latency` time passed
+   *    since event.
+   * 2. FileEvents - fire callback for file changes too (by default it is firing
+   *    it only for directory changes).
+   */
+  flags = kFSEventStreamCreateFlagNoDefer | kFSEventStreamCreateFlagFileEvents;
+
+  /*
+   * NOTE: It might sound like a good idea to remember last seen StreamEventId,
+   * but in reality one dir might have last StreamEventId less than, the other,
+   * that is being watched now. Which will cause FSEventStream API to report
+   * changes to files from the past.
+   */
+  ref = pFSEventStreamCreate(NULL,
+                             &uv__fsevents_event_cb,
+                             &ctx,
+                             paths,
+                             kFSEventStreamEventIdSinceNow,
+                             latency,
+                             flags);
+  assert(ref != NULL);
+
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  pFSEventStreamScheduleWithRunLoop(ref,
+                                    state->loop,
+                                    *pkCFRunLoopDefaultMode);
+  if (!pFSEventStreamStart(ref)) {
+    pFSEventStreamInvalidate(ref);
+    pFSEventStreamRelease(ref);
+    return UV_EMFILE;
+  }
+
+  state->fsevent_stream = ref;
+  return 0;
+}
+
+
+/* Runs in CF thread */
+static void uv__fsevents_destroy_stream(uv_loop_t* loop) {
+  uv__cf_loop_state_t* state;
+
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+
+  if (state->fsevent_stream == NULL)
+    return;
+
+  /* Stop emitting events */
+  pFSEventStreamStop(state->fsevent_stream);
+
+  /* Release stream */
+  pFSEventStreamInvalidate(state->fsevent_stream);
+  pFSEventStreamRelease(state->fsevent_stream);
+  state->fsevent_stream = NULL;
+}
+
+
+/* Runs in CF thread, when there're new fsevent handles to add to stream */
+static void uv__fsevents_reschedule(uv_fs_event_t* handle,
+                                    uv__cf_loop_signal_type_t type) {
+  uv__cf_loop_state_t* state;
+  QUEUE* q;
+  uv_fs_event_t* curr;
+  CFArrayRef cf_paths;
+  CFStringRef* paths;
+  unsigned int i;
+  int err;
+  unsigned int path_count;
+
+  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+  paths = NULL;
+  cf_paths = NULL;
+  err = 0;
+  /* NOTE: `i` is used in deallocation loop below */
+  i = 0;
+
+  /* Optimization to prevent O(n^2) time spent when starting to watch
+   * many files simultaneously
+   */
+  uv_mutex_lock(&state->fsevent_mutex);
+  if (state->fsevent_need_reschedule == 0) {
+    uv_mutex_unlock(&state->fsevent_mutex);
+    goto final;
+  }
+  state->fsevent_need_reschedule = 0;
+  uv_mutex_unlock(&state->fsevent_mutex);
+
+  /* Destroy previous FSEventStream */
+  uv__fsevents_destroy_stream(handle->loop);
+
+  /* Any failure below will be a memory failure */
+  err = UV_ENOMEM;
+
+  /* Create list of all watched paths */
+  uv_mutex_lock(&state->fsevent_mutex);
+  path_count = state->fsevent_handle_count;
+  if (path_count != 0) {
+    paths = (CFStringRef*)uv__malloc(sizeof(*paths) * path_count);
+    if (paths == NULL) {
+      uv_mutex_unlock(&state->fsevent_mutex);
+      goto final;
+    }
+
+    q = &state->fsevent_handles;
+    for (; i < path_count; i++) {
+      q = QUEUE_NEXT(q);
+      assert(q != &state->fsevent_handles);
+      curr = QUEUE_DATA(q, uv_fs_event_t, cf_member);
+
+      assert(curr->realpath != NULL);
+      paths[i] =
+          pCFStringCreateWithFileSystemRepresentation(NULL, curr->realpath);
+      if (paths[i] == NULL) {
+        uv_mutex_unlock(&state->fsevent_mutex);
+        goto final;
+      }
+    }
+  }
+  uv_mutex_unlock(&state->fsevent_mutex);
+  err = 0;
+
+  if (path_count != 0) {
+    /* Create new FSEventStream */
+    cf_paths = pCFArrayCreate(NULL, (const void**) paths, path_count, NULL);
+    if (cf_paths == NULL) {
+      err = UV_ENOMEM;
+      goto final;
+    }
+    err = uv__fsevents_create_stream(handle->loop, cf_paths);
+  }
+
+final:
+  /* Deallocate all paths in case of failure */
+  if (err != 0) {
+    if (cf_paths == NULL) {
+      while (i != 0)
+        pCFRelease(paths[--i]);
+      uv__free(paths);
+    } else {
+      /* CFArray takes ownership of both strings and original C-array */
+      pCFRelease(cf_paths);
+    }
+
+    /* Broadcast error to all handles */
+    uv_mutex_lock(&state->fsevent_mutex);
+    QUEUE_FOREACH(q, &state->fsevent_handles) {
+      curr = QUEUE_DATA(q, uv_fs_event_t, cf_member);
+      uv__fsevents_push_event(curr, NULL, err);
+    }
+    uv_mutex_unlock(&state->fsevent_mutex);
+  }
+
+  /*
+   * Main thread will block until the removal of handle from the list,
+   * we must tell it when we're ready.
+   *
+   * NOTE: This is coupled with `uv_sem_wait()` in `uv__fsevents_close`
+   */
+  if (type == kUVCFLoopSignalClosing)
+    uv_sem_post(&state->fsevent_sem);
+}
+
+
+static int uv__fsevents_global_init(void) {
+  static pthread_mutex_t global_init_mutex = PTHREAD_MUTEX_INITIALIZER;
+  static void* core_foundation_handle;
+  static void* core_services_handle;
+  int err;
+
+  err = 0;
+  pthread_mutex_lock(&global_init_mutex);
+  if (core_foundation_handle != NULL)
+    goto out;
+
+  /* The libraries are never unloaded because we currently don't have a good
+   * mechanism for keeping a reference count. It's unlikely to be an issue
+   * but if it ever becomes one, we can turn the dynamic library handles into
+   * per-event loop properties and have the dynamic linker keep track for us.
+   */
+  err = UV_ENOSYS;
+  core_foundation_handle = dlopen("/System/Library/Frameworks/"
+                                  "CoreFoundation.framework/"
+                                  "Versions/A/CoreFoundation",
+                                  RTLD_LAZY | RTLD_LOCAL);
+  if (core_foundation_handle == NULL)
+    goto out;
+
+  core_services_handle = dlopen("/System/Library/Frameworks/"
+                                "CoreServices.framework/"
+                                "Versions/A/CoreServices",
+                                RTLD_LAZY | RTLD_LOCAL);
+  if (core_services_handle == NULL)
+    goto out;
+
+  err = UV_ENOENT;
+#define V(handle, symbol)                                                     \
+  do {                                                                        \
+    *(void **)(&p ## symbol) = dlsym((handle), #symbol);                      \
+    if (p ## symbol == NULL)                                                  \
+      goto out;                                                               \
+  }                                                                           \
+  while (0)
+  V(core_foundation_handle, CFArrayCreate);
+  V(core_foundation_handle, CFRelease);
+  V(core_foundation_handle, CFRunLoopAddSource);
+  V(core_foundation_handle, CFRunLoopGetCurrent);
+  V(core_foundation_handle, CFRunLoopRemoveSource);
+  V(core_foundation_handle, CFRunLoopRun);
+  V(core_foundation_handle, CFRunLoopSourceCreate);
+  V(core_foundation_handle, CFRunLoopSourceSignal);
+  V(core_foundation_handle, CFRunLoopStop);
+  V(core_foundation_handle, CFRunLoopWakeUp);
+  V(core_foundation_handle, CFStringCreateWithFileSystemRepresentation);
+  V(core_foundation_handle, CFStringGetSystemEncoding);
+  V(core_foundation_handle, kCFRunLoopDefaultMode);
+  V(core_services_handle, FSEventStreamCreate);
+  V(core_services_handle, FSEventStreamFlushSync);
+  V(core_services_handle, FSEventStreamInvalidate);
+  V(core_services_handle, FSEventStreamRelease);
+  V(core_services_handle, FSEventStreamScheduleWithRunLoop);
+  V(core_services_handle, FSEventStreamStart);
+  V(core_services_handle, FSEventStreamStop);
+#undef V
+  err = 0;
+
+out:
+  if (err && core_services_handle != NULL) {
+    dlclose(core_services_handle);
+    core_services_handle = NULL;
+  }
+
+  if (err && core_foundation_handle != NULL) {
+    dlclose(core_foundation_handle);
+    core_foundation_handle = NULL;
+  }
+
+  pthread_mutex_unlock(&global_init_mutex);
+  return err;
+}
+
+
+/* Runs in UV loop */
+static int uv__fsevents_loop_init(uv_loop_t* loop) {
+  CFRunLoopSourceContext ctx;
+  uv__cf_loop_state_t* state;
+  pthread_attr_t attr_storage;
+  pthread_attr_t* attr;
+  int err;
+
+  if (loop->cf_state != NULL)
+    return 0;
+
+  err = uv__fsevents_global_init();
+  if (err)
+    return err;
+
+  state = (uv__cf_loop_state_t*)uv__calloc(1, sizeof(*state));
+  if (state == NULL)
+    return UV_ENOMEM;
+
+  err = uv_mutex_init(&loop->cf_mutex);
+  if (err)
+    goto fail_mutex_init;
+
+  err = uv_sem_init(&loop->cf_sem, 0);
+  if (err)
+    goto fail_sem_init;
+
+  QUEUE_INIT(&loop->cf_signals);
+
+  err = uv_sem_init(&state->fsevent_sem, 0);
+  if (err)
+    goto fail_fsevent_sem_init;
+
+  err = uv_mutex_init(&state->fsevent_mutex);
+  if (err)
+    goto fail_fsevent_mutex_init;
+
+  QUEUE_INIT(&state->fsevent_handles);
+  state->fsevent_need_reschedule = 0;
+  state->fsevent_handle_count = 0;
+
+  memset(&ctx, 0, sizeof(ctx));
+  ctx.info = loop;
+  ctx.perform = uv__cf_loop_cb;
+  state->signal_source = pCFRunLoopSourceCreate(NULL, 0, &ctx);
+  if (state->signal_source == NULL) {
+    err = UV_ENOMEM;
+    goto fail_signal_source_create;
+  }
+
+  /* In the unlikely event that pthread_attr_init() fails, create the thread
+   * with the default stack size. We'll use a little more address space but
+   * that in itself is not a fatal error.
+   */
+  attr = &attr_storage;
+  if (pthread_attr_init(attr))
+    attr = NULL;
+
+  if (attr != NULL)
+    if (pthread_attr_setstacksize(attr, 4 * PTHREAD_STACK_MIN))
+      abort();
+
+  loop->cf_state = state;
+
+  /* uv_thread_t is an alias for pthread_t. */
+  err = UV__ERR(pthread_create(&loop->cf_thread, attr, uv__cf_loop_runner, loop));
+
+  if (attr != NULL)
+    pthread_attr_destroy(attr);
+
+  if (err)
+    goto fail_thread_create;
+
+  /* Synchronize threads */
+  uv_sem_wait(&loop->cf_sem);
+  return 0;
+
+fail_thread_create:
+  loop->cf_state = NULL;
+
+fail_signal_source_create:
+  uv_mutex_destroy(&state->fsevent_mutex);
+
+fail_fsevent_mutex_init:
+  uv_sem_destroy(&state->fsevent_sem);
+
+fail_fsevent_sem_init:
+  uv_sem_destroy(&loop->cf_sem);
+
+fail_sem_init:
+  uv_mutex_destroy(&loop->cf_mutex);
+
+fail_mutex_init:
+  uv__free(state);
+  return err;
+}
+
+
+/* Runs in UV loop */
+void uv__fsevents_loop_delete(uv_loop_t* loop) {
+  uv__cf_loop_signal_t* s;
+  uv__cf_loop_state_t* state;
+  QUEUE* q;
+
+  if (loop->cf_state == NULL)
+    return;
+
+  if (uv__cf_loop_signal(loop, NULL, kUVCFLoopSignalRegular) != 0)
+    abort();
+
+  uv_thread_join(&loop->cf_thread);
+  uv_sem_destroy(&loop->cf_sem);
+  uv_mutex_destroy(&loop->cf_mutex);
+
+  /* Free any remaining data */
+  while (!QUEUE_EMPTY(&loop->cf_signals)) {
+    q = QUEUE_HEAD(&loop->cf_signals);
+    s = QUEUE_DATA(q, uv__cf_loop_signal_t, member);
+    QUEUE_REMOVE(q);
+    uv__free(s);
+  }
+
+  /* Destroy state */
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  uv_sem_destroy(&state->fsevent_sem);
+  uv_mutex_destroy(&state->fsevent_mutex);
+  pCFRelease(state->signal_source);
+  uv__free(state);
+  loop->cf_state = NULL;
+}
+
+
+/* Runs in CF thread. This is the CF loop's body */
+static void* uv__cf_loop_runner(void* arg) {
+  uv_loop_t* loop;
+  uv__cf_loop_state_t* state;
+
+  loop = (uv_loop_t*)arg;
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  state->loop = pCFRunLoopGetCurrent();
+
+  pCFRunLoopAddSource(state->loop,
+                      state->signal_source,
+                      *pkCFRunLoopDefaultMode);
+
+  uv_sem_post(&loop->cf_sem);
+
+  pCFRunLoopRun();
+  pCFRunLoopRemoveSource(state->loop,
+                         state->signal_source,
+                         *pkCFRunLoopDefaultMode);
+
+  return NULL;
+}
+
+
+/* Runs in CF thread, executed after `uv__cf_loop_signal()` */
+static void uv__cf_loop_cb(void* arg) {
+  uv_loop_t* loop;
+  uv__cf_loop_state_t* state;
+  QUEUE* item;
+  QUEUE split_head;
+  uv__cf_loop_signal_t* s;
+
+  loop = (uv_loop_t*)arg;
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+
+  uv_mutex_lock(&loop->cf_mutex);
+  QUEUE_MOVE(&loop->cf_signals, &split_head);
+  uv_mutex_unlock(&loop->cf_mutex);
+
+  while (!QUEUE_EMPTY(&split_head)) {
+    item = QUEUE_HEAD(&split_head);
+    QUEUE_REMOVE(item);
+
+    s = QUEUE_DATA(item, uv__cf_loop_signal_t, member);
+
+    /* This was a termination signal */
+    if (s->handle == NULL)
+      pCFRunLoopStop(state->loop);
+    else
+      uv__fsevents_reschedule(s->handle, s->type);
+
+    uv__free(s);
+  }
+}
+
+
+/* Runs in UV loop to notify CF thread */
+int uv__cf_loop_signal(uv_loop_t* loop,
+                       uv_fs_event_t* handle,
+                       uv__cf_loop_signal_type_t type) {
+  uv__cf_loop_signal_t* item;
+  uv__cf_loop_state_t* state;
+
+  item = (uv__cf_loop_signal_t*)uv__malloc(sizeof(*item));
+  if (item == NULL)
+    return UV_ENOMEM;
+
+  item->handle = handle;
+  item->type = type;
+
+  uv_mutex_lock(&loop->cf_mutex);
+  QUEUE_INSERT_TAIL(&loop->cf_signals, &item->member);
+  uv_mutex_unlock(&loop->cf_mutex);
+
+  state = (uv__cf_loop_state_t*)loop->cf_state;
+  assert(state != NULL);
+  pCFRunLoopSourceSignal(state->signal_source);
+  pCFRunLoopWakeUp(state->loop);
+
+  return 0;
+}
+
+
+/* Runs in UV loop to initialize handle */
+int uv__fsevents_init(uv_fs_event_t* handle) {
+  int err;
+  uv__cf_loop_state_t* state;
+
+  err = uv__fsevents_loop_init(handle->loop);
+  if (err)
+    return err;
+
+  /* Get absolute path to file */
+  handle->realpath = realpath(handle->path, NULL);
+  if (handle->realpath == NULL)
+    return UV__ERR(errno);
+  handle->realpath_len = strlen(handle->realpath);
+
+  /* Initialize event queue */
+  QUEUE_INIT(&handle->cf_events);
+  handle->cf_error = 0;
+
+  /*
+   * Events will occur in other thread.
+   * Initialize callback for getting them back into event loop's thread
+   */
+  handle->cf_cb = (uv_async_t*)uv__malloc(sizeof(*handle->cf_cb));
+  if (handle->cf_cb == NULL) {
+    err = UV_ENOMEM;
+    goto fail_cf_cb_malloc;
+  }
+
+  handle->cf_cb->data = handle;
+  uv_async_init(handle->loop, handle->cf_cb, uv__fsevents_cb);
+  handle->cf_cb->flags |= UV__HANDLE_INTERNAL;
+  uv_unref((uv_handle_t*) handle->cf_cb);
+
+  err = uv_mutex_init(&handle->cf_mutex);
+  if (err)
+    goto fail_cf_mutex_init;
+
+  /* Insert handle into the list */
+  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+  uv_mutex_lock(&state->fsevent_mutex);
+  QUEUE_INSERT_TAIL(&state->fsevent_handles, &handle->cf_member);
+  state->fsevent_handle_count++;
+  state->fsevent_need_reschedule = 1;
+  uv_mutex_unlock(&state->fsevent_mutex);
+
+  /* Reschedule FSEventStream */
+  assert(handle != NULL);
+  err = uv__cf_loop_signal(handle->loop, handle, kUVCFLoopSignalRegular);
+  if (err)
+    goto fail_loop_signal;
+
+  return 0;
+
+fail_loop_signal:
+  uv_mutex_destroy(&handle->cf_mutex);
+
+fail_cf_mutex_init:
+  uv__free(handle->cf_cb);
+  handle->cf_cb = NULL;
+
+fail_cf_cb_malloc:
+  uv__free(handle->realpath);
+  handle->realpath = NULL;
+  handle->realpath_len = 0;
+
+  return err;
+}
+
+
+/* Runs in UV loop to de-initialize handle */
+int uv__fsevents_close(uv_fs_event_t* handle) {
+  int err;
+  uv__cf_loop_state_t* state;
+
+  if (handle->cf_cb == NULL)
+    return UV_EINVAL;
+
+  /* Remove handle from  the list */
+  state = (uv__cf_loop_state_t*)handle->loop->cf_state;
+  uv_mutex_lock(&state->fsevent_mutex);
+  QUEUE_REMOVE(&handle->cf_member);
+  state->fsevent_handle_count--;
+  state->fsevent_need_reschedule = 1;
+  uv_mutex_unlock(&state->fsevent_mutex);
+
+  /* Reschedule FSEventStream */
+  assert(handle != NULL);
+  err = uv__cf_loop_signal(handle->loop, handle, kUVCFLoopSignalClosing);
+  if (err)
+    return UV__ERR(err);
+
+  /* Wait for deinitialization */
+  uv_sem_wait(&state->fsevent_sem);
+
+  uv_close((uv_handle_t*) handle->cf_cb, (uv_close_cb) uv__free);
+  handle->cf_cb = NULL;
+
+  /* Free data in queue */
+  UV__FSEVENTS_PROCESS(handle, {
+    /* NOP */
+  });
+
+  uv_mutex_destroy(&handle->cf_mutex);
+  uv__free(handle->realpath);
+  handle->realpath = NULL;
+  handle->realpath_len = 0;
+
+  return 0;
+}
+
+#endif /* TARGET_OS_IPHONE */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/getaddrinfo.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/getaddrinfo.cpp
new file mode 100644
index 0000000..a39a947
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/getaddrinfo.cpp
@@ -0,0 +1,232 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* Expose glibc-specific EAI_* error codes. Needs to be defined before we
+ * include any headers.
+ */
+#ifndef _GNU_SOURCE
+# define _GNU_SOURCE
+#endif
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+#include <stddef.h> /* NULL */
+#include <stdlib.h>
+#include <string.h>
+#include <net/if.h> /* if_indextoname() */
+
+/* EAI_* constants. */
+#include <netdb.h>
+
+
+int uv__getaddrinfo_translate_error(int sys_err) {
+  switch (sys_err) {
+  case 0: return 0;
+#if defined(EAI_ADDRFAMILY)
+  case EAI_ADDRFAMILY: return UV_EAI_ADDRFAMILY;
+#endif
+#if defined(EAI_AGAIN)
+  case EAI_AGAIN: return UV_EAI_AGAIN;
+#endif
+#if defined(EAI_BADFLAGS)
+  case EAI_BADFLAGS: return UV_EAI_BADFLAGS;
+#endif
+#if defined(EAI_BADHINTS)
+  case EAI_BADHINTS: return UV_EAI_BADHINTS;
+#endif
+#if defined(EAI_CANCELED)
+  case EAI_CANCELED: return UV_EAI_CANCELED;
+#endif
+#if defined(EAI_FAIL)
+  case EAI_FAIL: return UV_EAI_FAIL;
+#endif
+#if defined(EAI_FAMILY)
+  case EAI_FAMILY: return UV_EAI_FAMILY;
+#endif
+#if defined(EAI_MEMORY)
+  case EAI_MEMORY: return UV_EAI_MEMORY;
+#endif
+#if defined(EAI_NODATA)
+  case EAI_NODATA: return UV_EAI_NODATA;
+#endif
+#if defined(EAI_NONAME)
+# if !defined(EAI_NODATA) || EAI_NODATA != EAI_NONAME
+  case EAI_NONAME: return UV_EAI_NONAME;
+# endif
+#endif
+#if defined(EAI_OVERFLOW)
+  case EAI_OVERFLOW: return UV_EAI_OVERFLOW;
+#endif
+#if defined(EAI_PROTOCOL)
+  case EAI_PROTOCOL: return UV_EAI_PROTOCOL;
+#endif
+#if defined(EAI_SERVICE)
+  case EAI_SERVICE: return UV_EAI_SERVICE;
+#endif
+#if defined(EAI_SOCKTYPE)
+  case EAI_SOCKTYPE: return UV_EAI_SOCKTYPE;
+#endif
+#if defined(EAI_SYSTEM)
+  case EAI_SYSTEM: return UV__ERR(errno);
+#endif
+  }
+  assert(!"unknown EAI_* error code");
+  abort();
+  return 0;  /* Pacify compiler. */
+}
+
+
+static void uv__getaddrinfo_work(struct uv__work* w) {
+  uv_getaddrinfo_t* req;
+  int err;
+
+  req = container_of(w, uv_getaddrinfo_t, work_req);
+  err = getaddrinfo(req->hostname, req->service, req->hints, &req->addrinfo);
+  req->retcode = uv__getaddrinfo_translate_error(err);
+}
+
+
+static void uv__getaddrinfo_done(struct uv__work* w, int status) {
+  uv_getaddrinfo_t* req;
+
+  req = container_of(w, uv_getaddrinfo_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  /* See initialization in uv_getaddrinfo(). */
+  if (req->hints)
+    uv__free(req->hints);
+  else if (req->service)
+    uv__free(req->service);
+  else if (req->hostname)
+    uv__free(req->hostname);
+  else
+    assert(0);
+
+  req->hints = NULL;
+  req->service = NULL;
+  req->hostname = NULL;
+
+  if (status == UV_ECANCELED) {
+    assert(req->retcode == 0);
+    req->retcode = UV_EAI_CANCELED;
+  }
+
+  if (req->cb)
+    req->cb(req, req->retcode, req->addrinfo);
+}
+
+
+int uv_getaddrinfo(uv_loop_t* loop,
+                   uv_getaddrinfo_t* req,
+                   uv_getaddrinfo_cb cb,
+                   const char* hostname,
+                   const char* service,
+                   const struct addrinfo* hints) {
+  size_t hostname_len;
+  size_t service_len;
+  size_t hints_len;
+  size_t len;
+  char* buf;
+
+  if (req == NULL || (hostname == NULL && service == NULL))
+    return UV_EINVAL;
+
+  hostname_len = hostname ? strlen(hostname) + 1 : 0;
+  service_len = service ? strlen(service) + 1 : 0;
+  hints_len = hints ? sizeof(*hints) : 0;
+  buf = (char*)uv__malloc(hostname_len + service_len + hints_len);
+
+  if (buf == NULL)
+    return UV_ENOMEM;
+
+  uv__req_init(loop, req, UV_GETADDRINFO);
+  req->loop = loop;
+  req->cb = cb;
+  req->addrinfo = NULL;
+  req->hints = NULL;
+  req->service = NULL;
+  req->hostname = NULL;
+  req->retcode = 0;
+
+  /* order matters, see uv_getaddrinfo_done() */
+  len = 0;
+
+  if (hints) {
+    req->hints = (struct addrinfo*)memcpy(buf + len, hints, sizeof(*hints));
+    len += sizeof(*hints);
+  }
+
+  if (service) {
+    req->service = (char*)memcpy(buf + len, service, service_len);
+    len += service_len;
+  }
+
+  if (hostname)
+    req->hostname = (char*)memcpy(buf + len, hostname, hostname_len);
+
+  if (cb) {
+    uv__work_submit(loop,
+                    &req->work_req,
+                    uv__getaddrinfo_work,
+                    uv__getaddrinfo_done);
+    return 0;
+  } else {
+    uv__getaddrinfo_work(&req->work_req);
+    uv__getaddrinfo_done(&req->work_req, 0);
+    return req->retcode;
+  }
+}
+
+
+void uv_freeaddrinfo(struct addrinfo* ai) {
+  if (ai)
+    freeaddrinfo(ai);
+}
+
+
+int uv_if_indextoname(unsigned int ifindex, char* buffer, size_t* size) {
+  char ifname_buf[UV_IF_NAMESIZE];
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  if (if_indextoname(ifindex, ifname_buf) == NULL)
+    return UV__ERR(errno);
+
+  len = strnlen(ifname_buf, sizeof(ifname_buf));
+
+  if (*size <= len) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, ifname_buf, len);
+  buffer[len] = '\0';
+  *size = len;
+
+  return 0;
+}
+
+int uv_if_indextoiid(unsigned int ifindex, char* buffer, size_t* size) {
+  return uv_if_indextoname(ifindex, buffer, size);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/getnameinfo.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/getnameinfo.cpp
new file mode 100644
index 0000000..9a43672
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/getnameinfo.cpp
@@ -0,0 +1,120 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+*
+* Permission is hereby granted, free of charge, to any person obtaining a copy
+* of this software and associated documentation files (the "Software"), to
+* deal in the Software without restriction, including without limitation the
+* rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+* sell copies of the Software, and to permit persons to whom the Software is
+* furnished to do so, subject to the following conditions:
+*
+* The above copyright notice and this permission notice shall be included in
+* all copies or substantial portions of the Software.
+*
+* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+* IN THE SOFTWARE.
+*/
+
+#include <assert.h>
+#include <stdlib.h>
+#include <stdio.h>
+#include <string.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+static void uv__getnameinfo_work(struct uv__work* w) {
+  uv_getnameinfo_t* req;
+  int err;
+  socklen_t salen;
+
+  req = container_of(w, uv_getnameinfo_t, work_req);
+
+  if (req->storage.ss_family == AF_INET)
+    salen = sizeof(struct sockaddr_in);
+  else if (req->storage.ss_family == AF_INET6)
+    salen = sizeof(struct sockaddr_in6);
+  else
+    abort();
+
+  err = getnameinfo((struct sockaddr*) &req->storage,
+                    salen,
+                    req->host,
+                    sizeof(req->host),
+                    req->service,
+                    sizeof(req->service),
+                    req->flags);
+  req->retcode = uv__getaddrinfo_translate_error(err);
+}
+
+static void uv__getnameinfo_done(struct uv__work* w, int status) {
+  uv_getnameinfo_t* req;
+  char* host;
+  char* service;
+
+  req = container_of(w, uv_getnameinfo_t, work_req);
+  uv__req_unregister(req->loop, req);
+  host = service = NULL;
+
+  if (status == UV_ECANCELED) {
+    assert(req->retcode == 0);
+    req->retcode = UV_EAI_CANCELED;
+  } else if (req->retcode == 0) {
+    host = req->host;
+    service = req->service;
+  }
+
+  if (req->getnameinfo_cb)
+    req->getnameinfo_cb(req, req->retcode, host, service);
+}
+
+/*
+* Entry point for getnameinfo
+* return 0 if a callback will be made
+* return error code if validation fails
+*/
+int uv_getnameinfo(uv_loop_t* loop,
+                   uv_getnameinfo_t* req,
+                   uv_getnameinfo_cb getnameinfo_cb,
+                   const struct sockaddr* addr,
+                   int flags) {
+  if (req == NULL || addr == NULL)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET) {
+    memcpy(&req->storage,
+           addr,
+           sizeof(struct sockaddr_in));
+  } else if (addr->sa_family == AF_INET6) {
+    memcpy(&req->storage,
+           addr,
+           sizeof(struct sockaddr_in6));
+  } else {
+    return UV_EINVAL;
+  }
+
+  uv__req_init(loop, (uv_req_t*)req, UV_GETNAMEINFO);
+
+  req->getnameinfo_cb = getnameinfo_cb;
+  req->flags = flags;
+  req->type = UV_GETNAMEINFO;
+  req->loop = loop;
+  req->retcode = 0;
+
+  if (getnameinfo_cb) {
+    uv__work_submit(loop,
+                    &req->work_req,
+                    uv__getnameinfo_work,
+                    uv__getnameinfo_done);
+    return 0;
+  } else {
+    uv__getnameinfo_work(&req->work_req);
+    uv__getnameinfo_done(&req->work_req, 0);
+    return req->retcode;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/ibmi.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/ibmi.cpp
new file mode 100644
index 0000000..9b434fe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/ibmi.cpp
@@ -0,0 +1,112 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdio.h>
+#include <stdint.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/ioctl.h>
+#include <net/if.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+
+#include <sys/time.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <utmp.h>
+#include <libgen.h>
+
+#include <sys/protosw.h>
+#include <procinfo.h>
+#include <sys/proc.h>
+#include <sys/procfs.h>
+
+#include <ctype.h>
+
+#include <sys/mntctl.h>
+#include <sys/vmount.h>
+#include <limits.h>
+#include <strings.h>
+#include <sys/vnode.h>
+
+uint64_t uv_get_free_memory(void) {
+  return (uint64_t) sysconf(_SC_PAGESIZE) * sysconf(_SC_AVPHYS_PAGES);
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  return (uint64_t) sysconf(_SC_PAGESIZE) * sysconf(_SC_PHYS_PAGES);
+}
+
+
+void uv_loadavg(double avg[3]) {
+    avg[0] = avg[1] = avg[2] = 0;
+    return;
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  return UV_ENOSYS;
+}
+
+
+int uv_uptime(double* uptime) {
+  return UV_ENOSYS;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int numcpus, idx = 0;
+  uv_cpu_info_t* cpu_info;
+
+  *cpu_infos = NULL;
+  *count = 0;
+
+  numcpus = sysconf(_SC_NPROCESSORS_ONLN);
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(uv_cpu_info_t));
+  if (!*cpu_infos) {
+    return UV_ENOMEM;
+  }
+
+  cpu_info = *cpu_infos;
+  for (idx = 0; idx < numcpus; idx++) {
+    cpu_info->speed = 0;
+    cpu_info->model = uv__strdup("unknown");
+    cpu_info->cpu_times.user = 0;
+    cpu_info->cpu_times.sys = 0;
+    cpu_info->cpu_times.idle = 0;
+    cpu_info->cpu_times.irq = 0;
+    cpu_info->cpu_times.nice = 0;
+    cpu_info++;
+  }
+  *count = numcpus;
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/internal.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/internal.h
new file mode 100644
index 0000000..2adc66b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/internal.h
@@ -0,0 +1,357 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_UNIX_INTERNAL_H_
+#define UV_UNIX_INTERNAL_H_
+
+#include "uv-common.h"
+
+#include <assert.h>
+#include <stdlib.h> /* abort */
+#include <string.h> /* strrchr */
+#include <fcntl.h>  /* O_CLOEXEC, may be */
+#include <stdio.h>
+#include <errno.h>
+
+#if defined(__STRICT_ANSI__)
+# define inline __inline
+#endif
+
+#if defined(__linux__)
+# include "linux-syscalls.h"
+#endif /* __linux__ */
+
+#if defined(__MVS__)
+# include "os390-syscalls.h"
+#endif /* __MVS__ */
+
+#if defined(__sun)
+# include <sys/port.h>
+# include <port.h>
+#endif /* __sun */
+
+#if defined(_AIX)
+# define reqevents events
+# define rtnevents revents
+# include <sys/poll.h>
+#else
+# include <poll.h>
+#endif /* _AIX */
+
+#if defined(__APPLE__) && !TARGET_OS_IPHONE
+# include <AvailabilityMacros.h>
+#endif
+
+#if defined(__ANDROID__)
+int uv__pthread_sigmask(int how, const sigset_t* set, sigset_t* oset);
+# ifdef pthread_sigmask
+# undef pthread_sigmask
+# endif
+# define pthread_sigmask(how, set, oldset) uv__pthread_sigmask(how, set, oldset)
+#endif
+
+#define ACCESS_ONCE(type, var)                                                \
+  (*(volatile type*) &(var))
+
+#define ROUND_UP(a, b)                                                        \
+  ((a) % (b) ? ((a) + (b)) - ((a) % (b)) : (a))
+
+#define UNREACHABLE()                                                         \
+  do {                                                                        \
+    assert(0 && "unreachable code");                                          \
+    abort();                                                                  \
+  }                                                                           \
+  while (0)
+
+#define SAVE_ERRNO(block)                                                     \
+  do {                                                                        \
+    int _saved_errno = errno;                                                 \
+    do { block; } while (0);                                                  \
+    errno = _saved_errno;                                                     \
+  }                                                                           \
+  while (0)
+
+/* The __clang__ and __INTEL_COMPILER checks are superfluous because they
+ * define __GNUC__. They are here to convey to you, dear reader, that these
+ * macros are enabled when compiling with clang or icc.
+ */
+#if defined(__clang__) ||                                                     \
+    defined(__GNUC__) ||                                                      \
+    defined(__INTEL_COMPILER) ||                                              \
+    defined(__SUNPRO_C)
+# define UV_DESTRUCTOR(declaration) __attribute__((destructor)) declaration
+# define UV_UNUSED(declaration)     __attribute__((unused)) declaration
+#else
+# define UV_DESTRUCTOR(declaration) declaration
+# define UV_UNUSED(declaration)     declaration
+#endif
+
+/* Leans on the fact that, on Linux, POLLRDHUP == EPOLLRDHUP. */
+#ifdef POLLRDHUP
+# define UV__POLLRDHUP POLLRDHUP
+#else
+# define UV__POLLRDHUP 0x2000
+#endif
+
+#ifdef POLLPRI
+# define UV__POLLPRI POLLPRI
+#else
+# define UV__POLLPRI 0
+#endif
+
+#if !defined(O_CLOEXEC) && defined(__FreeBSD__)
+/*
+ * It may be that we are just missing `__POSIX_VISIBLE >= 200809`.
+ * Try using fixed value const and give up, if it doesn't work
+ */
+# define O_CLOEXEC 0x00100000
+#endif
+
+typedef struct uv__stream_queued_fds_s uv__stream_queued_fds_t;
+
+/* handle flags */
+enum {
+  UV_CLOSING              = 0x01,   /* uv_close() called but not finished. */
+  UV_CLOSED               = 0x02,   /* close(2) finished. */
+  UV_STREAM_READING       = 0x04,   /* uv_read_start() called. */
+  UV_STREAM_SHUTTING      = 0x08,   /* uv_shutdown() called but not complete. */
+  UV_STREAM_SHUT          = 0x10,   /* Write side closed. */
+  UV_STREAM_READABLE      = 0x20,   /* The stream is readable */
+  UV_STREAM_WRITABLE      = 0x40,   /* The stream is writable */
+  UV_STREAM_BLOCKING      = 0x80,   /* Synchronous writes. */
+  UV_STREAM_READ_PARTIAL  = 0x100,  /* read(2) read less than requested. */
+  UV_STREAM_READ_EOF      = 0x200,  /* read(2) read EOF. */
+  UV_TCP_NODELAY          = 0x400,  /* Disable Nagle. */
+  UV_TCP_KEEPALIVE        = 0x800,  /* Turn on keep-alive. */
+  UV_TCP_SINGLE_ACCEPT    = 0x1000, /* Only accept() when idle. */
+  UV_HANDLE_IPV6          = 0x10000, /* Handle is bound to a IPv6 socket. */
+  UV_UDP_PROCESSING       = 0x20000, /* Handle is running the send callback queue. */
+  UV_HANDLE_BOUND         = 0x40000  /* Handle is bound to an address and port */
+};
+
+/* loop flags */
+enum {
+  UV_LOOP_BLOCK_SIGPROF = 1
+};
+
+/* flags of excluding ifaddr */
+enum {
+  UV__EXCLUDE_IFPHYS,
+  UV__EXCLUDE_IFADDR
+};
+
+typedef enum {
+  UV_CLOCK_PRECISE = 0,  /* Use the highest resolution clock available. */
+  UV_CLOCK_FAST = 1      /* Use the fastest clock with <= 1ms granularity. */
+} uv_clocktype_t;
+
+struct uv__stream_queued_fds_s {
+  unsigned int size;
+  unsigned int offset;
+  int fds[1];
+};
+
+
+#if defined(_AIX) || \
+    defined(__APPLE__) || \
+    defined(__DragonFly__) || \
+    defined(__FreeBSD__) || \
+    defined(__FreeBSD_kernel__) || \
+    defined(__linux__) || \
+    defined(__OpenBSD__) || \
+    defined(__NetBSD__)
+#define uv__cloexec uv__cloexec_ioctl
+#define uv__nonblock uv__nonblock_ioctl
+#define UV__NONBLOCK_IS_IOCTL
+#else
+#define uv__cloexec uv__cloexec_fcntl
+#define uv__nonblock uv__nonblock_fcntl
+#define UV__NONBLOCK_IS_FCNTL
+#endif
+
+/* On Linux, uv__nonblock_fcntl() and uv__nonblock_ioctl() do not commute
+ * when O_NDELAY is not equal to O_NONBLOCK.  Case in point: linux/sparc32
+ * and linux/sparc64, where O_NDELAY is O_NONBLOCK + another bit.
+ *
+ * Libuv uses uv__nonblock_fcntl() directly sometimes so ensure that it
+ * commutes with uv__nonblock().
+ */
+#if defined(__linux__) && O_NDELAY != O_NONBLOCK
+#undef uv__nonblock
+#define uv__nonblock uv__nonblock_fcntl
+#undef UV__NONBLOCK_IS_IOCTL
+#define UV__NONBLOCK_IS_FCNTL
+#endif
+
+/* core */
+int uv__cloexec_ioctl(int fd, int set);
+int uv__cloexec_fcntl(int fd, int set);
+int uv__nonblock_ioctl(int fd, int set);
+int uv__nonblock_fcntl(int fd, int set);
+int uv__close(int fd); /* preserves errno */
+int uv__close_nocheckstdio(int fd);
+int uv__socket(int domain, int type, int protocol);
+int uv__dup(int fd);
+ssize_t uv__recvmsg(int fd, struct msghdr *msg, int flags);
+void uv__make_close_pending(uv_handle_t* handle);
+int uv__getiovmax(void);
+
+void uv__io_init(uv__io_t* w, uv__io_cb cb, int fd);
+void uv__io_start(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+void uv__io_stop(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+void uv__io_close(uv_loop_t* loop, uv__io_t* w);
+void uv__io_feed(uv_loop_t* loop, uv__io_t* w);
+int uv__io_active(const uv__io_t* w, unsigned int events);
+int uv__io_check_fd(uv_loop_t* loop, int fd);
+void uv__io_poll(uv_loop_t* loop, int timeout); /* in milliseconds or -1 */
+int uv__io_fork(uv_loop_t* loop);
+int uv__fd_exists(uv_loop_t* loop, int fd);
+
+/* async */
+void uv__async_stop(uv_loop_t* loop);
+int uv__async_fork(uv_loop_t* loop);
+
+
+/* loop */
+void uv__run_idle(uv_loop_t* loop);
+void uv__run_check(uv_loop_t* loop);
+void uv__run_prepare(uv_loop_t* loop);
+
+/* stream */
+void uv__stream_init(uv_loop_t* loop, uv_stream_t* stream,
+    uv_handle_type type);
+int uv__stream_open(uv_stream_t*, int fd, int flags);
+void uv__stream_destroy(uv_stream_t* stream);
+#if defined(__APPLE__)
+int uv__stream_try_select(uv_stream_t* stream, int* fd);
+#endif /* defined(__APPLE__) */
+void uv__server_io(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+int uv__accept(int sockfd);
+int uv__dup2_cloexec(int oldfd, int newfd);
+int uv__open_cloexec(const char* path, int flags);
+
+/* tcp */
+int uv_tcp_listen(uv_tcp_t* tcp, int backlog, uv_connection_cb cb);
+int uv__tcp_nodelay(int fd, int on);
+int uv__tcp_keepalive(int fd, int on, unsigned int delay);
+
+/* pipe */
+int uv_pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb);
+
+/* timer */
+void uv__run_timers(uv_loop_t* loop);
+int uv__next_timeout(const uv_loop_t* loop);
+
+/* signal */
+void uv__signal_close(uv_signal_t* handle);
+void uv__signal_global_once_init(void);
+void uv__signal_loop_cleanup(uv_loop_t* loop);
+int uv__signal_loop_fork(uv_loop_t* loop);
+
+/* platform specific */
+uint64_t uv__hrtime(uv_clocktype_t type);
+int uv__kqueue_init(uv_loop_t* loop);
+int uv__platform_loop_init(uv_loop_t* loop);
+void uv__platform_loop_delete(uv_loop_t* loop);
+void uv__platform_invalidate_fd(uv_loop_t* loop, int fd);
+
+/* various */
+void uv__async_close(uv_async_t* handle);
+void uv__check_close(uv_check_t* handle);
+void uv__fs_event_close(uv_fs_event_t* handle);
+void uv__idle_close(uv_idle_t* handle);
+void uv__pipe_close(uv_pipe_t* handle);
+void uv__poll_close(uv_poll_t* handle);
+void uv__prepare_close(uv_prepare_t* handle);
+void uv__process_close(uv_process_t* handle);
+void uv__stream_close(uv_stream_t* handle);
+void uv__tcp_close(uv_tcp_t* handle);
+void uv__timer_close(uv_timer_t* handle);
+void uv__udp_close(uv_udp_t* handle);
+void uv__udp_finish_close(uv_udp_t* handle);
+uv_handle_type uv__handle_type(int fd);
+FILE* uv__open_file(const char* path);
+int uv__getpwuid_r(uv_passwd_t* pwd);
+
+
+#if defined(__APPLE__)
+int uv___stream_fd(const uv_stream_t* handle);
+#define uv__stream_fd(handle) (uv___stream_fd((const uv_stream_t*) (handle)))
+#else
+#define uv__stream_fd(handle) ((handle)->io_watcher.fd)
+#endif /* defined(__APPLE__) */
+
+#ifdef UV__O_NONBLOCK
+# define UV__F_NONBLOCK UV__O_NONBLOCK
+#else
+# define UV__F_NONBLOCK 1
+#endif
+
+int uv__make_socketpair(int fds[2], int flags);
+int uv__make_pipe(int fds[2], int flags);
+
+#if defined(__APPLE__)
+
+int uv__fsevents_init(uv_fs_event_t* handle);
+int uv__fsevents_close(uv_fs_event_t* handle);
+void uv__fsevents_loop_delete(uv_loop_t* loop);
+
+/* OSX < 10.7 has no file events, polyfill them */
+#ifndef MAC_OS_X_VERSION_10_7
+
+static const int kFSEventStreamCreateFlagFileEvents = 0x00000010;
+static const int kFSEventStreamEventFlagItemCreated = 0x00000100;
+static const int kFSEventStreamEventFlagItemRemoved = 0x00000200;
+static const int kFSEventStreamEventFlagItemInodeMetaMod = 0x00000400;
+static const int kFSEventStreamEventFlagItemRenamed = 0x00000800;
+static const int kFSEventStreamEventFlagItemModified = 0x00001000;
+static const int kFSEventStreamEventFlagItemFinderInfoMod = 0x00002000;
+static const int kFSEventStreamEventFlagItemChangeOwner = 0x00004000;
+static const int kFSEventStreamEventFlagItemXattrMod = 0x00008000;
+static const int kFSEventStreamEventFlagItemIsFile = 0x00010000;
+static const int kFSEventStreamEventFlagItemIsDir = 0x00020000;
+static const int kFSEventStreamEventFlagItemIsSymlink = 0x00040000;
+
+#endif /* __ENVIRONMENT_MAC_OS_X_VERSION_MIN_REQUIRED__ < 1070 */
+
+#endif /* defined(__APPLE__) */
+
+UV_UNUSED(static void uv__update_time(uv_loop_t* loop)) {
+  /* Use a fast time source if available.  We only need millisecond precision.
+   */
+  loop->time = uv__hrtime(UV_CLOCK_FAST) / 1000000;
+}
+
+UV_UNUSED(static const char* uv__basename_r(const char* path)) {
+  const char* s;
+
+  s = strrchr(path, '/');
+  if (s == NULL)
+    return (char*) path;
+
+  return s + 1;
+}
+
+#if defined(__linux__)
+int uv__inotify_fork(uv_loop_t* loop, void* old_watchers);
+#endif
+
+#endif /* UV_UNIX_INTERNAL_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/kqueue.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/kqueue.cpp
new file mode 100644
index 0000000..6e2b2bb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/kqueue.cpp
@@ -0,0 +1,533 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <errno.h>
+
+#include <sys/sysctl.h>
+#include <sys/types.h>
+#include <sys/event.h>
+#include <sys/time.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <time.h>
+
+/*
+ * Required on
+ * - Until at least FreeBSD 11.0
+ * - Older versions of Mac OS X
+ *
+ * http://www.boost.org/doc/libs/1_61_0/boost/asio/detail/kqueue_reactor.hpp
+ */
+#ifndef EV_OOBAND
+#define EV_OOBAND  EV_FLAG1
+#endif
+
+static void uv__fs_event(uv_loop_t* loop, uv__io_t* w, unsigned int fflags);
+
+
+int uv__kqueue_init(uv_loop_t* loop) {
+  loop->backend_fd = kqueue();
+  if (loop->backend_fd == -1)
+    return UV__ERR(errno);
+
+  uv__cloexec(loop->backend_fd, 1);
+
+  return 0;
+}
+
+
+#if defined(__APPLE__)
+static int uv__has_forked_with_cfrunloop;
+#endif
+
+int uv__io_fork(uv_loop_t* loop) {
+  int err;
+  loop->backend_fd = -1;
+  err = uv__kqueue_init(loop);
+  if (err)
+    return err;
+
+#if defined(__APPLE__)
+  if (loop->cf_state != NULL) {
+    /* We cannot start another CFRunloop and/or thread in the child
+       process; CF aborts if you try or if you try to touch the thread
+       at all to kill it. So the best we can do is ignore it from now
+       on. This means we can't watch directories in the same way
+       anymore (like other BSDs). It also means we cannot properly
+       clean up the allocated resources; calling
+       uv__fsevents_loop_delete from uv_loop_close will crash the
+       process. So we sidestep the issue by pretending like we never
+       started it in the first place.
+    */
+    uv__has_forked_with_cfrunloop = 1;
+    uv__free(loop->cf_state);
+    loop->cf_state = NULL;
+  }
+#endif
+  return err;
+}
+
+
+int uv__io_check_fd(uv_loop_t* loop, int fd) {
+  struct kevent ev;
+  int rc;
+
+  rc = 0;
+  EV_SET(&ev, fd, EVFILT_READ, EV_ADD, 0, 0, 0);
+  if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
+    rc = UV__ERR(errno);
+
+  EV_SET(&ev, fd, EVFILT_READ, EV_DELETE, 0, 0, 0);
+  if (rc == 0)
+    if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
+      abort();
+
+  return rc;
+}
+
+
+void uv__io_poll(uv_loop_t* loop, int timeout) {
+  struct kevent events[1024];
+  struct kevent* ev;
+  struct timespec spec;
+  unsigned int nevents;
+  unsigned int revents;
+  QUEUE* q;
+  uv__io_t* w;
+  sigset_t* pset;
+  sigset_t set;
+  uint64_t base;
+  uint64_t diff;
+  int have_signals;
+  int filter;
+  int fflags;
+  int count;
+  int nfds;
+  int fd;
+  int op;
+  int i;
+
+  if (loop->nfds == 0) {
+    assert(QUEUE_EMPTY(&loop->watcher_queue));
+    return;
+  }
+
+  nevents = 0;
+
+  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
+    q = QUEUE_HEAD(&loop->watcher_queue);
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);
+
+    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
+    assert(w->pevents != 0);
+    assert(w->fd >= 0);
+    assert(w->fd < (int) loop->nwatchers);
+
+    if ((w->events & POLLIN) == 0 && (w->pevents & POLLIN) != 0) {
+      filter = EVFILT_READ;
+      fflags = 0;
+      op = EV_ADD;
+
+      if (w->cb == uv__fs_event) {
+        filter = EVFILT_VNODE;
+        fflags = NOTE_ATTRIB | NOTE_WRITE  | NOTE_RENAME
+               | NOTE_DELETE | NOTE_EXTEND | NOTE_REVOKE;
+        op = EV_ADD | EV_ONESHOT; /* Stop the event from firing repeatedly. */
+      }
+
+      EV_SET(events + nevents, w->fd, filter, op, fflags, 0, 0);
+
+      if (++nevents == ARRAY_SIZE(events)) {
+        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
+          abort();
+        nevents = 0;
+      }
+    }
+
+    if ((w->events & POLLOUT) == 0 && (w->pevents & POLLOUT) != 0) {
+      EV_SET(events + nevents, w->fd, EVFILT_WRITE, EV_ADD, 0, 0, 0);
+
+      if (++nevents == ARRAY_SIZE(events)) {
+        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
+          abort();
+        nevents = 0;
+      }
+    }
+
+   if ((w->events & UV__POLLPRI) == 0 && (w->pevents & UV__POLLPRI) != 0) {
+      EV_SET(events + nevents, w->fd, EV_OOBAND, EV_ADD, 0, 0, 0);
+
+      if (++nevents == ARRAY_SIZE(events)) {
+        if (kevent(loop->backend_fd, events, nevents, NULL, 0, NULL))
+          abort();
+        nevents = 0;
+      }
+    }
+
+    w->events = w->pevents;
+  }
+
+  pset = NULL;
+  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
+    pset = &set;
+    sigemptyset(pset);
+    sigaddset(pset, SIGPROF);
+  }
+
+  assert(timeout >= -1);
+  base = loop->time;
+  count = 48; /* Benchmarks suggest this gives the best throughput. */
+
+  for (;; nevents = 0) {
+    if (timeout != -1) {
+      spec.tv_sec = timeout / 1000;
+      spec.tv_nsec = (timeout % 1000) * 1000000;
+    }
+
+    if (pset != NULL)
+      pthread_sigmask(SIG_BLOCK, pset, NULL);
+
+    nfds = kevent(loop->backend_fd,
+                  events,
+                  nevents,
+                  events,
+                  ARRAY_SIZE(events),
+                  timeout == -1 ? NULL : &spec);
+
+    if (pset != NULL)
+      pthread_sigmask(SIG_UNBLOCK, pset, NULL);
+
+    /* Update loop->time unconditionally. It's tempting to skip the update when
+     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
+     * operating system didn't reschedule our process while in the syscall.
+     */
+    SAVE_ERRNO(uv__update_time(loop));
+
+    if (nfds == 0) {
+      assert(timeout != -1);
+      return;
+    }
+
+    if (nfds == -1) {
+      if (errno != EINTR)
+        abort();
+
+      if (timeout == 0)
+        return;
+
+      if (timeout == -1)
+        continue;
+
+      /* Interrupted by a signal. Update timeout and poll again. */
+      goto update_timeout;
+    }
+
+    have_signals = 0;
+    nevents = 0;
+
+    assert(loop->watchers != NULL);
+    loop->watchers[loop->nwatchers] = (uv__io_t*) events;
+    loop->watchers[loop->nwatchers + 1] = (uv__io_t*) (uintptr_t) nfds;
+    for (i = 0; i < nfds; i++) {
+      ev = events + i;
+      fd = ev->ident;
+      /* Skip invalidated events, see uv__platform_invalidate_fd */
+      if (fd == -1)
+        continue;
+      w = loop->watchers[fd];
+
+      if (w == NULL) {
+        /* File descriptor that we've stopped watching, disarm it.
+         * TODO: batch up. */
+        struct kevent events[1];
+
+        EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
+        if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
+          if (errno != EBADF && errno != ENOENT)
+            abort();
+
+        continue;
+      }
+
+      if (ev->filter == EVFILT_VNODE) {
+        assert(w->events == POLLIN);
+        assert(w->pevents == POLLIN);
+        w->cb(loop, w, ev->fflags); /* XXX always uv__fs_event() */
+        nevents++;
+        continue;
+      }
+
+      revents = 0;
+
+      if (ev->filter == EVFILT_READ) {
+        if (w->pevents & POLLIN) {
+          revents |= POLLIN;
+          w->rcount = ev->data;
+        } else {
+          /* TODO batch up */
+          struct kevent events[1];
+          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
+          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
+            if (errno != ENOENT)
+              abort();
+        }
+      }
+
+      if (ev->filter == EV_OOBAND) {
+        if (w->pevents & UV__POLLPRI) {
+          revents |= UV__POLLPRI;
+          w->rcount = ev->data;
+        } else {
+          /* TODO batch up */
+          struct kevent events[1];
+          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
+          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
+            if (errno != ENOENT)
+              abort();
+        }
+      }
+
+      if (ev->filter == EVFILT_WRITE) {
+        if (w->pevents & POLLOUT) {
+          revents |= POLLOUT;
+          w->wcount = ev->data;
+        } else {
+          /* TODO batch up */
+          struct kevent events[1];
+          EV_SET(events + 0, fd, ev->filter, EV_DELETE, 0, 0, 0);
+          if (kevent(loop->backend_fd, events, 1, NULL, 0, NULL))
+            if (errno != ENOENT)
+              abort();
+        }
+      }
+
+      if (ev->flags & EV_ERROR)
+        revents |= POLLERR;
+
+      if ((ev->flags & EV_EOF) && (w->pevents & UV__POLLRDHUP))
+        revents |= UV__POLLRDHUP;
+
+      if (revents == 0)
+        continue;
+
+      /* Run signal watchers last.  This also affects child process watchers
+       * because those are implemented in terms of signal watchers.
+       */
+      if (w == &loop->signal_io_watcher)
+        have_signals = 1;
+      else
+        w->cb(loop, w, revents);
+
+      nevents++;
+    }
+
+    if (have_signals != 0)
+      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
+
+    loop->watchers[loop->nwatchers] = NULL;
+    loop->watchers[loop->nwatchers + 1] = NULL;
+
+    if (have_signals != 0)
+      return;  /* Event loop should cycle now so don't poll again. */
+
+    if (nevents != 0) {
+      if (nfds == ARRAY_SIZE(events) && --count != 0) {
+        /* Poll for more events but don't block this time. */
+        timeout = 0;
+        continue;
+      }
+      return;
+    }
+
+    if (timeout == 0)
+      return;
+
+    if (timeout == -1)
+      continue;
+
+update_timeout:
+    assert(timeout > 0);
+
+    diff = loop->time - base;
+    if (diff >= (uint64_t) timeout)
+      return;
+
+    timeout -= diff;
+  }
+}
+
+
+void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
+  struct kevent* events;
+  uintptr_t i;
+  uintptr_t nfds;
+
+  assert(loop->watchers != NULL);
+
+  events = (struct kevent*) loop->watchers[loop->nwatchers];
+  nfds = (uintptr_t) loop->watchers[loop->nwatchers + 1];
+  if (events == NULL)
+    return;
+
+  /* Invalidate events with same file descriptor */
+  for (i = 0; i < nfds; i++)
+    if ((int) events[i].ident == fd)
+      events[i].ident = -1;
+}
+
+
+static void uv__fs_event(uv_loop_t* loop, uv__io_t* w, unsigned int fflags) {
+  uv_fs_event_t* handle;
+  struct kevent ev;
+  int events;
+  const char* path;
+#if defined(F_GETPATH)
+  /* MAXPATHLEN == PATH_MAX but the former is what XNU calls it internally. */
+  char pathbuf[MAXPATHLEN];
+#endif
+
+  handle = container_of(w, uv_fs_event_t, event_watcher);
+
+  if (fflags & (NOTE_ATTRIB | NOTE_EXTEND))
+    events = UV_CHANGE;
+  else
+    events = UV_RENAME;
+
+  path = NULL;
+#if defined(F_GETPATH)
+  /* Also works when the file has been unlinked from the file system. Passing
+   * in the path when the file has been deleted is arguably a little strange
+   * but it's consistent with what the inotify backend does.
+   */
+  if (fcntl(handle->event_watcher.fd, F_GETPATH, pathbuf) == 0)
+    path = uv__basename_r(pathbuf);
+#endif
+  handle->cb(handle, path, events, 0);
+
+  if (handle->event_watcher.fd == -1)
+    return;
+
+  /* Watcher operates in one-shot mode, re-arm it. */
+  fflags = NOTE_ATTRIB | NOTE_WRITE  | NOTE_RENAME
+         | NOTE_DELETE | NOTE_EXTEND | NOTE_REVOKE;
+
+  EV_SET(&ev, w->fd, EVFILT_VNODE, EV_ADD | EV_ONESHOT, fflags, 0, 0);
+
+  if (kevent(loop->backend_fd, &ev, 1, NULL, 0, NULL))
+    abort();
+}
+
+
+int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_EVENT);
+  return 0;
+}
+
+
+int uv_fs_event_start(uv_fs_event_t* handle,
+                      uv_fs_event_cb cb,
+                      const char* path,
+                      unsigned int flags) {
+#if defined(__APPLE__)
+  struct stat statbuf;
+#endif /* defined(__APPLE__) */
+  int fd;
+
+  if (uv__is_active(handle))
+    return UV_EINVAL;
+
+  /* TODO open asynchronously - but how do we report back errors? */
+  fd = open(path, O_RDONLY);
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  uv__handle_start(handle);
+  uv__io_init(&handle->event_watcher, uv__fs_event, fd);
+  handle->path = uv__strdup(path);
+  handle->cb = cb;
+
+#if defined(__APPLE__)
+  if (uv__has_forked_with_cfrunloop)
+    goto fallback;
+
+  /* Nullify field to perform checks later */
+  handle->cf_cb = NULL;
+  handle->realpath = NULL;
+  handle->realpath_len = 0;
+  handle->cf_flags = flags;
+
+  if (fstat(fd, &statbuf))
+    goto fallback;
+  /* FSEvents works only with directories */
+  if (!(statbuf.st_mode & S_IFDIR))
+    goto fallback;
+
+  /* The fallback fd is no longer needed */
+  uv__close(fd);
+  handle->event_watcher.fd = -1;
+
+  return uv__fsevents_init(handle);
+
+fallback:
+#endif /* defined(__APPLE__) */
+
+  uv__io_start(handle->loop, &handle->event_watcher, POLLIN);
+
+  return 0;
+}
+
+
+int uv_fs_event_stop(uv_fs_event_t* handle) {
+  if (!uv__is_active(handle))
+    return 0;
+
+  uv__handle_stop(handle);
+
+#if defined(__APPLE__)
+  if (uv__has_forked_with_cfrunloop || uv__fsevents_close(handle))
+#endif /* defined(__APPLE__) */
+  {
+    uv__io_close(handle->loop, &handle->event_watcher);
+  }
+
+  uv__free(handle->path);
+  handle->path = NULL;
+
+  if (handle->event_watcher.fd != -1) {
+    /* When FSEvents is used, we don't use the event_watcher's fd under certain
+     * confitions. (see uv_fs_event_start) */
+    uv__close(handle->event_watcher.fd);
+    handle->event_watcher.fd = -1;
+  }
+
+  return 0;
+}
+
+
+void uv__fs_event_close(uv_fs_event_t* handle) {
+  uv_fs_event_stop(handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-core.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-core.cpp
new file mode 100644
index 0000000..3bf8beb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-core.cpp
@@ -0,0 +1,961 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/* We lean on the fact that POLL{IN,OUT,ERR,HUP} correspond with their
+ * EPOLL* counterparts.  We use the POLL* variants in this file because that
+ * is what libuv uses elsewhere and it avoids a dependency on <sys/epoll.h>.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdint.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <net/if.h>
+#include <sys/param.h>
+#include <sys/prctl.h>
+#include <sys/sysinfo.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <time.h>
+
+#define HAVE_IFADDRS_H 1
+
+#ifdef __UCLIBC__
+# if __UCLIBC_MAJOR__ < 0 && __UCLIBC_MINOR__ < 9 && __UCLIBC_SUBLEVEL__ < 32
+#  undef HAVE_IFADDRS_H
+# endif
+#endif
+
+#ifdef HAVE_IFADDRS_H
+# if defined(__ANDROID__)
+#  include "uv/android-ifaddrs.h"
+# else
+#  include <ifaddrs.h>
+# endif
+# include <sys/socket.h>
+# include <net/ethernet.h>
+# include <netpacket/packet.h>
+#endif /* HAVE_IFADDRS_H */
+
+/* Available from 2.6.32 onwards. */
+#ifndef CLOCK_MONOTONIC_COARSE
+# define CLOCK_MONOTONIC_COARSE 6
+#endif
+
+#ifdef __FRC_ROBORIO__
+#include "wpi/timestamp.h"
+#endif
+
+/* This is rather annoying: CLOCK_BOOTTIME lives in <linux/time.h> but we can't
+ * include that file because it conflicts with <time.h>. We'll just have to
+ * define it ourselves.
+ */
+#ifndef CLOCK_BOOTTIME
+# define CLOCK_BOOTTIME 7
+#endif
+
+static int read_models(unsigned int numcpus, uv_cpu_info_t* ci);
+static int read_times(FILE* statfile_fp,
+                      unsigned int numcpus,
+                      uv_cpu_info_t* ci);
+static void read_speeds(unsigned int numcpus, uv_cpu_info_t* ci);
+static unsigned long read_cpufreq(unsigned int cpunum);
+
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  int fd;
+
+  fd = uv__epoll_create1(UV__EPOLL_CLOEXEC);
+
+  /* epoll_create1() can fail either because it's not implemented (old kernel)
+   * or because it doesn't understand the EPOLL_CLOEXEC flag.
+   */
+  if (fd == -1 && (errno == ENOSYS || errno == EINVAL)) {
+    fd = uv__epoll_create(256);
+
+    if (fd != -1)
+      uv__cloexec(fd, 1);
+  }
+
+  loop->backend_fd = fd;
+  loop->inotify_fd = -1;
+  loop->inotify_watchers = NULL;
+
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+int uv__io_fork(uv_loop_t* loop) {
+  int err;
+  void* old_watchers;
+
+  old_watchers = loop->inotify_watchers;
+
+  uv__close(loop->backend_fd);
+  loop->backend_fd = -1;
+  uv__platform_loop_delete(loop);
+
+  err = uv__platform_loop_init(loop);
+  if (err)
+    return err;
+
+  return uv__inotify_fork(loop, old_watchers);
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+  if (loop->inotify_fd == -1) return;
+  uv__io_stop(loop, &loop->inotify_read_watcher, POLLIN);
+  uv__close(loop->inotify_fd);
+  loop->inotify_fd = -1;
+}
+
+
+void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
+  struct uv__epoll_event* events;
+  struct uv__epoll_event dummy;
+  uintptr_t i;
+  uintptr_t nfds;
+
+  assert(loop->watchers != NULL);
+
+  events = (struct uv__epoll_event*) loop->watchers[loop->nwatchers];
+  nfds = (uintptr_t) loop->watchers[loop->nwatchers + 1];
+  if (events != NULL)
+    /* Invalidate events with same file descriptor */
+    for (i = 0; i < nfds; i++)
+      if ((int) events[i].data == fd)
+        events[i].data = -1;
+
+  /* Remove the file descriptor from the epoll.
+   * This avoids a problem where the same file description remains open
+   * in another process, causing repeated junk epoll events.
+   *
+   * We pass in a dummy epoll_event, to work around a bug in old kernels.
+   */
+  if (loop->backend_fd >= 0) {
+    /* Work around a bug in kernels 3.10 to 3.19 where passing a struct that
+     * has the EPOLLWAKEUP flag set generates spurious audit syslog warnings.
+     */
+    memset(&dummy, 0, sizeof(dummy));
+    uv__epoll_ctl(loop->backend_fd, UV__EPOLL_CTL_DEL, fd, &dummy);
+  }
+}
+
+
+int uv__io_check_fd(uv_loop_t* loop, int fd) {
+  struct uv__epoll_event e;
+  int rc;
+
+  e.events = POLLIN;
+  e.data = -1;
+
+  rc = 0;
+  if (uv__epoll_ctl(loop->backend_fd, UV__EPOLL_CTL_ADD, fd, &e))
+    if (errno != EEXIST)
+      rc = UV__ERR(errno);
+
+  if (rc == 0)
+    if (uv__epoll_ctl(loop->backend_fd, UV__EPOLL_CTL_DEL, fd, &e))
+      abort();
+
+  return rc;
+}
+
+
+void uv__io_poll(uv_loop_t* loop, int timeout) {
+  /* A bug in kernels < 2.6.37 makes timeouts larger than ~30 minutes
+   * effectively infinite on 32 bits architectures.  To avoid blocking
+   * indefinitely, we cap the timeout and poll again if necessary.
+   *
+   * Note that "30 minutes" is a simplification because it depends on
+   * the value of CONFIG_HZ.  The magic constant assumes CONFIG_HZ=1200,
+   * that being the largest value I have seen in the wild (and only once.)
+   */
+  static const int max_safe_timeout = 1789569;
+  static int no_epoll_pwait;
+  static int no_epoll_wait;
+  struct uv__epoll_event events[1024];
+  struct uv__epoll_event* pe;
+  struct uv__epoll_event e;
+  int real_timeout;
+  QUEUE* q;
+  uv__io_t* w;
+  sigset_t sigset;
+  uint64_t sigmask;
+  uint64_t base;
+  int have_signals;
+  int nevents;
+  int count;
+  int nfds;
+  int fd;
+  int op;
+  int i;
+
+  if (loop->nfds == 0) {
+    assert(QUEUE_EMPTY(&loop->watcher_queue));
+    return;
+  }
+
+  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
+    q = QUEUE_HEAD(&loop->watcher_queue);
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);
+
+    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
+    assert(w->pevents != 0);
+    assert(w->fd >= 0);
+    assert(w->fd < (int) loop->nwatchers);
+
+    e.events = w->pevents;
+    e.data = w->fd;
+
+    if (w->events == 0)
+      op = UV__EPOLL_CTL_ADD;
+    else
+      op = UV__EPOLL_CTL_MOD;
+
+    /* XXX Future optimization: do EPOLL_CTL_MOD lazily if we stop watching
+     * events, skip the syscall and squelch the events after epoll_wait().
+     */
+    if (uv__epoll_ctl(loop->backend_fd, op, w->fd, &e)) {
+      if (errno != EEXIST)
+        abort();
+
+      assert(op == UV__EPOLL_CTL_ADD);
+
+      /* We've reactivated a file descriptor that's been watched before. */
+      if (uv__epoll_ctl(loop->backend_fd, UV__EPOLL_CTL_MOD, w->fd, &e))
+        abort();
+    }
+
+    w->events = w->pevents;
+  }
+
+  sigmask = 0;
+  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
+    sigemptyset(&sigset);
+    sigaddset(&sigset, SIGPROF);
+    sigmask |= 1 << (SIGPROF - 1);
+  }
+
+  assert(timeout >= -1);
+  base = loop->time;
+  count = 48; /* Benchmarks suggest this gives the best throughput. */
+  real_timeout = timeout;
+
+  for (;;) {
+    /* See the comment for max_safe_timeout for an explanation of why
+     * this is necessary.  Executive summary: kernel bug workaround.
+     */
+    if (sizeof(int32_t) == sizeof(long) && timeout >= max_safe_timeout)
+      timeout = max_safe_timeout;
+
+    if (sigmask != 0 && no_epoll_pwait != 0)
+      if (pthread_sigmask(SIG_BLOCK, &sigset, NULL))
+        abort();
+
+    if (no_epoll_wait != 0 || (sigmask != 0 && no_epoll_pwait == 0)) {
+      nfds = uv__epoll_pwait(loop->backend_fd,
+                             events,
+                             ARRAY_SIZE(events),
+                             timeout,
+                             sigmask);
+      if (nfds == -1 && errno == ENOSYS)
+        no_epoll_pwait = 1;
+    } else {
+      nfds = uv__epoll_wait(loop->backend_fd,
+                            events,
+                            ARRAY_SIZE(events),
+                            timeout);
+      if (nfds == -1 && errno == ENOSYS)
+        no_epoll_wait = 1;
+    }
+
+    if (sigmask != 0 && no_epoll_pwait != 0)
+      if (pthread_sigmask(SIG_UNBLOCK, &sigset, NULL))
+        abort();
+
+    /* Update loop->time unconditionally. It's tempting to skip the update when
+     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
+     * operating system didn't reschedule our process while in the syscall.
+     */
+    SAVE_ERRNO(uv__update_time(loop));
+
+    if (nfds == 0) {
+      assert(timeout != -1);
+
+      if (timeout == 0)
+        return;
+
+      /* We may have been inside the system call for longer than |timeout|
+       * milliseconds so we need to update the timestamp to avoid drift.
+       */
+      goto update_timeout;
+    }
+
+    if (nfds == -1) {
+      if (errno == ENOSYS) {
+        /* epoll_wait() or epoll_pwait() failed, try the other system call. */
+        assert(no_epoll_wait == 0 || no_epoll_pwait == 0);
+        continue;
+      }
+
+      if (errno != EINTR)
+        abort();
+
+      if (timeout == -1)
+        continue;
+
+      if (timeout == 0)
+        return;
+
+      /* Interrupted by a signal. Update timeout and poll again. */
+      goto update_timeout;
+    }
+
+    have_signals = 0;
+    nevents = 0;
+
+    assert(loop->watchers != NULL);
+    loop->watchers[loop->nwatchers] = (uv__io_t*) events;
+    loop->watchers[loop->nwatchers + 1] = (uv__io_t*) (uintptr_t) nfds;
+    for (i = 0; i < nfds; i++) {
+      pe = events + i;
+      fd = pe->data;
+
+      /* Skip invalidated events, see uv__platform_invalidate_fd */
+      if (fd == -1)
+        continue;
+
+      assert(fd >= 0);
+      assert((unsigned) fd < loop->nwatchers);
+
+      w = loop->watchers[fd];
+
+      if (w == NULL) {
+        /* File descriptor that we've stopped watching, disarm it.
+         *
+         * Ignore all errors because we may be racing with another thread
+         * when the file descriptor is closed.
+         */
+        uv__epoll_ctl(loop->backend_fd, UV__EPOLL_CTL_DEL, fd, pe);
+        continue;
+      }
+
+      /* Give users only events they're interested in. Prevents spurious
+       * callbacks when previous callback invocation in this loop has stopped
+       * the current watcher. Also, filters out events that users has not
+       * requested us to watch.
+       */
+      pe->events &= w->pevents | POLLERR | POLLHUP;
+
+      /* Work around an epoll quirk where it sometimes reports just the
+       * EPOLLERR or EPOLLHUP event.  In order to force the event loop to
+       * move forward, we merge in the read/write events that the watcher
+       * is interested in; uv__read() and uv__write() will then deal with
+       * the error or hangup in the usual fashion.
+       *
+       * Note to self: happens when epoll reports EPOLLIN|EPOLLHUP, the user
+       * reads the available data, calls uv_read_stop(), then sometime later
+       * calls uv_read_start() again.  By then, libuv has forgotten about the
+       * hangup and the kernel won't report EPOLLIN again because there's
+       * nothing left to read.  If anything, libuv is to blame here.  The
+       * current hack is just a quick bandaid; to properly fix it, libuv
+       * needs to remember the error/hangup event.  We should get that for
+       * free when we switch over to edge-triggered I/O.
+       */
+      if (pe->events == POLLERR || pe->events == POLLHUP)
+        pe->events |=
+          w->pevents & (POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
+
+      if (pe->events != 0) {
+        /* Run signal watchers last.  This also affects child process watchers
+         * because those are implemented in terms of signal watchers.
+         */
+        if (w == &loop->signal_io_watcher)
+          have_signals = 1;
+        else
+          w->cb(loop, w, pe->events);
+
+        nevents++;
+      }
+    }
+
+    if (have_signals != 0)
+      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
+
+    loop->watchers[loop->nwatchers] = NULL;
+    loop->watchers[loop->nwatchers + 1] = NULL;
+
+    if (have_signals != 0)
+      return;  /* Event loop should cycle now so don't poll again. */
+
+    if (nevents != 0) {
+      if (nfds == ARRAY_SIZE(events) && --count != 0) {
+        /* Poll for more events but don't block this time. */
+        timeout = 0;
+        continue;
+      }
+      return;
+    }
+
+    if (timeout == 0)
+      return;
+
+    if (timeout == -1)
+      continue;
+
+update_timeout:
+    assert(timeout > 0);
+
+    real_timeout -= (loop->time - base);
+    if (real_timeout <= 0)
+      return;
+
+    timeout = real_timeout;
+  }
+}
+
+
+uint64_t uv__hrtime(uv_clocktype_t type) {
+#ifdef __FRC_ROBORIO__
+  return wpi::Now() * 1000u;
+#else
+  static clock_t fast_clock_id = -1;
+  struct timespec t;
+  clock_t clock_id;
+
+  /* Prefer CLOCK_MONOTONIC_COARSE if available but only when it has
+   * millisecond granularity or better.  CLOCK_MONOTONIC_COARSE is
+   * serviced entirely from the vDSO, whereas CLOCK_MONOTONIC may
+   * decide to make a costly system call.
+   */
+  /* TODO(bnoordhuis) Use CLOCK_MONOTONIC_COARSE for UV_CLOCK_PRECISE
+   * when it has microsecond granularity or better (unlikely).
+   */
+  if (type == UV_CLOCK_FAST && fast_clock_id == -1) {
+    if (clock_getres(CLOCK_MONOTONIC_COARSE, &t) == 0 &&
+        t.tv_nsec <= 1 * 1000 * 1000) {
+      fast_clock_id = CLOCK_MONOTONIC_COARSE;
+    } else {
+      fast_clock_id = CLOCK_MONOTONIC;
+    }
+  }
+
+  clock_id = CLOCK_MONOTONIC;
+  if (type == UV_CLOCK_FAST)
+    clock_id = fast_clock_id;
+
+  if (clock_gettime(clock_id, &t))
+    return 0;  /* Not really possible. */
+
+  return t.tv_sec * (uint64_t) 1e9 + t.tv_nsec;
+#endif
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  char buf[1024];
+  const char* s;
+  ssize_t n;
+  long val;
+  int fd;
+  int i;
+
+  do
+    fd = open("/proc/self/stat", O_RDONLY);
+  while (fd == -1 && errno == EINTR);
+
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  do
+    n = read(fd, buf, sizeof(buf) - 1);
+  while (n == -1 && errno == EINTR);
+
+  uv__close(fd);
+  if (n == -1)
+    return UV__ERR(errno);
+  buf[n] = '\0';
+
+  s = strchr(buf, ' ');
+  if (s == NULL)
+    goto err;
+
+  s += 1;
+  if (*s != '(')
+    goto err;
+
+  s = strchr(s, ')');
+  if (s == NULL)
+    goto err;
+
+  for (i = 1; i <= 22; i++) {
+    s = strchr(s + 1, ' ');
+    if (s == NULL)
+      goto err;
+  }
+
+  errno = 0;
+  val = strtol(s, NULL, 10);
+  if (errno != 0)
+    goto err;
+  if (val < 0)
+    goto err;
+
+  *rss = val * getpagesize();
+  return 0;
+
+err:
+  return UV_EINVAL;
+}
+
+
+int uv_uptime(double* uptime) {
+  static volatile int no_clock_boottime;
+  struct timespec now;
+  int r;
+
+  /* Try CLOCK_BOOTTIME first, fall back to CLOCK_MONOTONIC if not available
+   * (pre-2.6.39 kernels). CLOCK_MONOTONIC doesn't increase when the system
+   * is suspended.
+   */
+  if (no_clock_boottime) {
+    retry: r = clock_gettime(CLOCK_MONOTONIC, &now);
+  }
+  else if ((r = clock_gettime(CLOCK_BOOTTIME, &now)) && errno == EINVAL) {
+    no_clock_boottime = 1;
+    goto retry;
+  }
+
+  if (r)
+    return UV__ERR(errno);
+
+  *uptime = now.tv_sec;
+  return 0;
+}
+
+
+static int uv__cpu_num(FILE* statfile_fp, unsigned int* numcpus) {
+  unsigned int num;
+  char buf[1024];
+
+  if (!fgets(buf, sizeof(buf), statfile_fp))
+    return UV_EIO;
+
+  num = 0;
+  while (fgets(buf, sizeof(buf), statfile_fp)) {
+    if (strncmp(buf, "cpu", 3))
+      break;
+    num++;
+  }
+
+  if (num == 0)
+    return UV_EIO;
+
+  *numcpus = num;
+  return 0;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int numcpus;
+  uv_cpu_info_t* ci;
+  int err;
+  FILE* statfile_fp;
+
+  *cpu_infos = NULL;
+  *count = 0;
+
+  statfile_fp = uv__open_file("/proc/stat");
+  if (statfile_fp == NULL)
+    return UV__ERR(errno);
+
+  err = uv__cpu_num(statfile_fp, &numcpus);
+  if (err < 0)
+    goto out;
+
+  err = UV_ENOMEM;
+  ci = (uv_cpu_info_t*)uv__calloc(numcpus, sizeof(*ci));
+  if (ci == NULL)
+    goto out;
+
+  err = read_models(numcpus, ci);
+  if (err == 0)
+    err = read_times(statfile_fp, numcpus, ci);
+
+  if (err) {
+    uv_free_cpu_info(ci, numcpus);
+    goto out;
+  }
+
+  /* read_models() on x86 also reads the CPU speed from /proc/cpuinfo.
+   * We don't check for errors here. Worst case, the field is left zero.
+   */
+  if (ci[0].speed == 0)
+    read_speeds(numcpus, ci);
+
+  *cpu_infos = ci;
+  *count = numcpus;
+  err = 0;
+
+out:
+
+  if (fclose(statfile_fp))
+    if (errno != EINTR && errno != EINPROGRESS)
+      abort();
+
+  return err;
+}
+
+
+static void read_speeds(unsigned int numcpus, uv_cpu_info_t* ci) {
+  unsigned int num;
+
+  for (num = 0; num < numcpus; num++)
+    ci[num].speed = read_cpufreq(num) / 1000;
+}
+
+
+/* Also reads the CPU frequency on x86. The other architectures only have
+ * a BogoMIPS field, which may not be very accurate.
+ *
+ * Note: Simply returns on error, uv_cpu_info() takes care of the cleanup.
+ */
+static int read_models(unsigned int numcpus, uv_cpu_info_t* ci) {
+  static const char model_marker[] = "model name\t: ";
+  static const char speed_marker[] = "cpu MHz\t\t: ";
+  const char* inferred_model;
+  unsigned int model_idx;
+  unsigned int speed_idx;
+  char buf[1024];
+  char* model;
+  FILE* fp;
+
+  /* Most are unused on non-ARM, non-MIPS and non-x86 architectures. */
+  (void) &model_marker;
+  (void) &speed_marker;
+  (void) &speed_idx;
+  (void) &model;
+  (void) &buf;
+  (void) &fp;
+
+  model_idx = 0;
+  speed_idx = 0;
+
+#if defined(__arm__) || \
+    defined(__i386__) || \
+    defined(__mips__) || \
+    defined(__x86_64__)
+  fp = uv__open_file("/proc/cpuinfo");
+  if (fp == NULL)
+    return UV__ERR(errno);
+
+  while (fgets(buf, sizeof(buf), fp)) {
+    if (model_idx < numcpus) {
+      if (strncmp(buf, model_marker, sizeof(model_marker) - 1) == 0) {
+        model = buf + sizeof(model_marker) - 1;
+        model = uv__strndup(model, strlen(model) - 1);  /* Strip newline. */
+        if (model == NULL) {
+          fclose(fp);
+          return UV_ENOMEM;
+        }
+        ci[model_idx++].model = model;
+        continue;
+      }
+    }
+#if defined(__arm__) || defined(__mips__)
+    if (model_idx < numcpus) {
+#if defined(__arm__)
+      /* Fallback for pre-3.8 kernels. */
+      static const char model_marker[] = "Processor\t: ";
+#else	/* defined(__mips__) */
+      static const char model_marker[] = "cpu model\t\t: ";
+#endif
+      if (strncmp(buf, model_marker, sizeof(model_marker) - 1) == 0) {
+        model = buf + sizeof(model_marker) - 1;
+        model = uv__strndup(model, strlen(model) - 1);  /* Strip newline. */
+        if (model == NULL) {
+          fclose(fp);
+          return UV_ENOMEM;
+        }
+        ci[model_idx++].model = model;
+        continue;
+      }
+    }
+#else  /* !__arm__ && !__mips__ */
+    if (speed_idx < numcpus) {
+      if (strncmp(buf, speed_marker, sizeof(speed_marker) - 1) == 0) {
+        ci[speed_idx++].speed = atoi(buf + sizeof(speed_marker) - 1);
+        continue;
+      }
+    }
+#endif  /* __arm__ || __mips__ */
+  }
+
+  fclose(fp);
+#endif  /* __arm__ || __i386__ || __mips__ || __x86_64__ */
+
+  /* Now we want to make sure that all the models contain *something* because
+   * it's not safe to leave them as null. Copy the last entry unless there
+   * isn't one, in that case we simply put "unknown" into everything.
+   */
+  inferred_model = "unknown";
+  if (model_idx > 0)
+    inferred_model = ci[model_idx - 1].model;
+
+  while (model_idx < numcpus) {
+    model = uv__strndup(inferred_model, strlen(inferred_model));
+    if (model == NULL)
+      return UV_ENOMEM;
+    ci[model_idx++].model = model;
+  }
+
+  return 0;
+}
+
+
+static int read_times(FILE* statfile_fp,
+                      unsigned int numcpus,
+                      uv_cpu_info_t* ci) {
+  unsigned long clock_ticks;
+  struct uv_cpu_times_s ts;
+  unsigned long user;
+  unsigned long nice;
+  unsigned long sys;
+  unsigned long idle;
+  unsigned long dummy;
+  unsigned long irq;
+  unsigned int num;
+  unsigned int len;
+  char buf[1024];
+
+  clock_ticks = sysconf(_SC_CLK_TCK);
+  assert(clock_ticks != (unsigned long) -1);
+  assert(clock_ticks != 0);
+
+  rewind(statfile_fp);
+
+  if (!fgets(buf, sizeof(buf), statfile_fp))
+    abort();
+
+  num = 0;
+
+  while (fgets(buf, sizeof(buf), statfile_fp)) {
+    if (num >= numcpus)
+      break;
+
+    if (strncmp(buf, "cpu", 3))
+      break;
+
+    /* skip "cpu<num> " marker */
+    {
+      unsigned int n;
+      int r = sscanf(buf, "cpu%u ", &n);
+      assert(r == 1);
+      (void) r;  /* silence build warning */
+      for (len = sizeof("cpu0"); n /= 10; len++);
+    }
+
+    /* Line contains user, nice, system, idle, iowait, irq, softirq, steal,
+     * guest, guest_nice but we're only interested in the first four + irq.
+     *
+     * Don't use %*s to skip fields or %ll to read straight into the uint64_t
+     * fields, they're not allowed in C89 mode.
+     */
+    if (6 != sscanf(buf + len,
+                    "%lu %lu %lu %lu %lu %lu",
+                    &user,
+                    &nice,
+                    &sys,
+                    &idle,
+                    &dummy,
+                    &irq))
+      abort();
+
+    ts.user = clock_ticks * user;
+    ts.nice = clock_ticks * nice;
+    ts.sys  = clock_ticks * sys;
+    ts.idle = clock_ticks * idle;
+    ts.irq  = clock_ticks * irq;
+    ci[num++].cpu_times = ts;
+  }
+  assert(num == numcpus);
+
+  return 0;
+}
+
+
+static unsigned long read_cpufreq(unsigned int cpunum) {
+  unsigned long val;
+  char buf[1024];
+  FILE* fp;
+
+  snprintf(buf,
+           sizeof(buf),
+           "/sys/devices/system/cpu/cpu%u/cpufreq/scaling_cur_freq",
+           cpunum);
+
+  fp = uv__open_file(buf);
+  if (fp == NULL)
+    return 0;
+
+  if (fscanf(fp, "%lu", &val) != 1)
+    val = 0;
+
+  fclose(fp);
+
+  return val;
+}
+
+
+void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(cpu_infos[i].model);
+  }
+
+  uv__free(cpu_infos);
+}
+
+static int uv__ifaddr_exclude(struct ifaddrs *ent, int exclude_type) {
+  if (!((ent->ifa_flags & IFF_UP) && (ent->ifa_flags & IFF_RUNNING)))
+    return 1;
+  if (ent->ifa_addr == NULL)
+    return 1;
+  /*
+   * On Linux getifaddrs returns information related to the raw underlying
+   * devices. We're not interested in this information yet.
+   */
+  if (ent->ifa_addr->sa_family == PF_PACKET)
+    return exclude_type;
+  return !exclude_type;
+}
+
+int uv_interface_addresses(uv_interface_address_t** addresses,
+  int* count) {
+#ifndef HAVE_IFADDRS_H
+  return UV_ENOSYS;
+#else
+  struct ifaddrs *addrs, *ent;
+  uv_interface_address_t* address;
+  int i;
+  struct sockaddr_ll *sll;
+
+  if (getifaddrs(&addrs))
+    return UV__ERR(errno);
+
+  *count = 0;
+  *addresses = NULL;
+
+  /* Count the number of interfaces */
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
+      continue;
+
+    (*count)++;
+  }
+
+  if (*count == 0)
+    return 0;
+
+  *addresses =
+      (uv_interface_address_t*)uv__malloc(*count * sizeof(**addresses));
+  if (!(*addresses)) {
+    freeifaddrs(addrs);
+    return UV_ENOMEM;
+  }
+
+  address = *addresses;
+
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFADDR))
+      continue;
+
+    address->name = uv__strdup(ent->ifa_name);
+
+    if (ent->ifa_addr->sa_family == AF_INET6) {
+      address->address.address6 = *((struct sockaddr_in6*) ent->ifa_addr);
+    } else {
+      address->address.address4 = *((struct sockaddr_in*) ent->ifa_addr);
+    }
+
+    if (ent->ifa_netmask->sa_family == AF_INET6) {
+      address->netmask.netmask6 = *((struct sockaddr_in6*) ent->ifa_netmask);
+    } else {
+      address->netmask.netmask4 = *((struct sockaddr_in*) ent->ifa_netmask);
+    }
+
+    address->is_internal = !!(ent->ifa_flags & IFF_LOOPBACK);
+
+    address++;
+  }
+
+  /* Fill in physical addresses for each interface */
+  for (ent = addrs; ent != NULL; ent = ent->ifa_next) {
+    if (uv__ifaddr_exclude(ent, UV__EXCLUDE_IFPHYS))
+      continue;
+
+    address = *addresses;
+
+    for (i = 0; i < (*count); i++) {
+      if (strcmp(address->name, ent->ifa_name) == 0) {
+        sll = (struct sockaddr_ll*)ent->ifa_addr;
+        memcpy(address->phys_addr, sll->sll_addr, sizeof(address->phys_addr));
+      }
+      address++;
+    }
+  }
+
+  freeifaddrs(addrs);
+
+  return 0;
+#endif
+}
+
+
+void uv_free_interface_addresses(uv_interface_address_t* addresses,
+  int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(addresses[i].name);
+  }
+
+  uv__free(addresses);
+}
+
+
+void uv__set_process_title(const char* title) {
+#if defined(PR_SET_NAME)
+  prctl(PR_SET_NAME, title);  /* Only copies first 16 characters. */
+#endif
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-inotify.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-inotify.cpp
new file mode 100644
index 0000000..3f14974
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-inotify.cpp
@@ -0,0 +1,352 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv/tree.h"
+#include "internal.h"
+
+#include <stdint.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <sys/types.h>
+#include <unistd.h>
+
+struct watcher_list {
+  RB_ENTRY(watcher_list) entry;
+  QUEUE watchers;
+  int iterating;
+  char* path;
+  int wd;
+};
+
+struct watcher_root {
+  struct watcher_list* rbh_root;
+};
+#define CAST(p) ((struct watcher_root*)(p))
+
+
+static int compare_watchers(const struct watcher_list* a,
+                            const struct watcher_list* b) {
+  if (a->wd < b->wd) return -1;
+  if (a->wd > b->wd) return 1;
+  return 0;
+}
+
+
+RB_GENERATE_STATIC(watcher_root, watcher_list, entry, compare_watchers)
+
+
+static void uv__inotify_read(uv_loop_t* loop,
+                             uv__io_t* w,
+                             unsigned int revents);
+
+static void maybe_free_watcher_list(struct watcher_list* w,
+                                    uv_loop_t* loop);
+
+static int new_inotify_fd(void) {
+  int err;
+  int fd;
+
+  fd = uv__inotify_init1(UV__IN_NONBLOCK | UV__IN_CLOEXEC);
+  if (fd != -1)
+    return fd;
+
+  if (errno != ENOSYS)
+    return UV__ERR(errno);
+
+  fd = uv__inotify_init();
+  if (fd == -1)
+    return UV__ERR(errno);
+
+  err = uv__cloexec(fd, 1);
+  if (err == 0)
+    err = uv__nonblock(fd, 1);
+
+  if (err) {
+    uv__close(fd);
+    return err;
+  }
+
+  return fd;
+}
+
+
+static int init_inotify(uv_loop_t* loop) {
+  int err;
+
+  if (loop->inotify_fd != -1)
+    return 0;
+
+  err = new_inotify_fd();
+  if (err < 0)
+    return err;
+
+  loop->inotify_fd = err;
+  uv__io_init(&loop->inotify_read_watcher, uv__inotify_read, loop->inotify_fd);
+  uv__io_start(loop, &loop->inotify_read_watcher, POLLIN);
+
+  return 0;
+}
+
+
+int uv__inotify_fork(uv_loop_t* loop, void* old_watchers) {
+  /* Open the inotify_fd, and re-arm all the inotify watchers. */
+  int err;
+  struct watcher_list* tmp_watcher_list_iter;
+  struct watcher_list* watcher_list;
+  struct watcher_list tmp_watcher_list;
+  QUEUE queue;
+  QUEUE* q;
+  uv_fs_event_t* handle;
+  char* tmp_path;
+
+  if (old_watchers != NULL) {
+    /* We must restore the old watcher list to be able to close items
+     * out of it.
+     */
+    loop->inotify_watchers = old_watchers;
+
+    QUEUE_INIT(&tmp_watcher_list.watchers);
+    /* Note that the queue we use is shared with the start and stop()
+     * functions, making QUEUE_FOREACH unsafe to use. So we use the
+     * QUEUE_MOVE trick to safely iterate. Also don't free the watcher
+     * list until we're done iterating. c.f. uv__inotify_read.
+     */
+    RB_FOREACH_SAFE(watcher_list, watcher_root,
+                    CAST(&old_watchers), tmp_watcher_list_iter) {
+      watcher_list->iterating = 1;
+      QUEUE_MOVE(&watcher_list->watchers, &queue);
+      while (!QUEUE_EMPTY(&queue)) {
+        q = QUEUE_HEAD(&queue);
+        handle = QUEUE_DATA(q, uv_fs_event_t, watchers);
+        /* It's critical to keep a copy of path here, because it
+         * will be set to NULL by stop() and then deallocated by
+         * maybe_free_watcher_list
+         */
+        tmp_path = uv__strdup(handle->path);
+        assert(tmp_path != NULL);
+        QUEUE_REMOVE(q);
+        QUEUE_INSERT_TAIL(&watcher_list->watchers, q);
+        uv_fs_event_stop(handle);
+
+        QUEUE_INSERT_TAIL(&tmp_watcher_list.watchers, &handle->watchers);
+        handle->path = tmp_path;
+      }
+      watcher_list->iterating = 0;
+      maybe_free_watcher_list(watcher_list, loop);
+    }
+
+    QUEUE_MOVE(&tmp_watcher_list.watchers, &queue);
+    while (!QUEUE_EMPTY(&queue)) {
+        q = QUEUE_HEAD(&queue);
+        QUEUE_REMOVE(q);
+        handle = QUEUE_DATA(q, uv_fs_event_t, watchers);
+        tmp_path = handle->path;
+        handle->path = NULL;
+        err = uv_fs_event_start(handle, handle->cb, tmp_path, 0);
+        uv__free(tmp_path);
+        if (err)
+          return err;
+    }
+  }
+
+  return 0;
+}
+
+
+static struct watcher_list* find_watcher(uv_loop_t* loop, int wd) {
+  struct watcher_list w;
+  w.wd = wd;
+  return RB_FIND(watcher_root, CAST(&loop->inotify_watchers), &w);
+}
+
+static void maybe_free_watcher_list(struct watcher_list* w, uv_loop_t* loop) {
+  /* if the watcher_list->watchers is being iterated over, we can't free it. */
+  if ((!w->iterating) && QUEUE_EMPTY(&w->watchers)) {
+    /* No watchers left for this path. Clean up. */
+    RB_REMOVE(watcher_root, CAST(&loop->inotify_watchers), w);
+    uv__inotify_rm_watch(loop->inotify_fd, w->wd);
+    uv__free(w);
+  }
+}
+
+static void uv__inotify_read(uv_loop_t* loop,
+                             uv__io_t* dummy,
+                             unsigned int events) {
+  const struct uv__inotify_event* e;
+  struct watcher_list* w;
+  uv_fs_event_t* h;
+  QUEUE queue;
+  QUEUE* q;
+  const char* path;
+  ssize_t size;
+  const char *p;
+  /* needs to be large enough for sizeof(inotify_event) + strlen(path) */
+  char buf[4096];
+
+  while (1) {
+    do
+      size = read(loop->inotify_fd, buf, sizeof(buf));
+    while (size == -1 && errno == EINTR);
+
+    if (size == -1) {
+      assert(errno == EAGAIN || errno == EWOULDBLOCK);
+      break;
+    }
+
+    assert(size > 0); /* pre-2.6.21 thing, size=0 == read buffer too small */
+
+    /* Now we have one or more inotify_event structs. */
+    for (p = buf; p < buf + size; p += sizeof(*e) + e->len) {
+      e = (const struct uv__inotify_event*)p;
+
+      events = 0;
+      if (e->mask & (UV__IN_ATTRIB|UV__IN_MODIFY))
+        events |= UV_CHANGE;
+      if (e->mask & ~(UV__IN_ATTRIB|UV__IN_MODIFY))
+        events |= UV_RENAME;
+
+      w = find_watcher(loop, e->wd);
+      if (w == NULL)
+        continue; /* Stale event, no watchers left. */
+
+      /* inotify does not return the filename when monitoring a single file
+       * for modifications. Repurpose the filename for API compatibility.
+       * I'm not convinced this is a good thing, maybe it should go.
+       */
+      path = e->len ? (const char*) (e + 1) : uv__basename_r(w->path);
+
+      /* We're about to iterate over the queue and call user's callbacks.
+       * What can go wrong?
+       * A callback could call uv_fs_event_stop()
+       * and the queue can change under our feet.
+       * So, we use QUEUE_MOVE() trick to safely iterate over the queue.
+       * And we don't free the watcher_list until we're done iterating.
+       *
+       * First,
+       * tell uv_fs_event_stop() (that could be called from a user's callback)
+       * not to free watcher_list.
+       */
+      w->iterating = 1;
+      QUEUE_MOVE(&w->watchers, &queue);
+      while (!QUEUE_EMPTY(&queue)) {
+        q = QUEUE_HEAD(&queue);
+        h = QUEUE_DATA(q, uv_fs_event_t, watchers);
+
+        QUEUE_REMOVE(q);
+        QUEUE_INSERT_TAIL(&w->watchers, q);
+
+        h->cb(h, path, events, 0);
+      }
+      /* done iterating, time to (maybe) free empty watcher_list */
+      w->iterating = 0;
+      maybe_free_watcher_list(w, loop);
+    }
+  }
+}
+
+
+int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_FS_EVENT);
+  return 0;
+}
+
+
+int uv_fs_event_start(uv_fs_event_t* handle,
+                      uv_fs_event_cb cb,
+                      const char* path,
+                      unsigned int flags) {
+  struct watcher_list* w;
+  int events;
+  int err;
+  int wd;
+
+  if (uv__is_active(handle))
+    return UV_EINVAL;
+
+  err = init_inotify(handle->loop);
+  if (err)
+    return err;
+
+  events = UV__IN_ATTRIB
+         | UV__IN_CREATE
+         | UV__IN_MODIFY
+         | UV__IN_DELETE
+         | UV__IN_DELETE_SELF
+         | UV__IN_MOVE_SELF
+         | UV__IN_MOVED_FROM
+         | UV__IN_MOVED_TO;
+
+  wd = uv__inotify_add_watch(handle->loop->inotify_fd, path, events);
+  if (wd == -1)
+    return UV__ERR(errno);
+
+  w = find_watcher(handle->loop, wd);
+  if (w)
+    goto no_insert;
+
+  w = (watcher_list*)uv__malloc(sizeof(*w) + strlen(path) + 1);
+  if (w == NULL)
+    return UV_ENOMEM;
+
+  w->wd = wd;
+  w->path = strcpy((char*)(w + 1), path);
+  QUEUE_INIT(&w->watchers);
+  w->iterating = 0;
+  RB_INSERT(watcher_root, CAST(&handle->loop->inotify_watchers), w);
+
+no_insert:
+  uv__handle_start(handle);
+  QUEUE_INSERT_TAIL(&w->watchers, &handle->watchers);
+  handle->path = w->path;
+  handle->cb = cb;
+  handle->wd = wd;
+
+  return 0;
+}
+
+
+int uv_fs_event_stop(uv_fs_event_t* handle) {
+  struct watcher_list* w;
+
+  if (!uv__is_active(handle))
+    return 0;
+
+  w = find_watcher(handle->loop, handle->wd);
+  assert(w != NULL);
+
+  handle->wd = -1;
+  handle->path = NULL;
+  uv__handle_stop(handle);
+  QUEUE_REMOVE(&handle->watchers);
+
+  maybe_free_watcher_list(w, handle->loop);
+
+  return 0;
+}
+
+
+void uv__fs_event_close(uv_fs_event_t* handle) {
+  uv_fs_event_stop(handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-syscalls.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-syscalls.cpp
new file mode 100644
index 0000000..89998de
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-syscalls.cpp
@@ -0,0 +1,471 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "linux-syscalls.h"
+#include <unistd.h>
+#include <signal.h>
+#include <sys/syscall.h>
+#include <sys/types.h>
+#include <errno.h>
+
+#if defined(__has_feature)
+# if __has_feature(memory_sanitizer)
+#  define MSAN_ACTIVE 1
+#  include <sanitizer/msan_interface.h>
+# endif
+#endif
+
+#if defined(__i386__)
+# ifndef __NR_socketcall
+#  define __NR_socketcall 102
+# endif
+#endif
+
+#if defined(__arm__)
+# if defined(__thumb__) || defined(__ARM_EABI__)
+#  define UV_SYSCALL_BASE 0
+# else
+#  define UV_SYSCALL_BASE 0x900000
+# endif
+#endif /* __arm__ */
+
+#ifndef __NR_accept4
+# if defined(__x86_64__)
+#  define __NR_accept4 288
+# elif defined(__i386__)
+   /* Nothing. Handled through socketcall(). */
+# elif defined(__arm__)
+#  define __NR_accept4 (UV_SYSCALL_BASE + 366)
+# endif
+#endif /* __NR_accept4 */
+
+#ifndef __NR_eventfd
+# if defined(__x86_64__)
+#  define __NR_eventfd 284
+# elif defined(__i386__)
+#  define __NR_eventfd 323
+# elif defined(__arm__)
+#  define __NR_eventfd (UV_SYSCALL_BASE + 351)
+# endif
+#endif /* __NR_eventfd */
+
+#ifndef __NR_eventfd2
+# if defined(__x86_64__)
+#  define __NR_eventfd2 290
+# elif defined(__i386__)
+#  define __NR_eventfd2 328
+# elif defined(__arm__)
+#  define __NR_eventfd2 (UV_SYSCALL_BASE + 356)
+# endif
+#endif /* __NR_eventfd2 */
+
+#ifndef __NR_epoll_create
+# if defined(__x86_64__)
+#  define __NR_epoll_create 213
+# elif defined(__i386__)
+#  define __NR_epoll_create 254
+# elif defined(__arm__)
+#  define __NR_epoll_create (UV_SYSCALL_BASE + 250)
+# endif
+#endif /* __NR_epoll_create */
+
+#ifndef __NR_epoll_create1
+# if defined(__x86_64__)
+#  define __NR_epoll_create1 291
+# elif defined(__i386__)
+#  define __NR_epoll_create1 329
+# elif defined(__arm__)
+#  define __NR_epoll_create1 (UV_SYSCALL_BASE + 357)
+# endif
+#endif /* __NR_epoll_create1 */
+
+#ifndef __NR_epoll_ctl
+# if defined(__x86_64__)
+#  define __NR_epoll_ctl 233 /* used to be 214 */
+# elif defined(__i386__)
+#  define __NR_epoll_ctl 255
+# elif defined(__arm__)
+#  define __NR_epoll_ctl (UV_SYSCALL_BASE + 251)
+# endif
+#endif /* __NR_epoll_ctl */
+
+#ifndef __NR_epoll_wait
+# if defined(__x86_64__)
+#  define __NR_epoll_wait 232 /* used to be 215 */
+# elif defined(__i386__)
+#  define __NR_epoll_wait 256
+# elif defined(__arm__)
+#  define __NR_epoll_wait (UV_SYSCALL_BASE + 252)
+# endif
+#endif /* __NR_epoll_wait */
+
+#ifndef __NR_epoll_pwait
+# if defined(__x86_64__)
+#  define __NR_epoll_pwait 281
+# elif defined(__i386__)
+#  define __NR_epoll_pwait 319
+# elif defined(__arm__)
+#  define __NR_epoll_pwait (UV_SYSCALL_BASE + 346)
+# endif
+#endif /* __NR_epoll_pwait */
+
+#ifndef __NR_inotify_init
+# if defined(__x86_64__)
+#  define __NR_inotify_init 253
+# elif defined(__i386__)
+#  define __NR_inotify_init 291
+# elif defined(__arm__)
+#  define __NR_inotify_init (UV_SYSCALL_BASE + 316)
+# endif
+#endif /* __NR_inotify_init */
+
+#ifndef __NR_inotify_init1
+# if defined(__x86_64__)
+#  define __NR_inotify_init1 294
+# elif defined(__i386__)
+#  define __NR_inotify_init1 332
+# elif defined(__arm__)
+#  define __NR_inotify_init1 (UV_SYSCALL_BASE + 360)
+# endif
+#endif /* __NR_inotify_init1 */
+
+#ifndef __NR_inotify_add_watch
+# if defined(__x86_64__)
+#  define __NR_inotify_add_watch 254
+# elif defined(__i386__)
+#  define __NR_inotify_add_watch 292
+# elif defined(__arm__)
+#  define __NR_inotify_add_watch (UV_SYSCALL_BASE + 317)
+# endif
+#endif /* __NR_inotify_add_watch */
+
+#ifndef __NR_inotify_rm_watch
+# if defined(__x86_64__)
+#  define __NR_inotify_rm_watch 255
+# elif defined(__i386__)
+#  define __NR_inotify_rm_watch 293
+# elif defined(__arm__)
+#  define __NR_inotify_rm_watch (UV_SYSCALL_BASE + 318)
+# endif
+#endif /* __NR_inotify_rm_watch */
+
+#ifndef __NR_pipe2
+# if defined(__x86_64__)
+#  define __NR_pipe2 293
+# elif defined(__i386__)
+#  define __NR_pipe2 331
+# elif defined(__arm__)
+#  define __NR_pipe2 (UV_SYSCALL_BASE + 359)
+# endif
+#endif /* __NR_pipe2 */
+
+#ifndef __NR_recvmmsg
+# if defined(__x86_64__)
+#  define __NR_recvmmsg 299
+# elif defined(__i386__)
+#  define __NR_recvmmsg 337
+# elif defined(__arm__)
+#  define __NR_recvmmsg (UV_SYSCALL_BASE + 365)
+# endif
+#endif /* __NR_recvmsg */
+
+#ifndef __NR_sendmmsg
+# if defined(__x86_64__)
+#  define __NR_sendmmsg 307
+# elif defined(__i386__)
+#  define __NR_sendmmsg 345
+# elif defined(__arm__)
+#  define __NR_sendmmsg (UV_SYSCALL_BASE + 374)
+# endif
+#endif /* __NR_sendmmsg */
+
+#ifndef __NR_utimensat
+# if defined(__x86_64__)
+#  define __NR_utimensat 280
+# elif defined(__i386__)
+#  define __NR_utimensat 320
+# elif defined(__arm__)
+#  define __NR_utimensat (UV_SYSCALL_BASE + 348)
+# endif
+#endif /* __NR_utimensat */
+
+#ifndef __NR_preadv
+# if defined(__x86_64__)
+#  define __NR_preadv 295
+# elif defined(__i386__)
+#  define __NR_preadv 333
+# elif defined(__arm__)
+#  define __NR_preadv (UV_SYSCALL_BASE + 361)
+# endif
+#endif /* __NR_preadv */
+
+#ifndef __NR_pwritev
+# if defined(__x86_64__)
+#  define __NR_pwritev 296
+# elif defined(__i386__)
+#  define __NR_pwritev 334
+# elif defined(__arm__)
+#  define __NR_pwritev (UV_SYSCALL_BASE + 362)
+# endif
+#endif /* __NR_pwritev */
+
+#ifndef __NR_dup3
+# if defined(__x86_64__)
+#  define __NR_dup3 292
+# elif defined(__i386__)
+#  define __NR_dup3 330
+# elif defined(__arm__)
+#  define __NR_dup3 (UV_SYSCALL_BASE + 358)
+# endif
+#endif /* __NR_pwritev */
+
+
+int uv__accept4(int fd, struct sockaddr* addr, socklen_t* addrlen, int flags) {
+#if defined(__i386__)
+  unsigned long args[4];
+  int r;
+
+  args[0] = (unsigned long) fd;
+  args[1] = (unsigned long) addr;
+  args[2] = (unsigned long) addrlen;
+  args[3] = (unsigned long) flags;
+
+  r = syscall(__NR_socketcall, 18 /* SYS_ACCEPT4 */, args);
+
+  /* socketcall() raises EINVAL when SYS_ACCEPT4 is not supported but so does
+   * a bad flags argument. Try to distinguish between the two cases.
+   */
+  if (r == -1)
+    if (errno == EINVAL)
+      if ((flags & ~(UV__SOCK_CLOEXEC|UV__SOCK_NONBLOCK)) == 0)
+        errno = ENOSYS;
+
+  return r;
+#elif defined(__NR_accept4)
+  return syscall(__NR_accept4, fd, addr, addrlen, flags);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__eventfd(unsigned int count) {
+#if defined(__NR_eventfd)
+  return syscall(__NR_eventfd, count);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__eventfd2(unsigned int count, int flags) {
+#if defined(__NR_eventfd2)
+  return syscall(__NR_eventfd2, count, flags);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__epoll_create(int size) {
+#if defined(__NR_epoll_create)
+  return syscall(__NR_epoll_create, size);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__epoll_create1(int flags) {
+#if defined(__NR_epoll_create1)
+  return syscall(__NR_epoll_create1, flags);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__epoll_ctl(int epfd, int op, int fd, struct uv__epoll_event* events) {
+#if defined(__NR_epoll_ctl)
+  return syscall(__NR_epoll_ctl, epfd, op, fd, events);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__epoll_wait(int epfd,
+                   struct uv__epoll_event* events,
+                   int nevents,
+                   int timeout) {
+#if defined(__NR_epoll_wait)
+  int result;
+  result = syscall(__NR_epoll_wait, epfd, events, nevents, timeout);
+#if MSAN_ACTIVE
+  if (result > 0)
+    __msan_unpoison(events, sizeof(events[0]) * result);
+#endif
+  return result;
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__epoll_pwait(int epfd,
+                    struct uv__epoll_event* events,
+                    int nevents,
+                    int timeout,
+                    uint64_t sigmask) {
+#if defined(__NR_epoll_pwait)
+  int result;
+  result = syscall(__NR_epoll_pwait,
+                   epfd,
+                   events,
+                   nevents,
+                   timeout,
+                   &sigmask,
+                   sizeof(sigmask));
+#if MSAN_ACTIVE
+  if (result > 0)
+    __msan_unpoison(events, sizeof(events[0]) * result);
+#endif
+  return result;
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__inotify_init(void) {
+#if defined(__NR_inotify_init)
+  return syscall(__NR_inotify_init);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__inotify_init1(int flags) {
+#if defined(__NR_inotify_init1)
+  return syscall(__NR_inotify_init1, flags);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__inotify_add_watch(int fd, const char* path, uint32_t mask) {
+#if defined(__NR_inotify_add_watch)
+  return syscall(__NR_inotify_add_watch, fd, path, mask);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__inotify_rm_watch(int fd, int32_t wd) {
+#if defined(__NR_inotify_rm_watch)
+  return syscall(__NR_inotify_rm_watch, fd, wd);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__pipe2(int pipefd[2], int flags) {
+#if defined(__NR_pipe2)
+  int result;
+  result = syscall(__NR_pipe2, pipefd, flags);
+#if MSAN_ACTIVE
+  if (!result)
+    __msan_unpoison(pipefd, sizeof(int[2]));
+#endif
+  return result;
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__sendmmsg(int fd,
+                 struct uv__mmsghdr* mmsg,
+                 unsigned int vlen,
+                 unsigned int flags) {
+#if defined(__NR_sendmmsg)
+  return syscall(__NR_sendmmsg, fd, mmsg, vlen, flags);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__recvmmsg(int fd,
+                 struct uv__mmsghdr* mmsg,
+                 unsigned int vlen,
+                 unsigned int flags,
+                 struct timespec* timeout) {
+#if defined(__NR_recvmmsg)
+  return syscall(__NR_recvmmsg, fd, mmsg, vlen, flags, timeout);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__utimesat(int dirfd,
+                 const char* path,
+                 const struct timespec times[2],
+                 int flags)
+{
+#if defined(__NR_utimensat)
+  return syscall(__NR_utimensat, dirfd, path, times, flags);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+ssize_t uv__preadv(int fd, const struct iovec *iov, int iovcnt, int64_t offset) {
+#if defined(__NR_preadv)
+  return syscall(__NR_preadv, fd, iov, iovcnt, (long)offset, (long)(offset >> 32));
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+ssize_t uv__pwritev(int fd, const struct iovec *iov, int iovcnt, int64_t offset) {
+#if defined(__NR_pwritev)
+  return syscall(__NR_pwritev, fd, iov, iovcnt, (long)offset, (long)(offset >> 32));
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
+
+
+int uv__dup3(int oldfd, int newfd, int flags) {
+#if defined(__NR_dup3)
+  return syscall(__NR_dup3, oldfd, newfd, flags);
+#else
+  return errno = ENOSYS, -1;
+#endif
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-syscalls.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-syscalls.h
new file mode 100644
index 0000000..4c095e9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/linux-syscalls.h
@@ -0,0 +1,151 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_LINUX_SYSCALL_H_
+#define UV_LINUX_SYSCALL_H_
+
+#undef  _GNU_SOURCE
+#define _GNU_SOURCE
+
+#include <stdint.h>
+#include <signal.h>
+#include <sys/types.h>
+#include <sys/time.h>
+#include <sys/socket.h>
+
+#if defined(__alpha__)
+# define UV__O_CLOEXEC        0x200000
+#elif defined(__hppa__)
+# define UV__O_CLOEXEC        0x200000
+#elif defined(__sparc__)
+# define UV__O_CLOEXEC        0x400000
+#else
+# define UV__O_CLOEXEC        0x80000
+#endif
+
+#if defined(__alpha__)
+# define UV__O_NONBLOCK       0x4
+#elif defined(__hppa__)
+# define UV__O_NONBLOCK       O_NONBLOCK
+#elif defined(__mips__)
+# define UV__O_NONBLOCK       0x80
+#elif defined(__sparc__)
+# define UV__O_NONBLOCK       0x4000
+#else
+# define UV__O_NONBLOCK       0x800
+#endif
+
+#define UV__EFD_CLOEXEC       UV__O_CLOEXEC
+#define UV__EFD_NONBLOCK      UV__O_NONBLOCK
+
+#define UV__IN_CLOEXEC        UV__O_CLOEXEC
+#define UV__IN_NONBLOCK       UV__O_NONBLOCK
+
+#define UV__SOCK_CLOEXEC      UV__O_CLOEXEC
+#if defined(SOCK_NONBLOCK)
+# define UV__SOCK_NONBLOCK    SOCK_NONBLOCK
+#else
+# define UV__SOCK_NONBLOCK    UV__O_NONBLOCK
+#endif
+
+/* epoll flags */
+#define UV__EPOLL_CLOEXEC     UV__O_CLOEXEC
+#define UV__EPOLL_CTL_ADD     1
+#define UV__EPOLL_CTL_DEL     2
+#define UV__EPOLL_CTL_MOD     3
+
+/* inotify flags */
+#define UV__IN_ACCESS         0x001
+#define UV__IN_MODIFY         0x002
+#define UV__IN_ATTRIB         0x004
+#define UV__IN_CLOSE_WRITE    0x008
+#define UV__IN_CLOSE_NOWRITE  0x010
+#define UV__IN_OPEN           0x020
+#define UV__IN_MOVED_FROM     0x040
+#define UV__IN_MOVED_TO       0x080
+#define UV__IN_CREATE         0x100
+#define UV__IN_DELETE         0x200
+#define UV__IN_DELETE_SELF    0x400
+#define UV__IN_MOVE_SELF      0x800
+
+#if defined(__x86_64__)
+struct uv__epoll_event {
+  uint32_t events;
+  uint64_t data;
+} __attribute__((packed));
+#else
+struct uv__epoll_event {
+  uint32_t events;
+  uint64_t data;
+};
+#endif
+
+struct uv__inotify_event {
+  int32_t wd;
+  uint32_t mask;
+  uint32_t cookie;
+  uint32_t len;
+  /* char name[0]; */
+};
+
+struct uv__mmsghdr {
+  struct msghdr msg_hdr;
+  unsigned int msg_len;
+};
+
+int uv__accept4(int fd, struct sockaddr* addr, socklen_t* addrlen, int flags);
+int uv__eventfd(unsigned int count);
+int uv__epoll_create(int size);
+int uv__epoll_create1(int flags);
+int uv__epoll_ctl(int epfd, int op, int fd, struct uv__epoll_event *ev);
+int uv__epoll_wait(int epfd,
+                   struct uv__epoll_event* events,
+                   int nevents,
+                   int timeout);
+int uv__epoll_pwait(int epfd,
+                    struct uv__epoll_event* events,
+                    int nevents,
+                    int timeout,
+                    uint64_t sigmask);
+int uv__eventfd2(unsigned int count, int flags);
+int uv__inotify_init(void);
+int uv__inotify_init1(int flags);
+int uv__inotify_add_watch(int fd, const char* path, uint32_t mask);
+int uv__inotify_rm_watch(int fd, int32_t wd);
+int uv__pipe2(int pipefd[2], int flags);
+int uv__recvmmsg(int fd,
+                 struct uv__mmsghdr* mmsg,
+                 unsigned int vlen,
+                 unsigned int flags,
+                 struct timespec* timeout);
+int uv__sendmmsg(int fd,
+                 struct uv__mmsghdr* mmsg,
+                 unsigned int vlen,
+                 unsigned int flags);
+int uv__utimesat(int dirfd,
+                 const char* path,
+                 const struct timespec times[2],
+                 int flags);
+ssize_t uv__preadv(int fd, const struct iovec *iov, int iovcnt, int64_t offset);
+ssize_t uv__pwritev(int fd, const struct iovec *iov, int iovcnt, int64_t offset);
+int uv__dup3(int oldfd, int newfd, int flags);
+
+#endif /* UV_LINUX_SYSCALL_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/loop-watcher.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/loop-watcher.cpp
new file mode 100644
index 0000000..b8c1c2a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/loop-watcher.cpp
@@ -0,0 +1,68 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#define UV_LOOP_WATCHER_DEFINE(name, type)                                    \
+  int uv_##name##_init(uv_loop_t* loop, uv_##name##_t* handle) {              \
+    uv__handle_init(loop, (uv_handle_t*)handle, UV_##type);                   \
+    handle->name##_cb = NULL;                                                 \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+  int uv_##name##_start(uv_##name##_t* handle, uv_##name##_cb cb) {           \
+    if (uv__is_active(handle)) return 0;                                      \
+    if (cb == NULL) return UV_EINVAL;                                         \
+    QUEUE_INSERT_HEAD(&handle->loop->name##_handles, &handle->queue);         \
+    handle->name##_cb = cb;                                                   \
+    uv__handle_start(handle);                                                 \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+  int uv_##name##_stop(uv_##name##_t* handle) {                               \
+    if (!uv__is_active(handle)) return 0;                                     \
+    QUEUE_REMOVE(&handle->queue);                                             \
+    uv__handle_stop(handle);                                                  \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+  void uv__run_##name(uv_loop_t* loop) {                                      \
+    uv_##name##_t* h;                                                         \
+    QUEUE queue;                                                              \
+    QUEUE* q;                                                                 \
+    QUEUE_MOVE(&loop->name##_handles, &queue);                                \
+    while (!QUEUE_EMPTY(&queue)) {                                            \
+      q = QUEUE_HEAD(&queue);                                                 \
+      h = QUEUE_DATA(q, uv_##name##_t, queue);                                \
+      QUEUE_REMOVE(q);                                                        \
+      QUEUE_INSERT_TAIL(&loop->name##_handles, q);                            \
+      h->name##_cb(h);                                                        \
+    }                                                                         \
+  }                                                                           \
+                                                                              \
+  void uv__##name##_close(uv_##name##_t* handle) {                            \
+    uv_##name##_stop(handle);                                                 \
+  }
+
+UV_LOOP_WATCHER_DEFINE(prepare, PREPARE)
+UV_LOOP_WATCHER_DEFINE(check, CHECK)
+UV_LOOP_WATCHER_DEFINE(idle, IDLE)
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/loop.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/loop.cpp
new file mode 100644
index 0000000..f990403
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/loop.cpp
@@ -0,0 +1,194 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv/tree.h"
+#include "internal.h"
+#include "heap-inl.h"
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+int uv_loop_init(uv_loop_t* loop) {
+  void* saved_data;
+  int err;
+
+
+  saved_data = loop->data;
+  memset(loop, 0, sizeof(*loop));
+  loop->data = saved_data;
+
+  heap_init((struct heap*) &loop->timer_heap);
+  QUEUE_INIT(&loop->wq);
+  QUEUE_INIT(&loop->idle_handles);
+  QUEUE_INIT(&loop->async_handles);
+  QUEUE_INIT(&loop->check_handles);
+  QUEUE_INIT(&loop->prepare_handles);
+  QUEUE_INIT(&loop->handle_queue);
+
+  loop->active_handles = 0;
+  loop->active_reqs.count = 0;
+  loop->nfds = 0;
+  loop->watchers = NULL;
+  loop->nwatchers = 0;
+  QUEUE_INIT(&loop->pending_queue);
+  QUEUE_INIT(&loop->watcher_queue);
+
+  loop->closing_handles = NULL;
+  uv__update_time(loop);
+  loop->async_io_watcher.fd = -1;
+  loop->async_wfd = -1;
+  loop->signal_pipefd[0] = -1;
+  loop->signal_pipefd[1] = -1;
+  loop->backend_fd = -1;
+  loop->emfile_fd = -1;
+
+  loop->timer_counter = 0;
+  loop->stop_flag = 0;
+
+  err = uv__platform_loop_init(loop);
+  if (err)
+    return err;
+
+  uv__signal_global_once_init();
+  err = uv_signal_init(loop, &loop->child_watcher);
+  if (err)
+    goto fail_signal_init;
+
+  uv__handle_unref(&loop->child_watcher);
+  loop->child_watcher.flags |= UV__HANDLE_INTERNAL;
+  QUEUE_INIT(&loop->process_handles);
+
+  err = uv_rwlock_init(&loop->cloexec_lock);
+  if (err)
+    goto fail_rwlock_init;
+
+  err = uv_mutex_init(&loop->wq_mutex);
+  if (err)
+    goto fail_mutex_init;
+
+  err = uv_async_init(loop, &loop->wq_async, uv__work_done);
+  if (err)
+    goto fail_async_init;
+
+  uv__handle_unref(&loop->wq_async);
+  loop->wq_async.flags |= UV__HANDLE_INTERNAL;
+
+  return 0;
+
+fail_async_init:
+  uv_mutex_destroy(&loop->wq_mutex);
+
+fail_mutex_init:
+  uv_rwlock_destroy(&loop->cloexec_lock);
+
+fail_rwlock_init:
+  uv__signal_loop_cleanup(loop);
+
+fail_signal_init:
+  uv__platform_loop_delete(loop);
+
+  return err;
+}
+
+
+int uv_loop_fork(uv_loop_t* loop) {
+  int err;
+  unsigned int i;
+  uv__io_t* w;
+
+  err = uv__io_fork(loop);
+  if (err)
+    return err;
+
+  err = uv__async_fork(loop);
+  if (err)
+    return err;
+
+  err = uv__signal_loop_fork(loop);
+  if (err)
+    return err;
+
+  /* Rearm all the watchers that aren't re-queued by the above. */
+  for (i = 0; i < loop->nwatchers; i++) {
+    w = loop->watchers[i];
+    if (w == NULL)
+      continue;
+
+    if (w->pevents != 0 && QUEUE_EMPTY(&w->watcher_queue)) {
+      w->events = 0; /* Force re-registration in uv__io_poll. */
+      QUEUE_INSERT_TAIL(&loop->watcher_queue, &w->watcher_queue);
+    }
+  }
+
+  return 0;
+}
+
+
+void uv__loop_close(uv_loop_t* loop) {
+  uv__signal_loop_cleanup(loop);
+  uv__platform_loop_delete(loop);
+  uv__async_stop(loop);
+
+  if (loop->emfile_fd != -1) {
+    uv__close(loop->emfile_fd);
+    loop->emfile_fd = -1;
+  }
+
+  if (loop->backend_fd != -1) {
+    uv__close(loop->backend_fd);
+    loop->backend_fd = -1;
+  }
+
+  uv_mutex_lock(&loop->wq_mutex);
+  assert(QUEUE_EMPTY(&loop->wq) && "thread pool work queue not empty!");
+  assert(!uv__has_active_reqs(loop));
+  uv_mutex_unlock(&loop->wq_mutex);
+  uv_mutex_destroy(&loop->wq_mutex);
+
+  /*
+   * Note that all thread pool stuff is finished at this point and
+   * it is safe to just destroy rw lock
+   */
+  uv_rwlock_destroy(&loop->cloexec_lock);
+
+#if 0
+  assert(QUEUE_EMPTY(&loop->pending_queue));
+  assert(QUEUE_EMPTY(&loop->watcher_queue));
+  assert(loop->nfds == 0);
+#endif
+
+  uv__free(loop->watchers);
+  loop->watchers = NULL;
+  loop->nwatchers = 0;
+}
+
+
+int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap) {
+  if (option != UV_LOOP_BLOCK_SIGNAL)
+    return UV_ENOSYS;
+
+  if (va_arg(ap, int) != SIGPROF)
+    return UV_EINVAL;
+
+  loop->flags |= UV_LOOP_BLOCK_SIGPROF;
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/netbsd.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/netbsd.cpp
new file mode 100644
index 0000000..fc9e588
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/netbsd.cpp
@@ -0,0 +1,309 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+
+#include <kvm.h>
+#include <paths.h>
+#include <unistd.h>
+#include <time.h>
+#include <stdlib.h>
+#include <fcntl.h>
+
+#include <sys/resource.h>
+#include <sys/types.h>
+#include <sys/sysctl.h>
+#include <uvm/uvm_extern.h>
+
+#include <unistd.h>
+#include <time.h>
+
+static uv_mutex_t process_title_mutex;
+static uv_once_t process_title_mutex_once = UV_ONCE_INIT;
+static char *process_title;
+
+
+static void init_process_title_mutex_once(void) {
+  uv_mutex_init(&process_title_mutex);
+}
+
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  return uv__kqueue_init(loop);
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct loadavg info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_LOADAVG};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0) == -1) return;
+
+  avg[0] = (double) info.ldavg[0] / info.fscale;
+  avg[1] = (double) info.ldavg[1] / info.fscale;
+  avg[2] = (double) info.ldavg[2] / info.fscale;
+}
+
+
+int uv_exepath(char* buffer, size_t* size) {
+  /* Intermediate buffer, retrieving partial path name does not work
+   * As of NetBSD-8(beta), vnode->path translator does not handle files
+   * with longer names than 31 characters.
+   */
+  char int_buf[PATH_MAX];
+  size_t int_size;
+  int mib[4];
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  mib[0] = CTL_KERN;
+  mib[1] = KERN_PROC_ARGS;
+  mib[2] = -1;
+  mib[3] = KERN_PROC_PATHNAME;
+  int_size = ARRAY_SIZE(int_buf);
+
+  if (sysctl(mib, 4, int_buf, &int_size, NULL, 0))
+    return UV__ERR(errno);
+
+  /* Copy string from the intermediate buffer to outer one with appropriate
+   * length.
+   */
+  strlcpy(buffer, int_buf, *size);
+
+  /* Set new size. */
+  *size = strlen(buffer);
+
+  return 0;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  struct uvmexp info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_UVMEXP};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info.free * sysconf(_SC_PAGESIZE);
+}
+
+
+uint64_t uv_get_total_memory(void) {
+#if defined(HW_PHYSMEM64)
+  uint64_t info;
+  int which[] = {CTL_HW, HW_PHYSMEM64};
+#else
+  unsigned int info;
+  int which[] = {CTL_HW, HW_PHYSMEM};
+#endif
+  size_t size = sizeof(info);
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info;
+}
+
+
+char** uv_setup_args(int argc, char** argv) {
+  process_title = argc ? uv__strdup(argv[0]) : NULL;
+  return argv;
+}
+
+
+int uv_set_process_title(const char* title) {
+  char* new_title;
+
+  new_title = uv__strdup(title);
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (process_title == NULL) {
+    uv_mutex_unlock(&process_title_mutex);
+    return UV_ENOMEM;
+  }
+
+  uv__free(process_title);
+  process_title = new_title;
+  setproctitle("%s", title);
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  return 0;
+}
+
+
+int uv_get_process_title(char* buffer, size_t size) {
+  size_t len;
+
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (process_title) {
+    len = strlen(process_title) + 1;
+
+    if (size < len) {
+      uv_mutex_unlock(&process_title_mutex);
+      return UV_ENOBUFS;
+    }
+
+    memcpy(buffer, process_title, len);
+  } else {
+    len = 0;
+  }
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  buffer[len] = '\0';
+
+  return 0;
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  kvm_t *kd = NULL;
+  struct kinfo_proc2 *kinfo = NULL;
+  pid_t pid;
+  int nprocs;
+  int max_size = sizeof(struct kinfo_proc2);
+  int page_size;
+
+  page_size = getpagesize();
+  pid = getpid();
+
+  kd = kvm_open(NULL, NULL, NULL, KVM_NO_FILES, "kvm_open");
+
+  if (kd == NULL) goto error;
+
+  kinfo = kvm_getproc2(kd, KERN_PROC_PID, pid, max_size, &nprocs);
+  if (kinfo == NULL) goto error;
+
+  *rss = kinfo->p_vm_rssize * page_size;
+
+  kvm_close(kd);
+
+  return 0;
+
+error:
+  if (kd) kvm_close(kd);
+  return UV_EPERM;
+}
+
+
+int uv_uptime(double* uptime) {
+  time_t now;
+  struct timeval info;
+  size_t size = sizeof(info);
+  static int which[] = {CTL_KERN, KERN_BOOTTIME};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  now = time(NULL);
+
+  *uptime = (double)(now - info.tv_sec);
+  return 0;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK);
+  unsigned int multiplier = ((uint64_t)1000L / ticks);
+  unsigned int cur = 0;
+  uv_cpu_info_t* cpu_info;
+  u_int64_t* cp_times;
+  char model[512];
+  u_int64_t cpuspeed;
+  int numcpus;
+  size_t size;
+  int i;
+
+  size = sizeof(model);
+  if (sysctlbyname("machdep.cpu_brand", &model, &size, NULL, 0) &&
+      sysctlbyname("hw.model", &model, &size, NULL, 0)) {
+    return UV__ERR(errno);
+  }
+
+  size = sizeof(numcpus);
+  if (sysctlbyname("hw.ncpu", &numcpus, &size, NULL, 0))
+    return UV__ERR(errno);
+  *count = numcpus;
+
+  /* Only i386 and amd64 have machdep.tsc_freq */
+  size = sizeof(cpuspeed);
+  if (sysctlbyname("machdep.tsc_freq", &cpuspeed, &size, NULL, 0))
+    cpuspeed = 0;
+
+  size = numcpus * CPUSTATES * sizeof(*cp_times);
+  cp_times = (u_int64_t*)uv__malloc(size);
+  if (cp_times == NULL)
+    return UV_ENOMEM;
+
+  if (sysctlbyname("kern.cp_time", cp_times, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+  if (!(*cpu_infos)) {
+    uv__free(cp_times);
+    uv__free(*cpu_infos);
+    return UV_ENOMEM;
+  }
+
+  for (i = 0; i < numcpus; i++) {
+    cpu_info = &(*cpu_infos)[i];
+    cpu_info->cpu_times.user = (uint64_t)(cp_times[CP_USER+cur]) * multiplier;
+    cpu_info->cpu_times.nice = (uint64_t)(cp_times[CP_NICE+cur]) * multiplier;
+    cpu_info->cpu_times.sys = (uint64_t)(cp_times[CP_SYS+cur]) * multiplier;
+    cpu_info->cpu_times.idle = (uint64_t)(cp_times[CP_IDLE+cur]) * multiplier;
+    cpu_info->cpu_times.irq = (uint64_t)(cp_times[CP_INTR+cur]) * multiplier;
+    cpu_info->model = uv__strdup(model);
+    cpu_info->speed = (int)(cpuspeed/(uint64_t) 1e6);
+    cur += CPUSTATES;
+  }
+  uv__free(cp_times);
+  return 0;
+}
+
+
+void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(cpu_infos[i].model);
+  }
+
+  uv__free(cpu_infos);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/no-fsevents.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/no-fsevents.cpp
new file mode 100644
index 0000000..158643a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/no-fsevents.cpp
@@ -0,0 +1,42 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+
+int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
+  return UV_ENOSYS;
+}
+
+int uv_fs_event_start(uv_fs_event_t* handle, uv_fs_event_cb cb,
+                      const char* filename, unsigned int flags) {
+  return UV_ENOSYS;
+}
+
+int uv_fs_event_stop(uv_fs_event_t* handle) {
+  return UV_ENOSYS;
+}
+
+void uv__fs_event_close(uv_fs_event_t* handle) {
+  UNREACHABLE();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/no-proctitle.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/no-proctitle.cpp
new file mode 100644
index 0000000..165740c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/no-proctitle.cpp
@@ -0,0 +1,42 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <errno.h>
+#include <stddef.h>
+
+char** uv_setup_args(int argc, char** argv) {
+  return argv;
+}
+
+int uv_set_process_title(const char* title) {
+  return 0;
+}
+
+int uv_get_process_title(char* buffer, size_t size) {
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  buffer[0] = '\0';
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/openbsd.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/openbsd.cpp
new file mode 100644
index 0000000..ecd7bbb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/openbsd.cpp
@@ -0,0 +1,313 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <sys/types.h>
+#include <sys/param.h>
+#include <sys/resource.h>
+#include <sys/sched.h>
+#include <sys/time.h>
+#include <sys/sysctl.h>
+
+#include <errno.h>
+#include <fcntl.h>
+#include <paths.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+
+static uv_mutex_t process_title_mutex;
+static uv_once_t process_title_mutex_once = UV_ONCE_INIT;
+static char *process_title;
+
+
+static void init_process_title_mutex_once(void) {
+  uv_mutex_init(&process_title_mutex);
+}
+
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  return uv__kqueue_init(loop);
+}
+
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+}
+
+
+void uv_loadavg(double avg[3]) {
+  struct loadavg info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_LOADAVG};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0) < 0) return;
+
+  avg[0] = (double) info.ldavg[0] / info.fscale;
+  avg[1] = (double) info.ldavg[1] / info.fscale;
+  avg[2] = (double) info.ldavg[2] / info.fscale;
+}
+
+
+int uv_exepath(char* buffer, size_t* size) {
+  int mib[4];
+  char **argsbuf = NULL;
+  char **argsbuf_tmp;
+  size_t argsbuf_size = 100U;
+  size_t exepath_size;
+  pid_t mypid;
+  int err;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  mypid = getpid();
+  for (;;) {
+    err = UV_ENOMEM;
+    argsbuf_tmp = (char**)uv__realloc(argsbuf, argsbuf_size);
+    if (argsbuf_tmp == NULL)
+      goto out;
+    argsbuf = argsbuf_tmp;
+    mib[0] = CTL_KERN;
+    mib[1] = KERN_PROC_ARGS;
+    mib[2] = mypid;
+    mib[3] = KERN_PROC_ARGV;
+    if (sysctl(mib, 4, argsbuf, &argsbuf_size, NULL, 0) == 0) {
+      break;
+    }
+    if (errno != ENOMEM) {
+      err = UV__ERR(errno);
+      goto out;
+    }
+    argsbuf_size *= 2U;
+  }
+
+  if (argsbuf[0] == NULL) {
+    err = UV_EINVAL;  /* FIXME(bnoordhuis) More appropriate error. */
+    goto out;
+  }
+
+  *size -= 1;
+  exepath_size = strlen(argsbuf[0]);
+  if (*size > exepath_size)
+    *size = exepath_size;
+
+  memcpy(buffer, argsbuf[0], *size);
+  buffer[*size] = '\0';
+  err = 0;
+
+out:
+  uv__free(argsbuf);
+
+  return err;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  struct uvmexp info;
+  size_t size = sizeof(info);
+  int which[] = {CTL_VM, VM_UVMEXP};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info.free * sysconf(_SC_PAGESIZE);
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  uint64_t info;
+  int which[] = {CTL_HW, HW_PHYSMEM64};
+  size_t size = sizeof(info);
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  return (uint64_t) info;
+}
+
+
+char** uv_setup_args(int argc, char** argv) {
+  process_title = argc ? uv__strdup(argv[0]) : NULL;
+  return argv;
+}
+
+
+int uv_set_process_title(const char* title) {
+  char* new_title;
+
+  new_title = uv__strdup(title);
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (process_title == NULL) {
+    uv_mutex_unlock(&process_title_mutex);
+    return UV_ENOMEM;
+  }
+
+  uv__free(process_title);
+  process_title = new_title;
+  setproctitle("%s", title);
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  return 0;
+}
+
+
+int uv_get_process_title(char* buffer, size_t size) {
+  size_t len;
+
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (process_title) {
+    len = strlen(process_title) + 1;
+
+    if (size < len) {
+      uv_mutex_unlock(&process_title_mutex);
+      return UV_ENOBUFS;
+    }
+
+    memcpy(buffer, process_title, len);
+  } else {
+    len = 0;
+  }
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  buffer[len] = '\0';
+
+  return 0;
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  struct kinfo_proc kinfo;
+  size_t page_size = getpagesize();
+  size_t size = sizeof(struct kinfo_proc);
+  int mib[6];
+
+  mib[0] = CTL_KERN;
+  mib[1] = KERN_PROC;
+  mib[2] = KERN_PROC_PID;
+  mib[3] = getpid();
+  mib[4] = sizeof(struct kinfo_proc);
+  mib[5] = 1;
+
+  if (sysctl(mib, 6, &kinfo, &size, NULL, 0) < 0)
+    return UV__ERR(errno);
+
+  *rss = kinfo.p_vm_rssize * page_size;
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  time_t now;
+  struct timeval info;
+  size_t size = sizeof(info);
+  static int which[] = {CTL_KERN, KERN_BOOTTIME};
+
+  if (sysctl(which, 2, &info, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  now = time(NULL);
+
+  *uptime = (double)(now - info.tv_sec);
+  return 0;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos, int* count) {
+  unsigned int ticks = (unsigned int)sysconf(_SC_CLK_TCK),
+               multiplier = ((uint64_t)1000L / ticks), cpuspeed;
+  uint64_t info[CPUSTATES];
+  char model[512];
+  int numcpus = 1;
+  int which[] = {CTL_HW,HW_MODEL,0};
+  size_t size;
+  int i;
+  uv_cpu_info_t* cpu_info;
+
+  size = sizeof(model);
+  if (sysctl(which, 2, &model, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  which[1] = HW_NCPU;
+  size = sizeof(numcpus);
+  if (sysctl(which, 2, &numcpus, &size, NULL, 0))
+    return UV__ERR(errno);
+
+  *cpu_infos = (uv_cpu_info_t*)uv__malloc(numcpus * sizeof(**cpu_infos));
+  if (!(*cpu_infos))
+    return UV_ENOMEM;
+
+  *count = numcpus;
+
+  which[1] = HW_CPUSPEED;
+  size = sizeof(cpuspeed);
+  if (sysctl(which, 2, &cpuspeed, &size, NULL, 0)) {
+    uv__free(*cpu_infos);
+    return UV__ERR(errno);
+  }
+
+  size = sizeof(info);
+  which[0] = CTL_KERN;
+  which[1] = KERN_CPTIME2;
+  for (i = 0; i < numcpus; i++) {
+    which[2] = i;
+    size = sizeof(info);
+    if (sysctl(which, 3, &info, &size, NULL, 0)) {
+      uv__free(*cpu_infos);
+      return UV__ERR(errno);
+    }
+
+    cpu_info = &(*cpu_infos)[i];
+
+    cpu_info->cpu_times.user = (uint64_t)(info[CP_USER]) * multiplier;
+    cpu_info->cpu_times.nice = (uint64_t)(info[CP_NICE]) * multiplier;
+    cpu_info->cpu_times.sys = (uint64_t)(info[CP_SYS]) * multiplier;
+    cpu_info->cpu_times.idle = (uint64_t)(info[CP_IDLE]) * multiplier;
+    cpu_info->cpu_times.irq = (uint64_t)(info[CP_INTR]) * multiplier;
+
+    cpu_info->model = uv__strdup(model);
+    cpu_info->speed = cpuspeed;
+  }
+
+  return 0;
+}
+
+
+void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(cpu_infos[i].model);
+  }
+
+  uv__free(cpu_infos);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/pipe.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/pipe.cpp
new file mode 100644
index 0000000..aef5a3b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/pipe.cpp
@@ -0,0 +1,365 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <errno.h>
+#include <string.h>
+#include <sys/un.h>
+#include <unistd.h>
+#include <stdlib.h>
+
+
+int uv_pipe_init(uv_loop_t* loop, uv_pipe_t* handle, int ipc) {
+  uv__stream_init(loop, (uv_stream_t*)handle, UV_NAMED_PIPE);
+  handle->shutdown_req = NULL;
+  handle->connect_req = NULL;
+  handle->pipe_fname = NULL;
+  handle->ipc = ipc;
+  return 0;
+}
+
+
+int uv_pipe_bind(uv_pipe_t* handle, const char* name) {
+  struct sockaddr_un saddr;
+  const char* pipe_fname;
+  int sockfd;
+  int err;
+
+  pipe_fname = NULL;
+
+  /* Already bound? */
+  if (uv__stream_fd(handle) >= 0)
+    return UV_EINVAL;
+
+  /* Make a copy of the file name, it outlives this function's scope. */
+  pipe_fname = uv__strdup(name);
+  if (pipe_fname == NULL)
+    return UV_ENOMEM;
+
+  /* We've got a copy, don't touch the original any more. */
+  name = NULL;
+
+  err = uv__socket(AF_UNIX, SOCK_STREAM, 0);
+  if (err < 0)
+    goto err_socket;
+  sockfd = err;
+
+  memset(&saddr, 0, sizeof saddr);
+  strncpy(saddr.sun_path, pipe_fname, sizeof(saddr.sun_path) - 1);
+  saddr.sun_path[sizeof(saddr.sun_path) - 1] = '\0';
+  saddr.sun_family = AF_UNIX;
+
+  if (bind(sockfd, (struct sockaddr*)&saddr, sizeof saddr)) {
+    err = UV__ERR(errno);
+    /* Convert ENOENT to EACCES for compatibility with Windows. */
+    if (err == UV_ENOENT)
+      err = UV_EACCES;
+
+    uv__close(sockfd);
+    goto err_socket;
+  }
+
+  /* Success. */
+  handle->flags |= UV_HANDLE_BOUND;
+  handle->pipe_fname = pipe_fname; /* Is a strdup'ed copy. */
+  handle->io_watcher.fd = sockfd;
+  return 0;
+
+err_socket:
+  uv__free((void*)pipe_fname);
+  return err;
+}
+
+
+int uv_pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb) {
+  if (uv__stream_fd(handle) == -1)
+    return UV_EINVAL;
+
+#if defined(__MVS__)
+  /* On zOS, backlog=0 has undefined behaviour */
+  if (backlog == 0)
+    backlog = 1;
+  else if (backlog < 0)
+    backlog = SOMAXCONN;
+#endif
+
+  if (listen(uv__stream_fd(handle), backlog))
+    return UV__ERR(errno);
+
+  handle->connection_cb = cb;
+  handle->io_watcher.cb = uv__server_io;
+  uv__io_start(handle->loop, &handle->io_watcher, POLLIN);
+  return 0;
+}
+
+
+void uv__pipe_close(uv_pipe_t* handle) {
+  if (handle->pipe_fname) {
+    /*
+     * Unlink the file system entity before closing the file descriptor.
+     * Doing it the other way around introduces a race where our process
+     * unlinks a socket with the same name that's just been created by
+     * another thread or process.
+     */
+    unlink(handle->pipe_fname);
+    uv__free((void*)handle->pipe_fname);
+    handle->pipe_fname = NULL;
+  }
+
+  uv__stream_close((uv_stream_t*)handle);
+}
+
+
+int uv_pipe_open(uv_pipe_t* handle, uv_file fd) {
+  int err;
+
+  if (uv__fd_exists(handle->loop, fd))
+    return UV_EEXIST;
+
+  err = uv__nonblock(fd, 1);
+  if (err)
+    return err;
+
+#if defined(__APPLE__)
+  err = uv__stream_try_select((uv_stream_t*) handle, &fd);
+  if (err)
+    return err;
+#endif /* defined(__APPLE__) */
+
+  return uv__stream_open((uv_stream_t*)handle,
+                         fd,
+                         UV_STREAM_READABLE | UV_STREAM_WRITABLE);
+}
+
+
+void uv_pipe_connect(uv_connect_t* req,
+                    uv_pipe_t* handle,
+                    const char* name,
+                    uv_connect_cb cb) {
+  struct sockaddr_un saddr;
+  int new_sock;
+  int err;
+  int r;
+
+  new_sock = (uv__stream_fd(handle) == -1);
+
+  if (new_sock) {
+    err = uv__socket(AF_UNIX, SOCK_STREAM, 0);
+    if (err < 0)
+      goto out;
+    handle->io_watcher.fd = err;
+  }
+
+  memset(&saddr, 0, sizeof saddr);
+  strncpy(saddr.sun_path, name, sizeof(saddr.sun_path) - 1);
+  saddr.sun_path[sizeof(saddr.sun_path) - 1] = '\0';
+  saddr.sun_family = AF_UNIX;
+
+  do {
+    r = connect(uv__stream_fd(handle),
+                (struct sockaddr*)&saddr, sizeof saddr);
+  }
+  while (r == -1 && errno == EINTR);
+
+  if (r == -1 && errno != EINPROGRESS) {
+    err = UV__ERR(errno);
+#if defined(__CYGWIN__) || defined(__MSYS__)
+    /* EBADF is supposed to mean that the socket fd is bad, but
+       Cygwin reports EBADF instead of ENOTSOCK when the file is
+       not a socket.  We do not expect to see a bad fd here
+       (e.g. due to new_sock), so translate the error.  */
+    if (err == UV_EBADF)
+      err = UV_ENOTSOCK;
+#endif
+    goto out;
+  }
+
+  err = 0;
+  if (new_sock) {
+    err = uv__stream_open((uv_stream_t*)handle,
+                          uv__stream_fd(handle),
+                          UV_STREAM_READABLE | UV_STREAM_WRITABLE);
+  }
+
+  if (err == 0)
+    uv__io_start(handle->loop, &handle->io_watcher, POLLIN | POLLOUT);
+
+out:
+  handle->delayed_error = err;
+  handle->connect_req = req;
+
+  uv__req_init(handle->loop, req, UV_CONNECT);
+  req->handle = (uv_stream_t*)handle;
+  req->cb = cb;
+  QUEUE_INIT(&req->queue);
+
+  /* Force callback to run on next tick in case of error. */
+  if (err)
+    uv__io_feed(handle->loop, &handle->io_watcher);
+
+}
+
+
+typedef int (*uv__peersockfunc)(int, struct sockaddr*, socklen_t*);
+
+
+static int uv__pipe_getsockpeername(const uv_pipe_t* handle,
+                                    uv__peersockfunc func,
+                                    char* buffer,
+                                    size_t* size) {
+  struct sockaddr_un sa;
+  socklen_t addrlen;
+  int err;
+
+  addrlen = sizeof(sa);
+  memset(&sa, 0, addrlen);
+  err = func(uv__stream_fd(handle), (struct sockaddr*) &sa, &addrlen);
+  if (err < 0) {
+    *size = 0;
+    return UV__ERR(errno);
+  }
+
+#if defined(__linux__)
+  if (sa.sun_path[0] == 0)
+    /* Linux abstract namespace */
+    addrlen -= offsetof(struct sockaddr_un, sun_path);
+  else
+#endif
+    addrlen = strlen(sa.sun_path);
+
+
+  if (addrlen >= *size) {
+    *size = addrlen + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, sa.sun_path, addrlen);
+  *size = addrlen;
+
+  /* only null-terminate if it's not an abstract socket */
+  if (buffer[0] != '\0')
+    buffer[addrlen] = '\0';
+
+  return 0;
+}
+
+
+int uv_pipe_getsockname(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  return uv__pipe_getsockpeername(handle, getsockname, buffer, size);
+}
+
+
+int uv_pipe_getpeername(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  return uv__pipe_getsockpeername(handle, getpeername, buffer, size);
+}
+
+
+void uv_pipe_pending_instances(uv_pipe_t* handle, int count) {
+}
+
+
+int uv_pipe_pending_count(uv_pipe_t* handle) {
+  uv__stream_queued_fds_t* queued_fds;
+
+  if (!handle->ipc)
+    return 0;
+
+  if (handle->accepted_fd == -1)
+    return 0;
+
+  if (handle->queued_fds == NULL)
+    return 1;
+
+  queued_fds = (uv__stream_queued_fds_t*)(handle->queued_fds);
+  return queued_fds->offset + 1;
+}
+
+
+uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle) {
+  if (!handle->ipc)
+    return UV_UNKNOWN_HANDLE;
+
+  if (handle->accepted_fd == -1)
+    return UV_UNKNOWN_HANDLE;
+  else
+    return uv__handle_type(handle->accepted_fd);
+}
+
+
+int uv_pipe_chmod(uv_pipe_t* handle, int mode) {
+  unsigned desired_mode;
+  struct stat pipe_stat;
+  char* name_buffer;
+  size_t name_len;
+  int r;
+
+  if (handle == NULL || uv__stream_fd(handle) == -1)
+    return UV_EBADF;
+
+  if (mode != UV_READABLE &&
+      mode != UV_WRITABLE &&
+      mode != (UV_WRITABLE | UV_READABLE))
+    return UV_EINVAL;
+
+  /* Unfortunately fchmod does not work on all platforms, we will use chmod. */
+  name_len = 0;
+  r = uv_pipe_getsockname(handle, NULL, &name_len);
+  if (r != UV_ENOBUFS)
+    return r;
+
+  name_buffer = (char*)uv__malloc(name_len);
+  if (name_buffer == NULL)
+    return UV_ENOMEM;
+
+  r = uv_pipe_getsockname(handle, name_buffer, &name_len);
+  if (r != 0) {
+    uv__free(name_buffer);
+    return r;
+  }
+
+  /* stat must be used as fstat has a bug on Darwin */
+  if (stat(name_buffer, &pipe_stat) == -1) {
+    uv__free(name_buffer);
+    return -errno;
+  }
+
+  desired_mode = 0;
+  if (mode & UV_READABLE)
+    desired_mode |= S_IRUSR | S_IRGRP | S_IROTH;
+  if (mode & UV_WRITABLE)
+    desired_mode |= S_IWUSR | S_IWGRP | S_IWOTH;
+
+  /* Exit early if pipe already has desired mode. */
+  if ((pipe_stat.st_mode & desired_mode) == desired_mode) {
+    uv__free(name_buffer);
+    return 0;
+  }
+
+  pipe_stat.st_mode |= desired_mode;
+
+  r = chmod(name_buffer, pipe_stat.st_mode);
+  uv__free(name_buffer);
+
+  return r != -1 ? 0 : UV__ERR(errno);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/poll.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/poll.cpp
new file mode 100644
index 0000000..d578611
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/poll.cpp
@@ -0,0 +1,151 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <unistd.h>
+#include <assert.h>
+#include <errno.h>
+
+
+static void uv__poll_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  uv_poll_t* handle;
+  int pevents;
+
+  handle = container_of(w, uv_poll_t, io_watcher);
+
+  /*
+   * As documented in the kernel source fs/kernfs/file.c #780
+   * poll will return POLLERR|POLLPRI in case of sysfs
+   * polling. This does not happen in case of out-of-band
+   * TCP messages.
+   *
+   * The above is the case on (at least) FreeBSD and Linux.
+   *
+   * So to properly determine a POLLPRI or a POLLERR we need
+   * to check for both.
+   */
+  if ((events & POLLERR) && !(events & UV__POLLPRI)) {
+    uv__io_stop(loop, w, POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
+    uv__handle_stop(handle);
+    handle->poll_cb(handle, UV_EBADF, 0);
+    return;
+  }
+
+  pevents = 0;
+  if (events & POLLIN)
+    pevents |= UV_READABLE;
+  if (events & UV__POLLPRI)
+    pevents |= UV_PRIORITIZED;
+  if (events & POLLOUT)
+    pevents |= UV_WRITABLE;
+  if (events & UV__POLLRDHUP)
+    pevents |= UV_DISCONNECT;
+
+  handle->poll_cb(handle, 0, pevents);
+}
+
+
+int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd) {
+  int err;
+
+  if (uv__fd_exists(loop, fd))
+    return UV_EEXIST;
+
+  err = uv__io_check_fd(loop, fd);
+  if (err)
+    return err;
+
+  /* If ioctl(FIONBIO) reports ENOTTY, try fcntl(F_GETFL) + fcntl(F_SETFL).
+   * Workaround for e.g. kqueue fds not supporting ioctls.
+   */
+  err = uv__nonblock(fd, 1);
+#ifdef UV__NONBLOCK_IS_IOCTL
+  if (err == UV_ENOTTY)
+    err = uv__nonblock_fcntl(fd, 1);
+#endif
+
+  if (err)
+    return err;
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_POLL);
+  uv__io_init(&handle->io_watcher, uv__poll_io, fd);
+  handle->poll_cb = NULL;
+  return 0;
+}
+
+
+int uv_poll_init_socket(uv_loop_t* loop, uv_poll_t* handle,
+    uv_os_sock_t socket) {
+  return uv_poll_init(loop, handle, socket);
+}
+
+
+static void uv__poll_stop(uv_poll_t* handle) {
+  uv__io_stop(handle->loop,
+              &handle->io_watcher,
+              POLLIN | POLLOUT | UV__POLLRDHUP | UV__POLLPRI);
+  uv__handle_stop(handle);
+  uv__platform_invalidate_fd(handle->loop, handle->io_watcher.fd);
+}
+
+
+int uv_poll_stop(uv_poll_t* handle) {
+  assert(!uv__is_closing(handle));
+  uv__poll_stop(handle);
+  return 0;
+}
+
+
+int uv_poll_start(uv_poll_t* handle, int pevents, uv_poll_cb poll_cb) {
+  int events;
+
+  assert((pevents & ~(UV_READABLE | UV_WRITABLE | UV_DISCONNECT |
+                      UV_PRIORITIZED)) == 0);
+  assert(!uv__is_closing(handle));
+
+  uv__poll_stop(handle);
+
+  if (pevents == 0)
+    return 0;
+
+  events = 0;
+  if (pevents & UV_READABLE)
+    events |= POLLIN;
+  if (pevents & UV_PRIORITIZED)
+    events |= UV__POLLPRI;
+  if (pevents & UV_WRITABLE)
+    events |= POLLOUT;
+  if (pevents & UV_DISCONNECT)
+    events |= UV__POLLRDHUP;
+
+  uv__io_start(handle->loop, &handle->io_watcher, events);
+  uv__handle_start(handle);
+  handle->poll_cb = poll_cb;
+
+  return 0;
+}
+
+
+void uv__poll_close(uv_poll_t* handle) {
+  uv__poll_stop(handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/posix-hrtime.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/posix-hrtime.cpp
new file mode 100644
index 0000000..323dfc2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/posix-hrtime.cpp
@@ -0,0 +1,35 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdint.h>
+#include <time.h>
+
+#undef NANOSEC
+#define NANOSEC ((uint64_t) 1e9)
+
+uint64_t uv__hrtime(uv_clocktype_t type) {
+  struct timespec ts;
+  clock_gettime(CLOCK_MONOTONIC, &ts);
+  return (((uint64_t) ts.tv_sec) * NANOSEC + ts.tv_nsec);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/posix-poll.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/posix-poll.cpp
new file mode 100644
index 0000000..0f7dbfa
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/posix-poll.cpp
@@ -0,0 +1,334 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+/* POSIX defines poll() as a portable way to wait on file descriptors.
+ * Here we maintain a dynamically sized array of file descriptors and
+ * events to pass as the first argument to poll().
+ */
+
+#include <assert.h>
+#include <stddef.h>
+#include <stdint.h>
+#include <errno.h>
+#include <unistd.h>
+
+int uv__platform_loop_init(uv_loop_t* loop) {
+  loop->poll_fds = NULL;
+  loop->poll_fds_used = 0;
+  loop->poll_fds_size = 0;
+  loop->poll_fds_iterating = 0;
+  return 0;
+}
+
+void uv__platform_loop_delete(uv_loop_t* loop) {
+  uv__free(loop->poll_fds);
+  loop->poll_fds = NULL;
+}
+
+int uv__io_fork(uv_loop_t* loop) {
+  uv__platform_loop_delete(loop);
+  return uv__platform_loop_init(loop);
+}
+
+/* Allocate or dynamically resize our poll fds array.  */
+static void uv__pollfds_maybe_resize(uv_loop_t* loop) {
+  size_t i;
+  size_t n;
+  struct pollfd* p;
+
+  if (loop->poll_fds_used < loop->poll_fds_size)
+    return;
+
+  n = loop->poll_fds_size ? loop->poll_fds_size * 2 : 64;
+  p = (struct pollfd*)uv__realloc(loop->poll_fds, n * sizeof(*loop->poll_fds));
+  if (p == NULL)
+    abort();
+
+  loop->poll_fds = p;
+  for (i = loop->poll_fds_size; i < n; i++) {
+    loop->poll_fds[i].fd = -1;
+    loop->poll_fds[i].events = 0;
+    loop->poll_fds[i].revents = 0;
+  }
+  loop->poll_fds_size = n;
+}
+
+/* Primitive swap operation on poll fds array elements.  */
+static void uv__pollfds_swap(uv_loop_t* loop, size_t l, size_t r) {
+  struct pollfd pfd;
+  pfd = loop->poll_fds[l];
+  loop->poll_fds[l] = loop->poll_fds[r];
+  loop->poll_fds[r] = pfd;
+}
+
+/* Add a watcher's fd to our poll fds array with its pending events.  */
+static void uv__pollfds_add(uv_loop_t* loop, uv__io_t* w) {
+  size_t i;
+  struct pollfd* pe;
+
+  /* If the fd is already in the set just update its events.  */
+  assert(!loop->poll_fds_iterating);
+  for (i = 0; i < loop->poll_fds_used; ++i) {
+    if (loop->poll_fds[i].fd == w->fd) {
+      loop->poll_fds[i].events = w->pevents;
+      return;
+    }
+  }
+
+  /* Otherwise, allocate a new slot in the set for the fd.  */
+  uv__pollfds_maybe_resize(loop);
+  pe = &loop->poll_fds[loop->poll_fds_used++];
+  pe->fd = w->fd;
+  pe->events = w->pevents;
+}
+
+/* Remove a watcher's fd from our poll fds array.  */
+static void uv__pollfds_del(uv_loop_t* loop, int fd) {
+  size_t i;
+  assert(!loop->poll_fds_iterating);
+  for (i = 0; i < loop->poll_fds_used;) {
+    if (loop->poll_fds[i].fd == fd) {
+      /* swap to last position and remove */
+      --loop->poll_fds_used;
+      uv__pollfds_swap(loop, i, loop->poll_fds_used);
+      loop->poll_fds[loop->poll_fds_used].fd = -1;
+      loop->poll_fds[loop->poll_fds_used].events = 0;
+      loop->poll_fds[loop->poll_fds_used].revents = 0;
+      /* This method is called with an fd of -1 to purge the invalidated fds,
+       * so we may possibly have multiples to remove.
+       */
+      if (-1 != fd)
+        return;
+    } else {
+      /* We must only increment the loop counter when the fds do not match.
+       * Otherwise, when we are purging an invalidated fd, the value just
+       * swapped here from the previous end of the array will be skipped.
+       */
+       ++i;
+    }
+  }
+}
+
+
+void uv__io_poll(uv_loop_t* loop, int timeout) {
+  sigset_t* pset;
+  sigset_t set;
+  uint64_t time_base;
+  uint64_t time_diff;
+  QUEUE* q;
+  uv__io_t* w;
+  size_t i;
+  unsigned int nevents;
+  int nfds;
+  int have_signals;
+  struct pollfd* pe;
+  int fd;
+
+  if (loop->nfds == 0) {
+    assert(QUEUE_EMPTY(&loop->watcher_queue));
+    return;
+  }
+
+  /* Take queued watchers and add their fds to our poll fds array.  */
+  while (!QUEUE_EMPTY(&loop->watcher_queue)) {
+    q = QUEUE_HEAD(&loop->watcher_queue);
+    QUEUE_REMOVE(q);
+    QUEUE_INIT(q);
+
+    w = QUEUE_DATA(q, uv__io_t, watcher_queue);
+    assert(w->pevents != 0);
+    assert(w->fd >= 0);
+    assert(w->fd < (int) loop->nwatchers);
+
+    uv__pollfds_add(loop, w);
+
+    w->events = w->pevents;
+  }
+
+  /* Prepare a set of signals to block around poll(), if any.  */
+  pset = NULL;
+  if (loop->flags & UV_LOOP_BLOCK_SIGPROF) {
+    pset = &set;
+    sigemptyset(pset);
+    sigaddset(pset, SIGPROF);
+  }
+
+  assert(timeout >= -1);
+  time_base = loop->time;
+
+  /* Loop calls to poll() and processing of results.  If we get some
+   * results from poll() but they turn out not to be interesting to
+   * our caller then we need to loop around and poll() again.
+   */
+  for (;;) {
+    if (pset != NULL)
+      if (pthread_sigmask(SIG_BLOCK, pset, NULL))
+        abort();
+    nfds = poll(loop->poll_fds, (nfds_t)loop->poll_fds_used, timeout);
+    if (pset != NULL)
+      if (pthread_sigmask(SIG_UNBLOCK, pset, NULL))
+        abort();
+
+    /* Update loop->time unconditionally. It's tempting to skip the update when
+     * timeout == 0 (i.e. non-blocking poll) but there is no guarantee that the
+     * operating system didn't reschedule our process while in the syscall.
+     */
+    SAVE_ERRNO(uv__update_time(loop));
+
+    if (nfds == 0) {
+      assert(timeout != -1);
+      return;
+    }
+
+    if (nfds == -1) {
+      if (errno != EINTR)
+        abort();
+
+      if (timeout == -1)
+        continue;
+
+      if (timeout == 0)
+        return;
+
+      /* Interrupted by a signal. Update timeout and poll again. */
+      goto update_timeout;
+    }
+
+    /* Tell uv__platform_invalidate_fd not to manipulate our array
+     * while we are iterating over it.
+     */
+    loop->poll_fds_iterating = 1;
+
+    /* Initialize a count of events that we care about.  */
+    nevents = 0;
+    have_signals = 0;
+
+    /* Loop over the entire poll fds array looking for returned events.  */
+    for (i = 0; i < loop->poll_fds_used; i++) {
+      pe = loop->poll_fds + i;
+      fd = pe->fd;
+
+      /* Skip invalidated events, see uv__platform_invalidate_fd.  */
+      if (fd == -1)
+        continue;
+
+      assert(fd >= 0);
+      assert((unsigned) fd < loop->nwatchers);
+
+      w = loop->watchers[fd];
+
+      if (w == NULL) {
+        /* File descriptor that we've stopped watching, ignore.  */
+        uv__platform_invalidate_fd(loop, fd);
+        continue;
+      }
+
+      /* Filter out events that user has not requested us to watch
+       * (e.g. POLLNVAL).
+       */
+      pe->revents &= w->pevents | POLLERR | POLLHUP;
+
+      if (pe->revents != 0) {
+        /* Run signal watchers last.  */
+        if (w == &loop->signal_io_watcher) {
+          have_signals = 1;
+        } else {
+          w->cb(loop, w, pe->revents);
+        }
+
+        nevents++;
+      }
+    }
+
+    if (have_signals != 0)
+      loop->signal_io_watcher.cb(loop, &loop->signal_io_watcher, POLLIN);
+
+    loop->poll_fds_iterating = 0;
+
+    /* Purge invalidated fds from our poll fds array.  */
+    uv__pollfds_del(loop, -1);
+
+    if (have_signals != 0)
+      return;  /* Event loop should cycle now so don't poll again. */
+
+    if (nevents != 0)
+      return;
+
+    if (timeout == 0)
+      return;
+
+    if (timeout == -1)
+      continue;
+
+update_timeout:
+    assert(timeout > 0);
+
+    time_diff = loop->time - time_base;
+    if (time_diff >= (uint64_t) timeout)
+      return;
+
+    timeout -= time_diff;
+  }
+}
+
+/* Remove the given fd from our poll fds array because no one
+ * is interested in its events anymore.
+ */
+void uv__platform_invalidate_fd(uv_loop_t* loop, int fd) {
+  size_t i;
+
+  if (loop->poll_fds_iterating) {
+    /* uv__io_poll is currently iterating.  Just invalidate fd.  */
+    for (i = 0; i < loop->poll_fds_used; i++)
+      if (loop->poll_fds[i].fd == fd) {
+        loop->poll_fds[i].fd = -1;
+        loop->poll_fds[i].events = 0;
+        loop->poll_fds[i].revents = 0;
+      }
+  } else {
+    /* uv__io_poll is not iterating.  Delete fd from the set.  */
+    uv__pollfds_del(loop, fd);
+  }
+}
+
+/* Check whether the given fd is supported by poll().  */
+int uv__io_check_fd(uv_loop_t* loop, int fd) {
+  struct pollfd p[1];
+  int rv;
+
+  p[0].fd = fd;
+  p[0].events = POLLIN;
+
+  do
+    rv = poll(p, 1, 0);
+  while (rv == -1 && (errno == EINTR || errno == EAGAIN));
+
+  if (rv == -1)
+    return UV__ERR(errno);
+
+  if (p[0].revents & POLLNVAL)
+    return UV_EINVAL;
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/process.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/process.cpp
new file mode 100644
index 0000000..ddd9d43
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/process.cpp
@@ -0,0 +1,596 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <sys/types.h>
+#include <sys/wait.h>
+#include <unistd.h>
+#include <fcntl.h>
+#include <poll.h>
+
+#if defined(__APPLE__) && !TARGET_OS_IPHONE
+# include <crt_externs.h>
+# define environ (*_NSGetEnviron())
+#else
+extern char **environ;
+#endif
+
+#if defined(__linux__) || defined(__GLIBC__)
+# include <grp.h>
+#endif
+
+
+static void uv__chld(uv_signal_t* handle, int signum) {
+  uv_process_t* process;
+  uv_loop_t* loop;
+  int exit_status;
+  int term_signal;
+  int status;
+  pid_t pid;
+  QUEUE pending;
+  QUEUE* q;
+  QUEUE* h;
+
+  assert(signum == SIGCHLD);
+
+  QUEUE_INIT(&pending);
+  loop = handle->loop;
+
+  h = &loop->process_handles;
+  q = QUEUE_HEAD(h);
+  while (q != h) {
+    process = QUEUE_DATA(q, uv_process_t, queue);
+    q = QUEUE_NEXT(q);
+
+    do
+      pid = waitpid(process->pid, &status, WNOHANG);
+    while (pid == -1 && errno == EINTR);
+
+    if (pid == 0)
+      continue;
+
+    if (pid == -1) {
+      if (errno != ECHILD)
+        abort();
+      continue;
+    }
+
+    process->status = status;
+    QUEUE_REMOVE(&process->queue);
+    QUEUE_INSERT_TAIL(&pending, &process->queue);
+  }
+
+  h = &pending;
+  q = QUEUE_HEAD(h);
+  while (q != h) {
+    process = QUEUE_DATA(q, uv_process_t, queue);
+    q = QUEUE_NEXT(q);
+
+    QUEUE_REMOVE(&process->queue);
+    QUEUE_INIT(&process->queue);
+    uv__handle_stop(process);
+
+    if (process->exit_cb == NULL)
+      continue;
+
+    exit_status = 0;
+    if (WIFEXITED(process->status))
+      exit_status = WEXITSTATUS(process->status);
+
+    term_signal = 0;
+    if (WIFSIGNALED(process->status))
+      term_signal = WTERMSIG(process->status);
+
+    process->exit_cb(process, exit_status, term_signal);
+  }
+  assert(QUEUE_EMPTY(&pending));
+}
+
+
+int uv__make_socketpair(int fds[2], int flags) {
+#if defined(__linux__)
+  static int no_cloexec;
+
+  if (no_cloexec)
+    goto skip;
+
+  if (socketpair(AF_UNIX, SOCK_STREAM | UV__SOCK_CLOEXEC | flags, 0, fds) == 0)
+    return 0;
+
+  /* Retry on EINVAL, it means SOCK_CLOEXEC is not supported.
+   * Anything else is a genuine error.
+   */
+  if (errno != EINVAL)
+    return UV__ERR(errno);
+
+  no_cloexec = 1;
+
+skip:
+#endif
+
+  if (socketpair(AF_UNIX, SOCK_STREAM, 0, fds))
+    return UV__ERR(errno);
+
+  uv__cloexec(fds[0], 1);
+  uv__cloexec(fds[1], 1);
+
+  if (flags & UV__F_NONBLOCK) {
+    uv__nonblock(fds[0], 1);
+    uv__nonblock(fds[1], 1);
+  }
+
+  return 0;
+}
+
+
+int uv__make_pipe(int fds[2], int flags) {
+#if defined(__linux__)
+  static int no_pipe2;
+
+  if (no_pipe2)
+    goto skip;
+
+  if (uv__pipe2(fds, flags | UV__O_CLOEXEC) == 0)
+    return 0;
+
+  if (errno != ENOSYS)
+    return UV__ERR(errno);
+
+  no_pipe2 = 1;
+
+skip:
+#endif
+
+  if (pipe(fds))
+    return UV__ERR(errno);
+
+  uv__cloexec(fds[0], 1);
+  uv__cloexec(fds[1], 1);
+
+  if (flags & UV__F_NONBLOCK) {
+    uv__nonblock(fds[0], 1);
+    uv__nonblock(fds[1], 1);
+  }
+
+  return 0;
+}
+
+
+/*
+ * Used for initializing stdio streams like options.stdin_stream. Returns
+ * zero on success. See also the cleanup section in uv_spawn().
+ */
+static int uv__process_init_stdio(uv_stdio_container_t* container, int fds[2]) {
+  int mask;
+  int fd;
+
+  mask = UV_IGNORE | UV_CREATE_PIPE | UV_INHERIT_FD | UV_INHERIT_STREAM;
+
+  switch (container->flags & mask) {
+  case UV_IGNORE:
+    return 0;
+
+  case UV_CREATE_PIPE:
+    assert(container->data.stream != NULL);
+    if (container->data.stream->type != UV_NAMED_PIPE)
+      return UV_EINVAL;
+    else
+      return uv__make_socketpair(fds, 0);
+
+  case UV_INHERIT_FD:
+  case UV_INHERIT_STREAM:
+    if (container->flags & UV_INHERIT_FD)
+      fd = container->data.fd;
+    else
+      fd = uv__stream_fd(container->data.stream);
+
+    if (fd == -1)
+      return UV_EINVAL;
+
+    fds[1] = fd;
+    return 0;
+
+  default:
+    assert(0 && "Unexpected flags");
+    return UV_EINVAL;
+  }
+}
+
+
+static int uv__process_open_stream(uv_stdio_container_t* container,
+                                   int pipefds[2]) {
+  int flags;
+  int err;
+
+  if (!(container->flags & UV_CREATE_PIPE) || pipefds[0] < 0)
+    return 0;
+
+  err = uv__close(pipefds[1]);
+  if (err != 0)
+    abort();
+
+  pipefds[1] = -1;
+  uv__nonblock(pipefds[0], 1);
+
+  flags = 0;
+  if (container->flags & UV_WRITABLE_PIPE)
+    flags |= UV_STREAM_READABLE;
+  if (container->flags & UV_READABLE_PIPE)
+    flags |= UV_STREAM_WRITABLE;
+
+  return uv__stream_open(container->data.stream, pipefds[0], flags);
+}
+
+
+static void uv__process_close_stream(uv_stdio_container_t* container) {
+  if (!(container->flags & UV_CREATE_PIPE)) return;
+  uv__stream_close((uv_stream_t*)container->data.stream);
+}
+
+
+static void uv__write_int(int fd, int val) {
+  ssize_t n;
+
+  do
+    n = write(fd, &val, sizeof(val));
+  while (n == -1 && errno == EINTR);
+
+  if (n == -1 && errno == EPIPE)
+    return; /* parent process has quit */
+
+  assert(n == sizeof(val));
+}
+
+
+#if !(defined(__APPLE__) && (TARGET_OS_TV || TARGET_OS_WATCH))
+/* execvp is marked __WATCHOS_PROHIBITED __TVOS_PROHIBITED, so must be
+ * avoided. Since this isn't called on those targets, the function
+ * doesn't even need to be defined for them.
+ */
+static void uv__process_child_init(const uv_process_options_t* options,
+                                   int stdio_count,
+                                   int (*pipes)[2],
+                                   int error_fd) {
+  sigset_t set;
+  int close_fd;
+  int use_fd;
+  int err;
+  int fd;
+  int n;
+
+  if (options->flags & UV_PROCESS_DETACHED)
+    setsid();
+
+  /* First duplicate low numbered fds, since it's not safe to duplicate them,
+   * they could get replaced. Example: swapping stdout and stderr; without
+   * this fd 2 (stderr) would be duplicated into fd 1, thus making both
+   * stdout and stderr go to the same fd, which was not the intention. */
+  for (fd = 0; fd < stdio_count; fd++) {
+    use_fd = pipes[fd][1];
+    if (use_fd < 0 || use_fd >= fd)
+      continue;
+    pipes[fd][1] = fcntl(use_fd, F_DUPFD, stdio_count);
+    if (pipes[fd][1] == -1) {
+      uv__write_int(error_fd, UV__ERR(errno));
+      _exit(127);
+    }
+  }
+
+  for (fd = 0; fd < stdio_count; fd++) {
+    close_fd = pipes[fd][0];
+    use_fd = pipes[fd][1];
+
+    if (use_fd < 0) {
+      if (fd >= 3)
+        continue;
+      else {
+        /* redirect stdin, stdout and stderr to /dev/null even if UV_IGNORE is
+         * set
+         */
+        use_fd = open("/dev/null", fd == 0 ? O_RDONLY : O_RDWR);
+        close_fd = use_fd;
+
+        if (use_fd == -1) {
+          uv__write_int(error_fd, UV__ERR(errno));
+          _exit(127);
+        }
+      }
+    }
+
+    if (fd == use_fd)
+      uv__cloexec_fcntl(use_fd, 0);
+    else
+      fd = dup2(use_fd, fd);
+
+    if (fd == -1) {
+      uv__write_int(error_fd, UV__ERR(errno));
+      _exit(127);
+    }
+
+    if (fd <= 2)
+      uv__nonblock_fcntl(fd, 0);
+
+    if (close_fd >= stdio_count)
+      uv__close(close_fd);
+  }
+
+  for (fd = 0; fd < stdio_count; fd++) {
+    use_fd = pipes[fd][1];
+
+    if (use_fd >= stdio_count)
+      uv__close(use_fd);
+  }
+
+  if (options->cwd != NULL && chdir(options->cwd)) {
+    uv__write_int(error_fd, UV__ERR(errno));
+    _exit(127);
+  }
+
+  if (options->flags & (UV_PROCESS_SETUID | UV_PROCESS_SETGID)) {
+    /* When dropping privileges from root, the `setgroups` call will
+     * remove any extraneous groups. If we don't call this, then
+     * even though our uid has dropped, we may still have groups
+     * that enable us to do super-user things. This will fail if we
+     * aren't root, so don't bother checking the return value, this
+     * is just done as an optimistic privilege dropping function.
+     */
+    SAVE_ERRNO(setgroups(0, NULL));
+  }
+
+  if ((options->flags & UV_PROCESS_SETGID) && setgid(options->gid)) {
+    uv__write_int(error_fd, UV__ERR(errno));
+    _exit(127);
+  }
+
+  if ((options->flags & UV_PROCESS_SETUID) && setuid(options->uid)) {
+    uv__write_int(error_fd, UV__ERR(errno));
+    _exit(127);
+  }
+
+  if (options->env != NULL) {
+    environ = options->env;
+  }
+
+  /* Reset signal disposition.  Use a hard-coded limit because NSIG
+   * is not fixed on Linux: it's either 32, 34 or 64, depending on
+   * whether RT signals are enabled.  We are not allowed to touch
+   * RT signal handlers, glibc uses them internally.
+   */
+  for (n = 1; n < 32; n += 1) {
+    if (n == SIGKILL || n == SIGSTOP)
+      continue;  /* Can't be changed. */
+
+    if (SIG_ERR != signal(n, SIG_DFL))
+      continue;
+
+    uv__write_int(error_fd, UV__ERR(errno));
+    _exit(127);
+  }
+
+  /* Reset signal mask. */
+  sigemptyset(&set);
+  err = pthread_sigmask(SIG_SETMASK, &set, NULL);
+
+  if (err != 0) {
+    uv__write_int(error_fd, UV__ERR(err));
+    _exit(127);
+  }
+
+  execvp(options->file, options->args);
+  uv__write_int(error_fd, UV__ERR(errno));
+  _exit(127);
+}
+#endif
+
+
+int uv_spawn(uv_loop_t* loop,
+             uv_process_t* process,
+             const uv_process_options_t* options) {
+#if defined(__APPLE__) && (TARGET_OS_TV || TARGET_OS_WATCH)
+  /* fork is marked __WATCHOS_PROHIBITED __TVOS_PROHIBITED. */
+  return UV_ENOSYS;
+#else
+  int signal_pipe[2] = { -1, -1 };
+  int pipes_storage[8][2];
+  int (*pipes)[2];
+  int stdio_count;
+  ssize_t r;
+  pid_t pid;
+  int err;
+  int exec_errorno;
+  int i;
+  int status;
+
+  assert(options->file != NULL);
+  assert(!(options->flags & ~(UV_PROCESS_DETACHED |
+                              UV_PROCESS_SETGID |
+                              UV_PROCESS_SETUID |
+                              UV_PROCESS_WINDOWS_HIDE |
+                              UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS)));
+
+  uv__handle_init(loop, (uv_handle_t*)process, UV_PROCESS);
+  QUEUE_INIT(&process->queue);
+
+  stdio_count = options->stdio_count;
+  if (stdio_count < 3)
+    stdio_count = 3;
+
+  err = UV_ENOMEM;
+  pipes = pipes_storage;
+  if (stdio_count > (int) ARRAY_SIZE(pipes_storage))
+    pipes = (int (*)[2])uv__malloc(stdio_count * sizeof(*pipes));
+
+  if (pipes == NULL)
+    goto error;
+
+  for (i = 0; i < stdio_count; i++) {
+    pipes[i][0] = -1;
+    pipes[i][1] = -1;
+  }
+
+  for (i = 0; i < options->stdio_count; i++) {
+    err = uv__process_init_stdio(options->stdio + i, pipes[i]);
+    if (err)
+      goto error;
+  }
+
+  /* This pipe is used by the parent to wait until
+   * the child has called `execve()`. We need this
+   * to avoid the following race condition:
+   *
+   *    if ((pid = fork()) > 0) {
+   *      kill(pid, SIGTERM);
+   *    }
+   *    else if (pid == 0) {
+   *      execve("/bin/cat", argp, envp);
+   *    }
+   *
+   * The parent sends a signal immediately after forking.
+   * Since the child may not have called `execve()` yet,
+   * there is no telling what process receives the signal,
+   * our fork or /bin/cat.
+   *
+   * To avoid ambiguity, we create a pipe with both ends
+   * marked close-on-exec. Then, after the call to `fork()`,
+   * the parent polls the read end until it EOFs or errors with EPIPE.
+   */
+  err = uv__make_pipe(signal_pipe, 0);
+  if (err)
+    goto error;
+
+  uv_signal_start(&loop->child_watcher, uv__chld, SIGCHLD);
+
+  /* Acquire write lock to prevent opening new fds in worker threads */
+  uv_rwlock_wrlock(&loop->cloexec_lock);
+  pid = fork();
+
+  if (pid == -1) {
+    err = UV__ERR(errno);
+    uv_rwlock_wrunlock(&loop->cloexec_lock);
+    uv__close(signal_pipe[0]);
+    uv__close(signal_pipe[1]);
+    goto error;
+  }
+
+  if (pid == 0) {
+    uv__process_child_init(options, stdio_count, pipes, signal_pipe[1]);
+    abort();
+  }
+
+  /* Release lock in parent process */
+  uv_rwlock_wrunlock(&loop->cloexec_lock);
+  uv__close(signal_pipe[1]);
+
+  process->status = 0;
+  exec_errorno = 0;
+  do
+    r = read(signal_pipe[0], &exec_errorno, sizeof(exec_errorno));
+  while (r == -1 && errno == EINTR);
+
+  if (r == 0)
+    ; /* okay, EOF */
+  else if (r == sizeof(exec_errorno)) {
+    do
+      err = waitpid(pid, &status, 0); /* okay, read errorno */
+    while (err == -1 && errno == EINTR);
+    assert(err == pid);
+  } else if (r == -1 && errno == EPIPE) {
+    do
+      err = waitpid(pid, &status, 0); /* okay, got EPIPE */
+    while (err == -1 && errno == EINTR);
+    assert(err == pid);
+  } else
+    abort();
+
+  uv__close_nocheckstdio(signal_pipe[0]);
+
+  for (i = 0; i < options->stdio_count; i++) {
+    err = uv__process_open_stream(options->stdio + i, pipes[i]);
+    if (err == 0)
+      continue;
+
+    while (i--)
+      uv__process_close_stream(options->stdio + i);
+
+    goto error;
+  }
+
+  /* Only activate this handle if exec() happened successfully */
+  if (exec_errorno == 0) {
+    QUEUE_INSERT_TAIL(&loop->process_handles, &process->queue);
+    uv__handle_start(process);
+  }
+
+  process->pid = pid;
+  process->exit_cb = options->exit_cb;
+
+  if (pipes != pipes_storage)
+    uv__free(pipes);
+
+  return exec_errorno;
+
+error:
+  if (pipes != NULL) {
+    for (i = 0; i < stdio_count; i++) {
+      if (i < options->stdio_count)
+        if (options->stdio[i].flags & (UV_INHERIT_FD | UV_INHERIT_STREAM))
+          continue;
+      if (pipes[i][0] != -1)
+        uv__close_nocheckstdio(pipes[i][0]);
+      if (pipes[i][1] != -1)
+        uv__close_nocheckstdio(pipes[i][1]);
+    }
+
+    if (pipes != pipes_storage)
+      uv__free(pipes);
+  }
+
+  return err;
+#endif
+}
+
+
+int uv_process_kill(uv_process_t* process, int signum) {
+  return uv_kill(process->pid, signum);
+}
+
+
+int uv_kill(int pid, int signum) {
+  if (kill(pid, signum))
+    return UV__ERR(errno);
+  else
+    return 0;
+}
+
+
+void uv__process_close(uv_process_t* handle) {
+  QUEUE_REMOVE(&handle->queue);
+  uv__handle_stop(handle);
+  if (QUEUE_EMPTY(&handle->loop->process_handles))
+    uv_signal_stop(&handle->loop->child_watcher);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/procfs-exepath.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/procfs-exepath.cpp
new file mode 100644
index 0000000..00dc021
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/procfs-exepath.cpp
@@ -0,0 +1,45 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stddef.h>
+#include <unistd.h>
+
+int uv_exepath(char* buffer, size_t* size) {
+  ssize_t n;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  n = *size - 1;
+  if (n > 0)
+    n = readlink("/proc/self/exe", buffer, n);
+
+  if (n == -1)
+    return UV__ERR(errno);
+
+  buffer[n] = '\0';
+  *size = n;
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/proctitle.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/proctitle.cpp
new file mode 100644
index 0000000..25bec48
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/proctitle.cpp
@@ -0,0 +1,132 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdlib.h>
+#include <string.h>
+
+extern void uv__set_process_title(const char* title);
+
+static uv_mutex_t process_title_mutex;
+static uv_once_t process_title_mutex_once = UV_ONCE_INIT;
+static void* args_mem;
+
+static struct {
+  char* str;
+  size_t len;
+} process_title;
+
+
+static void init_process_title_mutex_once(void) {
+  uv_mutex_init(&process_title_mutex);
+}
+
+
+char** uv_setup_args(int argc, char** argv) {
+  char** new_argv;
+  size_t size;
+  char* s;
+  int i;
+
+  if (argc <= 0)
+    return argv;
+
+  /* Calculate how much memory we need for the argv strings. */
+  size = 0;
+  for (i = 0; i < argc; i++)
+    size += strlen(argv[i]) + 1;
+
+#if defined(__MVS__)
+  /* argv is not adjacent. So just use argv[0] */
+  process_title.str = argv[0];
+  process_title.len = strlen(argv[0]);
+#else
+  process_title.str = argv[0];
+  process_title.len = argv[argc - 1] + strlen(argv[argc - 1]) - argv[0];
+  assert(process_title.len + 1 == size);  /* argv memory should be adjacent. */
+#endif
+
+  /* Add space for the argv pointers. */
+  size += (argc + 1) * sizeof(char*);
+
+  new_argv = (char**)uv__malloc(size);
+  if (new_argv == NULL)
+    return argv;
+  args_mem = new_argv;
+
+  /* Copy over the strings and set up the pointer table. */
+  s = (char*) &new_argv[argc + 1];
+  for (i = 0; i < argc; i++) {
+    size = strlen(argv[i]) + 1;
+    memcpy(s, argv[i], size);
+    new_argv[i] = s;
+    s += size;
+  }
+  new_argv[i] = NULL;
+
+  return new_argv;
+}
+
+
+int uv_set_process_title(const char* title) {
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (process_title.len != 0) {
+    /* No need to terminate, byte after is always '\0'. */
+    strncpy(process_title.str, title, process_title.len);
+    uv__set_process_title(title);
+  }
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  return 0;
+}
+
+
+int uv_get_process_title(char* buffer, size_t size) {
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  uv_once(&process_title_mutex_once, init_process_title_mutex_once);
+  uv_mutex_lock(&process_title_mutex);
+
+  if (size <= process_title.len) {
+    uv_mutex_unlock(&process_title_mutex);
+    return UV_ENOBUFS;
+  }
+
+  if (process_title.len != 0)
+    memcpy(buffer, process_title.str, process_title.len + 1);
+
+  buffer[process_title.len] = '\0';
+
+  uv_mutex_unlock(&process_title_mutex);
+
+  return 0;
+}
+
+
+UV_DESTRUCTOR(static void free_args_mem(void)) {
+  uv__free(args_mem);  /* Keep valgrind happy. */
+  args_mem = NULL;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/pthread-fixes.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/pthread-fixes.cpp
new file mode 100644
index 0000000..fb17995
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/pthread-fixes.cpp
@@ -0,0 +1,56 @@
+/* Copyright (c) 2013, Sony Mobile Communications AB
+ * Copyright (c) 2012, Google Inc.
+   All rights reserved.
+
+   Redistribution and use in source and binary forms, with or without
+   modification, are permitted provided that the following conditions are
+   met:
+
+     * Redistributions of source code must retain the above copyright
+   notice, this list of conditions and the following disclaimer.
+       * Redistributions in binary form must reproduce the above
+   copyright notice, this list of conditions and the following disclaimer
+   in the documentation and/or other materials provided with the
+   distribution.
+       * Neither the name of Google Inc. nor the names of its
+   contributors may be used to endorse or promote products derived from
+   this software without specific prior written permission.
+
+   THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
+   "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
+   LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
+   A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
+   OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
+   SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
+   LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
+   DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
+   THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
+   (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
+   OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
+*/
+
+/* Android versions < 4.1 have a broken pthread_sigmask. */
+#include <errno.h>
+#include <pthread.h>
+#include <signal.h>
+
+int uv__pthread_sigmask(int how, const sigset_t* set, sigset_t* oset) {
+  static int workaround;
+  int err;
+
+  if (workaround) {
+    return sigprocmask(how, set, oset);
+  } else {
+    err = pthread_sigmask(how, set, oset);
+    if (err) {
+      if (err == EINVAL && sigprocmask(how, set, oset) == 0) {
+        workaround = 1;
+        return 0;
+      } else {
+        return -1;
+      }
+    }
+  }
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/signal.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/signal.cpp
new file mode 100644
index 0000000..8da08b8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/signal.cpp
@@ -0,0 +1,573 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <errno.h>
+#include <signal.h>
+#include <stdlib.h>
+#include <string.h>
+#include <unistd.h>
+
+#ifndef SA_RESTART
+# define SA_RESTART 0
+#endif
+
+typedef struct {
+  uv_signal_t* handle;
+  int signum;
+} uv__signal_msg_t;
+
+RB_HEAD(uv__signal_tree_s, uv_signal_s);
+
+
+static int uv__signal_unlock(void);
+static int uv__signal_start(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum,
+                            int oneshot);
+static void uv__signal_event(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2);
+static void uv__signal_stop(uv_signal_t* handle);
+static void uv__signal_unregister_handler(int signum);
+
+
+static uv_once_t uv__signal_global_init_guard = UV_ONCE_INIT;
+static struct uv__signal_tree_s uv__signal_tree =
+    RB_INITIALIZER(uv__signal_tree);
+static int uv__signal_lock_pipefd[2] = { -1, -1 };
+
+RB_GENERATE_STATIC(uv__signal_tree_s,
+                   uv_signal_s, tree_entry,
+                   uv__signal_compare)
+
+static void uv__signal_global_reinit(void);
+
+static void uv__signal_global_init(void) {
+  if (uv__signal_lock_pipefd[0] == -1)
+    /* pthread_atfork can register before and after handlers, one
+     * for each child. This only registers one for the child. That
+     * state is both persistent and cumulative, so if we keep doing
+     * it the handler functions will be called multiple times. Thus
+     * we only want to do it once.
+     */
+    if (pthread_atfork(NULL, NULL, &uv__signal_global_reinit))
+      abort();
+
+  uv__signal_global_reinit();
+}
+
+
+UV_DESTRUCTOR(static void uv__signal_global_fini(void)) {
+  /* We can only use signal-safe functions here.
+   * That includes read/write and close, fortunately.
+   * We do all of this directly here instead of resetting
+   * uv__signal_global_init_guard because
+   * uv__signal_global_once_init is only called from uv_loop_init
+   * and this needs to function in existing loops.
+   */
+  if (uv__signal_lock_pipefd[0] != -1) {
+    uv__close(uv__signal_lock_pipefd[0]);
+    uv__signal_lock_pipefd[0] = -1;
+  }
+
+  if (uv__signal_lock_pipefd[1] != -1) {
+    uv__close(uv__signal_lock_pipefd[1]);
+    uv__signal_lock_pipefd[1] = -1;
+  }
+}
+
+
+static void uv__signal_global_reinit(void) {
+  uv__signal_global_fini();
+
+  if (uv__make_pipe(uv__signal_lock_pipefd, 0))
+    abort();
+
+  if (uv__signal_unlock())
+    abort();
+}
+
+
+void uv__signal_global_once_init(void) {
+  uv_once(&uv__signal_global_init_guard, uv__signal_global_init);
+}
+
+
+static int uv__signal_lock(void) {
+  int r;
+  char data;
+
+  do {
+    r = read(uv__signal_lock_pipefd[0], &data, sizeof data);
+  } while (r < 0 && errno == EINTR);
+
+  return (r < 0) ? -1 : 0;
+}
+
+
+static int uv__signal_unlock(void) {
+  int r;
+  char data = 42;
+
+  do {
+    r = write(uv__signal_lock_pipefd[1], &data, sizeof data);
+  } while (r < 0 && errno == EINTR);
+
+  return (r < 0) ? -1 : 0;
+}
+
+
+static void uv__signal_block_and_lock(sigset_t* saved_sigmask) {
+  sigset_t new_mask;
+
+  if (sigfillset(&new_mask))
+    abort();
+
+  if (pthread_sigmask(SIG_SETMASK, &new_mask, saved_sigmask))
+    abort();
+
+  if (uv__signal_lock())
+    abort();
+}
+
+
+static void uv__signal_unlock_and_unblock(sigset_t* saved_sigmask) {
+  if (uv__signal_unlock())
+    abort();
+
+  if (pthread_sigmask(SIG_SETMASK, saved_sigmask, NULL))
+    abort();
+}
+
+
+static uv_signal_t* uv__signal_first_handle(int signum) {
+  /* This function must be called with the signal lock held. */
+  uv_signal_t lookup;
+  uv_signal_t* handle;
+
+  lookup.signum = signum;
+  lookup.flags = 0;
+  lookup.loop = NULL;
+
+  handle = RB_NFIND(uv__signal_tree_s, &uv__signal_tree, &lookup);
+
+  if (handle != NULL && handle->signum == signum)
+    return handle;
+
+  return NULL;
+}
+
+
+static void uv__signal_handler(int signum) {
+  uv__signal_msg_t msg;
+  uv_signal_t* handle;
+  int saved_errno;
+
+  saved_errno = errno;
+  memset(&msg, 0, sizeof msg);
+
+  if (uv__signal_lock()) {
+    errno = saved_errno;
+    return;
+  }
+
+  for (handle = uv__signal_first_handle(signum);
+       handle != NULL && handle->signum == signum;
+       handle = RB_NEXT(uv__signal_tree_s, &uv__signal_tree, handle)) {
+    int r;
+
+    msg.signum = signum;
+    msg.handle = handle;
+
+    /* write() should be atomic for small data chunks, so the entire message
+     * should be written at once. In theory the pipe could become full, in
+     * which case the user is out of luck.
+     */
+    do {
+      r = write(handle->loop->signal_pipefd[1], &msg, sizeof msg);
+    } while (r == -1 && errno == EINTR);
+
+    assert(r == sizeof msg ||
+           (r == -1 && (errno == EAGAIN || errno == EWOULDBLOCK)));
+
+    if (r != -1)
+      handle->caught_signals++;
+  }
+
+  uv__signal_unlock();
+  errno = saved_errno;
+}
+
+
+static int uv__signal_register_handler(int signum, int oneshot) {
+  /* When this function is called, the signal lock must be held. */
+  struct sigaction sa;
+
+  /* XXX use a separate signal stack? */
+  memset(&sa, 0, sizeof(sa));
+  if (sigfillset(&sa.sa_mask))
+    abort();
+  sa.sa_handler = uv__signal_handler;
+  sa.sa_flags = SA_RESTART;
+  if (oneshot)
+    sa.sa_flags |= SA_RESETHAND;
+
+  /* XXX save old action so we can restore it later on? */
+  if (sigaction(signum, &sa, NULL))
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+
+static void uv__signal_unregister_handler(int signum) {
+  /* When this function is called, the signal lock must be held. */
+  struct sigaction sa;
+
+  memset(&sa, 0, sizeof(sa));
+  sa.sa_handler = SIG_DFL;
+
+  /* sigaction can only fail with EINVAL or EFAULT; an attempt to deregister a
+   * signal implies that it was successfully registered earlier, so EINVAL
+   * should never happen.
+   */
+  if (sigaction(signum, &sa, NULL))
+    abort();
+}
+
+
+static int uv__signal_loop_once_init(uv_loop_t* loop) {
+  int err;
+
+  /* Return if already initialized. */
+  if (loop->signal_pipefd[0] != -1)
+    return 0;
+
+  err = uv__make_pipe(loop->signal_pipefd, UV__F_NONBLOCK);
+  if (err)
+    return err;
+
+  uv__io_init(&loop->signal_io_watcher,
+              uv__signal_event,
+              loop->signal_pipefd[0]);
+  uv__io_start(loop, &loop->signal_io_watcher, POLLIN);
+
+  return 0;
+}
+
+
+int uv__signal_loop_fork(uv_loop_t* loop) {
+  uv__io_stop(loop, &loop->signal_io_watcher, POLLIN);
+  uv__close(loop->signal_pipefd[0]);
+  uv__close(loop->signal_pipefd[1]);
+  loop->signal_pipefd[0] = -1;
+  loop->signal_pipefd[1] = -1;
+  return uv__signal_loop_once_init(loop);
+}
+
+
+void uv__signal_loop_cleanup(uv_loop_t* loop) {
+  QUEUE* q;
+
+  /* Stop all the signal watchers that are still attached to this loop. This
+   * ensures that the (shared) signal tree doesn't contain any invalid entries
+   * entries, and that signal handlers are removed when appropriate.
+   * It's safe to use QUEUE_FOREACH here because the handles and the handle
+   * queue are not modified by uv__signal_stop().
+   */
+  QUEUE_FOREACH(q, &loop->handle_queue) {
+    uv_handle_t* handle = QUEUE_DATA(q, uv_handle_t, handle_queue);
+
+    if (handle->type == UV_SIGNAL)
+      uv__signal_stop((uv_signal_t*) handle);
+  }
+
+  if (loop->signal_pipefd[0] != -1) {
+    uv__close(loop->signal_pipefd[0]);
+    loop->signal_pipefd[0] = -1;
+  }
+
+  if (loop->signal_pipefd[1] != -1) {
+    uv__close(loop->signal_pipefd[1]);
+    loop->signal_pipefd[1] = -1;
+  }
+}
+
+
+int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle) {
+  int err;
+
+  err = uv__signal_loop_once_init(loop);
+  if (err)
+    return err;
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_SIGNAL);
+  handle->signum = 0;
+  handle->caught_signals = 0;
+  handle->dispatched_signals = 0;
+
+  return 0;
+}
+
+
+void uv__signal_close(uv_signal_t* handle) {
+
+  uv__signal_stop(handle);
+
+  /* If there are any caught signals "trapped" in the signal pipe, we can't
+   * call the close callback yet. Otherwise, add the handle to the finish_close
+   * queue.
+   */
+  if (handle->caught_signals == handle->dispatched_signals) {
+    uv__make_close_pending((uv_handle_t*) handle);
+  }
+}
+
+
+int uv_signal_start(uv_signal_t* handle, uv_signal_cb signal_cb, int signum) {
+  return uv__signal_start(handle, signal_cb, signum, 0);
+}
+
+
+int uv_signal_start_oneshot(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum) {
+  return uv__signal_start(handle, signal_cb, signum, 1);
+}
+
+
+static int uv__signal_start(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum,
+                            int oneshot) {
+  sigset_t saved_sigmask;
+  int err;
+  uv_signal_t* first_handle;
+
+  assert(!uv__is_closing(handle));
+
+  /* If the user supplies signum == 0, then return an error already. If the
+   * signum is otherwise invalid then uv__signal_register will find out
+   * eventually.
+   */
+  if (signum == 0)
+    return UV_EINVAL;
+
+  /* Short circuit: if the signal watcher is already watching {signum} don't
+   * go through the process of deregistering and registering the handler.
+   * Additionally, this avoids pending signals getting lost in the small time
+   * time frame that handle->signum == 0.
+   */
+  if (signum == handle->signum) {
+    handle->signal_cb = signal_cb;
+    return 0;
+  }
+
+  /* If the signal handler was already active, stop it first. */
+  if (handle->signum != 0) {
+    uv__signal_stop(handle);
+  }
+
+  uv__signal_block_and_lock(&saved_sigmask);
+
+  /* If at this point there are no active signal watchers for this signum (in
+   * any of the loops), it's time to try and register a handler for it here.
+   * Also in case there's only one-shot handlers and a regular handler comes in.
+   */
+  first_handle = uv__signal_first_handle(signum);
+  if (first_handle == NULL ||
+      (!oneshot && (first_handle->flags & UV__SIGNAL_ONE_SHOT))) {
+    err = uv__signal_register_handler(signum, oneshot);
+    if (err) {
+      /* Registering the signal handler failed. Must be an invalid signal. */
+      uv__signal_unlock_and_unblock(&saved_sigmask);
+      return err;
+    }
+  }
+
+  handle->signum = signum;
+  if (oneshot)
+    handle->flags |= UV__SIGNAL_ONE_SHOT;
+
+  RB_INSERT(uv__signal_tree_s, &uv__signal_tree, handle);
+
+  uv__signal_unlock_and_unblock(&saved_sigmask);
+
+  handle->signal_cb = signal_cb;
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+static void uv__signal_event(uv_loop_t* loop,
+                             uv__io_t* w,
+                             unsigned int events) {
+  uv__signal_msg_t* msg;
+  uv_signal_t* handle;
+  char buf[sizeof(uv__signal_msg_t) * 32];
+  size_t bytes, end, i;
+  int r;
+
+  bytes = 0;
+  end = 0;
+
+  do {
+    r = read(loop->signal_pipefd[0], buf + bytes, sizeof(buf) - bytes);
+
+    if (r == -1 && errno == EINTR)
+      continue;
+
+    if (r == -1 && (errno == EAGAIN || errno == EWOULDBLOCK)) {
+      /* If there are bytes in the buffer already (which really is extremely
+       * unlikely if possible at all) we can't exit the function here. We'll
+       * spin until more bytes are read instead.
+       */
+      if (bytes > 0)
+        continue;
+
+      /* Otherwise, there was nothing there. */
+      return;
+    }
+
+    /* Other errors really should never happen. */
+    if (r == -1)
+      abort();
+
+    bytes += r;
+
+    /* `end` is rounded down to a multiple of sizeof(uv__signal_msg_t). */
+    end = (bytes / sizeof(uv__signal_msg_t)) * sizeof(uv__signal_msg_t);
+
+    for (i = 0; i < end; i += sizeof(uv__signal_msg_t)) {
+      msg = (uv__signal_msg_t*) (buf + i);
+      handle = msg->handle;
+
+      if (msg->signum == handle->signum) {
+        assert(!(handle->flags & UV_CLOSING));
+        handle->signal_cb(handle, handle->signum);
+      }
+
+      handle->dispatched_signals++;
+
+      if (handle->flags & UV__SIGNAL_ONE_SHOT)
+        uv__signal_stop(handle);
+
+      /* If uv_close was called while there were caught signals that were not
+       * yet dispatched, the uv__finish_close was deferred. Make close pending
+       * now if this has happened.
+       */
+      if ((handle->flags & UV_CLOSING) &&
+          (handle->caught_signals == handle->dispatched_signals)) {
+        uv__make_close_pending((uv_handle_t*) handle);
+      }
+    }
+
+    bytes -= end;
+
+    /* If there are any "partial" messages left, move them to the start of the
+     * the buffer, and spin. This should not happen.
+     */
+    if (bytes) {
+      memmove(buf, buf + end, bytes);
+      continue;
+    }
+  } while (end == sizeof buf);
+}
+
+
+static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2) {
+  int f1;
+  int f2;
+  /* Compare signums first so all watchers with the same signnum end up
+   * adjacent.
+   */
+  if (w1->signum < w2->signum) return -1;
+  if (w1->signum > w2->signum) return 1;
+
+  /* Handlers without UV__SIGNAL_ONE_SHOT set will come first, so if the first
+   * handler returned is a one-shot handler, the rest will be too.
+   */
+  f1 = w1->flags & UV__SIGNAL_ONE_SHOT;
+  f2 = w2->flags & UV__SIGNAL_ONE_SHOT;
+  if (f1 < f2) return -1;
+  if (f1 > f2) return 1;
+
+  /* Sort by loop pointer, so we can easily look up the first item after
+   * { .signum = x, .loop = NULL }.
+   */
+  if (w1->loop < w2->loop) return -1;
+  if (w1->loop > w2->loop) return 1;
+
+  if (w1 < w2) return -1;
+  if (w1 > w2) return 1;
+
+  return 0;
+}
+
+
+int uv_signal_stop(uv_signal_t* handle) {
+  assert(!uv__is_closing(handle));
+  uv__signal_stop(handle);
+  return 0;
+}
+
+
+static void uv__signal_stop(uv_signal_t* handle) {
+  uv_signal_t* removed_handle;
+  sigset_t saved_sigmask;
+  uv_signal_t* first_handle;
+  int rem_oneshot;
+  int first_oneshot;
+  int ret;
+
+  /* If the watcher wasn't started, this is a no-op. */
+  if (handle->signum == 0)
+    return;
+
+  uv__signal_block_and_lock(&saved_sigmask);
+
+  removed_handle = RB_REMOVE(uv__signal_tree_s, &uv__signal_tree, handle);
+  assert(removed_handle == handle);
+  (void) removed_handle;
+
+  /* Check if there are other active signal watchers observing this signal. If
+   * not, unregister the signal handler.
+   */
+  first_handle = uv__signal_first_handle(handle->signum);
+  if (first_handle == NULL) {
+    uv__signal_unregister_handler(handle->signum);
+  } else {
+    rem_oneshot = handle->flags & UV__SIGNAL_ONE_SHOT;
+    first_oneshot = first_handle->flags & UV__SIGNAL_ONE_SHOT;
+    if (first_oneshot && !rem_oneshot) {
+      ret = uv__signal_register_handler(handle->signum, 1);
+      assert(ret == 0);
+    }
+  }
+
+  uv__signal_unlock_and_unblock(&saved_sigmask);
+
+  handle->signum = 0;
+  uv__handle_stop(handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/spinlock.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/spinlock.h
new file mode 100644
index 0000000..a20c83c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/spinlock.h
@@ -0,0 +1,53 @@
+/* Copyright (c) 2013, Ben Noordhuis <info@bnoordhuis.nl>
+ *
+ * Permission to use, copy, modify, and/or distribute this software for any
+ * purpose with or without fee is hereby granted, provided that the above
+ * copyright notice and this permission notice appear in all copies.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS" AND THE AUTHOR DISCLAIMS ALL WARRANTIES
+ * WITH REGARD TO THIS SOFTWARE INCLUDING ALL IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS. IN NO EVENT SHALL THE AUTHOR BE LIABLE FOR
+ * ANY SPECIAL, DIRECT, INDIRECT, OR CONSEQUENTIAL DAMAGES OR ANY DAMAGES
+ * WHATSOEVER RESULTING FROM LOSS OF USE, DATA OR PROFITS, WHETHER IN AN
+ * ACTION OF CONTRACT, NEGLIGENCE OR OTHER TORTIOUS ACTION, ARISING OUT OF
+ * OR IN CONNECTION WITH THE USE OR PERFORMANCE OF THIS SOFTWARE.
+ */
+
+#ifndef UV_SPINLOCK_H_
+#define UV_SPINLOCK_H_
+
+#include "internal.h"  /* ACCESS_ONCE, UV_UNUSED */
+#include "atomic-ops.h"
+
+#define UV_SPINLOCK_INITIALIZER { 0 }
+
+typedef struct {
+  int lock;
+} uv_spinlock_t;
+
+UV_UNUSED(static void uv_spinlock_init(uv_spinlock_t* spinlock));
+UV_UNUSED(static void uv_spinlock_lock(uv_spinlock_t* spinlock));
+UV_UNUSED(static void uv_spinlock_unlock(uv_spinlock_t* spinlock));
+UV_UNUSED(static int uv_spinlock_trylock(uv_spinlock_t* spinlock));
+
+UV_UNUSED(static void uv_spinlock_init(uv_spinlock_t* spinlock)) {
+  ACCESS_ONCE(int, spinlock->lock) = 0;
+}
+
+UV_UNUSED(static void uv_spinlock_lock(uv_spinlock_t* spinlock)) {
+  while (!uv_spinlock_trylock(spinlock)) cpu_relax();
+}
+
+UV_UNUSED(static void uv_spinlock_unlock(uv_spinlock_t* spinlock)) {
+  ACCESS_ONCE(int, spinlock->lock) = 0;
+}
+
+UV_UNUSED(static int uv_spinlock_trylock(uv_spinlock_t* spinlock)) {
+  /* TODO(bnoordhuis) Maybe change to a ticket lock to guarantee fair queueing.
+   * Not really critical until we have locks that are (frequently) contended
+   * for by several threads.
+   */
+  return 0 == cmpxchgi(&spinlock->lock, 0, 1);
+}
+
+#endif  /* UV_SPINLOCK_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/stream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/stream.cpp
new file mode 100644
index 0000000..fd61d82
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/stream.cpp
@@ -0,0 +1,1704 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/uio.h>
+#include <sys/un.h>
+#include <unistd.h>
+#include <limits.h> /* IOV_MAX */
+
+#if defined(__APPLE__)
+# include <sys/event.h>
+# include <sys/time.h>
+# include <sys/select.h>
+
+/* Forward declaration */
+typedef struct uv__stream_select_s uv__stream_select_t;
+
+struct uv__stream_select_s {
+  uv_stream_t* stream;
+  uv_thread_t thread;
+  uv_sem_t close_sem;
+  uv_sem_t async_sem;
+  uv_async_t async;
+  int events;
+  int fake_fd;
+  int int_fd;
+  int fd;
+  fd_set* sread;
+  size_t sread_sz;
+  fd_set* swrite;
+  size_t swrite_sz;
+};
+# define WRITE_RETRY_ON_ERROR(send_handle) \
+    (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS || \
+     (errno == EMSGSIZE && send_handle))
+#else
+# define WRITE_RETRY_ON_ERROR(send_handle) \
+    (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
+#endif /* defined(__APPLE__) */
+
+static void uv__stream_connect(uv_stream_t*);
+static void uv__write(uv_stream_t* stream);
+static void uv__read(uv_stream_t* stream);
+static void uv__stream_io(uv_loop_t* loop, uv__io_t* w, unsigned int events);
+static void uv__write_callbacks(uv_stream_t* stream);
+static size_t uv__write_req_size(uv_write_t* req);
+
+
+void uv__stream_init(uv_loop_t* loop,
+                     uv_stream_t* stream,
+                     uv_handle_type type) {
+  int err;
+
+  uv__handle_init(loop, (uv_handle_t*)stream, type);
+  stream->read_cb = NULL;
+  stream->alloc_cb = NULL;
+  stream->close_cb = NULL;
+  stream->connection_cb = NULL;
+  stream->connect_req = NULL;
+  stream->shutdown_req = NULL;
+  stream->accepted_fd = -1;
+  stream->queued_fds = NULL;
+  stream->delayed_error = 0;
+  QUEUE_INIT(&stream->write_queue);
+  QUEUE_INIT(&stream->write_completed_queue);
+  stream->write_queue_size = 0;
+
+  if (loop->emfile_fd == -1) {
+    err = uv__open_cloexec("/dev/null", O_RDONLY);
+    if (err < 0)
+        /* In the rare case that "/dev/null" isn't mounted open "/"
+         * instead.
+         */
+        err = uv__open_cloexec("/", O_RDONLY);
+    if (err >= 0)
+      loop->emfile_fd = err;
+  }
+
+#if defined(__APPLE__)
+  stream->select = NULL;
+#endif /* defined(__APPLE_) */
+
+  uv__io_init(&stream->io_watcher, uv__stream_io, -1);
+}
+
+
+static void uv__stream_osx_interrupt_select(uv_stream_t* stream) {
+#if defined(__APPLE__)
+  /* Notify select() thread about state change */
+  uv__stream_select_t* s;
+  int r;
+
+  s = (uv__stream_select_t*)stream->select;
+  if (s == NULL)
+    return;
+
+  /* Interrupt select() loop
+   * NOTE: fake_fd and int_fd are socketpair(), thus writing to one will
+   * emit read event on other side
+   */
+  do
+    r = write(s->fake_fd, "x", 1);
+  while (r == -1 && errno == EINTR);
+
+  assert(r == 1);
+#else  /* !defined(__APPLE__) */
+  /* No-op on any other platform */
+#endif  /* !defined(__APPLE__) */
+}
+
+
+#if defined(__APPLE__)
+static void uv__stream_osx_select(void* arg) {
+  uv_stream_t* stream;
+  uv__stream_select_t* s;
+  char buf[1024];
+  int events;
+  int fd;
+  int r;
+  int max_fd;
+
+  stream = (uv_stream_t*)arg;
+  s = (uv__stream_select_t*)stream->select;
+  fd = s->fd;
+
+  if (fd > s->int_fd)
+    max_fd = fd;
+  else
+    max_fd = s->int_fd;
+
+  while (1) {
+    /* Terminate on semaphore */
+    if (uv_sem_trywait(&s->close_sem) == 0)
+      break;
+
+    /* Watch fd using select(2) */
+    memset(s->sread, 0, s->sread_sz);
+    memset(s->swrite, 0, s->swrite_sz);
+
+    if (uv__io_active(&stream->io_watcher, POLLIN))
+      FD_SET(fd, s->sread);
+    if (uv__io_active(&stream->io_watcher, POLLOUT))
+      FD_SET(fd, s->swrite);
+    FD_SET(s->int_fd, s->sread);
+
+    /* Wait indefinitely for fd events */
+    r = select(max_fd + 1, s->sread, s->swrite, NULL, NULL);
+    if (r == -1) {
+      if (errno == EINTR)
+        continue;
+
+      /* XXX: Possible?! */
+      abort();
+    }
+
+    /* Ignore timeouts */
+    if (r == 0)
+      continue;
+
+    /* Empty socketpair's buffer in case of interruption */
+    if (FD_ISSET(s->int_fd, s->sread))
+      while (1) {
+        r = read(s->int_fd, buf, sizeof(buf));
+
+        if (r == sizeof(buf))
+          continue;
+
+        if (r != -1)
+          break;
+
+        if (errno == EAGAIN || errno == EWOULDBLOCK)
+          break;
+
+        if (errno == EINTR)
+          continue;
+
+        abort();
+      }
+
+    /* Handle events */
+    events = 0;
+    if (FD_ISSET(fd, s->sread))
+      events |= POLLIN;
+    if (FD_ISSET(fd, s->swrite))
+      events |= POLLOUT;
+
+    assert(events != 0 || FD_ISSET(s->int_fd, s->sread));
+    if (events != 0) {
+      ACCESS_ONCE(int, s->events) = events;
+
+      uv_async_send(&s->async);
+      uv_sem_wait(&s->async_sem);
+
+      /* Should be processed at this stage */
+      assert((s->events == 0) || (stream->flags & UV_CLOSING));
+    }
+  }
+}
+
+
+static void uv__stream_osx_select_cb(uv_async_t* handle) {
+  uv__stream_select_t* s;
+  uv_stream_t* stream;
+  int events;
+
+  s = container_of(handle, uv__stream_select_t, async);
+  stream = s->stream;
+
+  /* Get and reset stream's events */
+  events = s->events;
+  ACCESS_ONCE(int, s->events) = 0;
+
+  assert(events != 0);
+  assert(events == (events & (POLLIN | POLLOUT)));
+
+  /* Invoke callback on event-loop */
+  if ((events & POLLIN) && uv__io_active(&stream->io_watcher, POLLIN))
+    uv__stream_io(stream->loop, &stream->io_watcher, POLLIN);
+
+  if ((events & POLLOUT) && uv__io_active(&stream->io_watcher, POLLOUT))
+    uv__stream_io(stream->loop, &stream->io_watcher, POLLOUT);
+
+  if (stream->flags & UV_CLOSING)
+    return;
+
+  /* NOTE: It is important to do it here, otherwise `select()` might be called
+   * before the actual `uv__read()`, leading to the blocking syscall
+   */
+  uv_sem_post(&s->async_sem);
+}
+
+
+static void uv__stream_osx_cb_close(uv_handle_t* async) {
+  uv__stream_select_t* s;
+
+  s = container_of(async, uv__stream_select_t, async);
+  uv__free(s);
+}
+
+
+int uv__stream_try_select(uv_stream_t* stream, int* fd) {
+  /*
+   * kqueue doesn't work with some files from /dev mount on osx.
+   * select(2) in separate thread for those fds
+   */
+
+  struct kevent filter[1];
+  struct kevent events[1];
+  struct timespec timeout;
+  uv__stream_select_t* s;
+  int fds[2];
+  int err;
+  int ret;
+  int kq;
+  int old_fd;
+  int max_fd;
+  size_t sread_sz;
+  size_t swrite_sz;
+
+  kq = kqueue();
+  if (kq == -1) {
+    perror("(libuv) kqueue()");
+    return UV__ERR(errno);
+  }
+
+  EV_SET(&filter[0], *fd, EVFILT_READ, EV_ADD | EV_ENABLE, 0, 0, 0);
+
+  /* Use small timeout, because we only want to capture EINVALs */
+  timeout.tv_sec = 0;
+  timeout.tv_nsec = 1;
+
+  do
+    ret = kevent(kq, filter, 1, events, 1, &timeout);
+  while (ret == -1 && errno == EINTR);
+
+  uv__close(kq);
+
+  if (ret == -1)
+    return UV__ERR(errno);
+
+  if (ret == 0 || (events[0].flags & EV_ERROR) == 0 || events[0].data != EINVAL)
+    return 0;
+
+  /* At this point we definitely know that this fd won't work with kqueue */
+
+  /*
+   * Create fds for io watcher and to interrupt the select() loop.
+   * NOTE: do it ahead of malloc below to allocate enough space for fd_sets
+   */
+  if (socketpair(AF_UNIX, SOCK_STREAM, 0, fds))
+    return UV__ERR(errno);
+
+  max_fd = *fd;
+  if (fds[1] > max_fd)
+    max_fd = fds[1];
+
+  sread_sz = ROUND_UP(max_fd + 1, sizeof(uint32_t) * NBBY) / NBBY;
+  swrite_sz = sread_sz;
+
+  s = (uv__stream_select_t*)uv__malloc(sizeof(*s) + sread_sz + swrite_sz);
+  if (s == NULL) {
+    err = UV_ENOMEM;
+    goto failed_malloc;
+  }
+
+  s->events = 0;
+  s->fd = *fd;
+  s->sread = (fd_set*) ((char*) s + sizeof(*s));
+  s->sread_sz = sread_sz;
+  s->swrite = (fd_set*) ((char*) s->sread + sread_sz);
+  s->swrite_sz = swrite_sz;
+
+  err = uv_async_init(stream->loop, &s->async, uv__stream_osx_select_cb);
+  if (err)
+    goto failed_async_init;
+
+  s->async.flags |= UV__HANDLE_INTERNAL;
+  uv__handle_unref(&s->async);
+
+  err = uv_sem_init(&s->close_sem, 0);
+  if (err != 0)
+    goto failed_close_sem_init;
+
+  err = uv_sem_init(&s->async_sem, 0);
+  if (err != 0)
+    goto failed_async_sem_init;
+
+  s->fake_fd = fds[0];
+  s->int_fd = fds[1];
+
+  old_fd = *fd;
+  s->stream = stream;
+  stream->select = s;
+  *fd = s->fake_fd;
+
+  err = uv_thread_create(&s->thread, uv__stream_osx_select, stream);
+  if (err != 0)
+    goto failed_thread_create;
+
+  return 0;
+
+failed_thread_create:
+  s->stream = NULL;
+  stream->select = NULL;
+  *fd = old_fd;
+
+  uv_sem_destroy(&s->async_sem);
+
+failed_async_sem_init:
+  uv_sem_destroy(&s->close_sem);
+
+failed_close_sem_init:
+  uv__close(fds[0]);
+  uv__close(fds[1]);
+  uv_close((uv_handle_t*) &s->async, uv__stream_osx_cb_close);
+  return err;
+
+failed_async_init:
+  uv__free(s);
+
+failed_malloc:
+  uv__close(fds[0]);
+  uv__close(fds[1]);
+
+  return err;
+}
+#endif /* defined(__APPLE__) */
+
+
+int uv__stream_open(uv_stream_t* stream, int fd, int flags) {
+#if defined(__APPLE__)
+  int enable;
+#endif
+
+  if (!(stream->io_watcher.fd == -1 || stream->io_watcher.fd == fd))
+    return UV_EBUSY;
+
+  assert(fd >= 0);
+  stream->flags |= flags;
+
+  if (stream->type == UV_TCP) {
+    if ((stream->flags & UV_TCP_NODELAY) && uv__tcp_nodelay(fd, 1))
+      return UV__ERR(errno);
+
+    /* TODO Use delay the user passed in. */
+    if ((stream->flags & UV_TCP_KEEPALIVE) && uv__tcp_keepalive(fd, 1, 60))
+      return UV__ERR(errno);
+  }
+
+#if defined(__APPLE__)
+  enable = 1;
+  if (setsockopt(fd, SOL_SOCKET, SO_OOBINLINE, &enable, sizeof(enable)) &&
+      errno != ENOTSOCK &&
+      errno != EINVAL) {
+    return UV__ERR(errno);
+  }
+#endif
+
+  stream->io_watcher.fd = fd;
+
+  return 0;
+}
+
+
+void uv__stream_flush_write_queue(uv_stream_t* stream, int error) {
+  uv_write_t* req;
+  QUEUE* q;
+  while (!QUEUE_EMPTY(&stream->write_queue)) {
+    q = QUEUE_HEAD(&stream->write_queue);
+    QUEUE_REMOVE(q);
+
+    req = QUEUE_DATA(q, uv_write_t, queue);
+    req->error = error;
+
+    QUEUE_INSERT_TAIL(&stream->write_completed_queue, &req->queue);
+  }
+}
+
+
+void uv__stream_destroy(uv_stream_t* stream) {
+  assert(!uv__io_active(&stream->io_watcher, POLLIN | POLLOUT));
+  assert(stream->flags & UV_CLOSED);
+
+  if (stream->connect_req) {
+    uv__req_unregister(stream->loop, stream->connect_req);
+    stream->connect_req->cb(stream->connect_req, UV_ECANCELED);
+    stream->connect_req = NULL;
+  }
+
+  uv__stream_flush_write_queue(stream, UV_ECANCELED);
+  uv__write_callbacks(stream);
+
+  if (stream->shutdown_req) {
+    /* The ECANCELED error code is a lie, the shutdown(2) syscall is a
+     * fait accompli at this point. Maybe we should revisit this in v0.11.
+     * A possible reason for leaving it unchanged is that it informs the
+     * callee that the handle has been destroyed.
+     */
+    uv__req_unregister(stream->loop, stream->shutdown_req);
+    stream->shutdown_req->cb(stream->shutdown_req, UV_ECANCELED);
+    stream->shutdown_req = NULL;
+  }
+
+  assert(stream->write_queue_size == 0);
+}
+
+
+/* Implements a best effort approach to mitigating accept() EMFILE errors.
+ * We have a spare file descriptor stashed away that we close to get below
+ * the EMFILE limit. Next, we accept all pending connections and close them
+ * immediately to signal the clients that we're overloaded - and we are, but
+ * we still keep on trucking.
+ *
+ * There is one caveat: it's not reliable in a multi-threaded environment.
+ * The file descriptor limit is per process. Our party trick fails if another
+ * thread opens a file or creates a socket in the time window between us
+ * calling close() and accept().
+ */
+static int uv__emfile_trick(uv_loop_t* loop, int accept_fd) {
+  int err;
+  int emfile_fd;
+
+  if (loop->emfile_fd == -1)
+    return UV_EMFILE;
+
+  uv__close(loop->emfile_fd);
+  loop->emfile_fd = -1;
+
+  do {
+    err = uv__accept(accept_fd);
+    if (err >= 0)
+      uv__close(err);
+  } while (err >= 0 || err == UV_EINTR);
+
+  emfile_fd = uv__open_cloexec("/", O_RDONLY);
+  if (emfile_fd >= 0)
+    loop->emfile_fd = emfile_fd;
+
+  return err;
+}
+
+
+#if defined(UV_HAVE_KQUEUE)
+# define UV_DEC_BACKLOG(w) w->rcount--;
+#else
+# define UV_DEC_BACKLOG(w) /* no-op */
+#endif /* defined(UV_HAVE_KQUEUE) */
+
+
+void uv__server_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  uv_stream_t* stream;
+  int err;
+
+  stream = container_of(w, uv_stream_t, io_watcher);
+  assert(events & POLLIN);
+  assert(stream->accepted_fd == -1);
+  assert(!(stream->flags & UV_CLOSING));
+
+  uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
+
+  /* connection_cb can close the server socket while we're
+   * in the loop so check it on each iteration.
+   */
+  while (uv__stream_fd(stream) != -1) {
+    assert(stream->accepted_fd == -1);
+
+#if defined(UV_HAVE_KQUEUE)
+    if (w->rcount <= 0)
+      return;
+#endif /* defined(UV_HAVE_KQUEUE) */
+
+    err = uv__accept(uv__stream_fd(stream));
+    if (err < 0) {
+      if (err == UV_EAGAIN || err == UV__ERR(EWOULDBLOCK))
+        return;  /* Not an error. */
+
+      if (err == UV_ECONNABORTED)
+        continue;  /* Ignore. Nothing we can do about that. */
+
+      if (err == UV_EMFILE || err == UV_ENFILE) {
+        err = uv__emfile_trick(loop, uv__stream_fd(stream));
+        if (err == UV_EAGAIN || err == UV__ERR(EWOULDBLOCK))
+          break;
+      }
+
+      stream->connection_cb(stream, err);
+      continue;
+    }
+
+    UV_DEC_BACKLOG(w)
+    stream->accepted_fd = err;
+    stream->connection_cb(stream, 0);
+
+    if (stream->accepted_fd != -1) {
+      /* The user hasn't yet accepted called uv_accept() */
+      uv__io_stop(loop, &stream->io_watcher, POLLIN);
+      return;
+    }
+
+    if (stream->type == UV_TCP && (stream->flags & UV_TCP_SINGLE_ACCEPT)) {
+      /* Give other processes a chance to accept connections. */
+      struct timespec timeout = { 0, 1 };
+      nanosleep(&timeout, NULL);
+    }
+  }
+}
+
+
+#undef UV_DEC_BACKLOG
+
+
+int uv_accept(uv_stream_t* server, uv_stream_t* client) {
+  int err;
+
+  assert(server->loop == client->loop);
+
+  if (server->accepted_fd == -1)
+    return UV_EAGAIN;
+
+  switch (client->type) {
+    case UV_NAMED_PIPE:
+    case UV_TCP:
+      err = uv__stream_open(client,
+                            server->accepted_fd,
+                            UV_STREAM_READABLE | UV_STREAM_WRITABLE);
+      if (err) {
+        /* TODO handle error */
+        uv__close(server->accepted_fd);
+        goto done;
+      }
+      break;
+
+    case UV_UDP:
+      err = uv_udp_open((uv_udp_t*) client, server->accepted_fd);
+      if (err) {
+        uv__close(server->accepted_fd);
+        goto done;
+      }
+      break;
+
+    default:
+      return UV_EINVAL;
+  }
+
+  client->flags |= UV_HANDLE_BOUND;
+
+done:
+  /* Process queued fds */
+  if (server->queued_fds != NULL) {
+    uv__stream_queued_fds_t* queued_fds;
+
+    queued_fds = (uv__stream_queued_fds_t*)(server->queued_fds);
+
+    /* Read first */
+    server->accepted_fd = queued_fds->fds[0];
+
+    /* All read, free */
+    assert(queued_fds->offset > 0);
+    if (--queued_fds->offset == 0) {
+      uv__free(queued_fds);
+      server->queued_fds = NULL;
+    } else {
+      /* Shift rest */
+      memmove(queued_fds->fds,
+              queued_fds->fds + 1,
+              queued_fds->offset * sizeof(*queued_fds->fds));
+    }
+  } else {
+    server->accepted_fd = -1;
+    if (err == 0)
+      uv__io_start(server->loop, &server->io_watcher, POLLIN);
+  }
+  return err;
+}
+
+
+int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb) {
+  int err;
+
+  switch (stream->type) {
+  case UV_TCP:
+    err = uv_tcp_listen((uv_tcp_t*)stream, backlog, cb);
+    break;
+
+  case UV_NAMED_PIPE:
+    err = uv_pipe_listen((uv_pipe_t*)stream, backlog, cb);
+    break;
+
+  default:
+    err = UV_EINVAL;
+  }
+
+  if (err == 0)
+    uv__handle_start(stream);
+
+  return err;
+}
+
+
+static void uv__drain(uv_stream_t* stream) {
+  uv_shutdown_t* req;
+  int err;
+
+  assert(QUEUE_EMPTY(&stream->write_queue));
+  uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
+  uv__stream_osx_interrupt_select(stream);
+
+  /* Shutdown? */
+  if ((stream->flags & UV_STREAM_SHUTTING) &&
+      !(stream->flags & UV_CLOSING) &&
+      !(stream->flags & UV_STREAM_SHUT)) {
+    assert(stream->shutdown_req);
+
+    req = stream->shutdown_req;
+    stream->shutdown_req = NULL;
+    stream->flags &= ~UV_STREAM_SHUTTING;
+    uv__req_unregister(stream->loop, req);
+
+    err = 0;
+    if (shutdown(uv__stream_fd(stream), SHUT_WR))
+      err = UV__ERR(errno);
+
+    if (err == 0)
+      stream->flags |= UV_STREAM_SHUT;
+
+    if (req->cb != NULL)
+      req->cb(req, err);
+  }
+}
+
+
+static size_t uv__write_req_size(uv_write_t* req) {
+  size_t size;
+
+  assert(req->bufs != NULL);
+  size = uv__count_bufs(req->bufs + req->write_index,
+                        req->nbufs - req->write_index);
+  assert(req->handle->write_queue_size >= size);
+
+  return size;
+}
+
+
+static void uv__write_req_finish(uv_write_t* req) {
+  uv_stream_t* stream = req->handle;
+
+  /* Pop the req off tcp->write_queue. */
+  QUEUE_REMOVE(&req->queue);
+
+  /* Only free when there was no error. On error, we touch up write_queue_size
+   * right before making the callback. The reason we don't do that right away
+   * is that a write_queue_size > 0 is our only way to signal to the user that
+   * they should stop writing - which they should if we got an error. Something
+   * to revisit in future revisions of the libuv API.
+   */
+  if (req->error == 0) {
+    if (req->bufs != req->bufsml)
+      uv__free(req->bufs);
+    req->bufs = NULL;
+  }
+
+  /* Add it to the write_completed_queue where it will have its
+   * callback called in the near future.
+   */
+  QUEUE_INSERT_TAIL(&stream->write_completed_queue, &req->queue);
+  uv__io_feed(stream->loop, &stream->io_watcher);
+}
+
+
+static int uv__handle_fd(uv_handle_t* handle) {
+  switch (handle->type) {
+    case UV_NAMED_PIPE:
+    case UV_TCP:
+      return ((uv_stream_t*) handle)->io_watcher.fd;
+
+    case UV_UDP:
+      return ((uv_udp_t*) handle)->io_watcher.fd;
+
+    default:
+      return -1;
+  }
+}
+
+static void uv__write(uv_stream_t* stream) {
+  struct iovec* iov;
+  QUEUE* q;
+  uv_write_t* req;
+  int iovmax;
+  int iovcnt;
+  ssize_t n;
+  int err;
+
+start:
+
+  assert(uv__stream_fd(stream) >= 0);
+
+  if (QUEUE_EMPTY(&stream->write_queue))
+    return;
+
+  q = QUEUE_HEAD(&stream->write_queue);
+  req = QUEUE_DATA(q, uv_write_t, queue);
+  assert(req->handle == stream);
+
+  /*
+   * Cast to iovec. We had to have our own uv_buf_t instead of iovec
+   * because Windows's WSABUF is not an iovec.
+   */
+  assert(sizeof(uv_buf_t) == sizeof(struct iovec));
+  iov = (struct iovec*) &(req->bufs[req->write_index]);
+  iovcnt = req->nbufs - req->write_index;
+
+  iovmax = uv__getiovmax();
+
+  /* Limit iov count to avoid EINVALs from writev() */
+  if (iovcnt > iovmax)
+    iovcnt = iovmax;
+
+  /*
+   * Now do the actual writev. Note that we've been updating the pointers
+   * inside the iov each time we write. So there is no need to offset it.
+   */
+
+  if (req->send_handle) {
+    int fd_to_send;
+    struct msghdr msg;
+    struct cmsghdr *cmsg;
+    union {
+      char data[64];
+      struct cmsghdr alias;
+    } scratch;
+
+    if (uv__is_closing(req->send_handle)) {
+      err = UV_EBADF;
+      goto error;
+    }
+
+    fd_to_send = uv__handle_fd((uv_handle_t*) req->send_handle);
+
+    memset(&scratch, 0, sizeof(scratch));
+
+    assert(fd_to_send >= 0);
+
+    msg.msg_name = NULL;
+    msg.msg_namelen = 0;
+    msg.msg_iov = iov;
+    msg.msg_iovlen = iovcnt;
+    msg.msg_flags = 0;
+
+    msg.msg_control = &scratch.alias;
+    msg.msg_controllen = CMSG_SPACE(sizeof(fd_to_send));
+
+    cmsg = CMSG_FIRSTHDR(&msg);
+    cmsg->cmsg_level = SOL_SOCKET;
+    cmsg->cmsg_type = SCM_RIGHTS;
+    cmsg->cmsg_len = CMSG_LEN(sizeof(fd_to_send));
+
+    /* silence aliasing warning */
+    {
+      void* pv = CMSG_DATA(cmsg);
+      int* pi = (int*)pv;
+      *pi = fd_to_send;
+    }
+
+    do {
+      n = sendmsg(uv__stream_fd(stream), &msg, 0);
+    }
+#if defined(__APPLE__)
+    /*
+     * Due to a possible kernel bug at least in OS X 10.10 "Yosemite",
+     * EPROTOTYPE can be returned while trying to write to a socket that is
+     * shutting down. If we retry the write, we should get the expected EPIPE
+     * instead.
+     */
+    while (n == -1 && (errno == EINTR || errno == EPROTOTYPE));
+#else
+    while (n == -1 && errno == EINTR);
+#endif
+  } else {
+    do {
+      if (iovcnt == 1) {
+        n = write(uv__stream_fd(stream), iov[0].iov_base, iov[0].iov_len);
+      } else {
+        n = writev(uv__stream_fd(stream), iov, iovcnt);
+      }
+    }
+#if defined(__APPLE__)
+    /*
+     * Due to a possible kernel bug at least in OS X 10.10 "Yosemite",
+     * EPROTOTYPE can be returned while trying to write to a socket that is
+     * shutting down. If we retry the write, we should get the expected EPIPE
+     * instead.
+     */
+    while (n == -1 && (errno == EINTR || errno == EPROTOTYPE));
+#else
+    while (n == -1 && errno == EINTR);
+#endif
+  }
+
+  if (n < 0) {
+    if (!WRITE_RETRY_ON_ERROR(req->send_handle)) {
+      err = UV__ERR(errno);
+      goto error;
+    } else if (stream->flags & UV_STREAM_BLOCKING) {
+      /* If this is a blocking stream, try again. */
+      goto start;
+    }
+  } else {
+    /* Successful write */
+
+    while (n >= 0) {
+      uv_buf_t* buf = &(req->bufs[req->write_index]);
+      size_t len = buf->len;
+
+      assert(req->write_index < req->nbufs);
+
+      if ((size_t)n < len) {
+        buf->base += n;
+        buf->len -= n;
+        stream->write_queue_size -= n;
+        n = 0;
+
+        /* There is more to write. */
+        if (stream->flags & UV_STREAM_BLOCKING) {
+          /*
+           * If we're blocking then we should not be enabling the write
+           * watcher - instead we need to try again.
+           */
+          goto start;
+        } else {
+          /* Break loop and ensure the watcher is pending. */
+          break;
+        }
+
+      } else {
+        /* Finished writing the buf at index req->write_index. */
+        req->write_index++;
+
+        assert((size_t)n >= len);
+        n -= len;
+
+        assert(stream->write_queue_size >= len);
+        stream->write_queue_size -= len;
+
+        if (req->write_index == req->nbufs) {
+          /* Then we're done! */
+          assert(n == 0);
+          uv__write_req_finish(req);
+          /* TODO: start trying to write the next request. */
+          return;
+        }
+      }
+    }
+  }
+
+  /* Either we've counted n down to zero or we've got EAGAIN. */
+  assert(n == 0 || n == -1);
+
+  /* Only non-blocking streams should use the write_watcher. */
+  assert(!(stream->flags & UV_STREAM_BLOCKING));
+
+  /* We're not done. */
+  uv__io_start(stream->loop, &stream->io_watcher, POLLOUT);
+
+  /* Notify select() thread about state change */
+  uv__stream_osx_interrupt_select(stream);
+
+  return;
+
+error:
+  req->error = err;
+  uv__write_req_finish(req);
+  uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
+  if (!uv__io_active(&stream->io_watcher, POLLIN))
+    uv__handle_stop(stream);
+  uv__stream_osx_interrupt_select(stream);
+}
+
+
+static void uv__write_callbacks(uv_stream_t* stream) {
+  uv_write_t* req;
+  QUEUE* q;
+
+  while (!QUEUE_EMPTY(&stream->write_completed_queue)) {
+    /* Pop a req off write_completed_queue. */
+    q = QUEUE_HEAD(&stream->write_completed_queue);
+    req = QUEUE_DATA(q, uv_write_t, queue);
+    QUEUE_REMOVE(q);
+    uv__req_unregister(stream->loop, req);
+
+    if (req->bufs != NULL) {
+      stream->write_queue_size -= uv__write_req_size(req);
+      if (req->bufs != req->bufsml)
+        uv__free(req->bufs);
+      req->bufs = NULL;
+    }
+
+    /* NOTE: call callback AFTER freeing the request data. */
+    if (req->cb)
+      req->cb(req, req->error);
+  }
+
+  assert(QUEUE_EMPTY(&stream->write_completed_queue));
+}
+
+
+uv_handle_type uv__handle_type(int fd) {
+  struct sockaddr_storage ss;
+  socklen_t sslen;
+  socklen_t len;
+  int type;
+
+  memset(&ss, 0, sizeof(ss));
+  sslen = sizeof(ss);
+
+  if (getsockname(fd, (struct sockaddr*)&ss, &sslen))
+    return UV_UNKNOWN_HANDLE;
+
+  len = sizeof type;
+
+  if (getsockopt(fd, SOL_SOCKET, SO_TYPE, &type, &len))
+    return UV_UNKNOWN_HANDLE;
+
+  if (type == SOCK_STREAM) {
+#if defined(_AIX) || defined(__DragonFly__)
+    /* on AIX/DragonFly the getsockname call returns an empty sa structure
+     * for sockets of type AF_UNIX.  For all other types it will
+     * return a properly filled in structure.
+     */
+    if (sslen == 0)
+      return UV_NAMED_PIPE;
+#endif
+    switch (ss.ss_family) {
+      case AF_UNIX:
+        return UV_NAMED_PIPE;
+      case AF_INET:
+      case AF_INET6:
+        return UV_TCP;
+      }
+  }
+
+  if (type == SOCK_DGRAM &&
+      (ss.ss_family == AF_INET || ss.ss_family == AF_INET6))
+    return UV_UDP;
+
+  return UV_UNKNOWN_HANDLE;
+}
+
+
+static void uv__stream_eof(uv_stream_t* stream, const uv_buf_t* buf) {
+  stream->flags |= UV_STREAM_READ_EOF;
+  uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
+  if (!uv__io_active(&stream->io_watcher, POLLOUT))
+    uv__handle_stop(stream);
+  uv__stream_osx_interrupt_select(stream);
+  stream->read_cb(stream, UV_EOF, buf);
+  stream->flags &= ~UV_STREAM_READING;
+}
+
+
+static int uv__stream_queue_fd(uv_stream_t* stream, int fd) {
+  uv__stream_queued_fds_t* queued_fds;
+  unsigned int queue_size;
+
+  queued_fds = (uv__stream_queued_fds_t*)stream->queued_fds;
+  if (queued_fds == NULL) {
+    queue_size = 8;
+    queued_fds = (uv__stream_queued_fds_t*)
+        uv__malloc((queue_size - 1) * sizeof(*queued_fds->fds) +
+                   sizeof(*queued_fds));
+    if (queued_fds == NULL)
+      return UV_ENOMEM;
+    queued_fds->size = queue_size;
+    queued_fds->offset = 0;
+    stream->queued_fds = queued_fds;
+
+    /* Grow */
+  } else if (queued_fds->size == queued_fds->offset) {
+    queue_size = queued_fds->size + 8;
+    queued_fds = (uv__stream_queued_fds_t*)
+        uv__realloc(queued_fds, (queue_size - 1) * sizeof(*queued_fds->fds) +
+                    sizeof(*queued_fds));
+
+    /*
+     * Allocation failure, report back.
+     * NOTE: if it is fatal - sockets will be closed in uv__stream_close
+     */
+    if (queued_fds == NULL)
+      return UV_ENOMEM;
+    queued_fds->size = queue_size;
+    stream->queued_fds = queued_fds;
+  }
+
+  /* Put fd in a queue */
+  queued_fds->fds[queued_fds->offset++] = fd;
+
+  return 0;
+}
+
+
+#define UV__CMSG_FD_COUNT 64
+#define UV__CMSG_FD_SIZE (UV__CMSG_FD_COUNT * sizeof(int))
+
+
+static int uv__stream_recv_cmsg(uv_stream_t* stream, struct msghdr* msg) {
+  struct cmsghdr* cmsg;
+
+  for (cmsg = CMSG_FIRSTHDR(msg); cmsg != NULL; cmsg = CMSG_NXTHDR(msg, cmsg)) {
+    char* start;
+    char* end;
+    int err;
+    void* pv;
+    int* pi;
+    unsigned int i;
+    unsigned int count;
+
+    if (cmsg->cmsg_type != SCM_RIGHTS) {
+      fprintf(stderr, "ignoring non-SCM_RIGHTS ancillary data: %d\n",
+          cmsg->cmsg_type);
+      continue;
+    }
+
+    /* silence aliasing warning */
+    pv = CMSG_DATA(cmsg);
+    pi = (int*)pv;
+
+    /* Count available fds */
+    start = (char*) cmsg;
+    end = (char*) cmsg + cmsg->cmsg_len;
+    count = 0;
+    while (start + CMSG_LEN(count * sizeof(*pi)) < end)
+      count++;
+    assert(start + CMSG_LEN(count * sizeof(*pi)) == end);
+
+    for (i = 0; i < count; i++) {
+      /* Already has accepted fd, queue now */
+      if (stream->accepted_fd != -1) {
+        err = uv__stream_queue_fd(stream, pi[i]);
+        if (err != 0) {
+          /* Close rest */
+          for (; i < count; i++)
+            uv__close(pi[i]);
+          return err;
+        }
+      } else {
+        stream->accepted_fd = pi[i];
+      }
+    }
+  }
+
+  return 0;
+}
+
+
+#ifdef __clang__
+# pragma clang diagnostic push
+# pragma clang diagnostic ignored "-Wgnu-folding-constant"
+# pragma clang diagnostic ignored "-Wvla-extension"
+#endif
+
+static void uv__read(uv_stream_t* stream) {
+  uv_buf_t buf;
+  ssize_t nread;
+  struct msghdr msg;
+  char cmsg_space[CMSG_SPACE(UV__CMSG_FD_SIZE)];
+  int count;
+  int err;
+  int is_ipc;
+
+  stream->flags &= ~UV_STREAM_READ_PARTIAL;
+
+  /* Prevent loop starvation when the data comes in as fast as (or faster than)
+   * we can read it. XXX Need to rearm fd if we switch to edge-triggered I/O.
+   */
+  count = 32;
+
+  is_ipc = stream->type == UV_NAMED_PIPE && ((uv_pipe_t*) stream)->ipc;
+
+  /* XXX: Maybe instead of having UV_STREAM_READING we just test if
+   * tcp->read_cb is NULL or not?
+   */
+  while (stream->read_cb
+      && (stream->flags & UV_STREAM_READING)
+      && (count-- > 0)) {
+    assert(stream->alloc_cb != NULL);
+
+    buf = uv_buf_init(NULL, 0);
+    stream->alloc_cb((uv_handle_t*)stream, 64 * 1024, &buf);
+    if (buf.base == NULL || buf.len == 0) {
+      /* User indicates it can't or won't handle the read. */
+      stream->read_cb(stream, UV_ENOBUFS, &buf);
+      return;
+    }
+
+    assert(buf.base != NULL);
+    assert(uv__stream_fd(stream) >= 0);
+
+    if (!is_ipc) {
+      do {
+        nread = read(uv__stream_fd(stream), buf.base, buf.len);
+      }
+      while (nread < 0 && errno == EINTR);
+    } else {
+      /* ipc uses recvmsg */
+      msg.msg_flags = 0;
+      msg.msg_iov = (struct iovec*) &buf;
+      msg.msg_iovlen = 1;
+      msg.msg_name = NULL;
+      msg.msg_namelen = 0;
+      /* Set up to receive a descriptor even if one isn't in the message */
+      msg.msg_controllen = sizeof(cmsg_space);
+      msg.msg_control = cmsg_space;
+
+      do {
+        nread = uv__recvmsg(uv__stream_fd(stream), &msg, 0);
+      }
+      while (nread < 0 && errno == EINTR);
+    }
+
+    if (nread < 0) {
+      /* Error */
+      if (errno == EAGAIN || errno == EWOULDBLOCK) {
+        /* Wait for the next one. */
+        if (stream->flags & UV_STREAM_READING) {
+          uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
+          uv__stream_osx_interrupt_select(stream);
+        }
+        stream->read_cb(stream, 0, &buf);
+#if defined(__CYGWIN__) || defined(__MSYS__)
+      } else if (errno == ECONNRESET && stream->type == UV_NAMED_PIPE) {
+        uv__stream_eof(stream, &buf);
+        return;
+#endif
+      } else {
+        /* Error. User should call uv_close(). */
+        stream->read_cb(stream, UV__ERR(errno), &buf);
+        if (stream->flags & UV_STREAM_READING) {
+          stream->flags &= ~UV_STREAM_READING;
+          uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
+          if (!uv__io_active(&stream->io_watcher, POLLOUT))
+            uv__handle_stop(stream);
+          uv__stream_osx_interrupt_select(stream);
+        }
+      }
+      return;
+    } else if (nread == 0) {
+      uv__stream_eof(stream, &buf);
+      return;
+    } else {
+      /* Successful read */
+      ssize_t buflen = buf.len;
+
+      if (is_ipc) {
+        err = uv__stream_recv_cmsg(stream, &msg);
+        if (err != 0) {
+          stream->read_cb(stream, err, &buf);
+          return;
+        }
+      }
+
+#if defined(__MVS__)
+      if (is_ipc && msg.msg_controllen > 0) {
+        uv_buf_t blankbuf;
+        int nread;
+        struct iovec *old;
+
+        blankbuf.base = 0;
+        blankbuf.len = 0;
+        old = msg.msg_iov;
+        msg.msg_iov = (struct iovec*) &blankbuf;
+        nread = 0;
+        do {
+          nread = uv__recvmsg(uv__stream_fd(stream), &msg, 0);
+          err = uv__stream_recv_cmsg(stream, &msg);
+          if (err != 0) {
+            stream->read_cb(stream, err, &buf);
+            msg.msg_iov = old;
+            return;
+          }
+        } while (nread == 0 && msg.msg_controllen > 0);
+        msg.msg_iov = old;
+      }
+#endif
+      stream->read_cb(stream, nread, &buf);
+
+      /* Return if we didn't fill the buffer, there is no more data to read. */
+      if (nread < buflen) {
+        stream->flags |= UV_STREAM_READ_PARTIAL;
+        return;
+      }
+    }
+  }
+}
+
+
+#ifdef __clang__
+# pragma clang diagnostic pop
+#endif
+
+#undef UV__CMSG_FD_COUNT
+#undef UV__CMSG_FD_SIZE
+
+
+int uv_shutdown(uv_shutdown_t* req, uv_stream_t* stream, uv_shutdown_cb cb) {
+  assert(stream->type == UV_TCP ||
+         stream->type == UV_TTY ||
+         stream->type == UV_NAMED_PIPE);
+
+  if (!(stream->flags & UV_STREAM_WRITABLE) ||
+      stream->flags & UV_STREAM_SHUT ||
+      stream->flags & UV_STREAM_SHUTTING ||
+      uv__is_closing(stream)) {
+    return UV_ENOTCONN;
+  }
+
+  assert(uv__stream_fd(stream) >= 0);
+
+  /* Initialize request */
+  uv__req_init(stream->loop, req, UV_SHUTDOWN);
+  req->handle = stream;
+  req->cb = cb;
+  stream->shutdown_req = req;
+  stream->flags |= UV_STREAM_SHUTTING;
+
+  uv__io_start(stream->loop, &stream->io_watcher, POLLOUT);
+  uv__stream_osx_interrupt_select(stream);
+
+  return 0;
+}
+
+
+static void uv__stream_io(uv_loop_t* loop, uv__io_t* w, unsigned int events) {
+  uv_stream_t* stream;
+
+  stream = container_of(w, uv_stream_t, io_watcher);
+
+  assert(stream->type == UV_TCP ||
+         stream->type == UV_NAMED_PIPE ||
+         stream->type == UV_TTY);
+  assert(!(stream->flags & UV_CLOSING));
+
+  if (stream->connect_req) {
+    uv__stream_connect(stream);
+    return;
+  }
+
+  assert(uv__stream_fd(stream) >= 0);
+
+  /* Ignore POLLHUP here. Even if it's set, there may still be data to read. */
+  if (events & (POLLIN | POLLERR | POLLHUP))
+    uv__read(stream);
+
+  if (uv__stream_fd(stream) == -1)
+    return;  /* read_cb closed stream. */
+
+  /* Short-circuit iff POLLHUP is set, the user is still interested in read
+   * events and uv__read() reported a partial read but not EOF. If the EOF
+   * flag is set, uv__read() called read_cb with err=UV_EOF and we don't
+   * have to do anything. If the partial read flag is not set, we can't
+   * report the EOF yet because there is still data to read.
+   */
+  if ((events & POLLHUP) &&
+      (stream->flags & UV_STREAM_READING) &&
+      (stream->flags & UV_STREAM_READ_PARTIAL) &&
+      !(stream->flags & UV_STREAM_READ_EOF)) {
+    uv_buf_t buf = { NULL, 0 };
+    uv__stream_eof(stream, &buf);
+  }
+
+  if (uv__stream_fd(stream) == -1)
+    return;  /* read_cb closed stream. */
+
+  if (events & (POLLOUT | POLLERR | POLLHUP)) {
+    uv__write(stream);
+    uv__write_callbacks(stream);
+
+    /* Write queue drained. */
+    if (QUEUE_EMPTY(&stream->write_queue))
+      uv__drain(stream);
+  }
+}
+
+
+/**
+ * We get called here from directly following a call to connect(2).
+ * In order to determine if we've errored out or succeeded must call
+ * getsockopt.
+ */
+static void uv__stream_connect(uv_stream_t* stream) {
+  int error;
+  uv_connect_t* req = stream->connect_req;
+  socklen_t errorsize = sizeof(int);
+
+  assert(stream->type == UV_TCP || stream->type == UV_NAMED_PIPE);
+  assert(req);
+
+  if (stream->delayed_error) {
+    /* To smooth over the differences between unixes errors that
+     * were reported synchronously on the first connect can be delayed
+     * until the next tick--which is now.
+     */
+    error = stream->delayed_error;
+    stream->delayed_error = 0;
+  } else {
+    /* Normal situation: we need to get the socket error from the kernel. */
+    assert(uv__stream_fd(stream) >= 0);
+    getsockopt(uv__stream_fd(stream),
+               SOL_SOCKET,
+               SO_ERROR,
+               &error,
+               &errorsize);
+    error = UV__ERR(error);
+  }
+
+  if (error == UV__ERR(EINPROGRESS))
+    return;
+
+  stream->connect_req = NULL;
+  uv__req_unregister(stream->loop, req);
+
+  if (error < 0 || QUEUE_EMPTY(&stream->write_queue)) {
+    uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
+  }
+
+  if (req->cb)
+    req->cb(req, error);
+
+  if (uv__stream_fd(stream) == -1)
+    return;
+
+  if (error < 0) {
+    uv__stream_flush_write_queue(stream, UV_ECANCELED);
+    uv__write_callbacks(stream);
+  }
+}
+
+
+int uv_write2(uv_write_t* req,
+              uv_stream_t* stream,
+              const uv_buf_t bufs[],
+              unsigned int nbufs,
+              uv_stream_t* send_handle,
+              uv_write_cb cb) {
+  int empty_queue;
+
+  assert(nbufs > 0);
+  assert((stream->type == UV_TCP ||
+          stream->type == UV_NAMED_PIPE ||
+          stream->type == UV_TTY) &&
+         "uv_write (unix) does not yet support other types of streams");
+
+  if (uv__stream_fd(stream) < 0)
+    return UV_EBADF;
+
+  if (!(stream->flags & UV_STREAM_WRITABLE))
+    return -EPIPE;
+
+  if (send_handle) {
+    if (stream->type != UV_NAMED_PIPE || !((uv_pipe_t*)stream)->ipc)
+      return UV_EINVAL;
+
+    /* XXX We abuse uv_write2() to send over UDP handles to child processes.
+     * Don't call uv__stream_fd() on those handles, it's a macro that on OS X
+     * evaluates to a function that operates on a uv_stream_t with a couple of
+     * OS X specific fields. On other Unices it does (handle)->io_watcher.fd,
+     * which works but only by accident.
+     */
+    if (uv__handle_fd((uv_handle_t*) send_handle) < 0)
+      return UV_EBADF;
+
+#if defined(__CYGWIN__) || defined(__MSYS__)
+    /* Cygwin recvmsg always sets msg_controllen to zero, so we cannot send it.
+       See https://github.com/mirror/newlib-cygwin/blob/86fc4bf0/winsup/cygwin/fhandler_socket.cc#L1736-L1743 */
+    return UV_ENOSYS;
+#endif
+  }
+
+  /* It's legal for write_queue_size > 0 even when the write_queue is empty;
+   * it means there are error-state requests in the write_completed_queue that
+   * will touch up write_queue_size later, see also uv__write_req_finish().
+   * We could check that write_queue is empty instead but that implies making
+   * a write() syscall when we know that the handle is in error mode.
+   */
+  empty_queue = (stream->write_queue_size == 0);
+
+  /* Initialize the req */
+  uv__req_init(stream->loop, req, UV_WRITE);
+  req->cb = cb;
+  req->handle = stream;
+  req->error = 0;
+  req->send_handle = send_handle;
+  QUEUE_INIT(&req->queue);
+
+  req->bufs = req->bufsml;
+  if (nbufs > ARRAY_SIZE(req->bufsml))
+    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(bufs[0]));
+
+  if (req->bufs == NULL)
+    return UV_ENOMEM;
+
+  memcpy(req->bufs, bufs, nbufs * sizeof(bufs[0]));
+  req->nbufs = nbufs;
+  req->write_index = 0;
+  stream->write_queue_size += uv__count_bufs(bufs, nbufs);
+
+  /* Append the request to write_queue. */
+  QUEUE_INSERT_TAIL(&stream->write_queue, &req->queue);
+
+  /* If the queue was empty when this function began, we should attempt to
+   * do the write immediately. Otherwise start the write_watcher and wait
+   * for the fd to become writable.
+   */
+  if (stream->connect_req) {
+    /* Still connecting, do nothing. */
+  }
+  else if (empty_queue) {
+    uv__write(stream);
+  }
+  else {
+    /*
+     * blocking streams should never have anything in the queue.
+     * if this assert fires then somehow the blocking stream isn't being
+     * sufficiently flushed in uv__write.
+     */
+    assert(!(stream->flags & UV_STREAM_BLOCKING));
+    uv__io_start(stream->loop, &stream->io_watcher, POLLOUT);
+    uv__stream_osx_interrupt_select(stream);
+  }
+
+  return 0;
+}
+
+
+/* The buffers to be written must remain valid until the callback is called.
+ * This is not required for the uv_buf_t array.
+ */
+int uv_write(uv_write_t* req,
+             uv_stream_t* handle,
+             const uv_buf_t bufs[],
+             unsigned int nbufs,
+             uv_write_cb cb) {
+  return uv_write2(req, handle, bufs, nbufs, NULL, cb);
+}
+
+
+void uv_try_write_cb(uv_write_t* req, int status) {
+  /* Should not be called */
+  abort();
+}
+
+
+int uv_try_write(uv_stream_t* stream,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs) {
+  int r;
+  int has_pollout;
+  size_t written;
+  size_t req_size;
+  uv_write_t req;
+
+  /* Connecting or already writing some data */
+  if (stream->connect_req != NULL || stream->write_queue_size != 0)
+    return UV_EAGAIN;
+
+  has_pollout = uv__io_active(&stream->io_watcher, POLLOUT);
+
+  r = uv_write(&req, stream, bufs, nbufs, uv_try_write_cb);
+  if (r != 0)
+    return r;
+
+  /* Remove not written bytes from write queue size */
+  written = uv__count_bufs(bufs, nbufs);
+  if (req.bufs != NULL)
+    req_size = uv__write_req_size(&req);
+  else
+    req_size = 0;
+  written -= req_size;
+  stream->write_queue_size -= req_size;
+
+  /* Unqueue request, regardless of immediateness */
+  QUEUE_REMOVE(&req.queue);
+  uv__req_unregister(stream->loop, &req);
+  if (req.bufs != req.bufsml)
+    uv__free(req.bufs);
+  req.bufs = NULL;
+
+  /* Do not poll for writable, if we wasn't before calling this */
+  if (!has_pollout) {
+    uv__io_stop(stream->loop, &stream->io_watcher, POLLOUT);
+    uv__stream_osx_interrupt_select(stream);
+  }
+
+  if (written == 0 && req_size != 0)
+    return UV_EAGAIN;
+  else
+    return written;
+}
+
+
+int uv_read_start(uv_stream_t* stream,
+                  uv_alloc_cb alloc_cb,
+                  uv_read_cb read_cb) {
+  assert(stream->type == UV_TCP || stream->type == UV_NAMED_PIPE ||
+      stream->type == UV_TTY);
+
+  if (stream->flags & UV_CLOSING)
+    return UV_EINVAL;
+
+  if (!(stream->flags & UV_STREAM_READABLE))
+    return -ENOTCONN;
+
+  /* The UV_STREAM_READING flag is irrelevant of the state of the tcp - it just
+   * expresses the desired state of the user.
+   */
+  stream->flags |= UV_STREAM_READING;
+
+  /* TODO: try to do the read inline? */
+  /* TODO: keep track of tcp state. If we've gotten a EOF then we should
+   * not start the IO watcher.
+   */
+  assert(uv__stream_fd(stream) >= 0);
+  assert(alloc_cb);
+
+  stream->read_cb = read_cb;
+  stream->alloc_cb = alloc_cb;
+
+  uv__io_start(stream->loop, &stream->io_watcher, POLLIN);
+  uv__handle_start(stream);
+  uv__stream_osx_interrupt_select(stream);
+
+  return 0;
+}
+
+
+int uv_read_stop(uv_stream_t* stream) {
+  if (!(stream->flags & UV_STREAM_READING))
+    return 0;
+
+  stream->flags &= ~UV_STREAM_READING;
+  uv__io_stop(stream->loop, &stream->io_watcher, POLLIN);
+  if (!uv__io_active(&stream->io_watcher, POLLOUT))
+    uv__handle_stop(stream);
+  uv__stream_osx_interrupt_select(stream);
+
+  stream->read_cb = NULL;
+  stream->alloc_cb = NULL;
+  return 0;
+}
+
+
+int uv_is_readable(const uv_stream_t* stream) {
+  return !!(stream->flags & UV_STREAM_READABLE);
+}
+
+
+int uv_is_writable(const uv_stream_t* stream) {
+  return !!(stream->flags & UV_STREAM_WRITABLE);
+}
+
+
+#if defined(__APPLE__)
+int uv___stream_fd(const uv_stream_t* handle) {
+  const uv__stream_select_t* s;
+
+  assert(handle->type == UV_TCP ||
+         handle->type == UV_TTY ||
+         handle->type == UV_NAMED_PIPE);
+
+  s = (const uv__stream_select_t*)handle->select;
+  if (s != NULL)
+    return s->fd;
+
+  return handle->io_watcher.fd;
+}
+#endif /* defined(__APPLE__) */
+
+
+void uv__stream_close(uv_stream_t* handle) {
+  unsigned int i;
+  uv__stream_queued_fds_t* queued_fds;
+
+#if defined(__APPLE__)
+  /* Terminate select loop first */
+  if (handle->select != NULL) {
+    uv__stream_select_t* s;
+
+    s = (uv__stream_select_t*)handle->select;
+
+    uv_sem_post(&s->close_sem);
+    uv_sem_post(&s->async_sem);
+    uv__stream_osx_interrupt_select(handle);
+    uv_thread_join(&s->thread);
+    uv_sem_destroy(&s->close_sem);
+    uv_sem_destroy(&s->async_sem);
+    uv__close(s->fake_fd);
+    uv__close(s->int_fd);
+    uv_close((uv_handle_t*) &s->async, uv__stream_osx_cb_close);
+
+    handle->select = NULL;
+  }
+#endif /* defined(__APPLE__) */
+
+  uv__io_close(handle->loop, &handle->io_watcher);
+  uv_read_stop(handle);
+  uv__handle_stop(handle);
+
+  if (handle->io_watcher.fd != -1) {
+    /* Don't close stdio file descriptors.  Nothing good comes from it. */
+    if (handle->io_watcher.fd > STDERR_FILENO)
+      uv__close(handle->io_watcher.fd);
+    handle->io_watcher.fd = -1;
+  }
+
+  if (handle->accepted_fd != -1) {
+    uv__close(handle->accepted_fd);
+    handle->accepted_fd = -1;
+  }
+
+  /* Close all queued fds */
+  if (handle->queued_fds != NULL) {
+    queued_fds = (uv__stream_queued_fds_t*)(handle->queued_fds);
+    for (i = 0; i < queued_fds->offset; i++)
+      uv__close(queued_fds->fds[i]);
+    uv__free(handle->queued_fds);
+    handle->queued_fds = NULL;
+  }
+
+  assert(!uv__io_active(&handle->io_watcher, POLLIN | POLLOUT));
+}
+
+
+int uv_stream_set_blocking(uv_stream_t* handle, int blocking) {
+  /* Don't need to check the file descriptor, uv__nonblock()
+   * will fail with EBADF if it's not valid.
+   */
+  return uv__nonblock(uv__stream_fd(handle), !blocking);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/sysinfo-loadavg.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/sysinfo-loadavg.cpp
new file mode 100644
index 0000000..ebad0e8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/sysinfo-loadavg.cpp
@@ -0,0 +1,36 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdint.h>
+#include <sys/sysinfo.h>
+
+void uv_loadavg(double avg[3]) {
+  struct sysinfo info;
+
+  if (sysinfo(&info) < 0) return;
+
+  avg[0] = (double) info.loads[0] / 65536.0;
+  avg[1] = (double) info.loads[1] / 65536.0;
+  avg[2] = (double) info.loads[2] / 65536.0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/sysinfo-memory.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/sysinfo-memory.cpp
new file mode 100644
index 0000000..23b4fc6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/sysinfo-memory.cpp
@@ -0,0 +1,42 @@
+/* Copyright libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdint.h>
+#include <sys/sysinfo.h>
+
+uint64_t uv_get_free_memory(void) {
+  struct sysinfo info;
+
+  if (sysinfo(&info) == 0)
+    return (uint64_t) info.freeram * info.mem_unit;
+  return 0;
+}
+
+uint64_t uv_get_total_memory(void) {
+  struct sysinfo info;
+
+  if (sysinfo(&info) == 0)
+    return (uint64_t) info.totalram * info.mem_unit;
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/tcp.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/tcp.cpp
new file mode 100644
index 0000000..27a2a61
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/tcp.cpp
@@ -0,0 +1,445 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <stdlib.h>
+#include <unistd.h>
+#include <assert.h>
+#include <errno.h>
+
+
+static int new_socket(uv_tcp_t* handle, int domain, unsigned long flags) {
+  struct sockaddr_storage saddr;
+  socklen_t slen;
+  int sockfd;
+  int err;
+
+  err = uv__socket(domain, SOCK_STREAM, 0);
+  if (err < 0)
+    return err;
+  sockfd = err;
+
+  err = uv__stream_open((uv_stream_t*) handle, sockfd, flags);
+  if (err) {
+    uv__close(sockfd);
+    return err;
+  }
+
+  if (flags & UV_HANDLE_BOUND) {
+    /* Bind this new socket to an arbitrary port */
+    slen = sizeof(saddr);
+    memset(&saddr, 0, sizeof(saddr));
+    if (getsockname(uv__stream_fd(handle), (struct sockaddr*) &saddr, &slen)) {
+      uv__close(sockfd);
+      return UV__ERR(errno);
+    }
+
+    if (bind(uv__stream_fd(handle), (struct sockaddr*) &saddr, slen)) {
+      uv__close(sockfd);
+      return UV__ERR(errno);
+    }
+  }
+
+  return 0;
+}
+
+
+static int maybe_new_socket(uv_tcp_t* handle, int domain, unsigned long flags) {
+  struct sockaddr_storage saddr;
+  socklen_t slen;
+
+  if (domain == AF_UNSPEC) {
+    handle->flags |= flags;
+    return 0;
+  }
+
+  if (uv__stream_fd(handle) != -1) {
+
+    if (flags & UV_HANDLE_BOUND) {
+
+      if (handle->flags & UV_HANDLE_BOUND) {
+        /* It is already bound to a port. */
+        handle->flags |= flags;
+        return 0;
+      }
+      
+      /* Query to see if tcp socket is bound. */
+      slen = sizeof(saddr);
+      memset(&saddr, 0, sizeof(saddr));
+      if (getsockname(uv__stream_fd(handle), (struct sockaddr*) &saddr, &slen))
+        return UV__ERR(errno);
+
+      if ((saddr.ss_family == AF_INET6 &&
+          ((struct sockaddr_in6*) &saddr)->sin6_port != 0) ||
+          (saddr.ss_family == AF_INET &&
+          ((struct sockaddr_in*) &saddr)->sin_port != 0)) {
+        /* Handle is already bound to a port. */
+        handle->flags |= flags;
+        return 0;
+      }
+
+      /* Bind to arbitrary port */
+      if (bind(uv__stream_fd(handle), (struct sockaddr*) &saddr, slen))
+        return UV__ERR(errno);
+    }
+
+    handle->flags |= flags;
+    return 0;
+  }
+
+  return new_socket(handle, domain, flags);
+}
+
+
+int uv_tcp_init_ex(uv_loop_t* loop, uv_tcp_t* tcp, unsigned int flags) {
+  int domain;
+
+  /* Use the lower 8 bits for the domain */
+  domain = flags & 0xFF;
+  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
+    return UV_EINVAL;
+
+  if (flags & ~0xFF)
+    return UV_EINVAL;
+
+  uv__stream_init(loop, (uv_stream_t*)tcp, UV_TCP);
+
+  /* If anything fails beyond this point we need to remove the handle from
+   * the handle queue, since it was added by uv__handle_init in uv_stream_init.
+   */
+
+  if (domain != AF_UNSPEC) {
+    int err = maybe_new_socket(tcp, domain, 0);
+    if (err) {
+      QUEUE_REMOVE(&tcp->handle_queue);
+      return err;
+    }
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_init(uv_loop_t* loop, uv_tcp_t* tcp) {
+  return uv_tcp_init_ex(loop, tcp, AF_UNSPEC);
+}
+
+
+int uv__tcp_bind(uv_tcp_t* tcp,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags) {
+  int err;
+  int on;
+
+  /* Cannot set IPv6-only mode on non-IPv6 socket. */
+  if ((flags & UV_TCP_IPV6ONLY) && addr->sa_family != AF_INET6)
+    return UV_EINVAL;
+
+  err = maybe_new_socket(tcp, addr->sa_family, 0);
+  if (err)
+    return err;
+
+  on = 1;
+  if (setsockopt(tcp->io_watcher.fd, SOL_SOCKET, SO_REUSEADDR, &on, sizeof(on)))
+    return UV__ERR(errno);
+
+#ifndef __OpenBSD__
+#ifdef IPV6_V6ONLY
+  if (addr->sa_family == AF_INET6) {
+    on = (flags & UV_TCP_IPV6ONLY) != 0;
+    if (setsockopt(tcp->io_watcher.fd,
+                   IPPROTO_IPV6,
+                   IPV6_V6ONLY,
+                   &on,
+                   sizeof on) == -1) {
+#if defined(__MVS__)
+      if (errno == EOPNOTSUPP)
+        return UV_EINVAL;
+#endif
+      return UV__ERR(errno);
+    }
+  }
+#endif
+#endif
+
+  errno = 0;
+  if (bind(tcp->io_watcher.fd, addr, addrlen) && errno != EADDRINUSE) {
+    if (errno == EAFNOSUPPORT)
+      /* OSX, other BSDs and SunoS fail with EAFNOSUPPORT when binding a
+       * socket created with AF_INET to an AF_INET6 address or vice versa. */
+      return UV_EINVAL;
+    return UV__ERR(errno);
+  }
+  tcp->delayed_error = UV__ERR(errno);
+
+  tcp->flags |= UV_HANDLE_BOUND;
+  if (addr->sa_family == AF_INET6)
+    tcp->flags |= UV_HANDLE_IPV6;
+
+  return 0;
+}
+
+
+int uv__tcp_connect(uv_connect_t* req,
+                    uv_tcp_t* handle,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen,
+                    uv_connect_cb cb) {
+  int err;
+  int r;
+
+  assert(handle->type == UV_TCP);
+
+  if (handle->connect_req != NULL)
+    return UV_EALREADY;  /* FIXME(bnoordhuis) UV_EINVAL or maybe UV_EBUSY. */
+
+  err = maybe_new_socket(handle,
+                         addr->sa_family,
+                         UV_STREAM_READABLE | UV_STREAM_WRITABLE);
+  if (err)
+    return err;
+
+  handle->delayed_error = 0;
+
+  do {
+    errno = 0;
+    r = connect(uv__stream_fd(handle), addr, addrlen);
+  } while (r == -1 && errno == EINTR);
+
+  /* We not only check the return value, but also check the errno != 0.
+   * Because in rare cases connect() will return -1 but the errno
+   * is 0 (for example, on Android 4.3, OnePlus phone A0001_12_150227)
+   * and actually the tcp three-way handshake is completed.
+   */
+  if (r == -1 && errno != 0) {
+    if (errno == EINPROGRESS)
+      ; /* not an error */
+    else if (errno == ECONNREFUSED)
+    /* If we get a ECONNREFUSED wait until the next tick to report the
+     * error. Solaris wants to report immediately--other unixes want to
+     * wait.
+     */
+      handle->delayed_error = UV__ERR(errno);
+    else
+      return UV__ERR(errno);
+  }
+
+  uv__req_init(handle->loop, req, UV_CONNECT);
+  req->cb = cb;
+  req->handle = (uv_stream_t*) handle;
+  QUEUE_INIT(&req->queue);
+  handle->connect_req = req;
+
+  uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
+
+  if (handle->delayed_error)
+    uv__io_feed(handle->loop, &handle->io_watcher);
+
+  return 0;
+}
+
+
+int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock) {
+  int err;
+
+  if (uv__fd_exists(handle->loop, sock))
+    return UV_EEXIST;
+
+  err = uv__nonblock(sock, 1);
+  if (err)
+    return err;
+
+  return uv__stream_open((uv_stream_t*)handle,
+                         sock,
+                         UV_STREAM_READABLE | UV_STREAM_WRITABLE);
+}
+
+
+int uv_tcp_getsockname(const uv_tcp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+  socklen_t socklen;
+
+  if (handle->delayed_error)
+    return handle->delayed_error;
+
+  if (uv__stream_fd(handle) < 0)
+    return UV_EINVAL;  /* FIXME(bnoordhuis) UV_EBADF */
+
+  /* sizeof(socklen_t) != sizeof(int) on some systems. */
+  socklen = (socklen_t) *namelen;
+
+  if (getsockname(uv__stream_fd(handle), name, &socklen))
+    return UV__ERR(errno);
+
+  *namelen = (int) socklen;
+  return 0;
+}
+
+
+int uv_tcp_getpeername(const uv_tcp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+  socklen_t socklen;
+
+  if (handle->delayed_error)
+    return handle->delayed_error;
+
+  if (uv__stream_fd(handle) < 0)
+    return UV_EINVAL;  /* FIXME(bnoordhuis) UV_EBADF */
+
+  /* sizeof(socklen_t) != sizeof(int) on some systems. */
+  socklen = (socklen_t) *namelen;
+
+  if (getpeername(uv__stream_fd(handle), name, &socklen))
+    return UV__ERR(errno);
+
+  *namelen = (int) socklen;
+  return 0;
+}
+
+
+int uv_tcp_listen(uv_tcp_t* tcp, int backlog, uv_connection_cb cb) {
+  static int single_accept = -1;
+  unsigned long flags;
+  int err;
+
+  if (tcp->delayed_error)
+    return tcp->delayed_error;
+
+  if (single_accept == -1) {
+    const char* val = getenv("UV_TCP_SINGLE_ACCEPT");
+    single_accept = (val != NULL && atoi(val) != 0);  /* Off by default. */
+  }
+
+  if (single_accept)
+    tcp->flags |= UV_TCP_SINGLE_ACCEPT;
+
+  flags = 0;
+#if defined(__MVS__)
+  /* on zOS the listen call does not bind automatically
+     if the socket is unbound. Hence the manual binding to
+     an arbitrary port is required to be done manually
+  */
+  flags |= UV_HANDLE_BOUND;
+#endif
+  err = maybe_new_socket(tcp, AF_INET, flags);
+  if (err)
+    return err;
+
+  if (listen(tcp->io_watcher.fd, backlog))
+    return UV__ERR(errno);
+
+  tcp->connection_cb = cb;
+  tcp->flags |= UV_HANDLE_BOUND;
+
+  /* Start listening for connections. */
+  tcp->io_watcher.cb = uv__server_io;
+  uv__io_start(tcp->loop, &tcp->io_watcher, POLLIN);
+
+  return 0;
+}
+
+
+int uv__tcp_nodelay(int fd, int on) {
+  if (setsockopt(fd, IPPROTO_TCP, TCP_NODELAY, &on, sizeof(on)))
+    return UV__ERR(errno);
+  return 0;
+}
+
+
+int uv__tcp_keepalive(int fd, int on, unsigned int delay) {
+  if (setsockopt(fd, SOL_SOCKET, SO_KEEPALIVE, &on, sizeof(on)))
+    return UV__ERR(errno);
+
+#ifdef TCP_KEEPIDLE
+  if (on && setsockopt(fd, IPPROTO_TCP, TCP_KEEPIDLE, &delay, sizeof(delay)))
+    return UV__ERR(errno);
+#endif
+
+  /* Solaris/SmartOS, if you don't support keep-alive,
+   * then don't advertise it in your system headers...
+   */
+  /* FIXME(bnoordhuis) That's possibly because sizeof(delay) should be 1. */
+#if defined(TCP_KEEPALIVE) && !defined(__sun)
+  if (on && setsockopt(fd, IPPROTO_TCP, TCP_KEEPALIVE, &delay, sizeof(delay)))
+    return UV__ERR(errno);
+#endif
+
+  return 0;
+}
+
+
+int uv_tcp_nodelay(uv_tcp_t* handle, int on) {
+  int err;
+
+  if (uv__stream_fd(handle) != -1) {
+    err = uv__tcp_nodelay(uv__stream_fd(handle), on);
+    if (err)
+      return err;
+  }
+
+  if (on)
+    handle->flags |= UV_TCP_NODELAY;
+  else
+    handle->flags &= ~UV_TCP_NODELAY;
+
+  return 0;
+}
+
+
+int uv_tcp_keepalive(uv_tcp_t* handle, int on, unsigned int delay) {
+  int err;
+
+  if (uv__stream_fd(handle) != -1) {
+    err =uv__tcp_keepalive(uv__stream_fd(handle), on, delay);
+    if (err)
+      return err;
+  }
+
+  if (on)
+    handle->flags |= UV_TCP_KEEPALIVE;
+  else
+    handle->flags &= ~UV_TCP_KEEPALIVE;
+
+  /* TODO Store delay if uv__stream_fd(handle) == -1 but don't want to enlarge
+   *      uv_tcp_t with an int that's almost never used...
+   */
+
+  return 0;
+}
+
+
+int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable) {
+  if (enable)
+    handle->flags &= ~UV_TCP_SINGLE_ACCEPT;
+  else
+    handle->flags |= UV_TCP_SINGLE_ACCEPT;
+  return 0;
+}
+
+
+void uv__tcp_close(uv_tcp_t* handle) {
+  uv__stream_close((uv_stream_t*)handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/thread.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/thread.cpp
new file mode 100644
index 0000000..988b6fc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/thread.cpp
@@ -0,0 +1,812 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <pthread.h>
+#include <assert.h>
+#include <errno.h>
+
+#include <sys/time.h>
+#include <sys/resource.h>  /* getrlimit() */
+#include <unistd.h>  /* getpagesize() */
+
+#include <limits.h>
+
+#ifdef __MVS__
+#include <sys/ipc.h>
+#include <sys/sem.h>
+#endif
+
+#ifdef __GLIBC__
+#include <gnu/libc-version.h>  /* gnu_get_libc_version() */
+#endif
+
+#undef NANOSEC
+#define NANOSEC ((uint64_t) 1e9)
+
+
+#if defined(UV__PTHREAD_BARRIER_FALLBACK)
+/* TODO: support barrier_attr */
+int pthread_barrier_init(pthread_barrier_t* barrier,
+                         const void* barrier_attr,
+                         unsigned count) {
+  int rc;
+  _uv_barrier* b;
+
+  if (barrier == NULL || count == 0)
+    return EINVAL;
+
+  if (barrier_attr != NULL)
+    return ENOTSUP;
+
+  b = (_uv_barrier*)uv__malloc(sizeof(*b));
+  if (b == NULL)
+    return ENOMEM;
+
+  b->in = 0;
+  b->out = 0;
+  b->threshold = count;
+
+  if ((rc = pthread_mutex_init(&b->mutex, NULL)) != 0)
+    goto error2;
+  if ((rc = pthread_cond_init(&b->cond, NULL)) != 0)
+    goto error;
+
+  barrier->b = b;
+  return 0;
+
+error:
+  pthread_mutex_destroy(&b->mutex);
+error2:
+  uv__free(b);
+  return rc;
+}
+
+int pthread_barrier_wait(pthread_barrier_t* barrier) {
+  int rc;
+  _uv_barrier* b;
+
+  if (barrier == NULL || barrier->b == NULL)
+    return EINVAL;
+
+  b = barrier->b;
+  /* Lock the mutex*/
+  if ((rc = pthread_mutex_lock(&b->mutex)) != 0)
+    return rc;
+
+  /* Increment the count. If this is the first thread to reach the threshold,
+     wake up waiters, unlock the mutex, then return
+     PTHREAD_BARRIER_SERIAL_THREAD. */
+  if (++b->in == b->threshold) {
+    b->in = 0;
+    b->out = b->threshold - 1;
+    rc = pthread_cond_signal(&b->cond);
+    assert(rc == 0);
+
+    pthread_mutex_unlock(&b->mutex);
+    return PTHREAD_BARRIER_SERIAL_THREAD;
+  }
+  /* Otherwise, wait for other threads until in is set to 0,
+     then return 0 to indicate this is not the first thread. */
+  do {
+    if ((rc = pthread_cond_wait(&b->cond, &b->mutex)) != 0)
+      break;
+  } while (b->in != 0);
+
+  /* mark thread exit */
+  b->out--;
+  pthread_cond_signal(&b->cond);
+  pthread_mutex_unlock(&b->mutex);
+  return rc;
+}
+
+int pthread_barrier_destroy(pthread_barrier_t* barrier) {
+  int rc;
+  _uv_barrier* b;
+
+  if (barrier == NULL || barrier->b == NULL)
+    return EINVAL;
+
+  b = barrier->b;
+
+  if ((rc = pthread_mutex_lock(&b->mutex)) != 0)
+    return rc;
+
+  if (b->in > 0 || b->out > 0)
+    rc = EBUSY;
+
+  pthread_mutex_unlock(&b->mutex);
+
+  if (rc)
+    return rc;
+
+  pthread_cond_destroy(&b->cond);
+  pthread_mutex_destroy(&b->mutex);
+  uv__free(barrier->b);
+  barrier->b = NULL;
+  return 0;
+}
+#endif
+
+
+/* On MacOS, threads other than the main thread are created with a reduced
+ * stack size by default.  Adjust to RLIMIT_STACK aligned to the page size.
+ *
+ * On Linux, threads created by musl have a much smaller stack than threads
+ * created by glibc (80 vs. 2048 or 4096 kB.)  Follow glibc for consistency.
+ */
+static size_t thread_stack_size(void) {
+#if defined(__APPLE__) || defined(__linux__)
+  struct rlimit lim;
+
+  if (getrlimit(RLIMIT_STACK, &lim))
+    abort();
+
+  if (lim.rlim_cur != RLIM_INFINITY) {
+    /* pthread_attr_setstacksize() expects page-aligned values. */
+    lim.rlim_cur -= lim.rlim_cur % (rlim_t) getpagesize();
+    if (lim.rlim_cur >= PTHREAD_STACK_MIN)
+      return lim.rlim_cur;
+  }
+#endif
+
+#if !defined(__linux__)
+  return 0;
+#elif defined(__PPC__) || defined(__ppc__) || defined(__powerpc__)
+  return 4 << 20;  /* glibc default. */
+#else
+  return 2 << 20;  /* glibc default. */
+#endif
+}
+
+
+int uv_thread_create(uv_thread_t *tid, void (*entry)(void *arg), void *arg) {
+  int err;
+  size_t stack_size;
+  pthread_attr_t* attr;
+  pthread_attr_t attr_storage;
+
+  attr = NULL;
+  stack_size = thread_stack_size();
+
+  if (stack_size > 0) {
+    attr = &attr_storage;
+
+    if (pthread_attr_init(attr))
+      abort();
+
+    if (pthread_attr_setstacksize(attr, stack_size))
+      abort();
+  }
+
+  err = pthread_create(tid, attr, (void*(*)(void*)) (void(*)(void)) entry, arg);
+
+  if (attr != NULL)
+    pthread_attr_destroy(attr);
+
+  return UV__ERR(err);
+}
+
+
+uv_thread_t uv_thread_self(void) {
+  return pthread_self();
+}
+
+int uv_thread_join(uv_thread_t *tid) {
+  return UV__ERR(pthread_join(*tid, NULL));
+}
+
+
+int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2) {
+  return pthread_equal(*t1, *t2);
+}
+
+
+int uv_mutex_init(uv_mutex_t* mutex) {
+#if defined(NDEBUG) || !defined(PTHREAD_MUTEX_ERRORCHECK)
+  return UV__ERR(pthread_mutex_init(mutex, NULL));
+#else
+  pthread_mutexattr_t attr;
+  int err;
+
+  if (pthread_mutexattr_init(&attr))
+    abort();
+
+  if (pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_ERRORCHECK))
+    abort();
+
+  err = pthread_mutex_init(mutex, &attr);
+
+  if (pthread_mutexattr_destroy(&attr))
+    abort();
+
+  return UV__ERR(err);
+#endif
+}
+
+
+int uv_mutex_init_recursive(uv_mutex_t* mutex) {
+  pthread_mutexattr_t attr;
+  int err;
+
+  if (pthread_mutexattr_init(&attr))
+    abort();
+
+  if (pthread_mutexattr_settype(&attr, PTHREAD_MUTEX_RECURSIVE))
+    abort();
+
+  err = pthread_mutex_init(mutex, &attr);
+
+  if (pthread_mutexattr_destroy(&attr))
+    abort();
+
+  return UV__ERR(err);
+}
+
+
+void uv_mutex_destroy(uv_mutex_t* mutex) {
+  if (pthread_mutex_destroy(mutex))
+    abort();
+}
+
+
+void uv_mutex_lock(uv_mutex_t* mutex) {
+  if (pthread_mutex_lock(mutex))
+    abort();
+}
+
+
+int uv_mutex_trylock(uv_mutex_t* mutex) {
+  int err;
+
+  err = pthread_mutex_trylock(mutex);
+  if (err) {
+    if (err != EBUSY && err != EAGAIN)
+      abort();
+    return UV_EBUSY;
+  }
+
+  return 0;
+}
+
+
+void uv_mutex_unlock(uv_mutex_t* mutex) {
+  if (pthread_mutex_unlock(mutex))
+    abort();
+}
+
+
+int uv_rwlock_init(uv_rwlock_t* rwlock) {
+  return UV__ERR(pthread_rwlock_init(rwlock, NULL));
+}
+
+
+void uv_rwlock_destroy(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_destroy(rwlock))
+    abort();
+}
+
+
+void uv_rwlock_rdlock(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_rdlock(rwlock))
+    abort();
+}
+
+
+int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock) {
+  int err;
+
+  err = pthread_rwlock_tryrdlock(rwlock);
+  if (err) {
+    if (err != EBUSY && err != EAGAIN)
+      abort();
+    return UV_EBUSY;
+  }
+
+  return 0;
+}
+
+
+void uv_rwlock_rdunlock(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_unlock(rwlock))
+    abort();
+}
+
+
+void uv_rwlock_wrlock(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_wrlock(rwlock))
+    abort();
+}
+
+
+int uv_rwlock_trywrlock(uv_rwlock_t* rwlock) {
+  int err;
+
+  err = pthread_rwlock_trywrlock(rwlock);
+  if (err) {
+    if (err != EBUSY && err != EAGAIN)
+      abort();
+    return UV_EBUSY;
+  }
+
+  return 0;
+}
+
+
+void uv_rwlock_wrunlock(uv_rwlock_t* rwlock) {
+  if (pthread_rwlock_unlock(rwlock))
+    abort();
+}
+
+
+void uv_once(uv_once_t* guard, void (*callback)(void)) {
+  if (pthread_once(guard, callback))
+    abort();
+}
+
+#if defined(__APPLE__) && defined(__MACH__)
+
+int uv_sem_init(uv_sem_t* sem, unsigned int value) {
+  kern_return_t err;
+
+  err = semaphore_create(mach_task_self(), sem, SYNC_POLICY_FIFO, value);
+  if (err == KERN_SUCCESS)
+    return 0;
+  if (err == KERN_INVALID_ARGUMENT)
+    return UV_EINVAL;
+  if (err == KERN_RESOURCE_SHORTAGE)
+    return UV_ENOMEM;
+
+  abort();
+  return UV_EINVAL;  /* Satisfy the compiler. */
+}
+
+
+void uv_sem_destroy(uv_sem_t* sem) {
+  if (semaphore_destroy(mach_task_self(), *sem))
+    abort();
+}
+
+
+void uv_sem_post(uv_sem_t* sem) {
+  if (semaphore_signal(*sem))
+    abort();
+}
+
+
+void uv_sem_wait(uv_sem_t* sem) {
+  int r;
+
+  do
+    r = semaphore_wait(*sem);
+  while (r == KERN_ABORTED);
+
+  if (r != KERN_SUCCESS)
+    abort();
+}
+
+
+int uv_sem_trywait(uv_sem_t* sem) {
+  mach_timespec_t interval;
+  kern_return_t err;
+
+  interval.tv_sec = 0;
+  interval.tv_nsec = 0;
+
+  err = semaphore_timedwait(*sem, interval);
+  if (err == KERN_SUCCESS)
+    return 0;
+  if (err == KERN_OPERATION_TIMED_OUT)
+    return UV_EAGAIN;
+
+  abort();
+  return UV_EINVAL;  /* Satisfy the compiler. */
+}
+
+#else /* !(defined(__APPLE__) && defined(__MACH__)) */
+
+#ifdef __GLIBC__
+
+/* Hack around https://sourceware.org/bugzilla/show_bug.cgi?id=12674
+ * by providing a custom implementation for glibc < 2.21 in terms of other
+ * concurrency primitives.
+ * Refs: https://github.com/nodejs/node/issues/19903 */
+
+/* To preserve ABI compatibility, we treat the uv_sem_t as storage for
+ * a pointer to the actual struct we're using underneath. */
+
+static uv_once_t glibc_version_check_once = UV_ONCE_INIT;
+static int platform_needs_custom_semaphore = 0;
+
+static void glibc_version_check(void) {
+  const char* version = gnu_get_libc_version();
+  platform_needs_custom_semaphore =
+      version[0] == '2' && version[1] == '.' &&
+      atoi(version + 2) < 21;
+}
+
+#elif defined(__MVS__)
+
+#define platform_needs_custom_semaphore 1
+
+#else /* !defined(__GLIBC__) && !defined(__MVS__) */
+
+#define platform_needs_custom_semaphore 0
+
+#endif
+
+typedef struct uv_semaphore_s {
+  uv_mutex_t mutex;
+  uv_cond_t cond;
+  unsigned int value;
+} uv_semaphore_t;
+
+#if defined(__GLIBC__) || platform_needs_custom_semaphore
+STATIC_ASSERT(sizeof(uv_sem_t) >= sizeof(uv_semaphore_t*));
+#endif
+
+static int uv__custom_sem_init(uv_sem_t* sem_, unsigned int value) {
+  int err;
+  uv_semaphore_t* sem;
+
+  sem = (uv_semaphore_t*)uv__malloc(sizeof(*sem));
+  if (sem == NULL)
+    return UV_ENOMEM;
+
+  if ((err = uv_mutex_init(&sem->mutex)) != 0) {
+    uv__free(sem);
+    return err;
+  }
+
+  if ((err = uv_cond_init(&sem->cond)) != 0) {
+    uv_mutex_destroy(&sem->mutex);
+    uv__free(sem);
+    return err;
+  }
+
+  sem->value = value;
+  *(uv_semaphore_t**)sem_ = sem;
+  return 0;
+}
+
+
+static void uv__custom_sem_destroy(uv_sem_t* sem_) {
+  uv_semaphore_t* sem;
+
+  sem = *(uv_semaphore_t**)sem_;
+  uv_cond_destroy(&sem->cond);
+  uv_mutex_destroy(&sem->mutex);
+  uv__free(sem);
+}
+
+
+static void uv__custom_sem_post(uv_sem_t* sem_) {
+  uv_semaphore_t* sem;
+
+  sem = *(uv_semaphore_t**)sem_;
+  uv_mutex_lock(&sem->mutex);
+  sem->value++;
+  if (sem->value == 1)
+    uv_cond_signal(&sem->cond);
+  uv_mutex_unlock(&sem->mutex);
+}
+
+
+static void uv__custom_sem_wait(uv_sem_t* sem_) {
+  uv_semaphore_t* sem;
+
+  sem = *(uv_semaphore_t**)sem_;
+  uv_mutex_lock(&sem->mutex);
+  while (sem->value == 0)
+    uv_cond_wait(&sem->cond, &sem->mutex);
+  sem->value--;
+  uv_mutex_unlock(&sem->mutex);
+}
+
+
+static int uv__custom_sem_trywait(uv_sem_t* sem_) {
+  uv_semaphore_t* sem;
+
+  sem = *(uv_semaphore_t**)sem_;
+  if (uv_mutex_trylock(&sem->mutex) != 0)
+    return UV_EAGAIN;
+
+  if (sem->value == 0) {
+    uv_mutex_unlock(&sem->mutex);
+    return UV_EAGAIN;
+  }
+
+  sem->value--;
+  uv_mutex_unlock(&sem->mutex);
+
+  return 0;
+}
+
+static int uv__sem_init(uv_sem_t* sem, unsigned int value) {
+  if (sem_init(sem, 0, value))
+    return UV__ERR(errno);
+  return 0;
+}
+
+
+static void uv__sem_destroy(uv_sem_t* sem) {
+  if (sem_destroy(sem))
+    abort();
+}
+
+
+static void uv__sem_post(uv_sem_t* sem) {
+  if (sem_post(sem))
+    abort();
+}
+
+
+static void uv__sem_wait(uv_sem_t* sem) {
+  int r;
+
+  do
+    r = sem_wait(sem);
+  while (r == -1 && errno == EINTR);
+
+  if (r)
+    abort();
+}
+
+
+static int uv__sem_trywait(uv_sem_t* sem) {
+  int r;
+
+  do
+    r = sem_trywait(sem);
+  while (r == -1 && errno == EINTR);
+
+  if (r) {
+    if (errno == EAGAIN)
+      return UV_EAGAIN;
+    abort();
+  }
+
+  return 0;
+}
+
+int uv_sem_init(uv_sem_t* sem, unsigned int value) {
+#ifdef __GLIBC__
+  uv_once(&glibc_version_check_once, glibc_version_check);
+#endif
+
+  if (platform_needs_custom_semaphore)
+    return uv__custom_sem_init(sem, value);
+  else
+    return uv__sem_init(sem, value);
+}
+
+
+void uv_sem_destroy(uv_sem_t* sem) {
+  if (platform_needs_custom_semaphore)
+    uv__custom_sem_destroy(sem);
+  else
+    uv__sem_destroy(sem);
+}
+
+
+void uv_sem_post(uv_sem_t* sem) {
+  if (platform_needs_custom_semaphore)
+    uv__custom_sem_post(sem);
+  else
+    uv__sem_post(sem);
+}
+
+
+void uv_sem_wait(uv_sem_t* sem) {
+  if (platform_needs_custom_semaphore)
+    uv__custom_sem_wait(sem);
+  else
+    uv__sem_wait(sem);
+}
+
+
+int uv_sem_trywait(uv_sem_t* sem) {
+  if (platform_needs_custom_semaphore)
+    return uv__custom_sem_trywait(sem);
+  else
+    return uv__sem_trywait(sem);
+}
+
+#endif /* defined(__APPLE__) && defined(__MACH__) */
+
+
+#if defined(__APPLE__) && defined(__MACH__) || defined(__MVS__)
+
+int uv_cond_init(uv_cond_t* cond) {
+  return UV__ERR(pthread_cond_init(cond, NULL));
+}
+
+#else /* !(defined(__APPLE__) && defined(__MACH__)) */
+
+int uv_cond_init(uv_cond_t* cond) {
+  pthread_condattr_t attr;
+  int err;
+
+  err = pthread_condattr_init(&attr);
+  if (err)
+    return UV__ERR(err);
+
+#if !(defined(__ANDROID_API__) && __ANDROID_API__ < 21)
+  err = pthread_condattr_setclock(&attr, CLOCK_MONOTONIC);
+  if (err)
+    goto error2;
+#endif
+
+  err = pthread_cond_init(cond, &attr);
+  if (err)
+    goto error2;
+
+  err = pthread_condattr_destroy(&attr);
+  if (err)
+    goto error;
+
+  return 0;
+
+error:
+  pthread_cond_destroy(cond);
+error2:
+  pthread_condattr_destroy(&attr);
+  return UV__ERR(err);
+}
+
+#endif /* defined(__APPLE__) && defined(__MACH__) */
+
+void uv_cond_destroy(uv_cond_t* cond) {
+#if defined(__APPLE__) && defined(__MACH__)
+  /* It has been reported that destroying condition variables that have been
+   * signalled but not waited on can sometimes result in application crashes.
+   * See https://codereview.chromium.org/1323293005.
+   */
+  pthread_mutex_t mutex;
+  struct timespec ts;
+  int err;
+
+  if (pthread_mutex_init(&mutex, NULL))
+    abort();
+
+  if (pthread_mutex_lock(&mutex))
+    abort();
+
+  ts.tv_sec = 0;
+  ts.tv_nsec = 1;
+
+  err = pthread_cond_timedwait_relative_np(cond, &mutex, &ts);
+  if (err != 0 && err != ETIMEDOUT)
+    abort();
+
+  if (pthread_mutex_unlock(&mutex))
+    abort();
+
+  if (pthread_mutex_destroy(&mutex))
+    abort();
+#endif /* defined(__APPLE__) && defined(__MACH__) */
+
+  if (pthread_cond_destroy(cond))
+    abort();
+}
+
+void uv_cond_signal(uv_cond_t* cond) {
+  if (pthread_cond_signal(cond))
+    abort();
+}
+
+void uv_cond_broadcast(uv_cond_t* cond) {
+  if (pthread_cond_broadcast(cond))
+    abort();
+}
+
+void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex) {
+  if (pthread_cond_wait(cond, mutex))
+    abort();
+}
+
+
+int uv_cond_timedwait(uv_cond_t* cond, uv_mutex_t* mutex, uint64_t timeout) {
+  int r;
+  struct timespec ts;
+#if defined(__MVS__)
+  struct timeval tv;
+#endif
+
+#if defined(__APPLE__) && defined(__MACH__)
+  ts.tv_sec = timeout / NANOSEC;
+  ts.tv_nsec = timeout % NANOSEC;
+  r = pthread_cond_timedwait_relative_np(cond, mutex, &ts);
+#else
+#if defined(__MVS__)
+  if (gettimeofday(&tv, NULL))
+    abort();
+  timeout += tv.tv_sec * NANOSEC + tv.tv_usec * 1e3;
+#else
+  timeout += uv__hrtime(UV_CLOCK_PRECISE);
+#endif
+  ts.tv_sec = timeout / NANOSEC;
+  ts.tv_nsec = timeout % NANOSEC;
+#if defined(__ANDROID_API__) && __ANDROID_API__ < 21
+
+  /*
+   * The bionic pthread implementation doesn't support CLOCK_MONOTONIC,
+   * but has this alternative function instead.
+   */
+  r = pthread_cond_timedwait_monotonic_np(cond, mutex, &ts);
+#else
+  r = pthread_cond_timedwait(cond, mutex, &ts);
+#endif /* __ANDROID_API__ */
+#endif
+
+
+  if (r == 0)
+    return 0;
+
+  if (r == ETIMEDOUT)
+    return UV_ETIMEDOUT;
+
+  abort();
+  return UV_EINVAL;  /* Satisfy the compiler. */
+}
+
+
+int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
+  return UV__ERR(pthread_barrier_init(barrier, NULL, count));
+}
+
+
+void uv_barrier_destroy(uv_barrier_t* barrier) {
+  if (pthread_barrier_destroy(barrier))
+    abort();
+}
+
+
+int uv_barrier_wait(uv_barrier_t* barrier) {
+  int r = pthread_barrier_wait(barrier);
+  if (r && r != PTHREAD_BARRIER_SERIAL_THREAD)
+    abort();
+  return r == PTHREAD_BARRIER_SERIAL_THREAD;
+}
+
+
+int uv_key_create(uv_key_t* key) {
+  return UV__ERR(pthread_key_create(key, NULL));
+}
+
+
+void uv_key_delete(uv_key_t* key) {
+  if (pthread_key_delete(*key))
+    abort();
+}
+
+
+void* uv_key_get(uv_key_t* key) {
+  return pthread_getspecific(*key);
+}
+
+
+void uv_key_set(uv_key_t* key, void* value) {
+  if (pthread_setspecific(*key, value))
+    abort();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/timer.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/timer.cpp
new file mode 100644
index 0000000..54dabfe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/timer.cpp
@@ -0,0 +1,172 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include "heap-inl.h"
+
+#include <assert.h>
+#include <limits.h>
+
+
+static int timer_less_than(const struct heap_node* ha,
+                           const struct heap_node* hb) {
+  const uv_timer_t* a;
+  const uv_timer_t* b;
+
+  a = container_of(ha, uv_timer_t, heap_node);
+  b = container_of(hb, uv_timer_t, heap_node);
+
+  if (a->timeout < b->timeout)
+    return 1;
+  if (b->timeout < a->timeout)
+    return 0;
+
+  /* Compare start_id when both have the same timeout. start_id is
+   * allocated with loop->timer_counter in uv_timer_start().
+   */
+  if (a->start_id < b->start_id)
+    return 1;
+  if (b->start_id < a->start_id)
+    return 0;
+
+  return 0;
+}
+
+
+int uv_timer_init(uv_loop_t* loop, uv_timer_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_TIMER);
+  handle->timer_cb = NULL;
+  handle->repeat = 0;
+  return 0;
+}
+
+
+int uv_timer_start(uv_timer_t* handle,
+                   uv_timer_cb cb,
+                   uint64_t timeout,
+                   uint64_t repeat) {
+  uint64_t clamped_timeout;
+
+  if (cb == NULL)
+    return UV_EINVAL;
+
+  if (uv__is_active(handle))
+    uv_timer_stop(handle);
+
+  clamped_timeout = handle->loop->time + timeout;
+  if (clamped_timeout < timeout)
+    clamped_timeout = (uint64_t) -1;
+
+  handle->timer_cb = cb;
+  handle->timeout = clamped_timeout;
+  handle->repeat = repeat;
+  /* start_id is the second index to be compared in uv__timer_cmp() */
+  handle->start_id = handle->loop->timer_counter++;
+
+  heap_insert((struct heap*) &handle->loop->timer_heap,
+              (struct heap_node*) &handle->heap_node,
+              timer_less_than);
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+int uv_timer_stop(uv_timer_t* handle) {
+  if (!uv__is_active(handle))
+    return 0;
+
+  heap_remove((struct heap*) &handle->loop->timer_heap,
+              (struct heap_node*) &handle->heap_node,
+              timer_less_than);
+  uv__handle_stop(handle);
+
+  return 0;
+}
+
+
+int uv_timer_again(uv_timer_t* handle) {
+  if (handle->timer_cb == NULL)
+    return UV_EINVAL;
+
+  if (handle->repeat) {
+    uv_timer_stop(handle);
+    uv_timer_start(handle, handle->timer_cb, handle->repeat, handle->repeat);
+  }
+
+  return 0;
+}
+
+
+void uv_timer_set_repeat(uv_timer_t* handle, uint64_t repeat) {
+  handle->repeat = repeat;
+}
+
+
+uint64_t uv_timer_get_repeat(const uv_timer_t* handle) {
+  return handle->repeat;
+}
+
+
+int uv__next_timeout(const uv_loop_t* loop) {
+  const struct heap_node* heap_node;
+  const uv_timer_t* handle;
+  uint64_t diff;
+
+  heap_node = heap_min((const struct heap*) &loop->timer_heap);
+  if (heap_node == NULL)
+    return -1; /* block indefinitely */
+
+  handle = container_of(heap_node, uv_timer_t, heap_node);
+  if (handle->timeout <= loop->time)
+    return 0;
+
+  diff = handle->timeout - loop->time;
+  if (diff > INT_MAX)
+    diff = INT_MAX;
+
+  return diff;
+}
+
+
+void uv__run_timers(uv_loop_t* loop) {
+  struct heap_node* heap_node;
+  uv_timer_t* handle;
+
+  for (;;) {
+    heap_node = heap_min((struct heap*) &loop->timer_heap);
+    if (heap_node == NULL)
+      break;
+
+    handle = container_of(heap_node, uv_timer_t, heap_node);
+    if (handle->timeout > loop->time)
+      break;
+
+    uv_timer_stop(handle);
+    uv_timer_again(handle);
+    handle->timer_cb(handle);
+  }
+}
+
+
+void uv__timer_close(uv_timer_t* handle) {
+  uv_timer_stop(handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/tty.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/tty.cpp
new file mode 100644
index 0000000..f22b3b8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/tty.cpp
@@ -0,0 +1,372 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+#include "spinlock.h"
+
+#include <stdlib.h>
+#include <assert.h>
+#include <unistd.h>
+#include <termios.h>
+#include <errno.h>
+#include <sys/ioctl.h>
+
+#if defined(__MVS__) && !defined(IMAXBEL)
+#define IMAXBEL 0
+#endif
+
+static int orig_termios_fd = -1;
+static struct termios orig_termios;
+static uv_spinlock_t termios_spinlock = UV_SPINLOCK_INITIALIZER;
+
+static int uv__tty_is_slave(const int fd) {
+  int result;
+#if defined(__linux__) || defined(__FreeBSD__) || defined(__FreeBSD_kernel__)
+  int dummy;
+
+  result = ioctl(fd, TIOCGPTN, &dummy) != 0;
+#elif defined(__APPLE__)
+  char dummy[256];
+
+  result = ioctl(fd, TIOCPTYGNAME, &dummy) != 0;
+#elif defined(__NetBSD__)
+  /*
+   * NetBSD as an extension returns with ptsname(3) and ptsname_r(3) the slave
+   * device name for both descriptors, the master one and slave one.
+   *
+   * Implement function to compare major device number with pts devices.
+   *
+   * The major numbers are machine-dependent, on NetBSD/amd64 they are
+   * respectively:
+   *  - master tty: ptc - major 6
+   *  - slave tty:  pts - major 5
+   */
+
+  struct stat sb;
+  /* Lookup device's major for the pts driver and cache it. */
+  static devmajor_t pts = NODEVMAJOR;
+
+  if (pts == NODEVMAJOR) {
+    pts = getdevmajor("pts", S_IFCHR);
+    if (pts == NODEVMAJOR)
+      abort();
+  }
+
+  /* Lookup stat structure behind the file descriptor. */
+  if (fstat(fd, &sb) != 0)
+    abort();
+
+  /* Assert character device. */
+  if (!S_ISCHR(sb.st_mode))
+    abort();
+
+  /* Assert valid major. */
+  if (major(sb.st_rdev) == NODEVMAJOR)
+    abort();
+
+  result = (pts == major(sb.st_rdev));
+#else
+  /* Fallback to ptsname
+   */
+  result = ptsname(fd) == NULL;
+#endif
+  return result;
+}
+
+int uv_tty_init(uv_loop_t* loop, uv_tty_t* tty, int fd, int readable) {
+  uv_handle_type type;
+  int flags;
+  int newfd;
+  int r;
+  int saved_flags;
+  char path[256];
+
+  /* File descriptors that refer to files cannot be monitored with epoll.
+   * That restriction also applies to character devices like /dev/random
+   * (but obviously not /dev/tty.)
+   */
+  type = uv_guess_handle(fd);
+  if (type == UV_FILE || type == UV_UNKNOWN_HANDLE)
+    return UV_EINVAL;
+
+  flags = 0;
+  newfd = -1;
+
+  /* Reopen the file descriptor when it refers to a tty. This lets us put the
+   * tty in non-blocking mode without affecting other processes that share it
+   * with us.
+   *
+   * Example: `node | cat` - if we put our fd 0 in non-blocking mode, it also
+   * affects fd 1 of `cat` because both file descriptors refer to the same
+   * struct file in the kernel. When we reopen our fd 0, it points to a
+   * different struct file, hence changing its properties doesn't affect
+   * other processes.
+   */
+  if (type == UV_TTY) {
+    /* Reopening a pty in master mode won't work either because the reopened
+     * pty will be in slave mode (*BSD) or reopening will allocate a new
+     * master/slave pair (Linux). Therefore check if the fd points to a
+     * slave device.
+     */
+    if (uv__tty_is_slave(fd) && ttyname_r(fd, path, sizeof(path)) == 0)
+      r = uv__open_cloexec(path, O_RDWR);
+    else
+      r = -1;
+
+    if (r < 0) {
+      /* fallback to using blocking writes */
+      if (!readable)
+        flags |= UV_STREAM_BLOCKING;
+      goto skip;
+    }
+
+    newfd = r;
+
+    r = uv__dup2_cloexec(newfd, fd);
+    if (r < 0 && r != UV_EINVAL) {
+      /* EINVAL means newfd == fd which could conceivably happen if another
+       * thread called close(fd) between our calls to isatty() and open().
+       * That's a rather unlikely event but let's handle it anyway.
+       */
+      uv__close(newfd);
+      return r;
+    }
+
+    fd = newfd;
+  }
+
+#if defined(__APPLE__)
+  /* Save the fd flags in case we need to restore them due to an error. */
+  do
+    saved_flags = fcntl(fd, F_GETFL);
+  while (saved_flags == -1 && errno == EINTR);
+
+  if (saved_flags == -1) {
+    if (newfd != -1)
+      uv__close(newfd);
+    return UV__ERR(errno);
+  }
+#endif
+
+  /* Pacify the compiler. */
+  (void) &saved_flags;
+
+skip:
+  uv__stream_init(loop, (uv_stream_t*) tty, UV_TTY);
+
+  /* If anything fails beyond this point we need to remove the handle from
+   * the handle queue, since it was added by uv__handle_init in uv_stream_init.
+   */
+
+  if (!(flags & UV_STREAM_BLOCKING))
+    uv__nonblock(fd, 1);
+
+#if defined(__APPLE__)
+  r = uv__stream_try_select((uv_stream_t*) tty, &fd);
+  if (r) {
+    int rc = r;
+    if (newfd != -1)
+      uv__close(newfd);
+    QUEUE_REMOVE(&tty->handle_queue);
+    do
+      r = fcntl(fd, F_SETFL, saved_flags);
+    while (r == -1 && errno == EINTR);
+    return rc;
+  }
+#endif
+
+  if (readable)
+    flags |= UV_STREAM_READABLE;
+  else
+    flags |= UV_STREAM_WRITABLE;
+
+  uv__stream_open((uv_stream_t*) tty, fd, flags);
+  tty->mode = UV_TTY_MODE_NORMAL;
+
+  return 0;
+}
+
+static void uv__tty_make_raw(struct termios* tio) {
+  assert(tio != NULL);
+
+#if defined __sun || defined __MVS__
+  /*
+   * This implementation of cfmakeraw for Solaris and derivatives is taken from
+   * http://www.perkin.org.uk/posts/solaris-portability-cfmakeraw.html.
+   */
+  tio->c_iflag &= ~(IMAXBEL | IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR |
+                    IGNCR | ICRNL | IXON);
+  tio->c_oflag &= ~OPOST;
+  tio->c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
+  tio->c_cflag &= ~(CSIZE | PARENB);
+  tio->c_cflag |= CS8;
+#else
+  cfmakeraw(tio);
+#endif /* #ifdef __sun */
+}
+
+int uv_tty_set_mode(uv_tty_t* tty, uv_tty_mode_t mode) {
+  struct termios tmp;
+  int fd;
+
+  if (tty->mode == (int) mode)
+    return 0;
+
+  fd = uv__stream_fd(tty);
+  if (tty->mode == UV_TTY_MODE_NORMAL && mode != UV_TTY_MODE_NORMAL) {
+    if (tcgetattr(fd, &tty->orig_termios))
+      return UV__ERR(errno);
+
+    /* This is used for uv_tty_reset_mode() */
+    uv_spinlock_lock(&termios_spinlock);
+    if (orig_termios_fd == -1) {
+      orig_termios = tty->orig_termios;
+      orig_termios_fd = fd;
+    }
+    uv_spinlock_unlock(&termios_spinlock);
+  }
+
+  tmp = tty->orig_termios;
+  switch (mode) {
+    case UV_TTY_MODE_NORMAL:
+      break;
+    case UV_TTY_MODE_RAW:
+      tmp.c_iflag &= ~(BRKINT | ICRNL | INPCK | ISTRIP | IXON);
+      tmp.c_oflag |= (ONLCR);
+      tmp.c_cflag |= (CS8);
+      tmp.c_lflag &= ~(ECHO | ICANON | IEXTEN | ISIG);
+      tmp.c_cc[VMIN] = 1;
+      tmp.c_cc[VTIME] = 0;
+      break;
+    case UV_TTY_MODE_IO:
+      uv__tty_make_raw(&tmp);
+      break;
+  }
+
+  /* Apply changes after draining */
+  if (tcsetattr(fd, TCSADRAIN, &tmp))
+    return UV__ERR(errno);
+
+  tty->mode = mode;
+  return 0;
+}
+
+
+int uv_tty_get_winsize(uv_tty_t* tty, int* width, int* height) {
+  struct winsize ws;
+  int err;
+
+  do
+    err = ioctl(uv__stream_fd(tty), TIOCGWINSZ, &ws);
+  while (err == -1 && errno == EINTR);
+
+  if (err == -1)
+    return UV__ERR(errno);
+
+  *width = ws.ws_col;
+  *height = ws.ws_row;
+
+  return 0;
+}
+
+
+uv_handle_type uv_guess_handle(uv_file file) {
+  struct sockaddr sa;
+  struct stat s;
+  socklen_t len;
+  int type;
+
+  if (file < 0)
+    return UV_UNKNOWN_HANDLE;
+
+  if (isatty(file))
+    return UV_TTY;
+
+  if (fstat(file, &s))
+    return UV_UNKNOWN_HANDLE;
+
+  if (S_ISREG(s.st_mode))
+    return UV_FILE;
+
+  if (S_ISCHR(s.st_mode))
+    return UV_FILE;  /* XXX UV_NAMED_PIPE? */
+
+  if (S_ISFIFO(s.st_mode))
+    return UV_NAMED_PIPE;
+
+  if (!S_ISSOCK(s.st_mode))
+    return UV_UNKNOWN_HANDLE;
+
+  len = sizeof(type);
+  if (getsockopt(file, SOL_SOCKET, SO_TYPE, &type, &len))
+    return UV_UNKNOWN_HANDLE;
+
+  len = sizeof(sa);
+  if (getsockname(file, &sa, &len))
+    return UV_UNKNOWN_HANDLE;
+
+  if (type == SOCK_DGRAM)
+    if (sa.sa_family == AF_INET || sa.sa_family == AF_INET6)
+      return UV_UDP;
+
+  if (type == SOCK_STREAM) {
+#if defined(_AIX) || defined(__DragonFly__)
+    /* on AIX/DragonFly the getsockname call returns an empty sa structure
+     * for sockets of type AF_UNIX.  For all other types it will
+     * return a properly filled in structure.
+     */
+    if (len == 0)
+      return UV_NAMED_PIPE;
+#endif /* defined(_AIX) || defined(__DragonFly__) */
+
+    if (sa.sa_family == AF_INET || sa.sa_family == AF_INET6)
+      return UV_TCP;
+    if (sa.sa_family == AF_UNIX)
+      return UV_NAMED_PIPE;
+  }
+
+  return UV_UNKNOWN_HANDLE;
+}
+
+
+/* This function is async signal-safe, meaning that it's safe to call from
+ * inside a signal handler _unless_ execution was inside uv_tty_set_mode()'s
+ * critical section when the signal was raised.
+ */
+int uv_tty_reset_mode(void) {
+  int saved_errno;
+  int err;
+
+  saved_errno = errno;
+  if (!uv_spinlock_trylock(&termios_spinlock))
+    return UV_EBUSY;  /* In uv_tty_set_mode(). */
+
+  err = 0;
+  if (orig_termios_fd != -1)
+    if (tcsetattr(orig_termios_fd, TCSANOW, &orig_termios))
+      err = UV__ERR(errno);
+
+  uv_spinlock_unlock(&termios_spinlock);
+  errno = saved_errno;
+
+  return err;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/udp.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/udp.cpp
new file mode 100644
index 0000000..7fa1403
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/unix/udp.cpp
@@ -0,0 +1,905 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+#include <assert.h>
+#include <string.h>
+#include <errno.h>
+#include <stdlib.h>
+#include <unistd.h>
+#if defined(__MVS__)
+#include <xti.h>
+#endif
+
+#if defined(IPV6_JOIN_GROUP) && !defined(IPV6_ADD_MEMBERSHIP)
+# define IPV6_ADD_MEMBERSHIP IPV6_JOIN_GROUP
+#endif
+
+#if defined(IPV6_LEAVE_GROUP) && !defined(IPV6_DROP_MEMBERSHIP)
+# define IPV6_DROP_MEMBERSHIP IPV6_LEAVE_GROUP
+#endif
+
+
+static void uv__udp_run_completed(uv_udp_t* handle);
+static void uv__udp_io(uv_loop_t* loop, uv__io_t* w, unsigned int revents);
+static void uv__udp_recvmsg(uv_udp_t* handle);
+static void uv__udp_sendmsg(uv_udp_t* handle);
+static int uv__udp_maybe_deferred_bind(uv_udp_t* handle,
+                                       int domain,
+                                       unsigned int flags);
+
+
+void uv__udp_close(uv_udp_t* handle) {
+  uv__io_close(handle->loop, &handle->io_watcher);
+  uv__handle_stop(handle);
+
+  if (handle->io_watcher.fd != -1) {
+    uv__close(handle->io_watcher.fd);
+    handle->io_watcher.fd = -1;
+  }
+}
+
+
+void uv__udp_finish_close(uv_udp_t* handle) {
+  uv_udp_send_t* req;
+  QUEUE* q;
+
+  assert(!uv__io_active(&handle->io_watcher, POLLIN | POLLOUT));
+  assert(handle->io_watcher.fd == -1);
+
+  while (!QUEUE_EMPTY(&handle->write_queue)) {
+    q = QUEUE_HEAD(&handle->write_queue);
+    QUEUE_REMOVE(q);
+
+    req = QUEUE_DATA(q, uv_udp_send_t, queue);
+    req->status = UV_ECANCELED;
+    QUEUE_INSERT_TAIL(&handle->write_completed_queue, &req->queue);
+  }
+
+  uv__udp_run_completed(handle);
+
+  assert(handle->send_queue_size == 0);
+  assert(handle->send_queue_count == 0);
+
+  /* Now tear down the handle. */
+  handle->recv_cb = NULL;
+  handle->alloc_cb = NULL;
+  /* but _do not_ touch close_cb */
+}
+
+
+static void uv__udp_run_completed(uv_udp_t* handle) {
+  uv_udp_send_t* req;
+  QUEUE* q;
+
+  assert(!(handle->flags & UV_UDP_PROCESSING));
+  handle->flags |= UV_UDP_PROCESSING;
+
+  while (!QUEUE_EMPTY(&handle->write_completed_queue)) {
+    q = QUEUE_HEAD(&handle->write_completed_queue);
+    QUEUE_REMOVE(q);
+
+    req = QUEUE_DATA(q, uv_udp_send_t, queue);
+    uv__req_unregister(handle->loop, req);
+
+    handle->send_queue_size -= uv__count_bufs(req->bufs, req->nbufs);
+    handle->send_queue_count--;
+
+    if (req->bufs != req->bufsml)
+      uv__free(req->bufs);
+    req->bufs = NULL;
+
+    if (req->send_cb == NULL)
+      continue;
+
+    /* req->status >= 0 == bytes written
+     * req->status <  0 == errno
+     */
+    if (req->status >= 0)
+      req->send_cb(req, 0);
+    else
+      req->send_cb(req, req->status);
+  }
+
+  if (QUEUE_EMPTY(&handle->write_queue)) {
+    /* Pending queue and completion queue empty, stop watcher. */
+    uv__io_stop(handle->loop, &handle->io_watcher, POLLOUT);
+    if (!uv__io_active(&handle->io_watcher, POLLIN))
+      uv__handle_stop(handle);
+  }
+
+  handle->flags &= ~UV_UDP_PROCESSING;
+}
+
+
+static void uv__udp_io(uv_loop_t* loop, uv__io_t* w, unsigned int revents) {
+  uv_udp_t* handle;
+
+  handle = container_of(w, uv_udp_t, io_watcher);
+  assert(handle->type == UV_UDP);
+
+  if (revents & POLLIN)
+    uv__udp_recvmsg(handle);
+
+  if (revents & POLLOUT) {
+    uv__udp_sendmsg(handle);
+    uv__udp_run_completed(handle);
+  }
+}
+
+
+static void uv__udp_recvmsg(uv_udp_t* handle) {
+  struct sockaddr_storage peer;
+  struct msghdr h;
+  ssize_t nread;
+  uv_buf_t buf;
+  int flags;
+  int count;
+
+  assert(handle->recv_cb != NULL);
+  assert(handle->alloc_cb != NULL);
+
+  /* Prevent loop starvation when the data comes in as fast as (or faster than)
+   * we can read it. XXX Need to rearm fd if we switch to edge-triggered I/O.
+   */
+  count = 32;
+
+  memset(&h, 0, sizeof(h));
+  h.msg_name = &peer;
+
+  do {
+    buf = uv_buf_init(NULL, 0);
+    handle->alloc_cb((uv_handle_t*) handle, 64 * 1024, &buf);
+    if (buf.base == NULL || buf.len == 0) {
+      handle->recv_cb(handle, UV_ENOBUFS, &buf, NULL, 0);
+      return;
+    }
+    assert(buf.base != NULL);
+
+    h.msg_namelen = sizeof(peer);
+    h.msg_iov = (iovec*) &buf;
+    h.msg_iovlen = 1;
+
+    do {
+      nread = recvmsg(handle->io_watcher.fd, &h, 0);
+    }
+    while (nread == -1 && errno == EINTR);
+
+    if (nread == -1) {
+      if (errno == EAGAIN || errno == EWOULDBLOCK)
+        handle->recv_cb(handle, 0, &buf, NULL, 0);
+      else
+        handle->recv_cb(handle, UV__ERR(errno), &buf, NULL, 0);
+    }
+    else {
+      const struct sockaddr *addr;
+      if (h.msg_namelen == 0)
+        addr = NULL;
+      else
+        addr = (const struct sockaddr*) &peer;
+
+      flags = 0;
+      if (h.msg_flags & MSG_TRUNC)
+        flags |= UV_UDP_PARTIAL;
+
+      handle->recv_cb(handle, nread, &buf, addr, flags);
+    }
+  }
+  /* recv_cb callback may decide to pause or close the handle */
+  while (nread != -1
+      && count-- > 0
+      && handle->io_watcher.fd != -1
+      && handle->recv_cb != NULL);
+}
+
+
+static void uv__udp_sendmsg(uv_udp_t* handle) {
+  uv_udp_send_t* req;
+  QUEUE* q;
+  struct msghdr h;
+  ssize_t size;
+
+  while (!QUEUE_EMPTY(&handle->write_queue)) {
+    q = QUEUE_HEAD(&handle->write_queue);
+    assert(q != NULL);
+
+    req = QUEUE_DATA(q, uv_udp_send_t, queue);
+    assert(req != NULL);
+
+    memset(&h, 0, sizeof h);
+    h.msg_name = &req->addr;
+    h.msg_namelen = (req->addr.ss_family == AF_INET6 ?
+      sizeof(struct sockaddr_in6) : sizeof(struct sockaddr_in));
+    h.msg_iov = (struct iovec*) req->bufs;
+    h.msg_iovlen = req->nbufs;
+
+    do {
+      size = sendmsg(handle->io_watcher.fd, &h, 0);
+    } while (size == -1 && errno == EINTR);
+
+    if (size == -1) {
+      if (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
+        break;
+    }
+
+    req->status = (size == -1 ? UV__ERR(errno) : size);
+
+    /* Sending a datagram is an atomic operation: either all data
+     * is written or nothing is (and EMSGSIZE is raised). That is
+     * why we don't handle partial writes. Just pop the request
+     * off the write queue and onto the completed queue, done.
+     */
+    QUEUE_REMOVE(&req->queue);
+    QUEUE_INSERT_TAIL(&handle->write_completed_queue, &req->queue);
+    uv__io_feed(handle->loop, &handle->io_watcher);
+  }
+}
+
+
+/* On the BSDs, SO_REUSEPORT implies SO_REUSEADDR but with some additional
+ * refinements for programs that use multicast.
+ *
+ * Linux as of 3.9 has a SO_REUSEPORT socket option but with semantics that
+ * are different from the BSDs: it _shares_ the port rather than steal it
+ * from the current listener.  While useful, it's not something we can emulate
+ * on other platforms so we don't enable it.
+ */
+static int uv__set_reuse(int fd) {
+  int yes;
+
+#if defined(SO_REUSEPORT) && !defined(__linux__)
+  yes = 1;
+  if (setsockopt(fd, SOL_SOCKET, SO_REUSEPORT, &yes, sizeof(yes)))
+    return UV__ERR(errno);
+#else
+  yes = 1;
+  if (setsockopt(fd, SOL_SOCKET, SO_REUSEADDR, &yes, sizeof(yes)))
+    return UV__ERR(errno);
+#endif
+
+  return 0;
+}
+
+
+int uv__udp_bind(uv_udp_t* handle,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags) {
+  int err;
+  int yes;
+  int fd;
+
+  /* Check for bad flags. */
+  if (flags & ~(UV_UDP_IPV6ONLY | UV_UDP_REUSEADDR))
+    return UV_EINVAL;
+
+  /* Cannot set IPv6-only mode on non-IPv6 socket. */
+  if ((flags & UV_UDP_IPV6ONLY) && addr->sa_family != AF_INET6)
+    return UV_EINVAL;
+
+  fd = handle->io_watcher.fd;
+  if (fd == -1) {
+    err = uv__socket(addr->sa_family, SOCK_DGRAM, 0);
+    if (err < 0)
+      return err;
+    fd = err;
+    handle->io_watcher.fd = fd;
+  }
+
+  if (flags & UV_UDP_REUSEADDR) {
+    err = uv__set_reuse(fd);
+    if (err)
+      return err;
+  }
+
+  if (flags & UV_UDP_IPV6ONLY) {
+#ifdef IPV6_V6ONLY
+    yes = 1;
+    if (setsockopt(fd, IPPROTO_IPV6, IPV6_V6ONLY, &yes, sizeof yes) == -1) {
+      err = UV__ERR(errno);
+      return err;
+    }
+#else
+    err = UV_ENOTSUP;
+    return err;
+#endif
+  }
+
+  if (bind(fd, addr, addrlen)) {
+    err = UV__ERR(errno);
+    if (errno == EAFNOSUPPORT)
+      /* OSX, other BSDs and SunoS fail with EAFNOSUPPORT when binding a
+       * socket created with AF_INET to an AF_INET6 address or vice versa. */
+      err = UV_EINVAL;
+    return err;
+  }
+
+  if (addr->sa_family == AF_INET6)
+    handle->flags |= UV_HANDLE_IPV6;
+
+  handle->flags |= UV_HANDLE_BOUND;
+  return 0;
+}
+
+
+static int uv__udp_maybe_deferred_bind(uv_udp_t* handle,
+                                       int domain,
+                                       unsigned int flags) {
+  union {
+    struct sockaddr_in6 in6;
+    struct sockaddr_in in;
+    struct sockaddr addr;
+  } taddr;
+  socklen_t addrlen;
+
+  if (handle->io_watcher.fd != -1)
+    return 0;
+
+  switch (domain) {
+  case AF_INET:
+  {
+    struct sockaddr_in* addr = &taddr.in;
+    memset(addr, 0, sizeof *addr);
+    addr->sin_family = AF_INET;
+    addr->sin_addr.s_addr = INADDR_ANY;
+    addrlen = sizeof *addr;
+    break;
+  }
+  case AF_INET6:
+  {
+    struct sockaddr_in6* addr = &taddr.in6;
+    memset(addr, 0, sizeof *addr);
+    addr->sin6_family = AF_INET6;
+    addr->sin6_addr = in6addr_any;
+    addrlen = sizeof *addr;
+    break;
+  }
+  default:
+    assert(0 && "unsupported address family");
+    abort();
+  }
+
+  return uv__udp_bind(handle, &taddr.addr, addrlen, flags);
+}
+
+
+int uv__udp_send(uv_udp_send_t* req,
+                 uv_udp_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 uv_udp_send_cb send_cb) {
+  int err;
+  int empty_queue;
+
+  assert(nbufs > 0);
+
+  err = uv__udp_maybe_deferred_bind(handle, addr->sa_family, 0);
+  if (err)
+    return err;
+
+  /* It's legal for send_queue_count > 0 even when the write_queue is empty;
+   * it means there are error-state requests in the write_completed_queue that
+   * will touch up send_queue_size/count later.
+   */
+  empty_queue = (handle->send_queue_count == 0);
+
+  uv__req_init(handle->loop, req, UV_UDP_SEND);
+  assert(addrlen <= sizeof(req->addr));
+  memcpy(&req->addr, addr, addrlen);
+  req->send_cb = send_cb;
+  req->handle = handle;
+  req->nbufs = nbufs;
+
+  req->bufs = req->bufsml;
+  if (nbufs > ARRAY_SIZE(req->bufsml))
+    req->bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(bufs[0]));
+
+  if (req->bufs == NULL) {
+    uv__req_unregister(handle->loop, req);
+    return UV_ENOMEM;
+  }
+
+  memcpy(req->bufs, bufs, nbufs * sizeof(bufs[0]));
+  handle->send_queue_size += uv__count_bufs(req->bufs, req->nbufs);
+  handle->send_queue_count++;
+  QUEUE_INSERT_TAIL(&handle->write_queue, &req->queue);
+  uv__handle_start(handle);
+
+  if (empty_queue && !(handle->flags & UV_UDP_PROCESSING)) {
+    uv__udp_sendmsg(handle);
+
+    /* `uv__udp_sendmsg` may not be able to do non-blocking write straight
+     * away. In such cases the `io_watcher` has to be queued for asynchronous
+     * write.
+     */
+    if (!QUEUE_EMPTY(&handle->write_queue))
+      uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
+  } else {
+    uv__io_start(handle->loop, &handle->io_watcher, POLLOUT);
+  }
+
+  return 0;
+}
+
+
+int uv__udp_try_send(uv_udp_t* handle,
+                     const uv_buf_t bufs[],
+                     unsigned int nbufs,
+                     const struct sockaddr* addr,
+                     unsigned int addrlen) {
+  int err;
+  struct msghdr h;
+  ssize_t size;
+
+  assert(nbufs > 0);
+
+  /* already sending a message */
+  if (handle->send_queue_count != 0)
+    return UV_EAGAIN;
+
+  err = uv__udp_maybe_deferred_bind(handle, addr->sa_family, 0);
+  if (err)
+    return err;
+
+  memset(&h, 0, sizeof h);
+  h.msg_name = (struct sockaddr*) addr;
+  h.msg_namelen = addrlen;
+  h.msg_iov = (struct iovec*) bufs;
+  h.msg_iovlen = nbufs;
+
+  do {
+    size = sendmsg(handle->io_watcher.fd, &h, 0);
+  } while (size == -1 && errno == EINTR);
+
+  if (size == -1) {
+    if (errno == EAGAIN || errno == EWOULDBLOCK || errno == ENOBUFS)
+      return UV_EAGAIN;
+    else
+      return UV__ERR(errno);
+  }
+
+  return size;
+}
+
+
+static int uv__udp_set_membership4(uv_udp_t* handle,
+                                   const struct sockaddr_in* multicast_addr,
+                                   const char* interface_addr,
+                                   uv_membership membership) {
+  struct ip_mreq mreq;
+  int optname;
+  int err;
+
+  memset(&mreq, 0, sizeof mreq);
+
+  if (interface_addr) {
+    err = uv_inet_pton(AF_INET, interface_addr, &mreq.imr_interface.s_addr);
+    if (err)
+      return err;
+  } else {
+    mreq.imr_interface.s_addr = htonl(INADDR_ANY);
+  }
+
+  mreq.imr_multiaddr.s_addr = multicast_addr->sin_addr.s_addr;
+
+  switch (membership) {
+  case UV_JOIN_GROUP:
+    optname = IP_ADD_MEMBERSHIP;
+    break;
+  case UV_LEAVE_GROUP:
+    optname = IP_DROP_MEMBERSHIP;
+    break;
+  default:
+    return UV_EINVAL;
+  }
+
+  if (setsockopt(handle->io_watcher.fd,
+                 IPPROTO_IP,
+                 optname,
+                 &mreq,
+                 sizeof(mreq))) {
+#if defined(__MVS__)
+  if (errno == ENXIO)
+    return UV_ENODEV;
+#endif
+    return UV__ERR(errno);
+  }
+
+  return 0;
+}
+
+
+static int uv__udp_set_membership6(uv_udp_t* handle,
+                                   const struct sockaddr_in6* multicast_addr,
+                                   const char* interface_addr,
+                                   uv_membership membership) {
+  int optname;
+  struct ipv6_mreq mreq;
+  struct sockaddr_in6 addr6;
+
+  memset(&mreq, 0, sizeof mreq);
+
+  if (interface_addr) {
+    if (uv_ip6_addr(interface_addr, 0, &addr6))
+      return UV_EINVAL;
+    mreq.ipv6mr_interface = addr6.sin6_scope_id;
+  } else {
+    mreq.ipv6mr_interface = 0;
+  }
+
+  mreq.ipv6mr_multiaddr = multicast_addr->sin6_addr;
+
+  switch (membership) {
+  case UV_JOIN_GROUP:
+    optname = IPV6_ADD_MEMBERSHIP;
+    break;
+  case UV_LEAVE_GROUP:
+    optname = IPV6_DROP_MEMBERSHIP;
+    break;
+  default:
+    return UV_EINVAL;
+  }
+
+  if (setsockopt(handle->io_watcher.fd,
+                 IPPROTO_IPV6,
+                 optname,
+                 &mreq,
+                 sizeof(mreq))) {
+#if defined(__MVS__)
+  if (errno == ENXIO)
+    return UV_ENODEV;
+#endif
+    return UV__ERR(errno);
+  }
+
+  return 0;
+}
+
+
+int uv_udp_init_ex(uv_loop_t* loop, uv_udp_t* handle, unsigned int flags) {
+  int domain;
+  int err;
+  int fd;
+
+  /* Use the lower 8 bits for the domain */
+  domain = flags & 0xFF;
+  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
+    return UV_EINVAL;
+
+  if (flags & ~0xFF)
+    return UV_EINVAL;
+
+  if (domain != AF_UNSPEC) {
+    err = uv__socket(domain, SOCK_DGRAM, 0);
+    if (err < 0)
+      return err;
+    fd = err;
+  } else {
+    fd = -1;
+  }
+
+  uv__handle_init(loop, (uv_handle_t*)handle, UV_UDP);
+  handle->alloc_cb = NULL;
+  handle->recv_cb = NULL;
+  handle->send_queue_size = 0;
+  handle->send_queue_count = 0;
+  uv__io_init(&handle->io_watcher, uv__udp_io, fd);
+  QUEUE_INIT(&handle->write_queue);
+  QUEUE_INIT(&handle->write_completed_queue);
+  return 0;
+}
+
+
+int uv_udp_init(uv_loop_t* loop, uv_udp_t* handle) {
+  return uv_udp_init_ex(loop, handle, AF_UNSPEC);
+}
+
+
+int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock) {
+  int err;
+
+  /* Check for already active socket. */
+  if (handle->io_watcher.fd != -1)
+    return UV_EBUSY;
+
+  if (uv__fd_exists(handle->loop, sock))
+    return UV_EEXIST;
+
+  err = uv__nonblock(sock, 1);
+  if (err)
+    return err;
+
+  err = uv__set_reuse(sock);
+  if (err)
+    return err;
+
+  handle->io_watcher.fd = sock;
+  return 0;
+}
+
+
+int uv_udp_set_membership(uv_udp_t* handle,
+                          const char* multicast_addr,
+                          const char* interface_addr,
+                          uv_membership membership) {
+  int err;
+  struct sockaddr_in addr4;
+  struct sockaddr_in6 addr6;
+
+  if (uv_ip4_addr(multicast_addr, 0, &addr4) == 0) {
+    err = uv__udp_maybe_deferred_bind(handle, AF_INET, UV_UDP_REUSEADDR);
+    if (err)
+      return err;
+    return uv__udp_set_membership4(handle, &addr4, interface_addr, membership);
+  } else if (uv_ip6_addr(multicast_addr, 0, &addr6) == 0) {
+    err = uv__udp_maybe_deferred_bind(handle, AF_INET6, UV_UDP_REUSEADDR);
+    if (err)
+      return err;
+    return uv__udp_set_membership6(handle, &addr6, interface_addr, membership);
+  } else {
+    return UV_EINVAL;
+  }
+}
+
+static int uv__setsockopt(uv_udp_t* handle,
+                         int option4,
+                         int option6,
+                         const void* val,
+                         size_t size) {
+  int r;
+
+  if (handle->flags & UV_HANDLE_IPV6)
+    r = setsockopt(handle->io_watcher.fd,
+                   IPPROTO_IPV6,
+                   option6,
+                   val,
+                   size);
+  else
+    r = setsockopt(handle->io_watcher.fd,
+                   IPPROTO_IP,
+                   option4,
+                   val,
+                   size);
+  if (r)
+    return UV__ERR(errno);
+
+  return 0;
+}
+
+static int uv__setsockopt_maybe_char(uv_udp_t* handle,
+                                     int option4,
+                                     int option6,
+                                     int val) {
+#if defined(__sun) || defined(_AIX) || defined(__MVS__)
+  char arg = val;
+#elif defined(__OpenBSD__)
+  unsigned char arg = val;
+#else
+  int arg = val;
+#endif
+
+  if (val < 0 || val > 255)
+    return UV_EINVAL;
+
+  return uv__setsockopt(handle, option4, option6, &arg, sizeof(arg));
+}
+
+
+int uv_udp_set_broadcast(uv_udp_t* handle, int on) {
+  if (setsockopt(handle->io_watcher.fd,
+                 SOL_SOCKET,
+                 SO_BROADCAST,
+                 &on,
+                 sizeof(on))) {
+    return UV__ERR(errno);
+  }
+
+  return 0;
+}
+
+
+int uv_udp_set_ttl(uv_udp_t* handle, int ttl) {
+  if (ttl < 1 || ttl > 255)
+    return UV_EINVAL;
+
+#if defined(__MVS__)
+  if (!(handle->flags & UV_HANDLE_IPV6))
+    return UV_ENOTSUP;  /* zOS does not support setting ttl for IPv4 */
+#endif
+
+/*
+ * On Solaris and derivatives such as SmartOS, the length of socket options
+ * is sizeof(int) for IP_TTL and IPV6_UNICAST_HOPS,
+ * so hardcode the size of these options on this platform,
+ * and use the general uv__setsockopt_maybe_char call on other platforms.
+ */
+#if defined(__sun) || defined(_AIX) || defined(__OpenBSD__) || \
+    defined(__MVS__)
+
+  return uv__setsockopt(handle,
+                        IP_TTL,
+                        IPV6_UNICAST_HOPS,
+                        &ttl,
+                        sizeof(ttl));
+#endif /* defined(__sun) || defined(_AIX) || defined (__OpenBSD__) ||
+          defined(__MVS__) */
+
+  return uv__setsockopt_maybe_char(handle,
+                                   IP_TTL,
+                                   IPV6_UNICAST_HOPS,
+                                   ttl);
+}
+
+
+int uv_udp_set_multicast_ttl(uv_udp_t* handle, int ttl) {
+/*
+ * On Solaris and derivatives such as SmartOS, the length of socket options
+ * is sizeof(int) for IPV6_MULTICAST_HOPS and sizeof(char) for
+ * IP_MULTICAST_TTL, so hardcode the size of the option in the IPv6 case,
+ * and use the general uv__setsockopt_maybe_char call otherwise.
+ */
+#if defined(__sun) || defined(_AIX) || defined(__MVS__)
+  if (handle->flags & UV_HANDLE_IPV6)
+    return uv__setsockopt(handle,
+                          IP_MULTICAST_TTL,
+                          IPV6_MULTICAST_HOPS,
+                          &ttl,
+                          sizeof(ttl));
+#endif /* defined(__sun) || defined(_AIX) || defined(__MVS__) */
+
+  return uv__setsockopt_maybe_char(handle,
+                                   IP_MULTICAST_TTL,
+                                   IPV6_MULTICAST_HOPS,
+                                   ttl);
+}
+
+
+int uv_udp_set_multicast_loop(uv_udp_t* handle, int on) {
+/*
+ * On Solaris and derivatives such as SmartOS, the length of socket options
+ * is sizeof(int) for IPV6_MULTICAST_LOOP and sizeof(char) for
+ * IP_MULTICAST_LOOP, so hardcode the size of the option in the IPv6 case,
+ * and use the general uv__setsockopt_maybe_char call otherwise.
+ */
+#if defined(__sun) || defined(_AIX) || defined(__MVS__)
+  if (handle->flags & UV_HANDLE_IPV6)
+    return uv__setsockopt(handle,
+                          IP_MULTICAST_LOOP,
+                          IPV6_MULTICAST_LOOP,
+                          &on,
+                          sizeof(on));
+#endif /* defined(__sun) || defined(_AIX) || defined(__MVS__) */
+
+  return uv__setsockopt_maybe_char(handle,
+                                   IP_MULTICAST_LOOP,
+                                   IPV6_MULTICAST_LOOP,
+                                   on);
+}
+
+int uv_udp_set_multicast_interface(uv_udp_t* handle, const char* interface_addr) {
+  struct sockaddr_storage addr_st;
+  struct sockaddr_in* addr4;
+  struct sockaddr_in6* addr6;
+
+  addr4 = (struct sockaddr_in*) &addr_st;
+  addr6 = (struct sockaddr_in6*) &addr_st;
+
+  if (!interface_addr) {
+    memset(&addr_st, 0, sizeof addr_st);
+    if (handle->flags & UV_HANDLE_IPV6) {
+      addr_st.ss_family = AF_INET6;
+      addr6->sin6_scope_id = 0;
+    } else {
+      addr_st.ss_family = AF_INET;
+      addr4->sin_addr.s_addr = htonl(INADDR_ANY);
+    }
+  } else if (uv_ip4_addr(interface_addr, 0, addr4) == 0) {
+    /* nothing, address was parsed */
+  } else if (uv_ip6_addr(interface_addr, 0, addr6) == 0) {
+    /* nothing, address was parsed */
+  } else {
+    return UV_EINVAL;
+  }
+
+  if (addr_st.ss_family == AF_INET) {
+    if (setsockopt(handle->io_watcher.fd,
+                   IPPROTO_IP,
+                   IP_MULTICAST_IF,
+                   (void*) &addr4->sin_addr,
+                   sizeof(addr4->sin_addr)) == -1) {
+      return UV__ERR(errno);
+    }
+  } else if (addr_st.ss_family == AF_INET6) {
+    if (setsockopt(handle->io_watcher.fd,
+                   IPPROTO_IPV6,
+                   IPV6_MULTICAST_IF,
+                   &addr6->sin6_scope_id,
+                   sizeof(addr6->sin6_scope_id)) == -1) {
+      return UV__ERR(errno);
+    }
+  } else {
+    assert(0 && "unexpected address family");
+    abort();
+  }
+
+  return 0;
+}
+
+
+int uv_udp_getsockname(const uv_udp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+  socklen_t socklen;
+
+  if (handle->io_watcher.fd == -1)
+    return UV_EINVAL;  /* FIXME(bnoordhuis) UV_EBADF */
+
+  /* sizeof(socklen_t) != sizeof(int) on some systems. */
+  socklen = (socklen_t) *namelen;
+
+  if (getsockname(handle->io_watcher.fd, name, &socklen))
+    return UV__ERR(errno);
+
+  *namelen = (int) socklen;
+  return 0;
+}
+
+
+int uv__udp_recv_start(uv_udp_t* handle,
+                       uv_alloc_cb alloc_cb,
+                       uv_udp_recv_cb recv_cb) {
+  int err;
+
+  if (alloc_cb == NULL || recv_cb == NULL)
+    return UV_EINVAL;
+
+  if (uv__io_active(&handle->io_watcher, POLLIN))
+    return UV_EALREADY;  /* FIXME(bnoordhuis) Should be UV_EBUSY. */
+
+  err = uv__udp_maybe_deferred_bind(handle, AF_INET, 0);
+  if (err)
+    return err;
+
+  handle->alloc_cb = alloc_cb;
+  handle->recv_cb = recv_cb;
+
+  uv__io_start(handle->loop, &handle->io_watcher, POLLIN);
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+int uv__udp_recv_stop(uv_udp_t* handle) {
+  uv__io_stop(handle->loop, &handle->io_watcher, POLLIN);
+
+  if (!uv__io_active(&handle->io_watcher, POLLOUT))
+    uv__handle_stop(handle);
+
+  handle->alloc_cb = NULL;
+  handle->recv_cb = NULL;
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-common.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-common.cpp
new file mode 100644
index 0000000..52149e4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-common.cpp
@@ -0,0 +1,673 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "uv-common.h"
+
+#include <assert.h>
+#include <errno.h>
+#include <stdarg.h>
+#include <stddef.h> /* NULL */
+#include <stdio.h>
+#include <stdlib.h> /* malloc */
+#include <string.h> /* memset */
+
+#if defined(_WIN32)
+# include <malloc.h> /* malloc */
+#else
+# include <net/if.h> /* if_nametoindex */
+#endif
+
+
+typedef struct {
+  uv_malloc_func local_malloc;
+  uv_realloc_func local_realloc;
+  uv_calloc_func local_calloc;
+  uv_free_func local_free;
+} uv__allocator_t;
+
+static uv__allocator_t uv__allocator = {
+  malloc,
+  realloc,
+  calloc,
+  free,
+};
+
+char* uv__strdup(const char* s) {
+  size_t len = strlen(s) + 1;
+  char* m = (char*)uv__malloc(len);
+  if (m == NULL)
+    return NULL;
+  return (char*)memcpy(m, s, len);
+}
+
+char* uv__strndup(const char* s, size_t n) {
+  char* m;
+  size_t len = strlen(s);
+  if (n < len)
+    len = n;
+  m = (char*)uv__malloc(len + 1);
+  if (m == NULL)
+    return NULL;
+  m[len] = '\0';
+  return (char*)memcpy(m, s, len);
+}
+
+void* uv__malloc(size_t size) {
+  return uv__allocator.local_malloc(size);
+}
+
+void uv__free(void* ptr) {
+  int saved_errno;
+
+  /* Libuv expects that free() does not clobber errno.  The system allocator
+   * honors that assumption but custom allocators may not be so careful.
+   */
+  saved_errno = errno;
+  uv__allocator.local_free(ptr);
+  errno = saved_errno;
+}
+
+void* uv__calloc(size_t count, size_t size) {
+  return uv__allocator.local_calloc(count, size);
+}
+
+void* uv__realloc(void* ptr, size_t size) {
+  return uv__allocator.local_realloc(ptr, size);
+}
+
+int uv_replace_allocator(uv_malloc_func malloc_func,
+                         uv_realloc_func realloc_func,
+                         uv_calloc_func calloc_func,
+                         uv_free_func free_func) {
+  if (malloc_func == NULL || realloc_func == NULL ||
+      calloc_func == NULL || free_func == NULL) {
+    return UV_EINVAL;
+  }
+
+  uv__allocator.local_malloc = malloc_func;
+  uv__allocator.local_realloc = realloc_func;
+  uv__allocator.local_calloc = calloc_func;
+  uv__allocator.local_free = free_func;
+
+  return 0;
+}
+
+#define XX(uc, lc) case UV_##uc: return sizeof(uv_##lc##_t);
+
+size_t uv_handle_size(uv_handle_type type) {
+  switch (type) {
+    UV_HANDLE_TYPE_MAP(XX)
+    default:
+      return -1;
+  }
+}
+
+size_t uv_req_size(uv_req_type type) {
+  switch(type) {
+    UV_REQ_TYPE_MAP(XX)
+    default:
+      return -1;
+  }
+}
+
+#undef XX
+
+
+size_t uv_loop_size(void) {
+  return sizeof(uv_loop_t);
+}
+
+
+uv_buf_t uv_buf_init(char* base, unsigned int len) {
+  uv_buf_t buf;
+  buf.base = base;
+  buf.len = len;
+  return buf;
+}
+
+
+static const char* uv__unknown_err_code(int err) {
+  char buf[32];
+  char* copy;
+
+  snprintf(buf, sizeof(buf), "Unknown system error %d", err);
+  copy = uv__strdup(buf);
+
+  return copy != NULL ? copy : "Unknown system error";
+}
+
+
+#define UV_ERR_NAME_GEN(name, _) case UV_ ## name: return #name;
+const char* uv_err_name(int err) {
+  switch (err) {
+    UV_ERRNO_MAP(UV_ERR_NAME_GEN)
+  }
+  return uv__unknown_err_code(err);
+}
+#undef UV_ERR_NAME_GEN
+
+
+#define UV_STRERROR_GEN(name, msg) case UV_ ## name: return msg;
+const char* uv_strerror(int err) {
+  switch (err) {
+    UV_ERRNO_MAP(UV_STRERROR_GEN)
+  }
+  return uv__unknown_err_code(err);
+}
+#undef UV_STRERROR_GEN
+
+
+int uv_ip4_addr(const char* ip, int port, struct sockaddr_in* addr) {
+  memset(addr, 0, sizeof(*addr));
+  addr->sin_family = AF_INET;
+  addr->sin_port = htons(port);
+  return uv_inet_pton(AF_INET, ip, &(addr->sin_addr.s_addr));
+}
+
+
+int uv_ip6_addr(const char* ip, int port, struct sockaddr_in6* addr) {
+  char address_part[40];
+  size_t address_part_size;
+  const char* zone_index;
+
+  memset(addr, 0, sizeof(*addr));
+  addr->sin6_family = AF_INET6;
+  addr->sin6_port = htons(port);
+
+  zone_index = strchr(ip, '%');
+  if (zone_index != NULL) {
+    address_part_size = zone_index - ip;
+    if (address_part_size >= sizeof(address_part))
+      address_part_size = sizeof(address_part) - 1;
+
+    memcpy(address_part, ip, address_part_size);
+    address_part[address_part_size] = '\0';
+    ip = address_part;
+
+    zone_index++; /* skip '%' */
+    /* NOTE: unknown interface (id=0) is silently ignored */
+#ifdef _WIN32
+    addr->sin6_scope_id = atoi(zone_index);
+#else
+    addr->sin6_scope_id = if_nametoindex(zone_index);
+#endif
+  }
+
+  return uv_inet_pton(AF_INET6, ip, &addr->sin6_addr);
+}
+
+
+int uv_ip4_name(const struct sockaddr_in* src, char* dst, size_t size) {
+  return uv_inet_ntop(AF_INET, &src->sin_addr, dst, size);
+}
+
+
+int uv_ip6_name(const struct sockaddr_in6* src, char* dst, size_t size) {
+  return uv_inet_ntop(AF_INET6, &src->sin6_addr, dst, size);
+}
+
+
+int uv_tcp_bind(uv_tcp_t* handle,
+                const struct sockaddr* addr,
+                unsigned int flags) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_TCP)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  return uv__tcp_bind(handle, addr, addrlen, flags);
+}
+
+
+int uv_udp_bind(uv_udp_t* handle,
+                const struct sockaddr* addr,
+                unsigned int flags) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_UDP)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  return uv__udp_bind(handle, addr, addrlen, flags);
+}
+
+
+int uv_tcp_connect(uv_connect_t* req,
+                   uv_tcp_t* handle,
+                   const struct sockaddr* addr,
+                   uv_connect_cb cb) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_TCP)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  return uv__tcp_connect(req, handle, addr, addrlen, cb);
+}
+
+
+int uv_udp_send(uv_udp_send_t* req,
+                uv_udp_t* handle,
+                const uv_buf_t bufs[],
+                unsigned int nbufs,
+                const struct sockaddr* addr,
+                uv_udp_send_cb send_cb) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_UDP)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  return uv__udp_send(req, handle, bufs, nbufs, addr, addrlen, send_cb);
+}
+
+
+int uv_udp_try_send(uv_udp_t* handle,
+                    const uv_buf_t bufs[],
+                    unsigned int nbufs,
+                    const struct sockaddr* addr) {
+  unsigned int addrlen;
+
+  if (handle->type != UV_UDP)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET)
+    addrlen = sizeof(struct sockaddr_in);
+  else if (addr->sa_family == AF_INET6)
+    addrlen = sizeof(struct sockaddr_in6);
+  else
+    return UV_EINVAL;
+
+  return uv__udp_try_send(handle, bufs, nbufs, addr, addrlen);
+}
+
+
+int uv_udp_recv_start(uv_udp_t* handle,
+                      uv_alloc_cb alloc_cb,
+                      uv_udp_recv_cb recv_cb) {
+  if (handle->type != UV_UDP || alloc_cb == NULL || recv_cb == NULL)
+    return UV_EINVAL;
+  else
+    return uv__udp_recv_start(handle, alloc_cb, recv_cb);
+}
+
+
+int uv_udp_recv_stop(uv_udp_t* handle) {
+  if (handle->type != UV_UDP)
+    return UV_EINVAL;
+  else
+    return uv__udp_recv_stop(handle);
+}
+
+
+void uv_walk(uv_loop_t* loop, uv_walk_cb walk_cb, void* arg) {
+  QUEUE queue;
+  QUEUE* q;
+  uv_handle_t* h;
+
+  QUEUE_MOVE(&loop->handle_queue, &queue);
+  while (!QUEUE_EMPTY(&queue)) {
+    q = QUEUE_HEAD(&queue);
+    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
+
+    QUEUE_REMOVE(q);
+    QUEUE_INSERT_TAIL(&loop->handle_queue, q);
+
+    if (h->flags & UV__HANDLE_INTERNAL) continue;
+    walk_cb(h, arg);
+  }
+}
+
+
+static void uv__print_handles(uv_loop_t* loop, int only_active, FILE* stream) {
+  const char* type;
+  QUEUE* q;
+  uv_handle_t* h;
+
+  if (loop == NULL)
+    loop = uv_default_loop();
+
+  QUEUE_FOREACH(q, &loop->handle_queue) {
+    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
+
+    if (only_active && !uv__is_active(h))
+      continue;
+
+    switch (h->type) {
+#define X(uc, lc) case UV_##uc: type = #lc; break;
+      UV_HANDLE_TYPE_MAP(X)
+#undef X
+      default: type = "<unknown>";
+    }
+
+    fprintf(stream,
+            "[%c%c%c] %-8s %p\n",
+            "R-"[!(h->flags & UV__HANDLE_REF)],
+            "A-"[!(h->flags & UV__HANDLE_ACTIVE)],
+            "I-"[!(h->flags & UV__HANDLE_INTERNAL)],
+            type,
+            (void*)h);
+  }
+}
+
+
+void uv_print_all_handles(uv_loop_t* loop, FILE* stream) {
+  uv__print_handles(loop, 0, stream);
+}
+
+
+void uv_print_active_handles(uv_loop_t* loop, FILE* stream) {
+  uv__print_handles(loop, 1, stream);
+}
+
+
+void uv_ref(uv_handle_t* handle) {
+  uv__handle_ref(handle);
+}
+
+
+void uv_unref(uv_handle_t* handle) {
+  uv__handle_unref(handle);
+}
+
+
+int uv_has_ref(const uv_handle_t* handle) {
+  return uv__has_ref(handle);
+}
+
+
+void uv_stop(uv_loop_t* loop) {
+  loop->stop_flag = 1;
+}
+
+
+uint64_t uv_now(const uv_loop_t* loop) {
+  return loop->time;
+}
+
+
+
+size_t uv__count_bufs(const uv_buf_t bufs[], unsigned int nbufs) {
+  unsigned int i;
+  size_t bytes;
+
+  bytes = 0;
+  for (i = 0; i < nbufs; i++)
+    bytes += (size_t) bufs[i].len;
+
+  return bytes;
+}
+
+int uv_recv_buffer_size(uv_handle_t* handle, int* value) {
+  return uv__socket_sockopt(handle, SO_RCVBUF, value);
+}
+
+int uv_send_buffer_size(uv_handle_t* handle, int *value) {
+  return uv__socket_sockopt(handle, SO_SNDBUF, value);
+}
+
+int uv_fs_event_getpath(uv_fs_event_t* handle, char* buffer, size_t* size) {
+  size_t required_len;
+
+  if (!uv__is_active(handle)) {
+    *size = 0;
+    return UV_EINVAL;
+  }
+
+  required_len = strlen(handle->path);
+  if (required_len >= *size) {
+    *size = required_len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, handle->path, required_len);
+  *size = required_len;
+  buffer[required_len] = '\0';
+
+  return 0;
+}
+
+/* The windows implementation does not have the same structure layout as
+ * the unix implementation (nbufs is not directly inside req but is
+ * contained in a nested union/struct) so this function locates it.
+*/
+static unsigned int* uv__get_nbufs(uv_fs_t* req) {
+#ifdef _WIN32
+  return &req->fs.info.nbufs;
+#else
+  return &req->nbufs;
+#endif
+}
+
+/* uv_fs_scandir() uses the system allocator to allocate memory on non-Windows
+ * systems. So, the memory should be released using free(). On Windows,
+ * uv__malloc() is used, so use uv__free() to free memory.
+*/
+#ifdef _WIN32
+# define uv__fs_scandir_free uv__free
+#else
+# define uv__fs_scandir_free free
+#endif
+
+void uv__fs_scandir_cleanup(uv_fs_t* req) {
+  uv__dirent_t** dents;
+
+  unsigned int* nbufs = uv__get_nbufs(req);
+
+  dents = (uv__dirent_t**)(req->ptr);
+  if (*nbufs > 0 && *nbufs != (unsigned int) req->result)
+    (*nbufs)--;
+  for (; *nbufs < (unsigned int) req->result; (*nbufs)++)
+    uv__fs_scandir_free(dents[*nbufs]);
+
+  uv__fs_scandir_free(req->ptr);
+  req->ptr = NULL;
+}
+
+
+int uv_fs_scandir_next(uv_fs_t* req, uv_dirent_t* ent) {
+  uv__dirent_t** dents;
+  uv__dirent_t* dent;
+  unsigned int* nbufs;
+
+  /* Check to see if req passed */
+  if (req->result < 0)
+    return req->result;
+
+  /* Ptr will be null if req was canceled or no files found */
+  if (!req->ptr)
+    return UV_EOF;
+
+  nbufs = uv__get_nbufs(req);
+  assert(nbufs);
+
+  dents = (uv__dirent_t**)(req->ptr);
+
+  /* Free previous entity */
+  if (*nbufs > 0)
+    uv__fs_scandir_free(dents[*nbufs - 1]);
+
+  /* End was already reached */
+  if (*nbufs == (unsigned int) req->result) {
+    uv__fs_scandir_free(dents);
+    req->ptr = NULL;
+    return UV_EOF;
+  }
+
+  dent = dents[(*nbufs)++];
+
+  ent->name = dent->d_name;
+#ifdef HAVE_DIRENT_TYPES
+  switch (dent->d_type) {
+    case UV__DT_DIR:
+      ent->type = UV_DIRENT_DIR;
+      break;
+    case UV__DT_FILE:
+      ent->type = UV_DIRENT_FILE;
+      break;
+    case UV__DT_LINK:
+      ent->type = UV_DIRENT_LINK;
+      break;
+    case UV__DT_FIFO:
+      ent->type = UV_DIRENT_FIFO;
+      break;
+    case UV__DT_SOCKET:
+      ent->type = UV_DIRENT_SOCKET;
+      break;
+    case UV__DT_CHAR:
+      ent->type = UV_DIRENT_CHAR;
+      break;
+    case UV__DT_BLOCK:
+      ent->type = UV_DIRENT_BLOCK;
+      break;
+    default:
+      ent->type = UV_DIRENT_UNKNOWN;
+  }
+#else
+  ent->type = UV_DIRENT_UNKNOWN;
+#endif
+
+  return 0;
+}
+
+
+#ifdef __clang__
+# pragma clang diagnostic push
+# pragma clang diagnostic ignored "-Wvarargs"
+#endif
+
+int uv_loop_configure(uv_loop_t* loop, uv_loop_option option, ...) {
+  va_list ap;
+  int err;
+
+  va_start(ap, option);
+  /* Any platform-agnostic options should be handled here. */
+  err = uv__loop_configure(loop, option, ap);
+  va_end(ap);
+
+  return err;
+}
+
+#ifdef __clang__
+# pragma clang diagnostic pop
+#endif
+
+
+static uv_loop_t default_loop_struct;
+static uv_loop_t* default_loop_ptr;
+
+
+uv_loop_t* uv_default_loop(void) {
+  if (default_loop_ptr != NULL)
+    return default_loop_ptr;
+
+  if (uv_loop_init(&default_loop_struct))
+    return NULL;
+
+  default_loop_ptr = &default_loop_struct;
+  return default_loop_ptr;
+}
+
+
+uv_loop_t* uv_loop_new(void) {
+  uv_loop_t* loop;
+
+  loop = (uv_loop_t*)uv__malloc(sizeof(*loop));
+  if (loop == NULL)
+    return NULL;
+
+  if (uv_loop_init(loop)) {
+    uv__free(loop);
+    return NULL;
+  }
+
+  return loop;
+}
+
+
+int uv_loop_close(uv_loop_t* loop) {
+  QUEUE* q;
+  uv_handle_t* h;
+#ifndef NDEBUG
+  void* saved_data;
+#endif
+
+  if (uv__has_active_reqs(loop))
+    return UV_EBUSY;
+
+  QUEUE_FOREACH(q, &loop->handle_queue) {
+    h = QUEUE_DATA(q, uv_handle_t, handle_queue);
+    if (!(h->flags & UV__HANDLE_INTERNAL))
+      return UV_EBUSY;
+  }
+
+  uv__loop_close(loop);
+
+#ifndef NDEBUG
+  saved_data = loop->data;
+  memset(loop, -1, sizeof(*loop));
+  loop->data = saved_data;
+#endif
+  if (loop == default_loop_ptr)
+    default_loop_ptr = NULL;
+
+  return 0;
+}
+
+
+void uv_loop_delete(uv_loop_t* loop) {
+  uv_loop_t* default_loop;
+  int err;
+
+  default_loop = default_loop_ptr;
+
+  err = uv_loop_close(loop);
+  (void) err;    /* Squelch compiler warnings. */
+  assert(err == 0);
+  if (loop != default_loop)
+    uv__free(loop);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-common.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-common.h
new file mode 100644
index 0000000..85bcbe6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-common.h
@@ -0,0 +1,260 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+/*
+ * This file is private to libuv. It provides common functionality to both
+ * Windows and Unix backends.
+ */
+
+#ifndef UV_COMMON_H_
+#define UV_COMMON_H_
+
+#include <assert.h>
+#include <stdarg.h>
+#include <stddef.h>
+
+#if defined(_MSC_VER) && _MSC_VER < 1600
+# include "uv/stdint-msvc2008.h"
+#else
+# include <stdint.h>
+#endif
+
+#include "uv.h"
+#include "uv/tree.h"
+#include "queue.h"
+
+#if EDOM > 0
+# define UV__ERR(x) (-(x))
+#else
+# define UV__ERR(x) (x)
+#endif
+
+#if !defined(snprintf) && defined(_MSC_VER) && _MSC_VER < 1900
+extern int snprintf(char*, size_t, const char*, ...);
+#endif
+
+#define ARRAY_SIZE(a) (sizeof(a) / sizeof((a)[0]))
+
+#define container_of(ptr, type, member) \
+  ((type *) ((char *) (ptr) - offsetof(type, member)))
+
+#define STATIC_ASSERT(expr)                                                   \
+  void uv__static_assert(int static_assert_failed[1 - 2 * !(expr)])
+
+#ifndef _WIN32
+enum {
+  UV__SIGNAL_ONE_SHOT = 0x80000,  /* On signal reception remove sighandler */
+  UV__HANDLE_INTERNAL = 0x8000,
+  UV__HANDLE_ACTIVE   = 0x4000,
+  UV__HANDLE_REF      = 0x2000,
+  UV__HANDLE_CLOSING  = 0 /* no-op on unix */
+};
+#else
+# define UV__SIGNAL_ONE_SHOT_DISPATCHED   0x200
+# define UV__SIGNAL_ONE_SHOT              0x100
+# define UV__HANDLE_INTERNAL              0x80
+# define UV__HANDLE_ACTIVE                0x40
+# define UV__HANDLE_REF                   0x20
+# define UV__HANDLE_CLOSING               0x01
+#endif
+
+int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap);
+
+void uv__loop_close(uv_loop_t* loop);
+
+int uv__tcp_bind(uv_tcp_t* tcp,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags);
+
+int uv__tcp_connect(uv_connect_t* req,
+                   uv_tcp_t* handle,
+                   const struct sockaddr* addr,
+                   unsigned int addrlen,
+                   uv_connect_cb cb);
+
+int uv__udp_bind(uv_udp_t* handle,
+                 const struct sockaddr* addr,
+                 unsigned int  addrlen,
+                 unsigned int flags);
+
+int uv__udp_send(uv_udp_send_t* req,
+                 uv_udp_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 uv_udp_send_cb send_cb);
+
+int uv__udp_try_send(uv_udp_t* handle,
+                     const uv_buf_t bufs[],
+                     unsigned int nbufs,
+                     const struct sockaddr* addr,
+                     unsigned int addrlen);
+
+int uv__udp_recv_start(uv_udp_t* handle, uv_alloc_cb alloccb,
+                       uv_udp_recv_cb recv_cb);
+
+int uv__udp_recv_stop(uv_udp_t* handle);
+
+void uv__fs_poll_close(uv_fs_poll_t* handle);
+
+int uv__getaddrinfo_translate_error(int sys_err);    /* EAI_* error. */
+
+void uv__work_submit(uv_loop_t* loop,
+                     struct uv__work *w,
+                     void (*work)(struct uv__work *w),
+                     void (*done)(struct uv__work *w, int status));
+
+void uv__work_done(uv_async_t* handle);
+
+size_t uv__count_bufs(const uv_buf_t bufs[], unsigned int nbufs);
+
+int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value);
+
+void uv__fs_scandir_cleanup(uv_fs_t* req);
+
+#define uv__has_active_reqs(loop)                                             \
+  ((loop)->active_reqs.count > 0)
+
+#define uv__req_register(loop, req)                                           \
+  do {                                                                        \
+    (loop)->active_reqs.count++;                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__req_unregister(loop, req)                                         \
+  do {                                                                        \
+    assert(uv__has_active_reqs(loop));                                        \
+    (loop)->active_reqs.count--;                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__has_active_handles(loop)                                          \
+  ((loop)->active_handles > 0)
+
+#define uv__active_handle_add(h)                                              \
+  do {                                                                        \
+    (h)->loop->active_handles++;                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__active_handle_rm(h)                                               \
+  do {                                                                        \
+    (h)->loop->active_handles--;                                              \
+  }                                                                           \
+  while (0)
+
+#define uv__is_active(h)                                                      \
+  (((h)->flags & UV__HANDLE_ACTIVE) != 0)
+
+#define uv__is_closing(h)                                                     \
+  (((h)->flags & (UV_CLOSING |  UV_CLOSED)) != 0)
+
+#define uv__handle_start(h)                                                   \
+  do {                                                                        \
+    assert(((h)->flags & UV__HANDLE_CLOSING) == 0);                           \
+    if (((h)->flags & UV__HANDLE_ACTIVE) != 0) break;                         \
+    (h)->flags |= UV__HANDLE_ACTIVE;                                          \
+    if (((h)->flags & UV__HANDLE_REF) != 0) uv__active_handle_add(h);         \
+  }                                                                           \
+  while (0)
+
+#define uv__handle_stop(h)                                                    \
+  do {                                                                        \
+    assert(((h)->flags & UV__HANDLE_CLOSING) == 0);                           \
+    if (((h)->flags & UV__HANDLE_ACTIVE) == 0) break;                         \
+    (h)->flags &= ~UV__HANDLE_ACTIVE;                                         \
+    if (((h)->flags & UV__HANDLE_REF) != 0) uv__active_handle_rm(h);          \
+  }                                                                           \
+  while (0)
+
+#define uv__handle_ref(h)                                                     \
+  do {                                                                        \
+    if (((h)->flags & UV__HANDLE_REF) != 0) break;                            \
+    (h)->flags |= UV__HANDLE_REF;                                             \
+    if (((h)->flags & UV__HANDLE_CLOSING) != 0) break;                        \
+    if (((h)->flags & UV__HANDLE_ACTIVE) != 0) uv__active_handle_add(h);      \
+  }                                                                           \
+  while (0)
+
+#define uv__handle_unref(h)                                                   \
+  do {                                                                        \
+    if (((h)->flags & UV__HANDLE_REF) == 0) break;                            \
+    (h)->flags &= ~UV__HANDLE_REF;                                            \
+    if (((h)->flags & UV__HANDLE_CLOSING) != 0) break;                        \
+    if (((h)->flags & UV__HANDLE_ACTIVE) != 0) uv__active_handle_rm(h);       \
+  }                                                                           \
+  while (0)
+
+#define uv__has_ref(h)                                                        \
+  (((h)->flags & UV__HANDLE_REF) != 0)
+
+#if defined(_WIN32)
+# define uv__handle_platform_init(h) ((h)->u.fd = -1)
+#else
+# define uv__handle_platform_init(h) ((h)->next_closing = NULL)
+#endif
+
+#define uv__handle_init(loop_, h, type_)                                      \
+  do {                                                                        \
+    (h)->loop = (loop_);                                                      \
+    (h)->type = (type_);                                                      \
+    (h)->flags = UV__HANDLE_REF;  /* Ref the loop when active. */             \
+    QUEUE_INSERT_TAIL(&(loop_)->handle_queue, &(h)->handle_queue);            \
+    uv__handle_platform_init(h);                                              \
+  }                                                                           \
+  while (0)
+
+/* Note: uses an open-coded version of SET_REQ_SUCCESS() because of
+ * a circular dependency between src/uv-common.h and src/win/internal.h.
+ */
+#if defined(_WIN32)
+# define UV_REQ_INIT(req, typ)                                                \
+  do {                                                                        \
+    (req)->type = (typ);                                                      \
+    (req)->u.io.overlapped.Internal = 0;  /* SET_REQ_SUCCESS() */             \
+  }                                                                           \
+  while (0)
+#else
+# define UV_REQ_INIT(req, typ)                                                \
+  do {                                                                        \
+    (req)->type = (typ);                                                      \
+  }                                                                           \
+  while (0)
+#endif
+
+#define uv__req_init(loop, req, typ)                                          \
+  do {                                                                        \
+    UV_REQ_INIT(req, typ);                                                    \
+    uv__req_register(loop, req);                                              \
+  }                                                                           \
+  while (0)
+
+/* Allocator prototypes */
+void *uv__calloc(size_t count, size_t size);
+char *uv__strdup(const char* s);
+char *uv__strndup(const char* s, size_t n);
+void* uv__malloc(size_t size);
+void uv__free(void* ptr);
+void* uv__realloc(void* ptr, size_t size);
+
+#endif /* UV_COMMON_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-data-getter-setters.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-data-getter-setters.cpp
new file mode 100644
index 0000000..533e4a2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/uv-data-getter-setters.cpp
@@ -0,0 +1,96 @@
+#include "uv.h"
+
+const char* uv_handle_type_name(uv_handle_type type) {
+  switch (type) {
+#define XX(uc,lc) case UV_##uc: return #lc;
+    UV_HANDLE_TYPE_MAP(XX)
+#undef XX
+    case UV_FILE: return "file";
+    case UV_HANDLE_TYPE_MAX:
+    case UV_UNKNOWN_HANDLE: return NULL;
+  }
+  return NULL;
+}
+
+uv_handle_type uv_handle_get_type(const uv_handle_t* handle) {
+  return handle->type;
+}
+
+void* uv_handle_get_data(const uv_handle_t* handle) {
+  return handle->data;
+}
+
+uv_loop_t* uv_handle_get_loop(const uv_handle_t* handle) {
+  return handle->loop;
+}
+
+void uv_handle_set_data(uv_handle_t* handle, void* data) {
+  handle->data = data;
+}
+
+const char* uv_req_type_name(uv_req_type type) {
+  switch (type) {
+#define XX(uc,lc) case UV_##uc: return #lc;
+    UV_REQ_TYPE_MAP(XX)
+#undef XX
+    case UV_REQ_TYPE_MAX:
+    case UV_UNKNOWN_REQ: return NULL;
+  }
+  return NULL;
+}
+
+uv_req_type uv_req_get_type(const uv_req_t* req) {
+  return req->type;
+}
+
+void* uv_req_get_data(const uv_req_t* req) {
+  return req->data;
+}
+
+void uv_req_set_data(uv_req_t* req, void* data) {
+  req->data = data;
+}
+
+size_t uv_stream_get_write_queue_size(const uv_stream_t* stream) {
+  return stream->write_queue_size;
+}
+
+size_t uv_udp_get_send_queue_size(const uv_udp_t* handle) {
+  return handle->send_queue_size;
+}
+
+size_t uv_udp_get_send_queue_count(const uv_udp_t* handle) {
+  return handle->send_queue_count;
+}
+
+uv_pid_t uv_process_get_pid(const uv_process_t* proc) {
+  return proc->pid;
+}
+
+uv_fs_type uv_fs_get_type(const uv_fs_t* req) {
+  return req->fs_type;
+}
+
+ssize_t uv_fs_get_result(const uv_fs_t* req) {
+  return req->result;
+}
+
+void* uv_fs_get_ptr(const uv_fs_t* req) {
+  return req->ptr;
+}
+
+const char* uv_fs_get_path(const uv_fs_t* req) {
+  return req->path;
+}
+
+uv_stat_t* uv_fs_get_statbuf(uv_fs_t* req) {
+  return &req->statbuf;
+}
+
+void* uv_loop_get_data(const uv_loop_t* loop) {
+  return loop->data;
+}
+
+void uv_loop_set_data(uv_loop_t* loop, void* data) {
+  loop->data = data;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/version.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/version.cpp
new file mode 100644
index 0000000..686dedd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/version.cpp
@@ -0,0 +1,45 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+
+#define UV_STRINGIFY(v) UV_STRINGIFY_HELPER(v)
+#define UV_STRINGIFY_HELPER(v) #v
+
+#define UV_VERSION_STRING_BASE  UV_STRINGIFY(UV_VERSION_MAJOR) "." \
+                                UV_STRINGIFY(UV_VERSION_MINOR) "." \
+                                UV_STRINGIFY(UV_VERSION_PATCH)
+
+#if UV_VERSION_IS_RELEASE
+# define UV_VERSION_STRING  UV_VERSION_STRING_BASE
+#else
+# define UV_VERSION_STRING  UV_VERSION_STRING_BASE "-" UV_VERSION_SUFFIX
+#endif
+
+
+unsigned int uv_version(void) {
+  return UV_VERSION_HEX;
+}
+
+
+const char* uv_version_string(void) {
+  return UV_VERSION_STRING;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/async.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/async.cpp
new file mode 100644
index 0000000..13d3c7b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/async.cpp
@@ -0,0 +1,98 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "atomicops-inl.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+void uv_async_endgame(uv_loop_t* loop, uv_async_t* handle) {
+  if (handle->flags & UV__HANDLE_CLOSING &&
+      !handle->async_sent) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+    uv__handle_close(handle);
+  }
+}
+
+
+int uv_async_init(uv_loop_t* loop, uv_async_t* handle, uv_async_cb async_cb) {
+  uv_req_t* req;
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_ASYNC);
+  handle->async_sent = 0;
+  handle->async_cb = async_cb;
+
+  req = &handle->async_req;
+  UV_REQ_INIT(req, UV_WAKEUP);
+  req->data = handle;
+
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+void uv_async_close(uv_loop_t* loop, uv_async_t* handle) {
+  if (!((uv_async_t*)handle)->async_sent) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+  }
+
+  uv__handle_closing(handle);
+}
+
+
+int uv_async_send(uv_async_t* handle) {
+  uv_loop_t* loop = handle->loop;
+
+  if (handle->type != UV_ASYNC) {
+    /* Can't set errno because that's not thread-safe. */
+    return -1;
+  }
+
+  /* The user should make sure never to call uv_async_send to a closing or
+   * closed handle. */
+  assert(!(handle->flags & UV__HANDLE_CLOSING));
+
+  if (!uv__atomic_exchange_set(&handle->async_sent)) {
+    POST_COMPLETION_FOR_REQ(loop, &handle->async_req);
+  }
+
+  return 0;
+}
+
+
+void uv_process_async_wakeup_req(uv_loop_t* loop, uv_async_t* handle,
+    uv_req_t* req) {
+  assert(handle->type == UV_ASYNC);
+  assert(req->type == UV_WAKEUP);
+
+  handle->async_sent = 0;
+
+  if (handle->flags & UV__HANDLE_CLOSING) {
+    uv_want_endgame(loop, (uv_handle_t*)handle);
+  } else if (handle->async_cb != NULL) {
+    handle->async_cb(handle);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/atomicops-inl.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/atomicops-inl.h
new file mode 100644
index 0000000..52713cf
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/atomicops-inl.h
@@ -0,0 +1,57 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_ATOMICOPS_INL_H_
+#define UV_WIN_ATOMICOPS_INL_H_
+
+#include "uv.h"
+#include "internal.h"
+
+
+/* Atomic set operation on char */
+#ifdef _MSC_VER /* MSVC */
+
+/* _InterlockedOr8 is supported by MSVC on x32 and x64. It is slightly less
+ * efficient than InterlockedExchange, but InterlockedExchange8 does not exist,
+ * and interlocked operations on larger targets might require the target to be
+ * aligned. */
+#pragma intrinsic(_InterlockedOr8)
+
+static char INLINE uv__atomic_exchange_set(char volatile* target) {
+  return _InterlockedOr8(target, 1);
+}
+
+#else /* GCC */
+
+/* Mingw-32 version, hopefully this works for 64-bit gcc as well. */
+static inline char uv__atomic_exchange_set(char volatile* target) {
+  const char one = 1;
+  char old_value;
+  __asm__ __volatile__ ("lock xchgb %0, %1\n\t"
+                        : "=r"(old_value), "=m"(*target)
+                        : "0"(one), "m"(*target)
+                        : "memory");
+  return old_value;
+}
+
+#endif
+
+#endif /* UV_WIN_ATOMICOPS_INL_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/core.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/core.cpp
new file mode 100644
index 0000000..7020cb6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/core.cpp
@@ -0,0 +1,550 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <errno.h>
+#include <limits.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+#if defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR)
+#include <crtdbg.h>
+#endif
+
+#include "uv.h"
+#include "internal.h"
+#include "queue.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+/* uv_once initialization guards */
+static uv_once_t uv_init_guard_ = UV_ONCE_INIT;
+
+
+#if defined(_DEBUG) && (defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR))
+/* Our crt debug report handler allows us to temporarily disable asserts
+ * just for the current thread.
+ */
+
+UV_THREAD_LOCAL int uv__crt_assert_enabled = TRUE;
+
+static int uv__crt_dbg_report_handler(int report_type, char *message, int *ret_val) {
+  if (uv__crt_assert_enabled || report_type != _CRT_ASSERT)
+    return FALSE;
+
+  if (ret_val) {
+    /* Set ret_val to 0 to continue with normal execution.
+     * Set ret_val to 1 to trigger a breakpoint.
+    */
+
+    if(IsDebuggerPresent())
+      *ret_val = 1;
+    else
+      *ret_val = 0;
+  }
+
+  /* Don't call _CrtDbgReport. */
+  return TRUE;
+}
+#else
+UV_THREAD_LOCAL int uv__crt_assert_enabled = FALSE;
+#endif
+
+
+#if !defined(__MINGW32__) || __MSVCRT_VERSION__ >= 0x800
+static void uv__crt_invalid_parameter_handler(const wchar_t* expression,
+    const wchar_t* function, const wchar_t * file, unsigned int line,
+    uintptr_t reserved) {
+  /* No-op. */
+}
+#endif
+
+static uv_loop_t** uv__loops;
+static int uv__loops_size;
+static int uv__loops_capacity;
+#define UV__LOOPS_CHUNK_SIZE 8
+static uv_mutex_t uv__loops_lock;
+
+static void uv__loops_init(void) {
+  uv_mutex_init(&uv__loops_lock);
+}
+
+static int uv__loops_add(uv_loop_t* loop) {
+  uv_loop_t** new_loops;
+  int new_capacity, i;
+
+  uv_mutex_lock(&uv__loops_lock);
+
+  if (uv__loops_size == uv__loops_capacity) {
+    new_capacity = uv__loops_capacity + UV__LOOPS_CHUNK_SIZE;
+    new_loops = (uv_loop_t**)
+        uv__realloc(uv__loops, sizeof(uv_loop_t*) * new_capacity);
+    if (!new_loops)
+      goto failed_loops_realloc;
+    uv__loops = new_loops;
+    for (i = uv__loops_capacity; i < new_capacity; ++i)
+      uv__loops[i] = NULL;
+    uv__loops_capacity = new_capacity;
+  }
+  uv__loops[uv__loops_size] = loop;
+  ++uv__loops_size;
+
+  uv_mutex_unlock(&uv__loops_lock);
+  return 0;
+
+failed_loops_realloc:
+  uv_mutex_unlock(&uv__loops_lock);
+  return ERROR_OUTOFMEMORY;
+}
+
+static void uv__loops_remove(uv_loop_t* loop) {
+  int loop_index;
+  int smaller_capacity;
+  uv_loop_t** new_loops;
+
+  uv_mutex_lock(&uv__loops_lock);
+
+  for (loop_index = 0; loop_index < uv__loops_size; ++loop_index) {
+    if (uv__loops[loop_index] == loop)
+      break;
+  }
+  /* If loop was not found, ignore */
+  if (loop_index == uv__loops_size)
+    goto loop_removed;
+
+  uv__loops[loop_index] = uv__loops[uv__loops_size - 1];
+  uv__loops[uv__loops_size - 1] = NULL;
+  --uv__loops_size;
+
+  if (uv__loops_size == 0) {
+    uv__loops_capacity = 0;
+    uv__free(uv__loops);
+    uv__loops = NULL;
+    goto loop_removed;
+  }
+
+  /* If we didn't grow to big skip downsizing */
+  if (uv__loops_capacity < 4 * UV__LOOPS_CHUNK_SIZE)
+    goto loop_removed;
+
+  /* Downsize only if more than half of buffer is free */
+  smaller_capacity = uv__loops_capacity / 2;
+  if (uv__loops_size >= smaller_capacity)
+    goto loop_removed;
+  new_loops = (uv_loop_t**)
+      uv__realloc(uv__loops, sizeof(uv_loop_t*) * smaller_capacity);
+  if (!new_loops)
+    goto loop_removed;
+  uv__loops = new_loops;
+  uv__loops_capacity = smaller_capacity;
+
+loop_removed:
+  uv_mutex_unlock(&uv__loops_lock);
+}
+
+void uv__wake_all_loops(void) {
+  int i;
+  uv_loop_t* loop;
+
+  uv_mutex_lock(&uv__loops_lock);
+  for (i = 0; i < uv__loops_size; ++i) {
+    loop = uv__loops[i];
+    assert(loop);
+    if (loop->iocp != INVALID_HANDLE_VALUE)
+      PostQueuedCompletionStatus(loop->iocp, 0, 0, NULL);
+  }
+  uv_mutex_unlock(&uv__loops_lock);
+}
+
+static void uv_init(void) {
+  /* Tell Windows that we will handle critical errors. */
+  SetErrorMode(SEM_FAILCRITICALERRORS | SEM_NOGPFAULTERRORBOX |
+               SEM_NOOPENFILEERRORBOX);
+
+  /* Tell the CRT to not exit the application when an invalid parameter is
+   * passed. The main issue is that invalid FDs will trigger this behavior.
+   */
+#if !defined(__MINGW32__) || __MSVCRT_VERSION__ >= 0x800
+  _set_invalid_parameter_handler(uv__crt_invalid_parameter_handler);
+#endif
+
+  /* We also need to setup our debug report handler because some CRT
+   * functions (eg _get_osfhandle) raise an assert when called with invalid
+   * FDs even though they return the proper error code in the release build.
+   */
+#if defined(_DEBUG) && (defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR))
+  _CrtSetReportHook(uv__crt_dbg_report_handler);
+#endif
+
+  /* Initialize tracking of all uv loops */
+  uv__loops_init();
+
+  /* Fetch winapi function pointers. This must be done first because other
+   * initialization code might need these function pointers to be loaded.
+   */
+  uv_winapi_init();
+
+  /* Initialize winsock */
+  uv_winsock_init();
+
+  /* Initialize FS */
+  uv_fs_init();
+
+  /* Initialize signal stuff */
+  uv_signals_init();
+
+  /* Initialize console */
+  uv_console_init();
+
+  /* Initialize utilities */
+  uv__util_init();
+
+  /* Initialize system wakeup detection */
+  uv__init_detect_system_wakeup();
+}
+
+
+int uv_loop_init(uv_loop_t* loop) {
+  int err;
+
+  /* Initialize libuv itself first */
+  uv__once_init();
+
+  /* Create an I/O completion port */
+  loop->iocp = CreateIoCompletionPort(INVALID_HANDLE_VALUE, NULL, 0, 1);
+  if (loop->iocp == NULL)
+    return uv_translate_sys_error(GetLastError());
+
+  /* To prevent uninitialized memory access, loop->time must be initialized
+   * to zero before calling uv_update_time for the first time.
+   */
+  loop->time = 0;
+  uv_update_time(loop);
+
+  QUEUE_INIT(&loop->wq);
+  QUEUE_INIT(&loop->handle_queue);
+  loop->active_reqs.count = 0;
+  loop->active_handles = 0;
+
+  loop->pending_reqs_tail = NULL;
+
+  loop->endgame_handles = NULL;
+
+  RB_INIT(&loop->timers);
+
+  loop->check_handles = NULL;
+  loop->prepare_handles = NULL;
+  loop->idle_handles = NULL;
+
+  loop->next_prepare_handle = NULL;
+  loop->next_check_handle = NULL;
+  loop->next_idle_handle = NULL;
+
+  memset(&loop->poll_peer_sockets, 0, sizeof loop->poll_peer_sockets);
+
+  loop->active_tcp_streams = 0;
+  loop->active_udp_streams = 0;
+
+  loop->timer_counter = 0;
+  loop->stop_flag = 0;
+
+  err = uv_mutex_init(&loop->wq_mutex);
+  if (err)
+    goto fail_mutex_init;
+
+  err = uv_async_init(loop, &loop->wq_async, uv__work_done);
+  if (err)
+    goto fail_async_init;
+
+  uv__handle_unref(&loop->wq_async);
+  loop->wq_async.flags |= UV__HANDLE_INTERNAL;
+
+  err = uv__loops_add(loop);
+  if (err)
+    goto fail_async_init;
+
+  return 0;
+
+fail_async_init:
+  uv_mutex_destroy(&loop->wq_mutex);
+
+fail_mutex_init:
+  CloseHandle(loop->iocp);
+  loop->iocp = INVALID_HANDLE_VALUE;
+
+  return err;
+}
+
+
+void uv__once_init(void) {
+  uv_once(&uv_init_guard_, uv_init);
+}
+
+
+void uv__loop_close(uv_loop_t* loop) {
+  size_t i;
+
+  uv__loops_remove(loop);
+
+  /* close the async handle without needing an extra loop iteration */
+  assert(!loop->wq_async.async_sent);
+  loop->wq_async.close_cb = NULL;
+  uv__handle_closing(&loop->wq_async);
+  uv__handle_close(&loop->wq_async);
+
+  for (i = 0; i < ARRAY_SIZE(loop->poll_peer_sockets); i++) {
+    SOCKET sock = loop->poll_peer_sockets[i];
+    if (sock != 0 && sock != INVALID_SOCKET)
+      closesocket(sock);
+  }
+
+  uv_mutex_lock(&loop->wq_mutex);
+  assert(QUEUE_EMPTY(&loop->wq) && "thread pool work queue not empty!");
+  assert(!uv__has_active_reqs(loop));
+  uv_mutex_unlock(&loop->wq_mutex);
+  uv_mutex_destroy(&loop->wq_mutex);
+
+  CloseHandle(loop->iocp);
+}
+
+
+int uv__loop_configure(uv_loop_t* loop, uv_loop_option option, va_list ap) {
+  return UV_ENOSYS;
+}
+
+
+int uv_backend_fd(const uv_loop_t* loop) {
+  return -1;
+}
+
+
+int uv_loop_fork(uv_loop_t* loop) {
+  return UV_ENOSYS;
+}
+
+
+int uv_backend_timeout(const uv_loop_t* loop) {
+  if (loop->stop_flag != 0)
+    return 0;
+
+  if (!uv__has_active_handles(loop) && !uv__has_active_reqs(loop))
+    return 0;
+
+  if (loop->pending_reqs_tail)
+    return 0;
+
+  if (loop->endgame_handles)
+    return 0;
+
+  if (loop->idle_handles)
+    return 0;
+
+  return uv__next_timeout(loop);
+}
+
+
+static void uv__poll(uv_loop_t* loop, DWORD timeout) {
+  BOOL success;
+  uv_req_t* req;
+  OVERLAPPED_ENTRY overlappeds[128];
+  ULONG count;
+  ULONG i;
+  int repeat;
+  uint64_t timeout_time;
+
+  timeout_time = loop->time + timeout;
+
+  for (repeat = 0; ; repeat++) {
+    success = GetQueuedCompletionStatusEx(loop->iocp,
+                                          overlappeds,
+                                          ARRAY_SIZE(overlappeds),
+                                          &count,
+                                          timeout,
+                                          FALSE);
+
+    if (success) {
+      for (i = 0; i < count; i++) {
+        /* Package was dequeued, but see if it is not a empty package
+         * meant only to wake us up.
+         */
+        if (overlappeds[i].lpOverlapped) {
+          req = uv_overlapped_to_req(overlappeds[i].lpOverlapped);
+          uv_insert_pending_req(loop, req);
+        }
+      }
+
+      /* Some time might have passed waiting for I/O,
+       * so update the loop time here.
+       */
+      uv_update_time(loop);
+    } else if (GetLastError() != WAIT_TIMEOUT) {
+      /* Serious error */
+      uv_fatal_error(GetLastError(), "GetQueuedCompletionStatusEx");
+    } else if (timeout > 0) {
+      /* GetQueuedCompletionStatus can occasionally return a little early.
+       * Make sure that the desired timeout target time is reached.
+       */
+      uv_update_time(loop);
+      if (timeout_time > loop->time) {
+        timeout = (DWORD)(timeout_time - loop->time);
+        /* The first call to GetQueuedCompletionStatus should return very
+         * close to the target time and the second should reach it, but
+         * this is not stated in the documentation. To make sure a busy
+         * loop cannot happen, the timeout is increased exponentially
+         * starting on the third round.
+         */
+        timeout += repeat ? (1 << (repeat - 1)) : 0;
+        continue;
+      }
+    }
+    break;
+  }
+}
+
+
+static int uv__loop_alive(const uv_loop_t* loop) {
+  return uv__has_active_handles(loop) ||
+         uv__has_active_reqs(loop) ||
+         loop->endgame_handles != NULL;
+}
+
+
+int uv_loop_alive(const uv_loop_t* loop) {
+    return uv__loop_alive(loop);
+}
+
+
+int uv_run(uv_loop_t *loop, uv_run_mode mode) {
+  DWORD timeout;
+  int r;
+  int ran_pending;
+
+  r = uv__loop_alive(loop);
+  if (!r)
+    uv_update_time(loop);
+
+  while (r != 0 && loop->stop_flag == 0) {
+    uv_update_time(loop);
+    uv_process_timers(loop);
+
+    ran_pending = uv_process_reqs(loop);
+    uv_idle_invoke(loop);
+    uv_prepare_invoke(loop);
+
+    timeout = 0;
+    if ((mode == UV_RUN_ONCE && !ran_pending) || mode == UV_RUN_DEFAULT)
+      timeout = uv_backend_timeout(loop);
+
+    uv__poll(loop, timeout);
+
+    uv_check_invoke(loop);
+    uv_process_endgames(loop);
+
+    if (mode == UV_RUN_ONCE) {
+      /* UV_RUN_ONCE implies forward progress: at least one callback must have
+       * been invoked when it returns. uv__io_poll() can return without doing
+       * I/O (meaning: no callbacks) when its timeout expires - which means we
+       * have pending timers that satisfy the forward progress constraint.
+       *
+       * UV_RUN_NOWAIT makes no guarantees about progress so it's omitted from
+       * the check.
+       */
+      uv_process_timers(loop);
+    }
+
+    r = uv__loop_alive(loop);
+    if (mode == UV_RUN_ONCE || mode == UV_RUN_NOWAIT)
+      break;
+  }
+
+  /* The if statement lets the compiler compile it to a conditional store.
+   * Avoids dirtying a cache line.
+   */
+  if (loop->stop_flag != 0)
+    loop->stop_flag = 0;
+
+  return r;
+}
+
+
+int uv_fileno(const uv_handle_t* handle, uv_os_fd_t* fd) {
+  uv_os_fd_t fd_out;
+
+  switch (handle->type) {
+  case UV_TCP:
+    fd_out = (uv_os_fd_t)((uv_tcp_t*) handle)->socket;
+    break;
+
+  case UV_NAMED_PIPE:
+    fd_out = ((uv_pipe_t*) handle)->handle;
+    break;
+
+  case UV_TTY:
+    fd_out = ((uv_tty_t*) handle)->handle;
+    break;
+
+  case UV_UDP:
+    fd_out = (uv_os_fd_t)((uv_udp_t*) handle)->socket;
+    break;
+
+  case UV_POLL:
+    fd_out = (uv_os_fd_t)((uv_poll_t*) handle)->socket;
+    break;
+
+  default:
+    return UV_EINVAL;
+  }
+
+  if (uv_is_closing(handle) || fd_out == INVALID_HANDLE_VALUE)
+    return UV_EBADF;
+
+  *fd = fd_out;
+  return 0;
+}
+
+
+int uv__socket_sockopt(uv_handle_t* handle, int optname, int* value) {
+  int r;
+  int len;
+  SOCKET socket;
+
+  if (handle == NULL || value == NULL)
+    return UV_EINVAL;
+
+  if (handle->type == UV_TCP)
+    socket = ((uv_tcp_t*) handle)->socket;
+  else if (handle->type == UV_UDP)
+    socket = ((uv_udp_t*) handle)->socket;
+  else
+    return UV_ENOTSUP;
+
+  len = sizeof(*value);
+
+  if (*value == 0)
+    r = getsockopt(socket, SOL_SOCKET, optname, (char*) value, &len);
+  else
+    r = setsockopt(socket, SOL_SOCKET, optname, (const char*) value, len);
+
+  if (r == SOCKET_ERROR)
+    return uv_translate_sys_error(WSAGetLastError());
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/detect-wakeup.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/detect-wakeup.cpp
new file mode 100644
index 0000000..72dfb7a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/detect-wakeup.cpp
@@ -0,0 +1,35 @@
+#include "uv.h"
+#include "internal.h"
+#include "winapi.h"
+
+static void uv__register_system_resume_callback(void);
+
+void uv__init_detect_system_wakeup(void) {
+  /* Try registering system power event callback. This is the cleanest
+   * method, but it will only work on Win8 and above.
+   */
+  uv__register_system_resume_callback();
+}
+
+static ULONG CALLBACK uv__system_resume_callback(PVOID Context,
+                                                 ULONG Type,
+                                                 PVOID Setting) {
+  if (Type == PBT_APMRESUMESUSPEND || Type == PBT_APMRESUMEAUTOMATIC)
+    uv__wake_all_loops();
+
+  return 0;
+}
+
+static void uv__register_system_resume_callback(void) {
+  _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS recipient;
+  _HPOWERNOTIFY registration_handle;
+
+  if (pPowerRegisterSuspendResumeNotification == NULL)
+    return;
+
+  recipient.Callback = uv__system_resume_callback;
+  recipient.Context = NULL;
+  (*pPowerRegisterSuspendResumeNotification)(DEVICE_NOTIFY_CALLBACK,
+                                             &recipient,
+                                             &registration_handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/dl.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/dl.cpp
new file mode 100644
index 0000000..97ac1c1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/dl.cpp
@@ -0,0 +1,133 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "uv.h"
+#include "internal.h"
+
+static int uv__dlerror(uv_lib_t* lib, const char* filename, DWORD errorno);
+
+
+int uv_dlopen(const char* filename, uv_lib_t* lib) {
+  WCHAR filename_w[32768];
+
+  lib->handle = NULL;
+  lib->errmsg = NULL;
+
+  if (!MultiByteToWideChar(CP_UTF8,
+                           0,
+                           filename,
+                           -1,
+                           filename_w,
+                           ARRAY_SIZE(filename_w))) {
+    return uv__dlerror(lib, filename, GetLastError());
+  }
+
+  lib->handle = LoadLibraryExW(filename_w, NULL, LOAD_WITH_ALTERED_SEARCH_PATH);
+  if (lib->handle == NULL) {
+    return uv__dlerror(lib, filename, GetLastError());
+  }
+
+  return 0;
+}
+
+
+void uv_dlclose(uv_lib_t* lib) {
+  if (lib->errmsg) {
+    LocalFree((void*)lib->errmsg);
+    lib->errmsg = NULL;
+  }
+
+  if (lib->handle) {
+    /* Ignore errors. No good way to signal them without leaking memory. */
+    FreeLibrary(lib->handle);
+    lib->handle = NULL;
+  }
+}
+
+
+int uv_dlsym(uv_lib_t* lib, const char* name, void** ptr) {
+  *ptr = (void*) GetProcAddress(lib->handle, name);
+  return uv__dlerror(lib, "", *ptr ? 0 : GetLastError());
+}
+
+
+const char* uv_dlerror(const uv_lib_t* lib) {
+  return lib->errmsg ? lib->errmsg : "no error";
+}
+
+
+static void uv__format_fallback_error(uv_lib_t* lib, int errorno){
+  DWORD_PTR args[1] = { (DWORD_PTR) errorno };
+  LPSTR fallback_error = "error: %1!d!";
+
+  FormatMessageA(FORMAT_MESSAGE_FROM_STRING |
+                 FORMAT_MESSAGE_ARGUMENT_ARRAY |
+                 FORMAT_MESSAGE_ALLOCATE_BUFFER,
+                 fallback_error, 0, 0,
+                 (LPSTR) &lib->errmsg,
+                 0, (va_list*) args);
+}
+
+
+
+static int uv__dlerror(uv_lib_t* lib, const char* filename, DWORD errorno) {
+  DWORD_PTR arg;
+  DWORD res;
+  char* msg;
+
+  if (lib->errmsg) {
+    LocalFree(lib->errmsg);
+    lib->errmsg = NULL;
+  }
+
+  if (errorno == 0)
+    return 0;
+
+  res = FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER |
+                       FORMAT_MESSAGE_FROM_SYSTEM |
+                       FORMAT_MESSAGE_IGNORE_INSERTS, NULL, errorno,
+                       MAKELANGID(LANG_ENGLISH, SUBLANG_ENGLISH_US),
+                       (LPSTR) &lib->errmsg, 0, NULL);
+
+  if (!res && GetLastError() == ERROR_MUI_FILE_NOT_FOUND) {
+    res = FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER |
+                         FORMAT_MESSAGE_FROM_SYSTEM |
+                         FORMAT_MESSAGE_IGNORE_INSERTS, NULL, errorno,
+                         0, (LPSTR) &lib->errmsg, 0, NULL);
+  }
+
+  if (res && errorno == ERROR_BAD_EXE_FORMAT && strstr(lib->errmsg, "%1")) {
+    msg = lib->errmsg;
+    lib->errmsg = NULL;
+    arg = (DWORD_PTR) filename;
+    res = FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER |
+                         FORMAT_MESSAGE_ARGUMENT_ARRAY |
+                         FORMAT_MESSAGE_FROM_STRING,
+                         msg,
+                         0, 0, (LPSTR) &lib->errmsg, 0, (va_list*) &arg);
+    LocalFree(msg);
+  }
+
+  if (!res)
+    uv__format_fallback_error(lib, errorno);
+
+  return -1;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/error.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/error.cpp
new file mode 100644
index 0000000..24924ba
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/error.cpp
@@ -0,0 +1,171 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <errno.h>
+#include <stdio.h>
+#include <string.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+/*
+ * Display an error message and abort the event loop.
+ */
+void uv_fatal_error(const int errorno, const char* syscall) {
+  char* buf = NULL;
+  const char* errmsg;
+
+  FormatMessageA(FORMAT_MESSAGE_ALLOCATE_BUFFER | FORMAT_MESSAGE_FROM_SYSTEM |
+      FORMAT_MESSAGE_IGNORE_INSERTS, NULL, errorno,
+      MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), (LPSTR)&buf, 0, NULL);
+
+  if (buf) {
+    errmsg = buf;
+  } else {
+    errmsg = "Unknown error";
+  }
+
+  /* FormatMessage messages include a newline character already, so don't add
+   * another. */
+  if (syscall) {
+    fprintf(stderr, "%s: (%d) %s", syscall, errorno, errmsg);
+  } else {
+    fprintf(stderr, "(%d) %s", errorno, errmsg);
+  }
+
+  if (buf) {
+    LocalFree(buf);
+  }
+
+  DebugBreak();
+  abort();
+}
+
+
+int uv_translate_sys_error(int sys_errno) {
+  if (sys_errno <= 0) {
+    return sys_errno;  /* If < 0 then it's already a libuv error. */
+  }
+
+  switch (sys_errno) {
+    case ERROR_NOACCESS:                    return UV_EACCES;
+    case WSAEACCES:                         return UV_EACCES;
+    case ERROR_ELEVATION_REQUIRED:          return UV_EACCES;
+    case ERROR_ADDRESS_ALREADY_ASSOCIATED:  return UV_EADDRINUSE;
+    case WSAEADDRINUSE:                     return UV_EADDRINUSE;
+    case WSAEADDRNOTAVAIL:                  return UV_EADDRNOTAVAIL;
+    case WSAEAFNOSUPPORT:                   return UV_EAFNOSUPPORT;
+    case WSAEWOULDBLOCK:                    return UV_EAGAIN;
+    case WSAEALREADY:                       return UV_EALREADY;
+    case ERROR_INVALID_FLAGS:               return UV_EBADF;
+    case ERROR_INVALID_HANDLE:              return UV_EBADF;
+    case ERROR_LOCK_VIOLATION:              return UV_EBUSY;
+    case ERROR_PIPE_BUSY:                   return UV_EBUSY;
+    case ERROR_SHARING_VIOLATION:           return UV_EBUSY;
+    case ERROR_OPERATION_ABORTED:           return UV_ECANCELED;
+    case WSAEINTR:                          return UV_ECANCELED;
+    case ERROR_NO_UNICODE_TRANSLATION:      return UV_ECHARSET;
+    case ERROR_CONNECTION_ABORTED:          return UV_ECONNABORTED;
+    case WSAECONNABORTED:                   return UV_ECONNABORTED;
+    case ERROR_CONNECTION_REFUSED:          return UV_ECONNREFUSED;
+    case WSAECONNREFUSED:                   return UV_ECONNREFUSED;
+    case ERROR_NETNAME_DELETED:             return UV_ECONNRESET;
+    case WSAECONNRESET:                     return UV_ECONNRESET;
+    case ERROR_ALREADY_EXISTS:              return UV_EEXIST;
+    case ERROR_FILE_EXISTS:                 return UV_EEXIST;
+    case ERROR_BUFFER_OVERFLOW:             return UV_EFAULT;
+    case WSAEFAULT:                         return UV_EFAULT;
+    case ERROR_HOST_UNREACHABLE:            return UV_EHOSTUNREACH;
+    case WSAEHOSTUNREACH:                   return UV_EHOSTUNREACH;
+    case ERROR_INSUFFICIENT_BUFFER:         return UV_EINVAL;
+    case ERROR_INVALID_DATA:                return UV_EINVAL;
+    case ERROR_INVALID_PARAMETER:           return UV_EINVAL;
+    case ERROR_SYMLINK_NOT_SUPPORTED:       return UV_EINVAL;
+    case WSAEINVAL:                         return UV_EINVAL;
+    case WSAEPFNOSUPPORT:                   return UV_EINVAL;
+    case WSAESOCKTNOSUPPORT:                return UV_EINVAL;
+    case ERROR_BEGINNING_OF_MEDIA:          return UV_EIO;
+    case ERROR_BUS_RESET:                   return UV_EIO;
+    case ERROR_CRC:                         return UV_EIO;
+    case ERROR_DEVICE_DOOR_OPEN:            return UV_EIO;
+    case ERROR_DEVICE_REQUIRES_CLEANING:    return UV_EIO;
+    case ERROR_DISK_CORRUPT:                return UV_EIO;
+    case ERROR_EOM_OVERFLOW:                return UV_EIO;
+    case ERROR_FILEMARK_DETECTED:           return UV_EIO;
+    case ERROR_GEN_FAILURE:                 return UV_EIO;
+    case ERROR_INVALID_BLOCK_LENGTH:        return UV_EIO;
+    case ERROR_IO_DEVICE:                   return UV_EIO;
+    case ERROR_NO_DATA_DETECTED:            return UV_EIO;
+    case ERROR_NO_SIGNAL_SENT:              return UV_EIO;
+    case ERROR_OPEN_FAILED:                 return UV_EIO;
+    case ERROR_SETMARK_DETECTED:            return UV_EIO;
+    case ERROR_SIGNAL_REFUSED:              return UV_EIO;
+    case WSAEISCONN:                        return UV_EISCONN;
+    case ERROR_CANT_RESOLVE_FILENAME:       return UV_ELOOP;
+    case ERROR_TOO_MANY_OPEN_FILES:         return UV_EMFILE;
+    case WSAEMFILE:                         return UV_EMFILE;
+    case WSAEMSGSIZE:                       return UV_EMSGSIZE;
+    case ERROR_FILENAME_EXCED_RANGE:        return UV_ENAMETOOLONG;
+    case ERROR_NETWORK_UNREACHABLE:         return UV_ENETUNREACH;
+    case WSAENETUNREACH:                    return UV_ENETUNREACH;
+    case WSAENOBUFS:                        return UV_ENOBUFS;
+    case ERROR_BAD_PATHNAME:                return UV_ENOENT;
+    case ERROR_DIRECTORY:                   return UV_ENOENT;
+    case ERROR_FILE_NOT_FOUND:              return UV_ENOENT;
+    case ERROR_INVALID_NAME:                return UV_ENOENT;
+    case ERROR_INVALID_DRIVE:               return UV_ENOENT;
+    case ERROR_INVALID_REPARSE_DATA:        return UV_ENOENT;
+    case ERROR_MOD_NOT_FOUND:               return UV_ENOENT;
+    case ERROR_PATH_NOT_FOUND:              return UV_ENOENT;
+    case WSAHOST_NOT_FOUND:                 return UV_ENOENT;
+    case WSANO_DATA:                        return UV_ENOENT;
+    case ERROR_NOT_ENOUGH_MEMORY:           return UV_ENOMEM;
+    case ERROR_OUTOFMEMORY:                 return UV_ENOMEM;
+    case ERROR_CANNOT_MAKE:                 return UV_ENOSPC;
+    case ERROR_DISK_FULL:                   return UV_ENOSPC;
+    case ERROR_EA_TABLE_FULL:               return UV_ENOSPC;
+    case ERROR_END_OF_MEDIA:                return UV_ENOSPC;
+    case ERROR_HANDLE_DISK_FULL:            return UV_ENOSPC;
+    case ERROR_NOT_CONNECTED:               return UV_ENOTCONN;
+    case WSAENOTCONN:                       return UV_ENOTCONN;
+    case ERROR_DIR_NOT_EMPTY:               return UV_ENOTEMPTY;
+    case WSAENOTSOCK:                       return UV_ENOTSOCK;
+    case ERROR_NOT_SUPPORTED:               return UV_ENOTSUP;
+    case ERROR_BROKEN_PIPE:                 return UV_EOF;
+    case ERROR_ACCESS_DENIED:               return UV_EPERM;
+    case ERROR_PRIVILEGE_NOT_HELD:          return UV_EPERM;
+    case ERROR_BAD_PIPE:                    return UV_EPIPE;
+    case ERROR_NO_DATA:                     return UV_EPIPE;
+    case ERROR_PIPE_NOT_CONNECTED:          return UV_EPIPE;
+    case WSAESHUTDOWN:                      return UV_EPIPE;
+    case WSAEPROTONOSUPPORT:                return UV_EPROTONOSUPPORT;
+    case ERROR_WRITE_PROTECT:               return UV_EROFS;
+    case ERROR_SEM_TIMEOUT:                 return UV_ETIMEDOUT;
+    case WSAETIMEDOUT:                      return UV_ETIMEDOUT;
+    case ERROR_NOT_SAME_DEVICE:             return UV_EXDEV;
+    case ERROR_INVALID_FUNCTION:            return UV_EISDIR;
+    case ERROR_META_EXPANSION_TOO_LONG:     return UV_E2BIG;
+    default:                                return UV_UNKNOWN;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/fs-event.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/fs-event.cpp
new file mode 100644
index 0000000..9ef90f3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/fs-event.cpp
@@ -0,0 +1,586 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <errno.h>
+#include <stdio.h>
+#include <string.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+const unsigned int uv_directory_watcher_buffer_size = 4096;
+
+
+static void uv_fs_event_queue_readdirchanges(uv_loop_t* loop,
+    uv_fs_event_t* handle) {
+  assert(handle->dir_handle != INVALID_HANDLE_VALUE);
+  assert(!handle->req_pending);
+
+  memset(&(handle->req.u.io.overlapped), 0,
+         sizeof(handle->req.u.io.overlapped));
+  if (!ReadDirectoryChangesW(handle->dir_handle,
+                             handle->buffer,
+                             uv_directory_watcher_buffer_size,
+                             (handle->flags & UV_FS_EVENT_RECURSIVE) ? TRUE : FALSE,
+                             FILE_NOTIFY_CHANGE_FILE_NAME      |
+                               FILE_NOTIFY_CHANGE_DIR_NAME     |
+                               FILE_NOTIFY_CHANGE_ATTRIBUTES   |
+                               FILE_NOTIFY_CHANGE_SIZE         |
+                               FILE_NOTIFY_CHANGE_LAST_WRITE   |
+                               FILE_NOTIFY_CHANGE_LAST_ACCESS  |
+                               FILE_NOTIFY_CHANGE_CREATION     |
+                               FILE_NOTIFY_CHANGE_SECURITY,
+                             NULL,
+                             &handle->req.u.io.overlapped,
+                             NULL)) {
+    /* Make this req pending reporting an error. */
+    SET_REQ_ERROR(&handle->req, GetLastError());
+    uv_insert_pending_req(loop, (uv_req_t*)&handle->req);
+  }
+
+  handle->req_pending = 1;
+}
+
+static void uv_relative_path(const WCHAR* filename,
+                             const WCHAR* dir,
+                             WCHAR** relpath) {
+  size_t relpathlen;
+  size_t filenamelen = wcslen(filename);
+  size_t dirlen = wcslen(dir);
+  assert(!_wcsnicmp(filename, dir, dirlen));
+  if (dirlen > 0 && dir[dirlen - 1] == '\\')
+    dirlen--;
+  relpathlen = filenamelen - dirlen - 1;
+  *relpath = (WCHAR*)uv__malloc((relpathlen + 1) * sizeof(WCHAR));
+  if (!*relpath)
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  wcsncpy(*relpath, filename + dirlen + 1, relpathlen);
+  (*relpath)[relpathlen] = L'\0';
+}
+
+static int uv_split_path(const WCHAR* filename, WCHAR** dir,
+    WCHAR** file) {
+  size_t len, i;
+ 
+  if (filename == NULL) {
+    if (dir != NULL)
+      *dir = NULL;
+    *file = NULL;
+    return 0;
+  }
+
+  len = wcslen(filename);
+  i = len;
+  while (i > 0 && filename[--i] != '\\' && filename[i] != '/');
+
+  if (i == 0) {
+    if (dir) {
+      *dir = (WCHAR*)uv__malloc((MAX_PATH + 1) * sizeof(WCHAR));
+      if (!*dir) {
+        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+      }
+
+      if (!GetCurrentDirectoryW(MAX_PATH, *dir)) {
+        uv__free(*dir);
+        *dir = NULL;
+        return -1;
+      }
+    }
+
+    *file = wcsdup(filename);
+  } else {
+    if (dir) {
+      *dir = (WCHAR*)uv__malloc((i + 2) * sizeof(WCHAR));
+      if (!*dir) {
+        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+      }
+      wcsncpy(*dir, filename, i + 1);
+      (*dir)[i + 1] = L'\0';
+    }
+
+    *file = (WCHAR*)uv__malloc((len - i) * sizeof(WCHAR));
+    if (!*file) {
+      uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+    }
+    wcsncpy(*file, filename + i + 1, len - i - 1);
+    (*file)[len - i - 1] = L'\0';
+  }
+
+  return 0;
+}
+
+
+int uv_fs_event_init(uv_loop_t* loop, uv_fs_event_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_FS_EVENT);
+  handle->dir_handle = INVALID_HANDLE_VALUE;
+  handle->buffer = NULL;
+  handle->req_pending = 0;
+  handle->filew = NULL;
+  handle->short_filew = NULL;
+  handle->dirw = NULL;
+
+  UV_REQ_INIT(&handle->req, UV_FS_EVENT_REQ);
+  handle->req.data = handle;
+
+  return 0;
+}
+
+
+int uv_fs_event_start(uv_fs_event_t* handle,
+                      uv_fs_event_cb cb,
+                      const char* path,
+                      unsigned int flags) {
+  int name_size, is_path_dir, size;
+  DWORD attr, last_error;
+  WCHAR* dir = NULL, *dir_to_watch, *pathw = NULL;
+  WCHAR short_path_buffer[MAX_PATH];
+  WCHAR* short_path, *long_path;
+
+  if (uv__is_active(handle))
+    return UV_EINVAL;
+
+  handle->cb = cb;
+  handle->path = uv__strdup(path);
+  if (!handle->path) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  uv__handle_start(handle);
+
+  /* Convert name to UTF16. */
+
+  name_size = MultiByteToWideChar(CP_UTF8, 0, path, -1, NULL, 0) *
+              sizeof(WCHAR);
+  pathw = (WCHAR*)uv__malloc(name_size);
+  if (!pathw) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  if (!MultiByteToWideChar(CP_UTF8,
+                           0,
+                           path,
+                           -1,
+                           pathw,
+                           name_size / sizeof(WCHAR))) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  /* Determine whether path is a file or a directory. */
+  attr = GetFileAttributesW(pathw);
+  if (attr == INVALID_FILE_ATTRIBUTES) {
+    last_error = GetLastError();
+    goto error;
+  }
+
+  is_path_dir = (attr & FILE_ATTRIBUTE_DIRECTORY) ? 1 : 0;
+
+  if (is_path_dir) {
+     /* path is a directory, so that's the directory that we will watch. */
+
+    /* Convert to long path. */
+    size = GetLongPathNameW(pathw, NULL, 0);
+
+    if (size) {
+      long_path = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
+      if (!long_path) {
+        uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+      }
+
+      size = GetLongPathNameW(pathw, long_path, size);
+      if (size) {
+        long_path[size] = '\0';
+      } else {
+        uv__free(long_path);
+        long_path = NULL;
+      }
+    }
+
+    if (long_path) {
+      uv__free(pathw);
+      pathw = long_path;
+    }
+
+    dir_to_watch = pathw;
+  } else {
+    /*
+     * path is a file.  So we split path into dir & file parts, and
+     * watch the dir directory.
+     */
+
+    /* Convert to short path. */
+    short_path = short_path_buffer;
+    if (!GetShortPathNameW(pathw, short_path, ARRAY_SIZE(short_path))) {
+      short_path = NULL;
+    }
+
+    if (uv_split_path(pathw, &dir, &handle->filew) != 0) {
+      last_error = GetLastError();
+      goto error;
+    }
+
+    if (uv_split_path(short_path, NULL, &handle->short_filew) != 0) {
+      last_error = GetLastError();
+      goto error;
+    }
+
+    dir_to_watch = dir;
+    uv__free(pathw);
+    pathw = NULL;
+  }
+
+  handle->dir_handle = CreateFileW(dir_to_watch,
+                                   FILE_LIST_DIRECTORY,
+                                   FILE_SHARE_READ | FILE_SHARE_DELETE |
+                                     FILE_SHARE_WRITE,
+                                   NULL,
+                                   OPEN_EXISTING,
+                                   FILE_FLAG_BACKUP_SEMANTICS |
+                                     FILE_FLAG_OVERLAPPED,
+                                   NULL);
+
+  if (dir) {
+    uv__free(dir);
+    dir = NULL;
+  }
+
+  if (handle->dir_handle == INVALID_HANDLE_VALUE) {
+    last_error = GetLastError();
+    goto error;
+  }
+
+  if (CreateIoCompletionPort(handle->dir_handle,
+                             handle->loop->iocp,
+                             (ULONG_PTR)handle,
+                             0) == NULL) {
+    last_error = GetLastError();
+    goto error;
+  }
+
+  if (!handle->buffer) {
+    handle->buffer = (char*)uv__malloc(uv_directory_watcher_buffer_size);
+  }
+  if (!handle->buffer) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  memset(&(handle->req.u.io.overlapped), 0,
+         sizeof(handle->req.u.io.overlapped));
+
+  if (!ReadDirectoryChangesW(handle->dir_handle,
+                             handle->buffer,
+                             uv_directory_watcher_buffer_size,
+                             (flags & UV_FS_EVENT_RECURSIVE) ? TRUE : FALSE,
+                             FILE_NOTIFY_CHANGE_FILE_NAME      |
+                               FILE_NOTIFY_CHANGE_DIR_NAME     |
+                               FILE_NOTIFY_CHANGE_ATTRIBUTES   |
+                               FILE_NOTIFY_CHANGE_SIZE         |
+                               FILE_NOTIFY_CHANGE_LAST_WRITE   |
+                               FILE_NOTIFY_CHANGE_LAST_ACCESS  |
+                               FILE_NOTIFY_CHANGE_CREATION     |
+                               FILE_NOTIFY_CHANGE_SECURITY,
+                             NULL,
+                             &handle->req.u.io.overlapped,
+                             NULL)) {
+    last_error = GetLastError();
+    goto error;
+  }
+
+  assert(is_path_dir ? pathw != NULL : pathw == NULL);
+  handle->dirw = pathw;
+  handle->req_pending = 1;
+  return 0;
+
+error:
+  if (handle->path) {
+    uv__free(handle->path);
+    handle->path = NULL;
+  }
+
+  if (handle->filew) {
+    uv__free(handle->filew);
+    handle->filew = NULL;
+  }
+
+  if (handle->short_filew) {
+    uv__free(handle->short_filew);
+    handle->short_filew = NULL;
+  }
+
+  uv__free(pathw);
+
+  if (handle->dir_handle != INVALID_HANDLE_VALUE) {
+    CloseHandle(handle->dir_handle);
+    handle->dir_handle = INVALID_HANDLE_VALUE;
+  }
+
+  if (handle->buffer) {
+    uv__free(handle->buffer);
+    handle->buffer = NULL;
+  }
+
+  if (uv__is_active(handle))
+    uv__handle_stop(handle);
+
+  return uv_translate_sys_error(last_error);
+}
+
+
+int uv_fs_event_stop(uv_fs_event_t* handle) {
+  if (!uv__is_active(handle))
+    return 0;
+
+  if (handle->dir_handle != INVALID_HANDLE_VALUE) {
+    CloseHandle(handle->dir_handle);
+    handle->dir_handle = INVALID_HANDLE_VALUE;
+  }
+
+  uv__handle_stop(handle);
+
+  if (handle->filew) {
+    uv__free(handle->filew);
+    handle->filew = NULL;
+  }
+
+  if (handle->short_filew) {
+    uv__free(handle->short_filew);
+    handle->short_filew = NULL;
+  }
+
+  if (handle->path) {
+    uv__free(handle->path);
+    handle->path = NULL;
+  }
+
+  if (handle->dirw) {
+    uv__free(handle->dirw);
+    handle->dirw = NULL;
+  }
+
+  return 0;
+}
+
+
+static int file_info_cmp(WCHAR* str, WCHAR* file_name, size_t file_name_len) {
+  size_t str_len;
+
+  if (str == NULL)
+    return -1;
+
+  str_len = wcslen(str);
+
+  /*
+    Since we only care about equality, return early if the strings
+    aren't the same length
+  */
+  if (str_len != (file_name_len / sizeof(WCHAR)))
+    return -1;
+
+  return _wcsnicmp(str, file_name, str_len);
+}
+
+
+void uv_process_fs_event_req(uv_loop_t* loop, uv_req_t* req,
+    uv_fs_event_t* handle) {
+  FILE_NOTIFY_INFORMATION* file_info;
+  int err, sizew, size;
+  char* filename = NULL;
+  WCHAR* filenamew = NULL;
+  WCHAR* long_filenamew = NULL;
+  DWORD offset = 0;
+
+  assert(req->type == UV_FS_EVENT_REQ);
+  assert(handle->req_pending);
+  handle->req_pending = 0;
+
+  /* Don't report any callbacks if:
+   * - We're closing, just push the handle onto the endgame queue
+   * - We are not active, just ignore the callback
+   */
+  if (!uv__is_active(handle)) {
+    if (handle->flags & UV__HANDLE_CLOSING) {
+      uv_want_endgame(loop, (uv_handle_t*) handle);
+    }
+    return;
+  }
+
+  file_info = (FILE_NOTIFY_INFORMATION*)(handle->buffer + offset);
+
+  if (REQ_SUCCESS(req)) {
+    if (req->u.io.overlapped.InternalHigh > 0) {
+      do {
+        file_info = (FILE_NOTIFY_INFORMATION*)((char*)file_info + offset);
+        assert(!filename);
+        assert(!filenamew);
+        assert(!long_filenamew);
+
+        /*
+         * Fire the event only if we were asked to watch a directory,
+         * or if the filename filter matches.
+         */
+        if (handle->dirw ||
+            file_info_cmp(handle->filew,
+                          file_info->FileName,
+                          file_info->FileNameLength) == 0 ||
+            file_info_cmp(handle->short_filew,
+                          file_info->FileName,
+                          file_info->FileNameLength) == 0) {
+
+          if (handle->dirw) {
+            /*
+             * We attempt to resolve the long form of the file name explicitly.
+             * We only do this for file names that might still exist on disk.
+             * If this fails, we use the name given by ReadDirectoryChangesW.
+             * This may be the long form or the 8.3 short name in some cases.
+             */
+            if (file_info->Action != FILE_ACTION_REMOVED &&
+              file_info->Action != FILE_ACTION_RENAMED_OLD_NAME) {
+              /* Construct a full path to the file. */
+              size = wcslen(handle->dirw) +
+                file_info->FileNameLength / sizeof(WCHAR) + 2;
+
+              filenamew = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
+              if (!filenamew) {
+                uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+              }
+
+              _snwprintf(filenamew, size, L"%s\\%.*s", handle->dirw,
+                file_info->FileNameLength / (DWORD)sizeof(WCHAR),
+                file_info->FileName);
+
+              filenamew[size - 1] = L'\0';
+
+              /* Convert to long name. */
+              size = GetLongPathNameW(filenamew, NULL, 0);
+
+              if (size) {
+                long_filenamew = (WCHAR*)uv__malloc(size * sizeof(WCHAR));
+                if (!long_filenamew) {
+                  uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+                }
+
+                size = GetLongPathNameW(filenamew, long_filenamew, size);
+                if (size) {
+                  long_filenamew[size] = '\0';
+                } else {
+                  uv__free(long_filenamew);
+                  long_filenamew = NULL;
+                }
+              }
+
+              uv__free(filenamew);
+
+              if (long_filenamew) {
+                /* Get the file name out of the long path. */
+                uv_relative_path(long_filenamew,
+                                 handle->dirw,
+                                 &filenamew);
+                uv__free(long_filenamew);
+                long_filenamew = filenamew;
+                sizew = -1;
+              } else {
+                /* We couldn't get the long filename, use the one reported. */
+                filenamew = file_info->FileName;
+                sizew = file_info->FileNameLength / sizeof(WCHAR);
+              }
+            } else {
+              /*
+               * Removed or renamed events cannot be resolved to the long form.
+               * We therefore use the name given by ReadDirectoryChangesW.
+               * This may be the long form or the 8.3 short name in some cases.
+               */
+              filenamew = file_info->FileName;
+              sizew = file_info->FileNameLength / sizeof(WCHAR);
+            }
+          } else {
+            /* We already have the long name of the file, so just use it. */
+            filenamew = handle->filew;
+            sizew = -1;
+          }
+
+          /* Convert the filename to utf8. */
+          uv__convert_utf16_to_utf8(filenamew, sizew, &filename);
+
+          switch (file_info->Action) {
+            case FILE_ACTION_ADDED:
+            case FILE_ACTION_REMOVED:
+            case FILE_ACTION_RENAMED_OLD_NAME:
+            case FILE_ACTION_RENAMED_NEW_NAME:
+              handle->cb(handle, filename, UV_RENAME, 0);
+              break;
+
+            case FILE_ACTION_MODIFIED:
+              handle->cb(handle, filename, UV_CHANGE, 0);
+              break;
+          }
+
+          uv__free(filename);
+          filename = NULL;
+          uv__free(long_filenamew);
+          long_filenamew = NULL;
+          filenamew = NULL;
+        }
+
+        offset = file_info->NextEntryOffset;
+      } while (offset && !(handle->flags & UV__HANDLE_CLOSING));
+    } else {
+      handle->cb(handle, NULL, UV_CHANGE, 0);
+    }
+  } else {
+    err = GET_REQ_ERROR(req);
+    handle->cb(handle, NULL, 0, uv_translate_sys_error(err));
+  }
+
+  if (!(handle->flags & UV__HANDLE_CLOSING)) {
+    uv_fs_event_queue_readdirchanges(loop, handle);
+  } else {
+    uv_want_endgame(loop, (uv_handle_t*)handle);
+  }
+}
+
+
+void uv_fs_event_close(uv_loop_t* loop, uv_fs_event_t* handle) {
+  uv_fs_event_stop(handle);
+
+  uv__handle_closing(handle);
+
+  if (!handle->req_pending) {
+    uv_want_endgame(loop, (uv_handle_t*)handle);
+  }
+
+}
+
+
+void uv_fs_event_endgame(uv_loop_t* loop, uv_fs_event_t* handle) {
+  if ((handle->flags & UV__HANDLE_CLOSING) && !handle->req_pending) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+    if (handle->buffer) {
+      uv__free(handle->buffer);
+      handle->buffer = NULL;
+    }
+
+    uv__handle_close(handle);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/fs.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/fs.cpp
new file mode 100644
index 0000000..d7698a7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/fs.cpp
@@ -0,0 +1,2486 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <stdlib.h>
+#include <direct.h>
+#include <errno.h>
+#include <fcntl.h>
+#include <io.h>
+#include <limits.h>
+#include <sys/stat.h>
+#include <sys/utime.h>
+#include <stdio.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "req-inl.h"
+#include "handle-inl.h"
+
+#include <wincrypt.h>
+
+#pragma comment(lib, "Advapi32.lib")
+
+#define UV_FS_FREE_PATHS         0x0002
+#define UV_FS_FREE_PTR           0x0008
+#define UV_FS_CLEANEDUP          0x0010
+
+
+#define INIT(subtype)                                                         \
+  do {                                                                        \
+    if (req == NULL)                                                          \
+      return UV_EINVAL;                                                       \
+    uv_fs_req_init(loop, req, subtype, cb);                                   \
+  }                                                                           \
+  while (0)
+
+#define POST                                                                  \
+  do {                                                                        \
+    if (cb != NULL) {                                                         \
+      uv__req_register(loop, req);                                            \
+      uv__work_submit(loop, &req->work_req, uv__fs_work, uv__fs_done);        \
+      return 0;                                                               \
+    } else {                                                                  \
+      uv__fs_work(&req->work_req);                                            \
+      return req->result;                                                     \
+    }                                                                         \
+  }                                                                           \
+  while (0)
+
+#define SET_REQ_RESULT(req, result_value)                                   \
+  do {                                                                      \
+    req->result = (result_value);                                           \
+    if (req->result == -1) {                                                \
+      req->sys_errno_ = _doserrno;                                          \
+      req->result = uv_translate_sys_error(req->sys_errno_);                \
+    }                                                                       \
+  } while (0)
+
+#define SET_REQ_WIN32_ERROR(req, sys_errno)                                 \
+  do {                                                                      \
+    req->sys_errno_ = (sys_errno);                                          \
+    req->result = uv_translate_sys_error(req->sys_errno_);                  \
+  } while (0)
+
+#define SET_REQ_UV_ERROR(req, uv_errno, sys_errno)                          \
+  do {                                                                      \
+    req->result = (uv_errno);                                               \
+    req->sys_errno_ = (sys_errno);                                          \
+  } while (0)
+
+#define VERIFY_FD(fd, req)                                                  \
+  if (fd == -1) {                                                           \
+    req->result = UV_EBADF;                                                 \
+    req->sys_errno_ = ERROR_INVALID_HANDLE;                                 \
+    return;                                                                 \
+  }
+
+#define FILETIME_TO_UINT(filetime)                                          \
+   (*((uint64_t*) &(filetime)) - 116444736000000000ULL)
+
+#define FILETIME_TO_TIME_T(filetime)                                        \
+   (FILETIME_TO_UINT(filetime) / 10000000ULL)
+
+#define FILETIME_TO_TIME_NS(filetime, secs)                                 \
+   ((FILETIME_TO_UINT(filetime) - (secs * 10000000ULL)) * 100)
+
+#define FILETIME_TO_TIMESPEC(ts, filetime)                                  \
+   do {                                                                     \
+     (ts).tv_sec = (long) FILETIME_TO_TIME_T(filetime);                     \
+     (ts).tv_nsec = (long) FILETIME_TO_TIME_NS(filetime, (ts).tv_sec);      \
+   } while(0)
+
+#define TIME_T_TO_FILETIME(time, filetime_ptr)                              \
+  do {                                                                      \
+    uint64_t bigtime = ((uint64_t) ((time) * 10000000ULL)) +                \
+                                  116444736000000000ULL;                    \
+    (filetime_ptr)->dwLowDateTime = bigtime & 0xFFFFFFFF;                   \
+    (filetime_ptr)->dwHighDateTime = bigtime >> 32;                         \
+  } while(0)
+
+#define IS_SLASH(c) ((c) == L'\\' || (c) == L'/')
+#define IS_LETTER(c) (((c) >= L'a' && (c) <= L'z') || \
+  ((c) >= L'A' && (c) <= L'Z'))
+
+const WCHAR JUNCTION_PREFIX[] = L"\\??\\";
+const WCHAR JUNCTION_PREFIX_LEN = 4;
+
+const WCHAR LONG_PATH_PREFIX[] = L"\\\\?\\";
+const WCHAR LONG_PATH_PREFIX_LEN = 4;
+
+const WCHAR UNC_PATH_PREFIX[] = L"\\\\?\\UNC\\";
+const WCHAR UNC_PATH_PREFIX_LEN = 8;
+
+static int uv__file_symlink_usermode_flag = SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE;
+
+void uv_fs_init(void) {
+  _fmode = _O_BINARY;
+}
+
+
+INLINE static int fs__capture_path(uv_fs_t* req, const char* path,
+    const char* new_path, const int copy_path) {
+  char* buf;
+  char* pos;
+  ssize_t buf_sz = 0, path_len = 0, pathw_len = 0, new_pathw_len = 0;
+
+  /* new_path can only be set if path is also set. */
+  assert(new_path == NULL || path != NULL);
+
+  if (path != NULL) {
+    pathw_len = MultiByteToWideChar(CP_UTF8,
+                                    0,
+                                    path,
+                                    -1,
+                                    NULL,
+                                    0);
+    if (pathw_len == 0) {
+      return GetLastError();
+    }
+
+    buf_sz += pathw_len * sizeof(WCHAR);
+  }
+
+  if (path != NULL && copy_path) {
+    path_len = 1 + strlen(path);
+    buf_sz += path_len;
+  }
+
+  if (new_path != NULL) {
+    new_pathw_len = MultiByteToWideChar(CP_UTF8,
+                                        0,
+                                        new_path,
+                                        -1,
+                                        NULL,
+                                        0);
+    if (new_pathw_len == 0) {
+      return GetLastError();
+    }
+
+    buf_sz += new_pathw_len * sizeof(WCHAR);
+  }
+
+
+  if (buf_sz == 0) {
+    req->file.pathw = NULL;
+    req->fs.info.new_pathw = NULL;
+    req->path = NULL;
+    return 0;
+  }
+
+  buf = (char*) uv__malloc(buf_sz);
+  if (buf == NULL) {
+    return ERROR_OUTOFMEMORY;
+  }
+
+  pos = buf;
+
+  if (path != NULL) {
+    DWORD r = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  path,
+                                  -1,
+                                  (WCHAR*) pos,
+                                  pathw_len);
+    assert(r == (DWORD) pathw_len);
+    req->file.pathw = (WCHAR*) pos;
+    pos += r * sizeof(WCHAR);
+  } else {
+    req->file.pathw = NULL;
+  }
+
+  if (new_path != NULL) {
+    DWORD r = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  new_path,
+                                  -1,
+                                  (WCHAR*) pos,
+                                  new_pathw_len);
+    assert(r == (DWORD) new_pathw_len);
+    req->fs.info.new_pathw = (WCHAR*) pos;
+    pos += r * sizeof(WCHAR);
+  } else {
+    req->fs.info.new_pathw = NULL;
+  }
+
+  req->path = path;
+  if (path != NULL && copy_path) {
+    memcpy(pos, path, path_len);
+    assert(path_len == buf_sz - (pos - buf));
+    req->path = pos;
+  }
+
+  req->flags |= UV_FS_FREE_PATHS;
+
+  return 0;
+}
+
+
+
+INLINE static void uv_fs_req_init(uv_loop_t* loop, uv_fs_t* req,
+    uv_fs_type fs_type, const uv_fs_cb cb) {
+  uv__once_init();
+  UV_REQ_INIT(req, UV_FS);
+  req->loop = loop;
+  req->flags = 0;
+  req->fs_type = fs_type;
+  req->result = 0;
+  req->ptr = NULL;
+  req->path = NULL;
+  req->cb = cb;
+  memset(&req->fs, 0, sizeof(req->fs));
+}
+
+
+static int fs__wide_to_utf8(WCHAR* w_source_ptr,
+                               DWORD w_source_len,
+                               char** target_ptr,
+                               uint64_t* target_len_ptr) {
+  int r;
+  int target_len;
+  char* target;
+  target_len = WideCharToMultiByte(CP_UTF8,
+                                   0,
+                                   w_source_ptr,
+                                   w_source_len,
+                                   NULL,
+                                   0,
+                                   NULL,
+                                   NULL);
+
+  if (target_len == 0) {
+    return -1;
+  }
+
+  if (target_len_ptr != NULL) {
+    *target_len_ptr = target_len;
+  }
+
+  if (target_ptr == NULL) {
+    return 0;
+  }
+
+  target = (char*)uv__malloc(target_len + 1);
+  if (target == NULL) {
+    SetLastError(ERROR_OUTOFMEMORY);
+    return -1;
+  }
+
+  r = WideCharToMultiByte(CP_UTF8,
+                          0,
+                          w_source_ptr,
+                          w_source_len,
+                          target,
+                          target_len,
+                          NULL,
+                          NULL);
+  assert(r == target_len);
+  target[target_len] = '\0';
+  *target_ptr = target;
+  return 0;
+}
+
+
+INLINE static int fs__readlink_handle(HANDLE handle, char** target_ptr,
+    uint64_t* target_len_ptr) {
+  char buffer[MAXIMUM_REPARSE_DATA_BUFFER_SIZE];
+  REPARSE_DATA_BUFFER* reparse_data = (REPARSE_DATA_BUFFER*) buffer;
+  WCHAR* w_target;
+  DWORD w_target_len;
+  DWORD bytes;
+
+  if (!DeviceIoControl(handle,
+                       FSCTL_GET_REPARSE_POINT,
+                       NULL,
+                       0,
+                       buffer,
+                       sizeof buffer,
+                       &bytes,
+                       NULL)) {
+    return -1;
+  }
+
+  if (reparse_data->ReparseTag == IO_REPARSE_TAG_SYMLINK) {
+    /* Real symlink */
+    w_target = reparse_data->SymbolicLinkReparseBuffer.PathBuffer +
+        (reparse_data->SymbolicLinkReparseBuffer.SubstituteNameOffset /
+        sizeof(WCHAR));
+    w_target_len =
+        reparse_data->SymbolicLinkReparseBuffer.SubstituteNameLength /
+        sizeof(WCHAR);
+
+    /* Real symlinks can contain pretty much everything, but the only thing we
+     * really care about is undoing the implicit conversion to an NT namespaced
+     * path that CreateSymbolicLink will perform on absolute paths. If the path
+     * is win32-namespaced then the user must have explicitly made it so, and
+     * we better just return the unmodified reparse data. */
+    if (w_target_len >= 4 &&
+        w_target[0] == L'\\' &&
+        w_target[1] == L'?' &&
+        w_target[2] == L'?' &&
+        w_target[3] == L'\\') {
+      /* Starts with \??\ */
+      if (w_target_len >= 6 &&
+          ((w_target[4] >= L'A' && w_target[4] <= L'Z') ||
+           (w_target[4] >= L'a' && w_target[4] <= L'z')) &&
+          w_target[5] == L':' &&
+          (w_target_len == 6 || w_target[6] == L'\\')) {
+        /* \??\<drive>:\ */
+        w_target += 4;
+        w_target_len -= 4;
+
+      } else if (w_target_len >= 8 &&
+                 (w_target[4] == L'U' || w_target[4] == L'u') &&
+                 (w_target[5] == L'N' || w_target[5] == L'n') &&
+                 (w_target[6] == L'C' || w_target[6] == L'c') &&
+                 w_target[7] == L'\\') {
+        /* \??\UNC\<server>\<share>\ - make sure the final path looks like
+         * \\<server>\<share>\ */
+        w_target += 6;
+        w_target[0] = L'\\';
+        w_target_len -= 6;
+      }
+    }
+
+  } else if (reparse_data->ReparseTag == IO_REPARSE_TAG_MOUNT_POINT) {
+    /* Junction. */
+    w_target = reparse_data->MountPointReparseBuffer.PathBuffer +
+        (reparse_data->MountPointReparseBuffer.SubstituteNameOffset /
+        sizeof(WCHAR));
+    w_target_len = reparse_data->MountPointReparseBuffer.SubstituteNameLength /
+        sizeof(WCHAR);
+
+    /* Only treat junctions that look like \??\<drive>:\ as symlink. Junctions
+     * can also be used as mount points, like \??\Volume{<guid>}, but that's
+     * confusing for programs since they wouldn't be able to actually
+     * understand such a path when returned by uv_readlink(). UNC paths are
+     * never valid for junctions so we don't care about them. */
+    if (!(w_target_len >= 6 &&
+          w_target[0] == L'\\' &&
+          w_target[1] == L'?' &&
+          w_target[2] == L'?' &&
+          w_target[3] == L'\\' &&
+          ((w_target[4] >= L'A' && w_target[4] <= L'Z') ||
+           (w_target[4] >= L'a' && w_target[4] <= L'z')) &&
+          w_target[5] == L':' &&
+          (w_target_len == 6 || w_target[6] == L'\\'))) {
+      SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
+      return -1;
+    }
+
+    /* Remove leading \??\ */
+    w_target += 4;
+    w_target_len -= 4;
+
+  } else {
+    /* Reparse tag does not indicate a symlink. */
+    SetLastError(ERROR_SYMLINK_NOT_SUPPORTED);
+    return -1;
+  }
+
+  return fs__wide_to_utf8(w_target, w_target_len, target_ptr, target_len_ptr);
+}
+
+
+void fs__open(uv_fs_t* req) {
+  DWORD access;
+  DWORD share;
+  DWORD disposition;
+  DWORD attributes = 0;
+  HANDLE file;
+  int fd, current_umask;
+  int flags = req->fs.info.file_flags;
+
+  /* Obtain the active umask. umask() never fails and returns the previous
+   * umask. */
+  current_umask = umask(0);
+  umask(current_umask);
+
+  /* convert flags and mode to CreateFile parameters */
+  switch (flags & (UV_FS_O_RDONLY | UV_FS_O_WRONLY | UV_FS_O_RDWR)) {
+  case UV_FS_O_RDONLY:
+    access = FILE_GENERIC_READ;
+    break;
+  case UV_FS_O_WRONLY:
+    access = FILE_GENERIC_WRITE;
+    break;
+  case UV_FS_O_RDWR:
+    access = FILE_GENERIC_READ | FILE_GENERIC_WRITE;
+    break;
+  default:
+    goto einval;
+  }
+
+  if (flags & UV_FS_O_APPEND) {
+    access &= ~FILE_WRITE_DATA;
+    access |= FILE_APPEND_DATA;
+  }
+
+  /*
+   * Here is where we deviate significantly from what CRT's _open()
+   * does. We indiscriminately use all the sharing modes, to match
+   * UNIX semantics. In particular, this ensures that the file can
+   * be deleted even whilst it's open, fixing issue #1449.
+   * We still support exclusive sharing mode, since it is necessary
+   * for opening raw block devices, otherwise Windows will prevent
+   * any attempt to write past the master boot record.
+   */
+  if (flags & UV_FS_O_EXLOCK) {
+    share = 0;
+  } else {
+    share = FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE;
+  }
+
+  switch (flags & (UV_FS_O_CREAT | UV_FS_O_EXCL | UV_FS_O_TRUNC)) {
+  case 0:
+  case UV_FS_O_EXCL:
+    disposition = OPEN_EXISTING;
+    break;
+  case UV_FS_O_CREAT:
+    disposition = OPEN_ALWAYS;
+    break;
+  case UV_FS_O_CREAT | UV_FS_O_EXCL:
+  case UV_FS_O_CREAT | UV_FS_O_TRUNC | UV_FS_O_EXCL:
+    disposition = CREATE_NEW;
+    break;
+  case UV_FS_O_TRUNC:
+  case UV_FS_O_TRUNC | UV_FS_O_EXCL:
+    disposition = TRUNCATE_EXISTING;
+    break;
+  case UV_FS_O_CREAT | UV_FS_O_TRUNC:
+    disposition = CREATE_ALWAYS;
+    break;
+  default:
+    goto einval;
+  }
+
+  attributes |= FILE_ATTRIBUTE_NORMAL;
+  if (flags & UV_FS_O_CREAT) {
+    if (!((req->fs.info.mode & ~current_umask) & _S_IWRITE)) {
+      attributes |= FILE_ATTRIBUTE_READONLY;
+    }
+  }
+
+  if (flags & UV_FS_O_TEMPORARY ) {
+    attributes |= FILE_FLAG_DELETE_ON_CLOSE | FILE_ATTRIBUTE_TEMPORARY;
+    access |= DELETE;
+  }
+
+  if (flags & UV_FS_O_SHORT_LIVED) {
+    attributes |= FILE_ATTRIBUTE_TEMPORARY;
+  }
+
+  switch (flags & (UV_FS_O_SEQUENTIAL | UV_FS_O_RANDOM)) {
+  case 0:
+    break;
+  case UV_FS_O_SEQUENTIAL:
+    attributes |= FILE_FLAG_SEQUENTIAL_SCAN;
+    break;
+  case UV_FS_O_RANDOM:
+    attributes |= FILE_FLAG_RANDOM_ACCESS;
+    break;
+  default:
+    goto einval;
+  }
+
+  if (flags & UV_FS_O_DIRECT) {
+    attributes |= FILE_FLAG_NO_BUFFERING;
+  }
+
+  switch (flags & (UV_FS_O_DSYNC | UV_FS_O_SYNC)) {
+  case 0:
+    break;
+  case UV_FS_O_DSYNC:
+  case UV_FS_O_SYNC:
+    attributes |= FILE_FLAG_WRITE_THROUGH;
+    break;
+  default:
+    goto einval;
+  }
+
+  /* Setting this flag makes it possible to open a directory. */
+  attributes |= FILE_FLAG_BACKUP_SEMANTICS;
+
+  file = CreateFileW(req->file.pathw,
+                     access,
+                     share,
+                     NULL,
+                     disposition,
+                     attributes,
+                     NULL);
+  if (file == INVALID_HANDLE_VALUE) {
+    DWORD error = GetLastError();
+    if (error == ERROR_FILE_EXISTS && (flags & UV_FS_O_CREAT) &&
+        !(flags & UV_FS_O_EXCL)) {
+      /* Special case: when ERROR_FILE_EXISTS happens and UV_FS_O_CREAT was
+       * specified, it means the path referred to a directory. */
+      SET_REQ_UV_ERROR(req, UV_EISDIR, error);
+    } else {
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+    }
+    return;
+  }
+
+  fd = _open_osfhandle((intptr_t) file, flags);
+  if (fd < 0) {
+    /* The only known failure mode for _open_osfhandle() is EMFILE, in which
+     * case GetLastError() will return zero. However we'll try to handle other
+     * errors as well, should they ever occur.
+     */
+    if (errno == EMFILE)
+      SET_REQ_UV_ERROR(req, UV_EMFILE, ERROR_TOO_MANY_OPEN_FILES);
+    else if (GetLastError() != ERROR_SUCCESS)
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+    else
+      SET_REQ_WIN32_ERROR(req, UV_UNKNOWN);
+    CloseHandle(file);
+    return;
+  }
+
+  SET_REQ_RESULT(req, fd);
+  return;
+
+ einval:
+  SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+}
+
+void fs__close(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int result;
+
+  VERIFY_FD(fd, req);
+
+  if (fd > 2)
+    result = _close(fd);
+  else
+    result = 0;
+
+  /* _close doesn't set _doserrno on failure, but it does always set errno
+   * to EBADF on failure.
+   */
+  if (result == -1) {
+    assert(errno == EBADF);
+    SET_REQ_UV_ERROR(req, UV_EBADF, ERROR_INVALID_HANDLE);
+  } else {
+    req->result = 0;
+  }
+}
+
+
+void fs__read(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int64_t offset = req->fs.info.offset;
+  HANDLE handle;
+  OVERLAPPED overlapped, *overlapped_ptr;
+  LARGE_INTEGER offset_;
+  DWORD bytes;
+  DWORD error;
+  int result;
+  unsigned int index;
+  LARGE_INTEGER original_position;
+  LARGE_INTEGER zero_offset;
+  int restore_position;
+
+  VERIFY_FD(fd, req);
+
+  zero_offset.QuadPart = 0;
+  restore_position = 0;
+  handle = uv__get_osfhandle(fd);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
+    return;
+  }
+
+  if (offset != -1) {
+    memset(&overlapped, 0, sizeof overlapped);
+    overlapped_ptr = &overlapped;
+    if (SetFilePointerEx(handle, zero_offset, &original_position,
+                         FILE_CURRENT)) {
+      restore_position = 1;
+    }
+  } else {
+    overlapped_ptr = NULL;
+  }
+
+  index = 0;
+  bytes = 0;
+  do {
+    DWORD incremental_bytes;
+
+    if (offset != -1) {
+      offset_.QuadPart = offset + bytes;
+      overlapped.Offset = offset_.LowPart;
+      overlapped.OffsetHigh = offset_.HighPart;
+    }
+
+    result = ReadFile(handle,
+                      req->fs.info.bufs[index].base,
+                      req->fs.info.bufs[index].len,
+                      &incremental_bytes,
+                      overlapped_ptr);
+    bytes += incremental_bytes;
+    ++index;
+  } while (result && index < req->fs.info.nbufs);
+
+  if (restore_position)
+    SetFilePointerEx(handle, original_position, NULL, FILE_BEGIN);
+
+  if (result || bytes > 0) {
+    SET_REQ_RESULT(req, bytes);
+  } else {
+    error = GetLastError();
+    if (error == ERROR_HANDLE_EOF) {
+      SET_REQ_RESULT(req, bytes);
+    } else {
+      SET_REQ_WIN32_ERROR(req, error);
+    }
+  }
+}
+
+
+void fs__write(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int64_t offset = req->fs.info.offset;
+  HANDLE handle;
+  OVERLAPPED overlapped, *overlapped_ptr;
+  LARGE_INTEGER offset_;
+  DWORD bytes;
+  int result;
+  unsigned int index;
+  LARGE_INTEGER original_position;
+  LARGE_INTEGER zero_offset;
+  int restore_position;
+
+  VERIFY_FD(fd, req);
+
+  zero_offset.QuadPart = 0;
+  restore_position = 0;
+  handle = uv__get_osfhandle(fd);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
+    return;
+  }
+
+  if (offset != -1) {
+    memset(&overlapped, 0, sizeof overlapped);
+    overlapped_ptr = &overlapped;
+    if (SetFilePointerEx(handle, zero_offset, &original_position,
+                         FILE_CURRENT)) {
+      restore_position = 1;
+    }
+  } else {
+    overlapped_ptr = NULL;
+  }
+
+  index = 0;
+  bytes = 0;
+  do {
+    DWORD incremental_bytes;
+
+    if (offset != -1) {
+      offset_.QuadPart = offset + bytes;
+      overlapped.Offset = offset_.LowPart;
+      overlapped.OffsetHigh = offset_.HighPart;
+    }
+
+    result = WriteFile(handle,
+                       req->fs.info.bufs[index].base,
+                       req->fs.info.bufs[index].len,
+                       &incremental_bytes,
+                       overlapped_ptr);
+    bytes += incremental_bytes;
+    ++index;
+  } while (result && index < req->fs.info.nbufs);
+
+  if (restore_position)
+    SetFilePointerEx(handle, original_position, NULL, FILE_BEGIN);
+
+  if (result || bytes > 0) {
+    SET_REQ_RESULT(req, bytes);
+  } else {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+  }
+}
+
+
+void fs__rmdir(uv_fs_t* req) {
+  int result = _wrmdir(req->file.pathw);
+  SET_REQ_RESULT(req, result);
+}
+
+
+void fs__unlink(uv_fs_t* req) {
+  const WCHAR* pathw = req->file.pathw;
+  HANDLE handle;
+  BY_HANDLE_FILE_INFORMATION info;
+  FILE_DISPOSITION_INFORMATION disposition;
+  IO_STATUS_BLOCK iosb;
+  NTSTATUS status;
+
+  handle = CreateFileW(pathw,
+                       FILE_READ_ATTRIBUTES | FILE_WRITE_ATTRIBUTES | DELETE,
+                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_FLAG_OPEN_REPARSE_POINT | FILE_FLAG_BACKUP_SEMANTICS,
+                       NULL);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (!GetFileInformationByHandle(handle, &info)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    CloseHandle(handle);
+    return;
+  }
+
+  if (info.dwFileAttributes & FILE_ATTRIBUTE_DIRECTORY) {
+    /* Do not allow deletion of directories, unless it is a symlink. When the
+     * path refers to a non-symlink directory, report EPERM as mandated by
+     * POSIX.1. */
+
+    /* Check if it is a reparse point. If it's not, it's a normal directory. */
+    if (!(info.dwFileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)) {
+      SET_REQ_WIN32_ERROR(req, ERROR_ACCESS_DENIED);
+      CloseHandle(handle);
+      return;
+    }
+
+    /* Read the reparse point and check if it is a valid symlink. If not, don't
+     * unlink. */
+    if (fs__readlink_handle(handle, NULL, NULL) < 0) {
+      DWORD error = GetLastError();
+      if (error == ERROR_SYMLINK_NOT_SUPPORTED)
+        error = ERROR_ACCESS_DENIED;
+      SET_REQ_WIN32_ERROR(req, error);
+      CloseHandle(handle);
+      return;
+    }
+  }
+
+  if (info.dwFileAttributes & FILE_ATTRIBUTE_READONLY) {
+    /* Remove read-only attribute */
+    FILE_BASIC_INFORMATION basic = { 0 };
+
+    basic.FileAttributes = info.dwFileAttributes
+                           & ~(FILE_ATTRIBUTE_READONLY)
+                           | FILE_ATTRIBUTE_ARCHIVE;
+
+    status = pNtSetInformationFile(handle,
+                                   &iosb,
+                                   &basic,
+                                   sizeof basic,
+                                   FileBasicInformation);
+    if (!NT_SUCCESS(status)) {
+      SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
+      CloseHandle(handle);
+      return;
+    }
+  }
+
+  /* Try to set the delete flag. */
+  disposition.DeleteFile = TRUE;
+  status = pNtSetInformationFile(handle,
+                                 &iosb,
+                                 &disposition,
+                                 sizeof disposition,
+                                 FileDispositionInformation);
+  if (NT_SUCCESS(status)) {
+    SET_REQ_SUCCESS(req);
+  } else {
+    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
+  }
+
+  CloseHandle(handle);
+}
+
+
+void fs__mkdir(uv_fs_t* req) {
+  /* TODO: use req->mode. */
+  int result = _wmkdir(req->file.pathw);
+  SET_REQ_RESULT(req, result);
+}
+
+
+/* OpenBSD original: lib/libc/stdio/mktemp.c */
+void fs__mkdtemp(uv_fs_t* req) {
+  static const WCHAR *tempchars =
+    L"abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ0123456789";
+  static const size_t num_chars = 62;
+  static const size_t num_x = 6;
+  WCHAR *cp, *ep;
+  unsigned int tries, i;
+  size_t len;
+  HCRYPTPROV h_crypt_prov;
+  uint64_t v;
+  BOOL released;
+
+  len = wcslen(req->file.pathw);
+  ep = req->file.pathw + len;
+  if (len < num_x || wcsncmp(ep - num_x, L"XXXXXX", num_x)) {
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_INVALID_PARAMETER);
+    return;
+  }
+
+  if (!CryptAcquireContext(&h_crypt_prov, NULL, NULL, PROV_RSA_FULL,
+                           CRYPT_VERIFYCONTEXT)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  tries = TMP_MAX;
+  do {
+    if (!CryptGenRandom(h_crypt_prov, sizeof(v), (BYTE*) &v)) {
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+      break;
+    }
+
+    cp = ep - num_x;
+    for (i = 0; i < num_x; i++) {
+      *cp++ = tempchars[v % num_chars];
+      v /= num_chars;
+    }
+
+    if (_wmkdir(req->file.pathw) == 0) {
+      len = strlen(req->path);
+      wcstombs((char*) req->path + len - num_x, ep - num_x, num_x);
+      SET_REQ_RESULT(req, 0);
+      break;
+    } else if (errno != EEXIST) {
+      SET_REQ_RESULT(req, -1);
+      break;
+    }
+  } while (--tries);
+
+  released = CryptReleaseContext(h_crypt_prov, 0);
+  assert(released);
+  if (tries == 0) {
+    SET_REQ_RESULT(req, -1);
+  }
+}
+
+
+void fs__scandir(uv_fs_t* req) {
+  static const size_t dirents_initial_size = 32;
+
+  HANDLE dir_handle = INVALID_HANDLE_VALUE;
+
+  uv__dirent_t** dirents = NULL;
+  size_t dirents_size = 0;
+  size_t dirents_used = 0;
+
+  IO_STATUS_BLOCK iosb;
+  NTSTATUS status;
+
+  /* Buffer to hold directory entries returned by NtQueryDirectoryFile.
+   * It's important that this buffer can hold at least one entry, regardless
+   * of the length of the file names present in the enumerated directory.
+   * A file name is at most 256 WCHARs long.
+   * According to MSDN, the buffer must be aligned at an 8-byte boundary.
+   */
+#if _MSC_VER
+  __declspec(align(8)) char buffer[8192];
+#else
+  __attribute__ ((aligned (8))) char buffer[8192];
+#endif
+
+  STATIC_ASSERT(sizeof buffer >=
+                sizeof(FILE_DIRECTORY_INFORMATION) + 256 * sizeof(WCHAR));
+
+  /* Open the directory. */
+  dir_handle =
+      CreateFileW(req->file.pathw,
+                  FILE_LIST_DIRECTORY | SYNCHRONIZE,
+                  FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                  NULL,
+                  OPEN_EXISTING,
+                  FILE_FLAG_BACKUP_SEMANTICS,
+                  NULL);
+  if (dir_handle == INVALID_HANDLE_VALUE)
+    goto win32_error;
+
+  /* Read the first chunk. */
+  status = pNtQueryDirectoryFile(dir_handle,
+                                 NULL,
+                                 NULL,
+                                 NULL,
+                                 &iosb,
+                                 &buffer,
+                                 sizeof buffer,
+                                 FileDirectoryInformation,
+                                 FALSE,
+                                 NULL,
+                                 TRUE);
+
+  /* If the handle is not a directory, we'll get STATUS_INVALID_PARAMETER.
+   * This should be reported back as UV_ENOTDIR.
+   */
+  if (status == STATUS_INVALID_PARAMETER)
+    goto not_a_directory_error;
+
+  while (NT_SUCCESS(status)) {
+    char* position = buffer;
+    size_t next_entry_offset = 0;
+
+    do {
+      FILE_DIRECTORY_INFORMATION* info;
+      uv__dirent_t* dirent;
+
+      size_t wchar_len;
+      size_t utf8_len;
+
+      /* Obtain a pointer to the current directory entry. */
+      position += next_entry_offset;
+      info = (FILE_DIRECTORY_INFORMATION*) position;
+
+      /* Fetch the offset to the next directory entry. */
+      next_entry_offset = info->NextEntryOffset;
+
+      /* Compute the length of the filename in WCHARs. */
+      wchar_len = info->FileNameLength / sizeof info->FileName[0];
+
+      /* Skip over '.' and '..' entries.  It has been reported that
+       * the SharePoint driver includes the terminating zero byte in
+       * the filename length.  Strip those first.
+       */
+      while (wchar_len > 0 && info->FileName[wchar_len - 1] == L'\0')
+        wchar_len -= 1;
+
+      if (wchar_len == 0)
+        continue;
+      if (wchar_len == 1 && info->FileName[0] == L'.')
+        continue;
+      if (wchar_len == 2 && info->FileName[0] == L'.' &&
+          info->FileName[1] == L'.')
+        continue;
+
+      /* Compute the space required to store the filename as UTF-8. */
+      utf8_len = WideCharToMultiByte(
+          CP_UTF8, 0, &info->FileName[0], wchar_len, NULL, 0, NULL, NULL);
+      if (utf8_len == 0)
+        goto win32_error;
+
+      /* Resize the dirent array if needed. */
+      if (dirents_used >= dirents_size) {
+        size_t new_dirents_size =
+            dirents_size == 0 ? dirents_initial_size : dirents_size << 1;
+        uv__dirent_t** new_dirents = (uv__dirent_t**)
+            uv__realloc(dirents, new_dirents_size * sizeof *dirents);
+
+        if (new_dirents == NULL)
+          goto out_of_memory_error;
+
+        dirents_size = new_dirents_size;
+        dirents = new_dirents;
+      }
+
+      /* Allocate space for the uv dirent structure. The dirent structure
+       * includes room for the first character of the filename, but `utf8_len`
+       * doesn't count the NULL terminator at this point.
+       */
+      dirent = (uv__dirent_t*)uv__malloc(sizeof *dirent + utf8_len);
+      if (dirent == NULL)
+        goto out_of_memory_error;
+
+      dirents[dirents_used++] = dirent;
+
+      /* Convert file name to UTF-8. */
+      if (WideCharToMultiByte(CP_UTF8,
+                              0,
+                              &info->FileName[0],
+                              wchar_len,
+                              &dirent->d_name[0],
+                              utf8_len,
+                              NULL,
+                              NULL) == 0)
+        goto win32_error;
+
+      /* Add a null terminator to the filename. */
+      dirent->d_name[utf8_len] = '\0';
+
+      /* Fill out the type field. */
+      if (info->FileAttributes & FILE_ATTRIBUTE_DEVICE)
+        dirent->d_type = UV__DT_CHAR;
+      else if (info->FileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)
+        dirent->d_type = UV__DT_LINK;
+      else if (info->FileAttributes & FILE_ATTRIBUTE_DIRECTORY)
+        dirent->d_type = UV__DT_DIR;
+      else
+        dirent->d_type = UV__DT_FILE;
+    } while (next_entry_offset != 0);
+
+    /* Read the next chunk. */
+    status = pNtQueryDirectoryFile(dir_handle,
+                                   NULL,
+                                   NULL,
+                                   NULL,
+                                   &iosb,
+                                   &buffer,
+                                   sizeof buffer,
+                                   FileDirectoryInformation,
+                                   FALSE,
+                                   NULL,
+                                   FALSE);
+
+    /* After the first pNtQueryDirectoryFile call, the function may return
+     * STATUS_SUCCESS even if the buffer was too small to hold at least one
+     * directory entry.
+     */
+    if (status == STATUS_SUCCESS && iosb.Information == 0)
+      status = STATUS_BUFFER_OVERFLOW;
+  }
+
+  if (status != STATUS_NO_MORE_FILES)
+    goto nt_error;
+
+  CloseHandle(dir_handle);
+
+  /* Store the result in the request object. */
+  req->ptr = dirents;
+  if (dirents != NULL)
+    req->flags |= UV_FS_FREE_PTR;
+
+  SET_REQ_RESULT(req, dirents_used);
+
+  /* `nbufs` will be used as index by uv_fs_scandir_next. */
+  req->fs.info.nbufs = 0;
+
+  return;
+
+nt_error:
+  SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
+  goto cleanup;
+
+win32_error:
+  SET_REQ_WIN32_ERROR(req, GetLastError());
+  goto cleanup;
+
+not_a_directory_error:
+  SET_REQ_UV_ERROR(req, UV_ENOTDIR, ERROR_DIRECTORY);
+  goto cleanup;
+
+out_of_memory_error:
+  SET_REQ_UV_ERROR(req, UV_ENOMEM, ERROR_OUTOFMEMORY);
+  goto cleanup;
+
+cleanup:
+  if (dir_handle != INVALID_HANDLE_VALUE)
+    CloseHandle(dir_handle);
+  while (dirents_used > 0)
+    uv__free(dirents[--dirents_used]);
+  if (dirents != NULL)
+    uv__free(dirents);
+}
+
+
+INLINE static int fs__stat_handle(HANDLE handle, uv_stat_t* statbuf,
+    int do_lstat) {
+  FILE_ALL_INFORMATION file_info;
+  FILE_FS_VOLUME_INFORMATION volume_info;
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+
+  nt_status = pNtQueryInformationFile(handle,
+                                      &io_status,
+                                      &file_info,
+                                      sizeof file_info,
+                                      FileAllInformation);
+
+  /* Buffer overflow (a warning status code) is expected here. */
+  if (NT_ERROR(nt_status)) {
+    SetLastError(pRtlNtStatusToDosError(nt_status));
+    return -1;
+  }
+
+  nt_status = pNtQueryVolumeInformationFile(handle,
+                                            &io_status,
+                                            &volume_info,
+                                            sizeof volume_info,
+                                            FileFsVolumeInformation);
+
+  /* Buffer overflow (a warning status code) is expected here. */
+  if (io_status.Status == STATUS_NOT_IMPLEMENTED) {
+    statbuf->st_dev = 0;
+  } else if (NT_ERROR(nt_status)) {
+    SetLastError(pRtlNtStatusToDosError(nt_status));
+    return -1;
+  } else {
+    statbuf->st_dev = volume_info.VolumeSerialNumber;
+  }
+
+  /* Todo: st_mode should probably always be 0666 for everyone. We might also
+   * want to report 0777 if the file is a .exe or a directory.
+   *
+   * Currently it's based on whether the 'readonly' attribute is set, which
+   * makes little sense because the semantics are so different: the 'read-only'
+   * flag is just a way for a user to protect against accidental deletion, and
+   * serves no security purpose. Windows uses ACLs for that.
+   *
+   * Also people now use uv_fs_chmod() to take away the writable bit for good
+   * reasons. Windows however just makes the file read-only, which makes it
+   * impossible to delete the file afterwards, since read-only files can't be
+   * deleted.
+   *
+   * IOW it's all just a clusterfuck and we should think of something that
+   * makes slightly more sense.
+   *
+   * And uv_fs_chmod should probably just fail on windows or be a total no-op.
+   * There's nothing sensible it can do anyway.
+   */
+  statbuf->st_mode = 0;
+
+  /*
+  * On Windows, FILE_ATTRIBUTE_REPARSE_POINT is a general purpose mechanism
+  * by which filesystem drivers can intercept and alter file system requests.
+  *
+  * The only reparse points we care about are symlinks and mount points, both
+  * of which are treated as POSIX symlinks. Further, we only care when
+  * invoked via lstat, which seeks information about the link instead of its
+  * target. Otherwise, reparse points must be treated as regular files.
+  */
+  if (do_lstat &&
+      (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_REPARSE_POINT)) {
+    /*
+     * If reading the link fails, the reparse point is not a symlink and needs
+     * to be treated as a regular file. The higher level lstat function will
+     * detect this failure and retry without do_lstat if appropriate.
+     */
+    if (fs__readlink_handle(handle, NULL, &statbuf->st_size) != 0)
+      return -1;
+    statbuf->st_mode |= S_IFLNK;
+  }
+
+  if (statbuf->st_mode == 0) {
+    if (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_DIRECTORY) {
+      statbuf->st_mode |= _S_IFDIR;
+      statbuf->st_size = 0;
+    } else {
+      statbuf->st_mode |= _S_IFREG;
+      statbuf->st_size = file_info.StandardInformation.EndOfFile.QuadPart;
+    }
+  }
+
+  if (file_info.BasicInformation.FileAttributes & FILE_ATTRIBUTE_READONLY)
+    statbuf->st_mode |= _S_IREAD | (_S_IREAD >> 3) | (_S_IREAD >> 6);
+  else
+    statbuf->st_mode |= (_S_IREAD | _S_IWRITE) | ((_S_IREAD | _S_IWRITE) >> 3) |
+                        ((_S_IREAD | _S_IWRITE) >> 6);
+
+  FILETIME_TO_TIMESPEC(statbuf->st_atim, file_info.BasicInformation.LastAccessTime);
+  FILETIME_TO_TIMESPEC(statbuf->st_ctim, file_info.BasicInformation.ChangeTime);
+  FILETIME_TO_TIMESPEC(statbuf->st_mtim, file_info.BasicInformation.LastWriteTime);
+  FILETIME_TO_TIMESPEC(statbuf->st_birthtim, file_info.BasicInformation.CreationTime);
+
+  statbuf->st_ino = file_info.InternalInformation.IndexNumber.QuadPart;
+
+  /* st_blocks contains the on-disk allocation size in 512-byte units. */
+  statbuf->st_blocks =
+      file_info.StandardInformation.AllocationSize.QuadPart >> 9ULL;
+
+  statbuf->st_nlink = file_info.StandardInformation.NumberOfLinks;
+
+  /* The st_blksize is supposed to be the 'optimal' number of bytes for reading
+   * and writing to the disk. That is, for any definition of 'optimal' - it's
+   * supposed to at least avoid read-update-write behavior when writing to the
+   * disk.
+   *
+   * However nobody knows this and even fewer people actually use this value,
+   * and in order to fill it out we'd have to make another syscall to query the
+   * volume for FILE_FS_SECTOR_SIZE_INFORMATION.
+   *
+   * Therefore we'll just report a sensible value that's quite commonly okay
+   * on modern hardware.
+   *
+   * 4096 is the minimum required to be compatible with newer Advanced Format
+   * drives (which have 4096 bytes per physical sector), and to be backwards
+   * compatible with older drives (which have 512 bytes per physical sector).
+   */
+  statbuf->st_blksize = 4096;
+
+  /* Todo: set st_flags to something meaningful. Also provide a wrapper for
+   * chattr(2).
+   */
+  statbuf->st_flags = 0;
+
+  /* Windows has nothing sensible to say about these values, so they'll just
+   * remain empty.
+   */
+  statbuf->st_gid = 0;
+  statbuf->st_uid = 0;
+  statbuf->st_rdev = 0;
+  statbuf->st_gen = 0;
+
+  return 0;
+}
+
+
+INLINE static void fs__stat_prepare_path(WCHAR* pathw) {
+  size_t len = wcslen(pathw);
+
+  /* TODO: ignore namespaced paths. */
+  if (len > 1 && pathw[len - 2] != L':' &&
+      (pathw[len - 1] == L'\\' || pathw[len - 1] == L'/')) {
+    pathw[len - 1] = '\0';
+  }
+}
+
+
+INLINE static void fs__stat_impl(uv_fs_t* req, int do_lstat) {
+  HANDLE handle;
+  DWORD flags;
+
+  flags = FILE_FLAG_BACKUP_SEMANTICS;
+  if (do_lstat) {
+    flags |= FILE_FLAG_OPEN_REPARSE_POINT;
+  }
+
+  handle = CreateFileW(req->file.pathw,
+                       FILE_READ_ATTRIBUTES,
+                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                       NULL,
+                       OPEN_EXISTING,
+                       flags,
+                       NULL);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (fs__stat_handle(handle, &req->statbuf, do_lstat) != 0) {
+    DWORD error = GetLastError();
+    if (do_lstat &&
+        (error == ERROR_SYMLINK_NOT_SUPPORTED ||
+         error == ERROR_NOT_A_REPARSE_POINT)) {
+      /* We opened a reparse point but it was not a symlink. Try again. */
+      fs__stat_impl(req, 0);
+
+    } else {
+      /* Stat failed. */
+      SET_REQ_WIN32_ERROR(req, GetLastError());
+    }
+
+    CloseHandle(handle);
+    return;
+  }
+
+  req->ptr = &req->statbuf;
+  req->result = 0;
+  CloseHandle(handle);
+}
+
+
+static void fs__stat(uv_fs_t* req) {
+  fs__stat_prepare_path(req->file.pathw);
+  fs__stat_impl(req, 0);
+}
+
+
+static void fs__lstat(uv_fs_t* req) {
+  fs__stat_prepare_path(req->file.pathw);
+  fs__stat_impl(req, 1);
+}
+
+
+static void fs__fstat(uv_fs_t* req) {
+  int fd = req->file.fd;
+  HANDLE handle;
+
+  VERIFY_FD(fd, req);
+
+  handle = uv__get_osfhandle(fd);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
+    return;
+  }
+
+  if (fs__stat_handle(handle, &req->statbuf, 0) != 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  req->ptr = &req->statbuf;
+  req->result = 0;
+}
+
+
+static void fs__rename(uv_fs_t* req) {
+  if (!MoveFileExW(req->file.pathw, req->fs.info.new_pathw, MOVEFILE_REPLACE_EXISTING)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  SET_REQ_RESULT(req, 0);
+}
+
+
+INLINE static void fs__sync_impl(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int result;
+
+  VERIFY_FD(fd, req);
+
+  result = FlushFileBuffers(uv__get_osfhandle(fd)) ? 0 : -1;
+  if (result == -1) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+  } else {
+    SET_REQ_RESULT(req, result);
+  }
+}
+
+
+static void fs__fsync(uv_fs_t* req) {
+  fs__sync_impl(req);
+}
+
+
+static void fs__fdatasync(uv_fs_t* req) {
+  fs__sync_impl(req);
+}
+
+
+static void fs__ftruncate(uv_fs_t* req) {
+  int fd = req->file.fd;
+  HANDLE handle;
+  NTSTATUS status;
+  IO_STATUS_BLOCK io_status;
+  FILE_END_OF_FILE_INFORMATION eof_info;
+
+  VERIFY_FD(fd, req);
+
+  handle = uv__get_osfhandle(fd);
+
+  eof_info.EndOfFile.QuadPart = req->fs.info.offset;
+
+  status = pNtSetInformationFile(handle,
+                                 &io_status,
+                                 &eof_info,
+                                 sizeof eof_info,
+                                 FileEndOfFileInformation);
+
+  if (NT_SUCCESS(status)) {
+    SET_REQ_RESULT(req, 0);
+  } else {
+    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(status));
+  }
+}
+
+
+static void fs__copyfile(uv_fs_t* req) {
+  int flags;
+  int overwrite;
+
+  flags = req->fs.info.file_flags;
+
+  if (flags & UV_FS_COPYFILE_FICLONE_FORCE) {
+    SET_REQ_UV_ERROR(req, UV_ENOSYS, ERROR_NOT_SUPPORTED);
+    return;
+  }
+
+  overwrite = flags & UV_FS_COPYFILE_EXCL;
+
+  if (CopyFileW(req->file.pathw, req->fs.info.new_pathw, overwrite) == 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__sendfile(uv_fs_t* req) {
+  int fd_in = req->file.fd, fd_out = req->fs.info.fd_out;
+  size_t length = req->fs.info.bufsml[0].len;
+  int64_t offset = req->fs.info.offset;
+  const size_t max_buf_size = 65536;
+  size_t buf_size = length < max_buf_size ? length : max_buf_size;
+  int n, result = 0;
+  int64_t result_offset = 0;
+  char* buf = (char*) uv__malloc(buf_size);
+  if (!buf) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  if (offset != -1) {
+    result_offset = _lseeki64(fd_in, offset, SEEK_SET);
+  }
+
+  if (result_offset == -1) {
+    result = -1;
+  } else {
+    while (length > 0) {
+      n = _read(fd_in, buf, length < buf_size ? length : buf_size);
+      if (n == 0) {
+        break;
+      } else if (n == -1) {
+        result = -1;
+        break;
+      }
+
+      length -= n;
+
+      n = _write(fd_out, buf, n);
+      if (n == -1) {
+        result = -1;
+        break;
+      }
+
+      result += n;
+    }
+  }
+
+  uv__free(buf);
+
+  SET_REQ_RESULT(req, result);
+}
+
+
+static void fs__access(uv_fs_t* req) {
+  DWORD attr = GetFileAttributesW(req->file.pathw);
+
+  if (attr == INVALID_FILE_ATTRIBUTES) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  /*
+   * Access is possible if
+   * - write access wasn't requested,
+   * - or the file isn't read-only,
+   * - or it's a directory.
+   * (Directories cannot be read-only on Windows.)
+   */
+  if (!(req->fs.info.mode & W_OK) ||
+      !(attr & FILE_ATTRIBUTE_READONLY) ||
+      (attr & FILE_ATTRIBUTE_DIRECTORY)) {
+    SET_REQ_RESULT(req, 0);
+  } else {
+    SET_REQ_WIN32_ERROR(req, UV_EPERM);
+  }
+
+}
+
+
+static void fs__chmod(uv_fs_t* req) {
+  int result = _wchmod(req->file.pathw, req->fs.info.mode);
+  SET_REQ_RESULT(req, result);
+}
+
+
+static void fs__fchmod(uv_fs_t* req) {
+  int fd = req->file.fd;
+  int clear_archive_flag;
+  HANDLE handle;
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_BASIC_INFORMATION file_info;
+
+  VERIFY_FD(fd, req);
+
+  handle = ReOpenFile(uv__get_osfhandle(fd), FILE_WRITE_ATTRIBUTES, 0, 0);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  nt_status = pNtQueryInformationFile(handle,
+                                      &io_status,
+                                      &file_info,
+                                      sizeof file_info,
+                                      FileBasicInformation);
+
+  if (!NT_SUCCESS(nt_status)) {
+    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
+    goto fchmod_cleanup;
+  }
+ 
+  /* Test if the Archive attribute is cleared */
+  if ((file_info.FileAttributes & FILE_ATTRIBUTE_ARCHIVE) == 0) {
+      /* Set Archive flag, otherwise setting or clearing the read-only 
+         flag will not work */
+      file_info.FileAttributes |= FILE_ATTRIBUTE_ARCHIVE;
+      nt_status = pNtSetInformationFile(handle,
+                                        &io_status,
+                                        &file_info,
+                                        sizeof file_info,
+                                        FileBasicInformation);
+      if (!NT_SUCCESS(nt_status)) {
+        SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
+        goto fchmod_cleanup;
+      }
+      /* Remeber to clear the flag later on */
+      clear_archive_flag = 1;
+  } else {
+      clear_archive_flag = 0;
+  }
+
+  if (req->fs.info.mode & _S_IWRITE) {
+    file_info.FileAttributes &= ~FILE_ATTRIBUTE_READONLY;
+  } else {
+    file_info.FileAttributes |= FILE_ATTRIBUTE_READONLY;
+  }
+
+  nt_status = pNtSetInformationFile(handle,
+                                    &io_status,
+                                    &file_info,
+                                    sizeof file_info,
+                                    FileBasicInformation);
+
+  if (!NT_SUCCESS(nt_status)) {
+    SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
+    goto fchmod_cleanup;
+  }
+
+  if (clear_archive_flag) {
+      file_info.FileAttributes &= ~FILE_ATTRIBUTE_ARCHIVE;
+      if (file_info.FileAttributes == 0) {
+          file_info.FileAttributes = FILE_ATTRIBUTE_NORMAL;
+      }
+      nt_status = pNtSetInformationFile(handle,
+                                        &io_status,
+                                        &file_info,
+                                        sizeof file_info,
+                                        FileBasicInformation);
+      if (!NT_SUCCESS(nt_status)) {
+        SET_REQ_WIN32_ERROR(req, pRtlNtStatusToDosError(nt_status));
+        goto fchmod_cleanup;
+      }
+  }
+
+  SET_REQ_SUCCESS(req);
+fchmod_cleanup:
+  CloseHandle(handle);
+}
+
+
+INLINE static int fs__utime_handle(HANDLE handle, double atime, double mtime) {
+  FILETIME filetime_a, filetime_m;
+
+  TIME_T_TO_FILETIME(atime, &filetime_a);
+  TIME_T_TO_FILETIME(mtime, &filetime_m);
+
+  if (!SetFileTime(handle, NULL, &filetime_a, &filetime_m)) {
+    return -1;
+  }
+
+  return 0;
+}
+
+
+static void fs__utime(uv_fs_t* req) {
+  HANDLE handle;
+
+  handle = CreateFileW(req->file.pathw,
+                       FILE_WRITE_ATTRIBUTES,
+                       FILE_SHARE_READ | FILE_SHARE_WRITE | FILE_SHARE_DELETE,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_FLAG_BACKUP_SEMANTICS,
+                       NULL);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (fs__utime_handle(handle, req->fs.time.atime, req->fs.time.mtime) != 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    CloseHandle(handle);
+    return;
+  }
+
+  CloseHandle(handle);
+
+  req->result = 0;
+}
+
+
+static void fs__futime(uv_fs_t* req) {
+  int fd = req->file.fd;
+  HANDLE handle;
+  VERIFY_FD(fd, req);
+
+  handle = uv__get_osfhandle(fd);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, ERROR_INVALID_HANDLE);
+    return;
+  }
+
+  if (fs__utime_handle(handle, req->fs.time.atime, req->fs.time.mtime) != 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  req->result = 0;
+}
+
+
+static void fs__link(uv_fs_t* req) {
+  DWORD r = CreateHardLinkW(req->fs.info.new_pathw, req->file.pathw, NULL);
+  if (r == 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+  } else {
+    req->result = 0;
+  }
+}
+
+
+static void fs__create_junction(uv_fs_t* req, const WCHAR* path,
+    const WCHAR* new_path) {
+  HANDLE handle = INVALID_HANDLE_VALUE;
+  REPARSE_DATA_BUFFER *buffer = NULL;
+  int created = 0;
+  int target_len;
+  int is_absolute, is_long_path;
+  int needed_buf_size, used_buf_size, used_data_size, path_buf_len;
+  int start, len, i;
+  int add_slash;
+  DWORD bytes;
+  WCHAR* path_buf;
+
+  target_len = wcslen(path);
+  is_long_path = wcsncmp(path, LONG_PATH_PREFIX, LONG_PATH_PREFIX_LEN) == 0;
+
+  if (is_long_path) {
+    is_absolute = 1;
+  } else {
+    is_absolute = target_len >= 3 && IS_LETTER(path[0]) &&
+      path[1] == L':' && IS_SLASH(path[2]);
+  }
+
+  if (!is_absolute) {
+    /* Not supporting relative paths */
+    SET_REQ_UV_ERROR(req, UV_EINVAL, ERROR_NOT_SUPPORTED);
+    return;
+  }
+
+  /* Do a pessimistic calculation of the required buffer size */
+  needed_buf_size =
+      FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer.PathBuffer) +
+      JUNCTION_PREFIX_LEN * sizeof(WCHAR) +
+      2 * (target_len + 2) * sizeof(WCHAR);
+
+  /* Allocate the buffer */
+  buffer = (REPARSE_DATA_BUFFER*)uv__malloc(needed_buf_size);
+  if (!buffer) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  /* Grab a pointer to the part of the buffer where filenames go */
+  path_buf = (WCHAR*)&(buffer->MountPointReparseBuffer.PathBuffer);
+  path_buf_len = 0;
+
+  /* Copy the substitute (internal) target path */
+  start = path_buf_len;
+
+  wcsncpy((WCHAR*)&path_buf[path_buf_len], JUNCTION_PREFIX,
+    JUNCTION_PREFIX_LEN);
+  path_buf_len += JUNCTION_PREFIX_LEN;
+
+  add_slash = 0;
+  for (i = is_long_path ? LONG_PATH_PREFIX_LEN : 0; path[i] != L'\0'; i++) {
+    if (IS_SLASH(path[i])) {
+      add_slash = 1;
+      continue;
+    }
+
+    if (add_slash) {
+      path_buf[path_buf_len++] = L'\\';
+      add_slash = 0;
+    }
+
+    path_buf[path_buf_len++] = path[i];
+  }
+  path_buf[path_buf_len++] = L'\\';
+  len = path_buf_len - start;
+
+  /* Set the info about the substitute name */
+  buffer->MountPointReparseBuffer.SubstituteNameOffset = start * sizeof(WCHAR);
+  buffer->MountPointReparseBuffer.SubstituteNameLength = len * sizeof(WCHAR);
+
+  /* Insert null terminator */
+  path_buf[path_buf_len++] = L'\0';
+
+  /* Copy the print name of the target path */
+  start = path_buf_len;
+  add_slash = 0;
+  for (i = is_long_path ? LONG_PATH_PREFIX_LEN : 0; path[i] != L'\0'; i++) {
+    if (IS_SLASH(path[i])) {
+      add_slash = 1;
+      continue;
+    }
+
+    if (add_slash) {
+      path_buf[path_buf_len++] = L'\\';
+      add_slash = 0;
+    }
+
+    path_buf[path_buf_len++] = path[i];
+  }
+  len = path_buf_len - start;
+  if (len == 2) {
+    path_buf[path_buf_len++] = L'\\';
+    len++;
+  }
+
+  /* Set the info about the print name */
+  buffer->MountPointReparseBuffer.PrintNameOffset = start * sizeof(WCHAR);
+  buffer->MountPointReparseBuffer.PrintNameLength = len * sizeof(WCHAR);
+
+  /* Insert another null terminator */
+  path_buf[path_buf_len++] = L'\0';
+
+  /* Calculate how much buffer space was actually used */
+  used_buf_size = FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer.PathBuffer) +
+    path_buf_len * sizeof(WCHAR);
+  used_data_size = used_buf_size -
+    FIELD_OFFSET(REPARSE_DATA_BUFFER, MountPointReparseBuffer);
+
+  /* Put general info in the data buffer */
+  buffer->ReparseTag = IO_REPARSE_TAG_MOUNT_POINT;
+  buffer->ReparseDataLength = used_data_size;
+  buffer->Reserved = 0;
+
+  /* Create a new directory */
+  if (!CreateDirectoryW(new_path, NULL)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    goto error;
+  }
+  created = 1;
+
+  /* Open the directory */
+  handle = CreateFileW(new_path,
+                       GENERIC_WRITE,
+                       0,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_FLAG_BACKUP_SEMANTICS |
+                         FILE_FLAG_OPEN_REPARSE_POINT,
+                       NULL);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    goto error;
+  }
+
+  /* Create the actual reparse point */
+  if (!DeviceIoControl(handle,
+                       FSCTL_SET_REPARSE_POINT,
+                       buffer,
+                       used_buf_size,
+                       NULL,
+                       0,
+                       &bytes,
+                       NULL)) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    goto error;
+  }
+
+  /* Clean up */
+  CloseHandle(handle);
+  uv__free(buffer);
+
+  SET_REQ_RESULT(req, 0);
+  return;
+
+error:
+  uv__free(buffer);
+
+  if (handle != INVALID_HANDLE_VALUE) {
+    CloseHandle(handle);
+  }
+
+  if (created) {
+    RemoveDirectoryW(new_path);
+  }
+}
+
+
+static void fs__symlink(uv_fs_t* req) {
+  WCHAR* pathw;
+  WCHAR* new_pathw;
+  int flags;
+  int err;
+
+  pathw = req->file.pathw;
+  new_pathw = req->fs.info.new_pathw;
+
+  if (req->fs.info.file_flags & UV_FS_SYMLINK_JUNCTION) {
+    fs__create_junction(req, pathw, new_pathw);
+    return;
+  }
+
+  if (req->fs.info.file_flags & UV_FS_SYMLINK_DIR)
+    flags = SYMBOLIC_LINK_FLAG_DIRECTORY | uv__file_symlink_usermode_flag;
+  else
+    flags = uv__file_symlink_usermode_flag;
+
+  if (CreateSymbolicLinkW(new_pathw, pathw, flags)) {
+    SET_REQ_RESULT(req, 0);
+    return;
+  }
+
+  /* Something went wrong. We will test if it is because of user-mode
+   * symlinks.
+   */
+  err = GetLastError();
+  if (err == ERROR_INVALID_PARAMETER &&
+      flags & SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE) {
+    /* This system does not support user-mode symlinks. We will clear the
+     * unsupported flag and retry.
+     */
+    uv__file_symlink_usermode_flag = 0;
+    fs__symlink(req);
+  } else {
+    SET_REQ_WIN32_ERROR(req, err);
+  }
+}
+
+
+static void fs__readlink(uv_fs_t* req) {
+  HANDLE handle;
+
+  handle = CreateFileW(req->file.pathw,
+                       0,
+                       0,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_FLAG_OPEN_REPARSE_POINT | FILE_FLAG_BACKUP_SEMANTICS,
+                       NULL);
+
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (fs__readlink_handle(handle, (char**) &req->ptr, NULL) != 0) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    CloseHandle(handle);
+    return;
+  }
+
+  req->flags |= UV_FS_FREE_PTR;
+  SET_REQ_RESULT(req, 0);
+
+  CloseHandle(handle);
+}
+
+
+static size_t fs__realpath_handle(HANDLE handle, char** realpath_ptr) {
+  int r;
+  DWORD w_realpath_len;
+  WCHAR* w_realpath_ptr = NULL;
+  WCHAR* w_realpath_buf;
+
+  w_realpath_len = GetFinalPathNameByHandleW(handle, NULL, 0, VOLUME_NAME_DOS);
+  if (w_realpath_len == 0) {
+    return -1;
+  }
+
+  w_realpath_buf = (WCHAR*)uv__malloc((w_realpath_len + 1) * sizeof(WCHAR));
+  if (w_realpath_buf == NULL) {
+    SetLastError(ERROR_OUTOFMEMORY);
+    return -1;
+  }
+  w_realpath_ptr = w_realpath_buf;
+
+  if (GetFinalPathNameByHandleW(
+          handle, w_realpath_ptr, w_realpath_len, VOLUME_NAME_DOS) == 0) {
+    uv__free(w_realpath_buf);
+    SetLastError(ERROR_INVALID_HANDLE);
+    return -1;
+  }
+
+  /* convert UNC path to long path */
+  if (wcsncmp(w_realpath_ptr,
+              UNC_PATH_PREFIX,
+              UNC_PATH_PREFIX_LEN) == 0) {
+    w_realpath_ptr += 6;
+    *w_realpath_ptr = L'\\';
+    w_realpath_len -= 6;
+  } else if (wcsncmp(w_realpath_ptr,
+                      LONG_PATH_PREFIX,
+                      LONG_PATH_PREFIX_LEN) == 0) {
+    w_realpath_ptr += 4;
+    w_realpath_len -= 4;
+  } else {
+    uv__free(w_realpath_buf);
+    SetLastError(ERROR_INVALID_HANDLE);
+    return -1;
+  }
+
+  r = fs__wide_to_utf8(w_realpath_ptr, w_realpath_len, realpath_ptr, NULL);
+  uv__free(w_realpath_buf);
+  return r;
+}
+
+static void fs__realpath(uv_fs_t* req) {
+  HANDLE handle;
+
+  handle = CreateFileW(req->file.pathw,
+                       0,
+                       0,
+                       NULL,
+                       OPEN_EXISTING,
+                       FILE_ATTRIBUTE_NORMAL | FILE_FLAG_BACKUP_SEMANTICS,
+                       NULL);
+  if (handle == INVALID_HANDLE_VALUE) {
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  if (fs__realpath_handle(handle, (char**) &req->ptr) == -1) {
+    CloseHandle(handle);
+    SET_REQ_WIN32_ERROR(req, GetLastError());
+    return;
+  }
+
+  CloseHandle(handle);
+  req->flags |= UV_FS_FREE_PTR;
+  SET_REQ_RESULT(req, 0);
+}
+
+
+static void fs__chown(uv_fs_t* req) {
+  req->result = 0;
+}
+
+
+static void fs__fchown(uv_fs_t* req) {
+  req->result = 0;
+}
+
+
+static void fs__lchown(uv_fs_t* req) {
+  req->result = 0;
+}
+
+static void uv__fs_work(struct uv__work* w) {
+  uv_fs_t* req;
+
+  req = container_of(w, uv_fs_t, work_req);
+  assert(req->type == UV_FS);
+
+#define XX(uc, lc)  case UV_FS_##uc: fs__##lc(req); break;
+  switch (req->fs_type) {
+    XX(OPEN, open)
+    XX(CLOSE, close)
+    XX(READ, read)
+    XX(WRITE, write)
+    XX(COPYFILE, copyfile)
+    XX(SENDFILE, sendfile)
+    XX(STAT, stat)
+    XX(LSTAT, lstat)
+    XX(FSTAT, fstat)
+    XX(FTRUNCATE, ftruncate)
+    XX(UTIME, utime)
+    XX(FUTIME, futime)
+    XX(ACCESS, access)
+    XX(CHMOD, chmod)
+    XX(FCHMOD, fchmod)
+    XX(FSYNC, fsync)
+    XX(FDATASYNC, fdatasync)
+    XX(UNLINK, unlink)
+    XX(RMDIR, rmdir)
+    XX(MKDIR, mkdir)
+    XX(MKDTEMP, mkdtemp)
+    XX(RENAME, rename)
+    XX(SCANDIR, scandir)
+    XX(LINK, link)
+    XX(SYMLINK, symlink)
+    XX(READLINK, readlink)
+    XX(REALPATH, realpath)
+    XX(CHOWN, chown)
+    XX(FCHOWN, fchown);
+    XX(LCHOWN, lchown);
+    default:
+      assert(!"bad uv_fs_type");
+  }
+}
+
+
+static void uv__fs_done(struct uv__work* w, int status) {
+  uv_fs_t* req;
+
+  req = container_of(w, uv_fs_t, work_req);
+  uv__req_unregister(req->loop, req);
+
+  if (status == UV_ECANCELED) {
+    assert(req->result == 0);
+    req->result = UV_ECANCELED;
+  }
+
+  req->cb(req);
+}
+
+
+void uv_fs_req_cleanup(uv_fs_t* req) {
+  if (req == NULL)
+    return;
+
+  if (req->flags & UV_FS_CLEANEDUP)
+    return;
+
+  if (req->flags & UV_FS_FREE_PATHS)
+    uv__free(req->file.pathw);
+
+  if (req->flags & UV_FS_FREE_PTR) {
+    if (req->fs_type == UV_FS_SCANDIR && req->ptr != NULL)
+      uv__fs_scandir_cleanup(req);
+    else
+      uv__free(req->ptr);
+  }
+
+  if (req->fs.info.bufs != req->fs.info.bufsml)
+    uv__free(req->fs.info.bufs);
+
+  req->path = NULL;
+  req->file.pathw = NULL;
+  req->fs.info.new_pathw = NULL;
+  req->fs.info.bufs = NULL;
+  req->ptr = NULL;
+
+  req->flags |= UV_FS_CLEANEDUP;
+}
+
+
+int uv_fs_open(uv_loop_t* loop, uv_fs_t* req, const char* path, int flags,
+    int mode, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_OPEN);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  req->fs.info.file_flags = flags;
+  req->fs.info.mode = mode;
+  POST;
+}
+
+
+int uv_fs_close(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
+  INIT(UV_FS_CLOSE);
+  req->file.fd = fd;
+  POST;
+}
+
+
+int uv_fs_read(uv_loop_t* loop,
+               uv_fs_t* req,
+               uv_file fd,
+               const uv_buf_t bufs[],
+               unsigned int nbufs,
+               int64_t offset,
+               uv_fs_cb cb) {
+  INIT(UV_FS_READ);
+
+  if (bufs == NULL || nbufs == 0)
+    return UV_EINVAL;
+
+  req->file.fd = fd;
+
+  req->fs.info.nbufs = nbufs;
+  req->fs.info.bufs = req->fs.info.bufsml;
+  if (nbufs > ARRAY_SIZE(req->fs.info.bufsml))
+    req->fs.info.bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+
+  if (req->fs.info.bufs == NULL)
+    return UV_ENOMEM;
+
+  memcpy(req->fs.info.bufs, bufs, nbufs * sizeof(*bufs));
+
+  req->fs.info.offset = offset;
+  POST;
+}
+
+
+int uv_fs_write(uv_loop_t* loop,
+                uv_fs_t* req,
+                uv_file fd,
+                const uv_buf_t bufs[],
+                unsigned int nbufs,
+                int64_t offset,
+                uv_fs_cb cb) {
+  INIT(UV_FS_WRITE);
+
+  if (bufs == NULL || nbufs == 0)
+    return UV_EINVAL;
+
+  req->file.fd = fd;
+
+  req->fs.info.nbufs = nbufs;
+  req->fs.info.bufs = req->fs.info.bufsml;
+  if (nbufs > ARRAY_SIZE(req->fs.info.bufsml))
+    req->fs.info.bufs = (uv_buf_t*)uv__malloc(nbufs * sizeof(*bufs));
+
+  if (req->fs.info.bufs == NULL)
+    return UV_ENOMEM;
+
+  memcpy(req->fs.info.bufs, bufs, nbufs * sizeof(*bufs));
+
+  req->fs.info.offset = offset;
+  POST;
+}
+
+
+int uv_fs_unlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_UNLINK);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_mkdir(uv_loop_t* loop, uv_fs_t* req, const char* path, int mode,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_MKDIR);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  req->fs.info.mode = mode;
+  POST;
+}
+
+
+int uv_fs_mkdtemp(uv_loop_t* loop, uv_fs_t* req, const char* tpl,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_MKDTEMP);
+  err = fs__capture_path(req, tpl, NULL, TRUE);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  POST;
+}
+
+
+int uv_fs_rmdir(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_RMDIR);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_scandir(uv_loop_t* loop, uv_fs_t* req, const char* path, int flags,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_SCANDIR);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  req->fs.info.file_flags = flags;
+  POST;
+}
+
+
+int uv_fs_link(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    const char* new_path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_LINK);
+  err = fs__capture_path(req, path, new_path, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_symlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    const char* new_path, int flags, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_SYMLINK);
+  err = fs__capture_path(req, path, new_path, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  req->fs.info.file_flags = flags;
+  POST;
+}
+
+
+int uv_fs_readlink(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_READLINK);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_realpath(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_REALPATH);
+
+  if (!path) {
+    return UV_EINVAL;
+  }
+
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_chown(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_uid_t uid,
+    uv_gid_t gid, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_CHOWN);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_fchown(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_uid_t uid,
+    uv_gid_t gid, uv_fs_cb cb) {
+  INIT(UV_FS_FCHOWN);
+  POST;
+}
+
+
+int uv_fs_lchown(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_uid_t uid,
+    uv_gid_t gid, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_LCHOWN);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+  POST;
+}
+
+
+int uv_fs_stat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_STAT);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_lstat(uv_loop_t* loop, uv_fs_t* req, const char* path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_LSTAT);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_fstat(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
+  INIT(UV_FS_FSTAT);
+  req->file.fd = fd;
+  POST;
+}
+
+
+int uv_fs_rename(uv_loop_t* loop, uv_fs_t* req, const char* path,
+    const char* new_path, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_RENAME);
+  err = fs__capture_path(req, path, new_path, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  POST;
+}
+
+
+int uv_fs_fsync(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
+  INIT(UV_FS_FSYNC);
+  req->file.fd = fd;
+  POST;
+}
+
+
+int uv_fs_fdatasync(uv_loop_t* loop, uv_fs_t* req, uv_file fd, uv_fs_cb cb) {
+  INIT(UV_FS_FDATASYNC);
+  req->file.fd = fd;
+  POST;
+}
+
+
+int uv_fs_ftruncate(uv_loop_t* loop, uv_fs_t* req, uv_file fd,
+    int64_t offset, uv_fs_cb cb) {
+  INIT(UV_FS_FTRUNCATE);
+  req->file.fd = fd;
+  req->fs.info.offset = offset;
+  POST;
+}
+
+
+int uv_fs_copyfile(uv_loop_t* loop,
+                   uv_fs_t* req,
+                   const char* path,
+                   const char* new_path,
+                   int flags,
+                   uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_COPYFILE);
+
+  if (flags & ~(UV_FS_COPYFILE_EXCL |
+                UV_FS_COPYFILE_FICLONE |
+                UV_FS_COPYFILE_FICLONE_FORCE)) {
+    return UV_EINVAL;
+  }
+
+  err = fs__capture_path(req, path, new_path, cb != NULL);
+
+  if (err)
+    return uv_translate_sys_error(err);
+
+  req->fs.info.file_flags = flags;
+  POST;
+}
+
+
+int uv_fs_sendfile(uv_loop_t* loop, uv_fs_t* req, uv_file fd_out,
+    uv_file fd_in, int64_t in_offset, size_t length, uv_fs_cb cb) {
+  INIT(UV_FS_SENDFILE);
+  req->file.fd = fd_in;
+  req->fs.info.fd_out = fd_out;
+  req->fs.info.offset = in_offset;
+  req->fs.info.bufsml[0].len = length;
+  POST;
+}
+
+
+int uv_fs_access(uv_loop_t* loop,
+                 uv_fs_t* req,
+                 const char* path,
+                 int flags,
+                 uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_ACCESS);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  req->fs.info.mode = flags;
+  POST;
+}
+
+
+int uv_fs_chmod(uv_loop_t* loop, uv_fs_t* req, const char* path, int mode,
+    uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_CHMOD);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  req->fs.info.mode = mode;
+  POST;
+}
+
+
+int uv_fs_fchmod(uv_loop_t* loop, uv_fs_t* req, uv_file fd, int mode,
+    uv_fs_cb cb) {
+  INIT(UV_FS_FCHMOD);
+  req->file.fd = fd;
+  req->fs.info.mode = mode;
+  POST;
+}
+
+
+int uv_fs_utime(uv_loop_t* loop, uv_fs_t* req, const char* path, double atime,
+    double mtime, uv_fs_cb cb) {
+  int err;
+
+  INIT(UV_FS_UTIME);
+  err = fs__capture_path(req, path, NULL, cb != NULL);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  req->fs.time.atime = atime;
+  req->fs.time.mtime = mtime;
+  POST;
+}
+
+
+int uv_fs_futime(uv_loop_t* loop, uv_fs_t* req, uv_file fd, double atime,
+    double mtime, uv_fs_cb cb) {
+  INIT(UV_FS_FUTIME);
+  req->file.fd = fd;
+  req->fs.time.atime = atime;
+  req->fs.time.mtime = mtime;
+  POST;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/getaddrinfo.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/getaddrinfo.cpp
new file mode 100644
index 0000000..063b493
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/getaddrinfo.cpp
@@ -0,0 +1,452 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "req-inl.h"
+
+/* EAI_* constants. */
+#include <winsock2.h>
+
+/* Needed for ConvertInterfaceIndexToLuid and ConvertInterfaceLuidToNameA */
+#include <iphlpapi.h>
+
+int uv__getaddrinfo_translate_error(int sys_err) {
+  switch (sys_err) {
+    case 0:                       return 0;
+    case WSATRY_AGAIN:            return UV_EAI_AGAIN;
+    case WSAEINVAL:               return UV_EAI_BADFLAGS;
+    case WSANO_RECOVERY:          return UV_EAI_FAIL;
+    case WSAEAFNOSUPPORT:         return UV_EAI_FAMILY;
+    case WSA_NOT_ENOUGH_MEMORY:   return UV_EAI_MEMORY;
+    case WSAHOST_NOT_FOUND:       return UV_EAI_NONAME;
+    case WSATYPE_NOT_FOUND:       return UV_EAI_SERVICE;
+    case WSAESOCKTNOSUPPORT:      return UV_EAI_SOCKTYPE;
+    default:                      return uv_translate_sys_error(sys_err);
+  }
+}
+
+
+/*
+ * MinGW is missing this
+ */
+#if !defined(_MSC_VER) && !defined(__MINGW64_VERSION_MAJOR)
+  typedef struct addrinfoW {
+    int ai_flags;
+    int ai_family;
+    int ai_socktype;
+    int ai_protocol;
+    size_t ai_addrlen;
+    WCHAR* ai_canonname;
+    struct sockaddr* ai_addr;
+    struct addrinfoW* ai_next;
+  } ADDRINFOW, *PADDRINFOW;
+
+  DECLSPEC_IMPORT int WSAAPI GetAddrInfoW(const WCHAR* node,
+                                          const WCHAR* service,
+                                          const ADDRINFOW* hints,
+                                          PADDRINFOW* result);
+
+  DECLSPEC_IMPORT void WSAAPI FreeAddrInfoW(PADDRINFOW pAddrInfo);
+#endif
+
+
+/* Adjust size value to be multiple of 4. Use to keep pointer aligned.
+ * Do we need different versions of this for different architectures? */
+#define ALIGNED_SIZE(X)     ((((X) + 3) >> 2) << 2)
+
+#ifndef NDIS_IF_MAX_STRING_SIZE
+#define NDIS_IF_MAX_STRING_SIZE IF_MAX_STRING_SIZE
+#endif
+
+static void uv__getaddrinfo_work(struct uv__work* w) {
+  uv_getaddrinfo_t* req;
+  struct addrinfoW* hints;
+  int err;
+
+  req = container_of(w, uv_getaddrinfo_t, work_req);
+  hints = req->addrinfow;
+  req->addrinfow = NULL;
+  err = GetAddrInfoW(req->node, req->service, hints, &req->addrinfow);
+  req->retcode = uv__getaddrinfo_translate_error(err);
+}
+
+
+/*
+ * Called from uv_run when complete. Call user specified callback
+ * then free returned addrinfo
+ * Returned addrinfo strings are converted from UTF-16 to UTF-8.
+ *
+ * To minimize allocation we calculate total size required,
+ * and copy all structs and referenced strings into the one block.
+ * Each size calculation is adjusted to avoid unaligned pointers.
+ */
+static void uv__getaddrinfo_done(struct uv__work* w, int status) {
+  uv_getaddrinfo_t* req;
+  int addrinfo_len = 0;
+  int name_len = 0;
+  size_t addrinfo_struct_len = ALIGNED_SIZE(sizeof(struct addrinfo));
+  struct addrinfoW* addrinfow_ptr;
+  struct addrinfo* addrinfo_ptr;
+  char* alloc_ptr = NULL;
+  char* cur_ptr = NULL;
+
+  req = container_of(w, uv_getaddrinfo_t, work_req);
+
+  /* release input parameter memory */
+  uv__free(req->alloc);
+  req->alloc = NULL;
+
+  if (status == UV_ECANCELED) {
+    assert(req->retcode == 0);
+    req->retcode = UV_EAI_CANCELED;
+    goto complete;
+  }
+
+  if (req->retcode == 0) {
+    /* Convert addrinfoW to addrinfo. First calculate required length. */
+    addrinfow_ptr = req->addrinfow;
+    while (addrinfow_ptr != NULL) {
+      addrinfo_len += addrinfo_struct_len +
+          ALIGNED_SIZE(addrinfow_ptr->ai_addrlen);
+      if (addrinfow_ptr->ai_canonname != NULL) {
+        name_len = WideCharToMultiByte(CP_UTF8,
+                                       0,
+                                       addrinfow_ptr->ai_canonname,
+                                       -1,
+                                       NULL,
+                                       0,
+                                       NULL,
+                                       NULL);
+        if (name_len == 0) {
+          req->retcode = uv_translate_sys_error(GetLastError());
+          goto complete;
+        }
+        addrinfo_len += ALIGNED_SIZE(name_len);
+      }
+      addrinfow_ptr = addrinfow_ptr->ai_next;
+    }
+
+    /* allocate memory for addrinfo results */
+    alloc_ptr = (char*)uv__malloc(addrinfo_len);
+
+    /* do conversions */
+    if (alloc_ptr != NULL) {
+      cur_ptr = alloc_ptr;
+      addrinfow_ptr = req->addrinfow;
+
+      while (addrinfow_ptr != NULL) {
+        /* copy addrinfo struct data */
+        assert(cur_ptr + addrinfo_struct_len <= alloc_ptr + addrinfo_len);
+        addrinfo_ptr = (struct addrinfo*)cur_ptr;
+        addrinfo_ptr->ai_family = addrinfow_ptr->ai_family;
+        addrinfo_ptr->ai_socktype = addrinfow_ptr->ai_socktype;
+        addrinfo_ptr->ai_protocol = addrinfow_ptr->ai_protocol;
+        addrinfo_ptr->ai_flags = addrinfow_ptr->ai_flags;
+        addrinfo_ptr->ai_addrlen = addrinfow_ptr->ai_addrlen;
+        addrinfo_ptr->ai_canonname = NULL;
+        addrinfo_ptr->ai_addr = NULL;
+        addrinfo_ptr->ai_next = NULL;
+
+        cur_ptr += addrinfo_struct_len;
+
+        /* copy sockaddr */
+        if (addrinfo_ptr->ai_addrlen > 0) {
+          assert(cur_ptr + addrinfo_ptr->ai_addrlen <=
+                 alloc_ptr + addrinfo_len);
+          memcpy(cur_ptr, addrinfow_ptr->ai_addr, addrinfo_ptr->ai_addrlen);
+          addrinfo_ptr->ai_addr = (struct sockaddr*)cur_ptr;
+          cur_ptr += ALIGNED_SIZE(addrinfo_ptr->ai_addrlen);
+        }
+
+        /* convert canonical name to UTF-8 */
+        if (addrinfow_ptr->ai_canonname != NULL) {
+          name_len = WideCharToMultiByte(CP_UTF8,
+                                         0,
+                                         addrinfow_ptr->ai_canonname,
+                                         -1,
+                                         NULL,
+                                         0,
+                                         NULL,
+                                         NULL);
+          assert(name_len > 0);
+          assert(cur_ptr + name_len <= alloc_ptr + addrinfo_len);
+          name_len = WideCharToMultiByte(CP_UTF8,
+                                         0,
+                                         addrinfow_ptr->ai_canonname,
+                                         -1,
+                                         cur_ptr,
+                                         name_len,
+                                         NULL,
+                                         NULL);
+          assert(name_len > 0);
+          addrinfo_ptr->ai_canonname = cur_ptr;
+          cur_ptr += ALIGNED_SIZE(name_len);
+        }
+        assert(cur_ptr <= alloc_ptr + addrinfo_len);
+
+        /* set next ptr */
+        addrinfow_ptr = addrinfow_ptr->ai_next;
+        if (addrinfow_ptr != NULL) {
+          addrinfo_ptr->ai_next = (struct addrinfo*)cur_ptr;
+        }
+      }
+      req->addrinfo = (struct addrinfo*)alloc_ptr;
+    } else {
+      req->retcode = UV_EAI_MEMORY;
+    }
+  }
+
+  /* return memory to system */
+  if (req->addrinfow != NULL) {
+    FreeAddrInfoW(req->addrinfow);
+    req->addrinfow = NULL;
+  }
+
+complete:
+  uv__req_unregister(req->loop, req);
+
+  /* finally do callback with converted result */
+  if (req->getaddrinfo_cb)
+    req->getaddrinfo_cb(req, req->retcode, req->addrinfo);
+}
+
+
+void uv_freeaddrinfo(struct addrinfo* ai) {
+  char* alloc_ptr = (char*)ai;
+
+  /* release copied result memory */
+  uv__free(alloc_ptr);
+}
+
+
+/*
+ * Entry point for getaddrinfo
+ * we convert the UTF-8 strings to UNICODE
+ * and save the UNICODE string pointers in the req
+ * We also copy hints so that caller does not need to keep memory until the
+ * callback.
+ * return 0 if a callback will be made
+ * return error code if validation fails
+ *
+ * To minimize allocation we calculate total size required,
+ * and copy all structs and referenced strings into the one block.
+ * Each size calculation is adjusted to avoid unaligned pointers.
+ */
+int uv_getaddrinfo(uv_loop_t* loop,
+                   uv_getaddrinfo_t* req,
+                   uv_getaddrinfo_cb getaddrinfo_cb,
+                   const char* node,
+                   const char* service,
+                   const struct addrinfo* hints) {
+  int nodesize = 0;
+  int servicesize = 0;
+  int hintssize = 0;
+  char* alloc_ptr = NULL;
+  int err;
+
+  if (req == NULL || (node == NULL && service == NULL)) {
+    return UV_EINVAL;
+  }
+
+  UV_REQ_INIT(req, UV_GETADDRINFO);
+  req->getaddrinfo_cb = getaddrinfo_cb;
+  req->addrinfo = NULL;
+  req->loop = loop;
+  req->retcode = 0;
+
+  /* calculate required memory size for all input values */
+  if (node != NULL) {
+    nodesize = ALIGNED_SIZE(MultiByteToWideChar(CP_UTF8, 0, node, -1, NULL, 0) *
+                            sizeof(WCHAR));
+    if (nodesize == 0) {
+      err = GetLastError();
+      goto error;
+    }
+  }
+
+  if (service != NULL) {
+    servicesize = ALIGNED_SIZE(MultiByteToWideChar(CP_UTF8,
+                                                   0,
+                                                   service,
+                                                   -1,
+                                                   NULL,
+                                                   0) *
+                               sizeof(WCHAR));
+    if (servicesize == 0) {
+      err = GetLastError();
+      goto error;
+    }
+  }
+  if (hints != NULL) {
+    hintssize = ALIGNED_SIZE(sizeof(struct addrinfoW));
+  }
+
+  /* allocate memory for inputs, and partition it as needed */
+  alloc_ptr = (char*)uv__malloc(nodesize + servicesize + hintssize);
+  if (!alloc_ptr) {
+    err = WSAENOBUFS;
+    goto error;
+  }
+
+  /* save alloc_ptr now so we can free if error */
+  req->alloc = (void*)alloc_ptr;
+
+  /* Convert node string to UTF16 into allocated memory and save pointer in the
+   * request. */
+  if (node != NULL) {
+    req->node = (WCHAR*)alloc_ptr;
+    if (MultiByteToWideChar(CP_UTF8,
+                            0,
+                            node,
+                            -1,
+                            (WCHAR*) alloc_ptr,
+                            nodesize / sizeof(WCHAR)) == 0) {
+      err = GetLastError();
+      goto error;
+    }
+    alloc_ptr += nodesize;
+  } else {
+    req->node = NULL;
+  }
+
+  /* Convert service string to UTF16 into allocated memory and save pointer in
+   * the req. */
+  if (service != NULL) {
+    req->service = (WCHAR*)alloc_ptr;
+    if (MultiByteToWideChar(CP_UTF8,
+                            0,
+                            service,
+                            -1,
+                            (WCHAR*) alloc_ptr,
+                            servicesize / sizeof(WCHAR)) == 0) {
+      err = GetLastError();
+      goto error;
+    }
+    alloc_ptr += servicesize;
+  } else {
+    req->service = NULL;
+  }
+
+  /* copy hints to allocated memory and save pointer in req */
+  if (hints != NULL) {
+    req->addrinfow = (struct addrinfoW*)alloc_ptr;
+    req->addrinfow->ai_family = hints->ai_family;
+    req->addrinfow->ai_socktype = hints->ai_socktype;
+    req->addrinfow->ai_protocol = hints->ai_protocol;
+    req->addrinfow->ai_flags = hints->ai_flags;
+    req->addrinfow->ai_addrlen = 0;
+    req->addrinfow->ai_canonname = NULL;
+    req->addrinfow->ai_addr = NULL;
+    req->addrinfow->ai_next = NULL;
+  } else {
+    req->addrinfow = NULL;
+  }
+
+  uv__req_register(loop, req);
+
+  if (getaddrinfo_cb) {
+    uv__work_submit(loop,
+                    &req->work_req,
+                    uv__getaddrinfo_work,
+                    uv__getaddrinfo_done);
+    return 0;
+  } else {
+    uv__getaddrinfo_work(&req->work_req);
+    uv__getaddrinfo_done(&req->work_req, 0);
+    return req->retcode;
+  }
+
+error:
+  if (req != NULL) {
+    uv__free(req->alloc);
+    req->alloc = NULL;
+  }
+  return uv_translate_sys_error(err);
+}
+
+int uv_if_indextoname(unsigned int ifindex, char* buffer, size_t* size) {
+  NET_LUID luid;
+  wchar_t wname[NDIS_IF_MAX_STRING_SIZE + 1]; /* Add one for the NUL. */
+  DWORD bufsize;
+  int r;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  r = ConvertInterfaceIndexToLuid(ifindex, &luid);
+
+  if (r != 0)
+    return uv_translate_sys_error(r);
+
+  r = ConvertInterfaceLuidToNameW(&luid, wname, ARRAY_SIZE(wname));
+
+  if (r != 0)
+    return uv_translate_sys_error(r);
+
+  /* Check how much space we need */
+  bufsize = WideCharToMultiByte(CP_UTF8, 0, wname, -1, NULL, 0, NULL, NULL);
+
+  if (bufsize == 0) {
+    return uv_translate_sys_error(GetLastError());
+  } else if (bufsize > *size) {
+    *size = bufsize;
+    return UV_ENOBUFS;
+  }
+
+  /* Convert to UTF-8 */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                wname,
+                                -1,
+                                buffer,
+                                *size,
+                                NULL,
+                                NULL);
+
+  if (bufsize == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  *size = bufsize - 1;
+  return 0;
+}
+
+int uv_if_indextoiid(unsigned int ifindex, char* buffer, size_t* size) {
+  int r;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  r = snprintf(buffer, *size, "%d", ifindex);
+
+  if (r < 0)
+    return uv_translate_sys_error(r);
+
+  if (r >= (int) *size) {
+    *size = r + 1;
+    return UV_ENOBUFS;
+  }
+
+  *size = r;
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/getnameinfo.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/getnameinfo.cpp
new file mode 100644
index 0000000..9f10cd2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/getnameinfo.cpp
@@ -0,0 +1,149 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+*
+* Permission is hereby granted, free of charge, to any person obtaining a copy
+* of this software and associated documentation files (the "Software"), to
+* deal in the Software without restriction, including without limitation the
+* rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+* sell copies of the Software, and to permit persons to whom the Software is
+* furnished to do so, subject to the following conditions:
+*
+* The above copyright notice and this permission notice shall be included in
+* all copies or substantial portions of the Software.
+*
+* THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+* IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+* FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+* AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+* LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+* FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+* IN THE SOFTWARE.
+*/
+
+#include <assert.h>
+#include <stdio.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "req-inl.h"
+
+#ifndef GetNameInfo
+int WSAAPI GetNameInfoW(
+  const SOCKADDR *pSockaddr,
+  socklen_t SockaddrLength,
+  PWCHAR pNodeBuffer,
+  DWORD NodeBufferSize,
+  PWCHAR pServiceBuffer,
+  DWORD ServiceBufferSize,
+  INT Flags
+);
+#endif
+
+static void uv__getnameinfo_work(struct uv__work* w) {
+  uv_getnameinfo_t* req;
+  WCHAR host[NI_MAXHOST];
+  WCHAR service[NI_MAXSERV];
+  int ret = 0;
+
+  req = container_of(w, uv_getnameinfo_t, work_req);
+  if (GetNameInfoW((struct sockaddr*)&req->storage,
+                   sizeof(req->storage),
+                   host,
+                   ARRAY_SIZE(host),
+                   service,
+                   ARRAY_SIZE(service),
+                   req->flags)) {
+    ret = WSAGetLastError();
+  }
+  req->retcode = uv__getaddrinfo_translate_error(ret);
+
+  /* convert results to UTF-8 */
+  WideCharToMultiByte(CP_UTF8,
+                      0,
+                      host,
+                      -1,
+                      req->host,
+                      sizeof(req->host),
+                      NULL,
+                      NULL);
+
+  WideCharToMultiByte(CP_UTF8,
+                      0,
+                      service,
+                      -1,
+                      req->service,
+                      sizeof(req->service),
+                      NULL,
+                      NULL);
+}
+
+
+/*
+* Called from uv_run when complete.
+*/
+static void uv__getnameinfo_done(struct uv__work* w, int status) {
+  uv_getnameinfo_t* req;
+  char* host;
+  char* service;
+
+  req = container_of(w, uv_getnameinfo_t, work_req);
+  uv__req_unregister(req->loop, req);
+  host = service = NULL;
+
+  if (status == UV_ECANCELED) {
+    assert(req->retcode == 0);
+    req->retcode = UV_EAI_CANCELED;
+  } else if (req->retcode == 0) {
+    host = req->host;
+    service = req->service;
+  }
+
+  if (req->getnameinfo_cb)
+    req->getnameinfo_cb(req, req->retcode, host, service);
+}
+
+
+/*
+* Entry point for getnameinfo
+* return 0 if a callback will be made
+* return error code if validation fails
+*/
+int uv_getnameinfo(uv_loop_t* loop,
+                   uv_getnameinfo_t* req,
+                   uv_getnameinfo_cb getnameinfo_cb,
+                   const struct sockaddr* addr,
+                   int flags) {
+  if (req == NULL || addr == NULL)
+    return UV_EINVAL;
+
+  if (addr->sa_family == AF_INET) {
+    memcpy(&req->storage,
+           addr,
+           sizeof(struct sockaddr_in));
+  } else if (addr->sa_family == AF_INET6) {
+    memcpy(&req->storage,
+           addr,
+           sizeof(struct sockaddr_in6));
+  } else {
+    return UV_EINVAL;
+  }
+
+  UV_REQ_INIT(req, UV_GETNAMEINFO);
+  uv__req_register(loop, req);
+
+  req->getnameinfo_cb = getnameinfo_cb;
+  req->flags = flags;
+  req->loop = loop;
+  req->retcode = 0;
+
+  if (getnameinfo_cb) {
+    uv__work_submit(loop,
+                    &req->work_req,
+                    uv__getnameinfo_work,
+                    uv__getnameinfo_done);
+    return 0;
+  } else {
+    uv__getnameinfo_work(&req->work_req);
+    uv__getnameinfo_done(&req->work_req, 0);
+    return req->retcode;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/handle-inl.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/handle-inl.h
new file mode 100644
index 0000000..ed84307
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/handle-inl.h
@@ -0,0 +1,179 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_HANDLE_INL_H_
+#define UV_WIN_HANDLE_INL_H_
+
+#include <assert.h>
+#include <io.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+#define DECREASE_ACTIVE_COUNT(loop, handle)                             \
+  do {                                                                  \
+    if (--(handle)->activecnt == 0 &&                                   \
+        !((handle)->flags & UV__HANDLE_CLOSING)) {                      \
+      uv__handle_stop((handle));                                        \
+    }                                                                   \
+    assert((handle)->activecnt >= 0);                                   \
+  } while (0)
+
+
+#define INCREASE_ACTIVE_COUNT(loop, handle)                             \
+  do {                                                                  \
+    if ((handle)->activecnt++ == 0) {                                   \
+      uv__handle_start((handle));                                       \
+    }                                                                   \
+    assert((handle)->activecnt > 0);                                    \
+  } while (0)
+
+
+#define DECREASE_PENDING_REQ_COUNT(handle)                              \
+  do {                                                                  \
+    assert(handle->reqs_pending > 0);                                   \
+    handle->reqs_pending--;                                             \
+                                                                        \
+    if (handle->flags & UV__HANDLE_CLOSING &&                           \
+        handle->reqs_pending == 0) {                                    \
+      uv_want_endgame(loop, (uv_handle_t*)handle);                      \
+    }                                                                   \
+  } while (0)
+
+
+#define uv__handle_closing(handle)                                      \
+  do {                                                                  \
+    assert(!((handle)->flags & UV__HANDLE_CLOSING));                    \
+                                                                        \
+    if (!(((handle)->flags & UV__HANDLE_ACTIVE) &&                      \
+          ((handle)->flags & UV__HANDLE_REF)))                          \
+      uv__active_handle_add((uv_handle_t*) (handle));                   \
+                                                                        \
+    (handle)->flags |= UV__HANDLE_CLOSING;                              \
+    (handle)->flags &= ~UV__HANDLE_ACTIVE;                              \
+  } while (0)
+
+
+#define uv__handle_close(handle)                                        \
+  do {                                                                  \
+    QUEUE_REMOVE(&(handle)->handle_queue);                              \
+    uv__active_handle_rm((uv_handle_t*) (handle));                      \
+                                                                        \
+    (handle)->flags |= UV_HANDLE_CLOSED;                                \
+                                                                        \
+    if ((handle)->close_cb)                                             \
+      (handle)->close_cb((uv_handle_t*) (handle));                      \
+  } while (0)
+
+
+INLINE static void uv_want_endgame(uv_loop_t* loop, uv_handle_t* handle) {
+  if (!(handle->flags & UV_HANDLE_ENDGAME_QUEUED)) {
+    handle->flags |= UV_HANDLE_ENDGAME_QUEUED;
+
+    handle->endgame_next = loop->endgame_handles;
+    loop->endgame_handles = handle;
+  }
+}
+
+
+INLINE static void uv_process_endgames(uv_loop_t* loop) {
+  uv_handle_t* handle;
+
+  while (loop->endgame_handles) {
+    handle = loop->endgame_handles;
+    loop->endgame_handles = handle->endgame_next;
+
+    handle->flags &= ~UV_HANDLE_ENDGAME_QUEUED;
+
+    switch (handle->type) {
+      case UV_TCP:
+        uv_tcp_endgame(loop, (uv_tcp_t*) handle);
+        break;
+
+      case UV_NAMED_PIPE:
+        uv_pipe_endgame(loop, (uv_pipe_t*) handle);
+        break;
+
+      case UV_TTY:
+        uv_tty_endgame(loop, (uv_tty_t*) handle);
+        break;
+
+      case UV_UDP:
+        uv_udp_endgame(loop, (uv_udp_t*) handle);
+        break;
+
+      case UV_POLL:
+        uv_poll_endgame(loop, (uv_poll_t*) handle);
+        break;
+
+      case UV_TIMER:
+        uv_timer_endgame(loop, (uv_timer_t*) handle);
+        break;
+
+      case UV_PREPARE:
+      case UV_CHECK:
+      case UV_IDLE:
+        uv_loop_watcher_endgame(loop, handle);
+        break;
+
+      case UV_ASYNC:
+        uv_async_endgame(loop, (uv_async_t*) handle);
+        break;
+
+      case UV_SIGNAL:
+        uv_signal_endgame(loop, (uv_signal_t*) handle);
+        break;
+
+      case UV_PROCESS:
+        uv_process_endgame(loop, (uv_process_t*) handle);
+        break;
+
+      case UV_FS_EVENT:
+        uv_fs_event_endgame(loop, (uv_fs_event_t*) handle);
+        break;
+
+      case UV_FS_POLL:
+        uv__fs_poll_endgame(loop, (uv_fs_poll_t*) handle);
+        break;
+
+      default:
+        assert(0);
+        break;
+    }
+  }
+}
+
+INLINE static HANDLE uv__get_osfhandle(int fd)
+{
+  /* _get_osfhandle() raises an assert in debug builds if the FD is invalid.
+   * But it also correctly checks the FD and returns INVALID_HANDLE_VALUE for
+   * invalid FDs in release builds (or if you let the assert continue). So this
+   * wrapper function disables asserts when calling _get_osfhandle. */
+
+  HANDLE handle;
+  UV_BEGIN_DISABLE_CRT_ASSERT();
+  handle = (HANDLE) _get_osfhandle(fd);
+  UV_END_DISABLE_CRT_ASSERT();
+  return handle;
+}
+
+#endif /* UV_WIN_HANDLE_INL_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/handle.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/handle.cpp
new file mode 100644
index 0000000..3915070
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/handle.cpp
@@ -0,0 +1,159 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+
+
+uv_handle_type uv_guess_handle(uv_file file) {
+  HANDLE handle;
+  DWORD mode;
+
+  if (file < 0) {
+    return UV_UNKNOWN_HANDLE;
+  }
+
+  handle = uv__get_osfhandle(file);
+
+  switch (GetFileType(handle)) {
+    case FILE_TYPE_CHAR:
+      if (GetConsoleMode(handle, &mode)) {
+        return UV_TTY;
+      } else {
+        return UV_FILE;
+      }
+
+    case FILE_TYPE_PIPE:
+      return UV_NAMED_PIPE;
+
+    case FILE_TYPE_DISK:
+      return UV_FILE;
+
+    default:
+      return UV_UNKNOWN_HANDLE;
+  }
+}
+
+
+int uv_is_active(const uv_handle_t* handle) {
+  return (handle->flags & UV__HANDLE_ACTIVE) &&
+        !(handle->flags & UV__HANDLE_CLOSING);
+}
+
+
+void uv_close(uv_handle_t* handle, uv_close_cb cb) {
+  uv_loop_t* loop = handle->loop;
+
+  if (handle->flags & UV__HANDLE_CLOSING) {
+    assert(0);
+    return;
+  }
+
+  handle->close_cb = cb;
+
+  /* Handle-specific close actions */
+  switch (handle->type) {
+    case UV_TCP:
+      uv_tcp_close(loop, (uv_tcp_t*)handle);
+      return;
+
+    case UV_NAMED_PIPE:
+      uv_pipe_close(loop, (uv_pipe_t*) handle);
+      return;
+
+    case UV_TTY:
+      uv_tty_close((uv_tty_t*) handle);
+      return;
+
+    case UV_UDP:
+      uv_udp_close(loop, (uv_udp_t*) handle);
+      return;
+
+    case UV_POLL:
+      uv_poll_close(loop, (uv_poll_t*) handle);
+      return;
+
+    case UV_TIMER:
+      uv_timer_stop((uv_timer_t*)handle);
+      uv__handle_closing(handle);
+      uv_want_endgame(loop, handle);
+      return;
+
+    case UV_PREPARE:
+      uv_prepare_stop((uv_prepare_t*)handle);
+      uv__handle_closing(handle);
+      uv_want_endgame(loop, handle);
+      return;
+
+    case UV_CHECK:
+      uv_check_stop((uv_check_t*)handle);
+      uv__handle_closing(handle);
+      uv_want_endgame(loop, handle);
+      return;
+
+    case UV_IDLE:
+      uv_idle_stop((uv_idle_t*)handle);
+      uv__handle_closing(handle);
+      uv_want_endgame(loop, handle);
+      return;
+
+    case UV_ASYNC:
+      uv_async_close(loop, (uv_async_t*) handle);
+      return;
+
+    case UV_SIGNAL:
+      uv_signal_close(loop, (uv_signal_t*) handle);
+      return;
+
+    case UV_PROCESS:
+      uv_process_close(loop, (uv_process_t*) handle);
+      return;
+
+    case UV_FS_EVENT:
+      uv_fs_event_close(loop, (uv_fs_event_t*) handle);
+      return;
+
+    case UV_FS_POLL:
+      uv__fs_poll_close((uv_fs_poll_t*) handle);
+      uv__handle_closing(handle);
+      uv_want_endgame(loop, handle);
+      return;
+
+    default:
+      /* Not supported */
+      abort();
+  }
+}
+
+
+int uv_is_closing(const uv_handle_t* handle) {
+  return !!(handle->flags & (UV__HANDLE_CLOSING | UV_HANDLE_CLOSED));
+}
+
+
+uv_os_fd_t uv_get_osfhandle(int fd) {
+  return uv__get_osfhandle(fd);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/internal.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/internal.h
new file mode 100644
index 0000000..fa926d9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/internal.h
@@ -0,0 +1,398 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_INTERNAL_H_
+#define UV_WIN_INTERNAL_H_
+
+#include "uv.h"
+#include "../uv-common.h"
+
+#include "uv/tree.h"
+#include "winapi.h"
+#include "winsock.h"
+
+#ifdef _MSC_VER
+# define INLINE __inline
+# define UV_THREAD_LOCAL __declspec( thread )
+#else
+# define INLINE inline
+# define UV_THREAD_LOCAL __thread
+#endif
+
+
+#ifdef _DEBUG
+
+extern UV_THREAD_LOCAL int uv__crt_assert_enabled;
+
+#define UV_BEGIN_DISABLE_CRT_ASSERT()                           \
+  {                                                             \
+    int uv__saved_crt_assert_enabled = uv__crt_assert_enabled;  \
+    uv__crt_assert_enabled = FALSE;
+
+
+#define UV_END_DISABLE_CRT_ASSERT()                             \
+    uv__crt_assert_enabled = uv__saved_crt_assert_enabled;      \
+  }
+
+#else
+#define UV_BEGIN_DISABLE_CRT_ASSERT()
+#define UV_END_DISABLE_CRT_ASSERT()
+#endif
+
+/*
+ * Handles
+ * (also see handle-inl.h)
+ */
+
+/* Used by all handles. */
+#define UV_HANDLE_CLOSED                        0x00000002
+#define UV_HANDLE_ENDGAME_QUEUED                0x00000008
+
+/* uv-common.h: #define UV__HANDLE_CLOSING      0x00000001 */
+/* uv-common.h: #define UV__HANDLE_ACTIVE       0x00000040 */
+/* uv-common.h: #define UV__HANDLE_REF          0x00000020 */
+/* uv-common.h: #define UV_HANDLE_INTERNAL      0x00000080 */
+
+/* Used by streams and UDP handles. */
+#define UV_HANDLE_READING                       0x00000100
+#define UV_HANDLE_BOUND                         0x00000200
+#define UV_HANDLE_LISTENING                     0x00000800
+#define UV_HANDLE_CONNECTION                    0x00001000
+#define UV_HANDLE_READABLE                      0x00008000
+#define UV_HANDLE_WRITABLE                      0x00010000
+#define UV_HANDLE_READ_PENDING                  0x00020000
+#define UV_HANDLE_SYNC_BYPASS_IOCP              0x00040000
+#define UV_HANDLE_ZERO_READ                     0x00080000
+#define UV_HANDLE_EMULATE_IOCP                  0x00100000
+#define UV_HANDLE_BLOCKING_WRITES               0x00200000
+#define UV_HANDLE_CANCELLATION_PENDING          0x00400000
+
+/* Used by uv_tcp_t and uv_udp_t handles */
+#define UV_HANDLE_IPV6                          0x01000000
+
+/* Only used by uv_tcp_t handles. */
+#define UV_HANDLE_TCP_NODELAY                   0x02000000
+#define UV_HANDLE_TCP_KEEPALIVE                 0x04000000
+#define UV_HANDLE_TCP_SINGLE_ACCEPT             0x08000000
+#define UV_HANDLE_TCP_ACCEPT_STATE_CHANGING     0x10000000
+#define UV_HANDLE_TCP_SOCKET_CLOSED             0x20000000
+#define UV_HANDLE_SHARED_TCP_SOCKET             0x40000000
+
+/* Only used by uv_pipe_t handles. */
+#define UV_HANDLE_NON_OVERLAPPED_PIPE           0x01000000
+#define UV_HANDLE_PIPESERVER                    0x02000000
+
+/* Only used by uv_tty_t handles. */
+#define UV_HANDLE_TTY_READABLE                  0x01000000
+#define UV_HANDLE_TTY_RAW                       0x02000000
+#define UV_HANDLE_TTY_SAVED_POSITION            0x04000000
+#define UV_HANDLE_TTY_SAVED_ATTRIBUTES          0x08000000
+
+/* Only used by uv_poll_t handles. */
+#define UV_HANDLE_POLL_SLOW                     0x02000000
+
+
+/*
+ * Requests: see req-inl.h
+ */
+
+
+/*
+ * Streams: see stream-inl.h
+ */
+
+
+/*
+ * TCP
+ */
+
+typedef struct {
+  WSAPROTOCOL_INFOW socket_info;
+  uint32_t delayed_error;
+  uint32_t flags; /* Either zero or UV_HANDLE_CONNECTION. */
+} uv__ipc_socket_xfer_info_t;
+
+int uv_tcp_listen(uv_tcp_t* handle, int backlog, uv_connection_cb cb);
+int uv_tcp_accept(uv_tcp_t* server, uv_tcp_t* client);
+int uv_tcp_read_start(uv_tcp_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb);
+int uv_tcp_write(uv_loop_t* loop, uv_write_t* req, uv_tcp_t* handle,
+    const uv_buf_t bufs[], unsigned int nbufs, uv_write_cb cb);
+int uv__tcp_try_write(uv_tcp_t* handle, const uv_buf_t bufs[],
+    unsigned int nbufs);
+
+void uv_process_tcp_read_req(uv_loop_t* loop, uv_tcp_t* handle, uv_req_t* req);
+void uv_process_tcp_write_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_write_t* req);
+void uv_process_tcp_accept_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_req_t* req);
+void uv_process_tcp_connect_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_connect_t* req);
+
+void uv_tcp_close(uv_loop_t* loop, uv_tcp_t* tcp);
+void uv_tcp_endgame(uv_loop_t* loop, uv_tcp_t* handle);
+
+int uv__tcp_xfer_export(uv_tcp_t* handle,
+                        int pid,
+                        uv__ipc_socket_xfer_info_t* xfer_info);
+int uv__tcp_xfer_import(uv_tcp_t* tcp, uv__ipc_socket_xfer_info_t* xfer_info);
+
+
+/*
+ * UDP
+ */
+void uv_process_udp_recv_req(uv_loop_t* loop, uv_udp_t* handle, uv_req_t* req);
+void uv_process_udp_send_req(uv_loop_t* loop, uv_udp_t* handle,
+    uv_udp_send_t* req);
+
+void uv_udp_close(uv_loop_t* loop, uv_udp_t* handle);
+void uv_udp_endgame(uv_loop_t* loop, uv_udp_t* handle);
+
+
+/*
+ * Pipes
+ */
+int uv_stdio_pipe_server(uv_loop_t* loop, uv_pipe_t* handle, DWORD access,
+    char* name, size_t nameSize);
+
+int uv_pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb);
+int uv_pipe_accept(uv_pipe_t* server, uv_stream_t* client);
+int uv_pipe_read_start(uv_pipe_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb);
+void uv__pipe_read_stop(uv_pipe_t* handle);
+int uv__pipe_write(uv_loop_t* loop,
+                   uv_write_t* req,
+                   uv_pipe_t* handle,
+                   const uv_buf_t bufs[],
+                   size_t nbufs,
+                   uv_stream_t* send_handle,
+                   uv_write_cb cb);
+
+void uv_process_pipe_read_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_req_t* req);
+void uv_process_pipe_write_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_write_t* req);
+void uv_process_pipe_accept_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_req_t* raw_req);
+void uv_process_pipe_connect_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_connect_t* req);
+void uv_process_pipe_shutdown_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_shutdown_t* req);
+
+void uv_pipe_close(uv_loop_t* loop, uv_pipe_t* handle);
+void uv_pipe_cleanup(uv_loop_t* loop, uv_pipe_t* handle);
+void uv_pipe_endgame(uv_loop_t* loop, uv_pipe_t* handle);
+
+
+/*
+ * TTY
+ */
+void uv_console_init(void);
+
+int uv_tty_read_start(uv_tty_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb);
+int uv_tty_read_stop(uv_tty_t* handle);
+int uv_tty_write(uv_loop_t* loop, uv_write_t* req, uv_tty_t* handle,
+    const uv_buf_t bufs[], unsigned int nbufs, uv_write_cb cb);
+int uv__tty_try_write(uv_tty_t* handle, const uv_buf_t bufs[],
+    unsigned int nbufs);
+void uv_tty_close(uv_tty_t* handle);
+
+void uv_process_tty_read_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* req);
+void uv_process_tty_write_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_write_t* req);
+/*
+ * uv_process_tty_accept_req() is a stub to keep DELEGATE_STREAM_REQ working
+ * TODO: find a way to remove it
+ */
+void uv_process_tty_accept_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* raw_req);
+/*
+ * uv_process_tty_connect_req() is a stub to keep DELEGATE_STREAM_REQ working
+ * TODO: find a way to remove it
+ */
+void uv_process_tty_connect_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_connect_t* req);
+
+void uv_tty_endgame(uv_loop_t* loop, uv_tty_t* handle);
+
+
+/*
+ * Poll watchers
+ */
+void uv_process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
+    uv_req_t* req);
+
+int uv_poll_close(uv_loop_t* loop, uv_poll_t* handle);
+void uv_poll_endgame(uv_loop_t* loop, uv_poll_t* handle);
+
+
+/*
+ * Timers
+ */
+void uv_timer_endgame(uv_loop_t* loop, uv_timer_t* handle);
+
+DWORD uv__next_timeout(const uv_loop_t* loop);
+void uv_process_timers(uv_loop_t* loop);
+
+
+/*
+ * Loop watchers
+ */
+void uv_loop_watcher_endgame(uv_loop_t* loop, uv_handle_t* handle);
+
+void uv_prepare_invoke(uv_loop_t* loop);
+void uv_check_invoke(uv_loop_t* loop);
+void uv_idle_invoke(uv_loop_t* loop);
+
+void uv__once_init(void);
+
+
+/*
+ * Async watcher
+ */
+void uv_async_close(uv_loop_t* loop, uv_async_t* handle);
+void uv_async_endgame(uv_loop_t* loop, uv_async_t* handle);
+
+void uv_process_async_wakeup_req(uv_loop_t* loop, uv_async_t* handle,
+    uv_req_t* req);
+
+
+/*
+ * Signal watcher
+ */
+void uv_signals_init(void);
+int uv__signal_dispatch(int signum);
+
+void uv_signal_close(uv_loop_t* loop, uv_signal_t* handle);
+void uv_signal_endgame(uv_loop_t* loop, uv_signal_t* handle);
+
+void uv_process_signal_req(uv_loop_t* loop, uv_signal_t* handle,
+    uv_req_t* req);
+
+
+/*
+ * Spawn
+ */
+void uv_process_proc_exit(uv_loop_t* loop, uv_process_t* handle);
+void uv_process_close(uv_loop_t* loop, uv_process_t* handle);
+void uv_process_endgame(uv_loop_t* loop, uv_process_t* handle);
+
+
+/*
+ * Error
+ */
+int uv_translate_sys_error(int sys_errno);
+
+
+/*
+ * FS
+ */
+void uv_fs_init(void);
+
+
+/*
+ * FS Event
+ */
+void uv_process_fs_event_req(uv_loop_t* loop, uv_req_t* req,
+    uv_fs_event_t* handle);
+void uv_fs_event_close(uv_loop_t* loop, uv_fs_event_t* handle);
+void uv_fs_event_endgame(uv_loop_t* loop, uv_fs_event_t* handle);
+
+
+/*
+ * Stat poller.
+ */
+void uv__fs_poll_endgame(uv_loop_t* loop, uv_fs_poll_t* handle);
+
+
+/*
+ * Utilities.
+ */
+void uv__util_init(void);
+
+uint64_t uv__hrtime(double scale);
+__declspec(noreturn) void uv_fatal_error(const int errorno, const char* syscall);
+int uv__getpwuid_r(uv_passwd_t* pwd);
+int uv__convert_utf16_to_utf8(const WCHAR* utf16, int utf16len, char** utf8);
+int uv__convert_utf8_to_utf16(const char* utf8, int utf8len, WCHAR** utf16);
+
+
+/*
+ * Process stdio handles.
+ */
+int uv__stdio_create(uv_loop_t* loop,
+                     const uv_process_options_t* options,
+                     BYTE** buffer_ptr);
+void uv__stdio_destroy(BYTE* buffer);
+void uv__stdio_noinherit(BYTE* buffer);
+int uv__stdio_verify(BYTE* buffer, WORD size);
+WORD uv__stdio_size(BYTE* buffer);
+HANDLE uv__stdio_handle(BYTE* buffer, int fd);
+
+
+/*
+ * Winapi and ntapi utility functions
+ */
+void uv_winapi_init(void);
+
+
+/*
+ * Winsock utility functions
+ */
+void uv_winsock_init(void);
+
+int uv_ntstatus_to_winsock_error(NTSTATUS status);
+
+BOOL uv_get_acceptex_function(SOCKET socket, LPFN_ACCEPTEX* target);
+BOOL uv_get_connectex_function(SOCKET socket, LPFN_CONNECTEX* target);
+
+int WSAAPI uv_wsarecv_workaround(SOCKET socket, WSABUF* buffers,
+    DWORD buffer_count, DWORD* bytes, DWORD* flags, WSAOVERLAPPED *overlapped,
+    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+int WSAAPI uv_wsarecvfrom_workaround(SOCKET socket, WSABUF* buffers,
+    DWORD buffer_count, DWORD* bytes, DWORD* flags, struct sockaddr* addr,
+    int* addr_len, WSAOVERLAPPED *overlapped,
+    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine);
+
+int WSAAPI uv_msafd_poll(SOCKET socket, AFD_POLL_INFO* info_in,
+    AFD_POLL_INFO* info_out, OVERLAPPED* overlapped);
+
+/* Whether there are any non-IFS LSPs stacked on TCP */
+extern int uv_tcp_non_ifs_lsp_ipv4;
+extern int uv_tcp_non_ifs_lsp_ipv6;
+
+/* Ip address used to bind to any port at any interface */
+extern struct sockaddr_in uv_addr_ip4_any_;
+extern struct sockaddr_in6 uv_addr_ip6_any_;
+
+/*
+ * Wake all loops with fake message
+ */
+void uv__wake_all_loops(void);
+
+/*
+ * Init system wake-up detection
+ */
+void uv__init_detect_system_wakeup(void);
+
+#endif /* UV_WIN_INTERNAL_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/loop-watcher.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/loop-watcher.cpp
new file mode 100644
index 0000000..20e4509
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/loop-watcher.cpp
@@ -0,0 +1,122 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+
+
+void uv_loop_watcher_endgame(uv_loop_t* loop, uv_handle_t* handle) {
+  if (handle->flags & UV__HANDLE_CLOSING) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+    handle->flags |= UV_HANDLE_CLOSED;
+    uv__handle_close(handle);
+  }
+}
+
+
+#define UV_LOOP_WATCHER_DEFINE(name, NAME)                                    \
+  int uv_##name##_init(uv_loop_t* loop, uv_##name##_t* handle) {              \
+    uv__handle_init(loop, (uv_handle_t*) handle, UV_##NAME);                  \
+                                                                              \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+                                                                              \
+  int uv_##name##_start(uv_##name##_t* handle, uv_##name##_cb cb) {           \
+    uv_loop_t* loop = handle->loop;                                           \
+    uv_##name##_t* old_head;                                                  \
+                                                                              \
+    assert(handle->type == UV_##NAME);                                        \
+                                                                              \
+    if (uv__is_active(handle))                                                \
+      return 0;                                                               \
+                                                                              \
+    if (cb == NULL)                                                           \
+      return UV_EINVAL;                                                       \
+                                                                              \
+    old_head = loop->name##_handles;                                          \
+                                                                              \
+    handle->name##_next = old_head;                                           \
+    handle->name##_prev = NULL;                                               \
+                                                                              \
+    if (old_head) {                                                           \
+      old_head->name##_prev = handle;                                         \
+    }                                                                         \
+                                                                              \
+    loop->name##_handles = handle;                                            \
+                                                                              \
+    handle->name##_cb = cb;                                                   \
+    uv__handle_start(handle);                                                 \
+                                                                              \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+                                                                              \
+  int uv_##name##_stop(uv_##name##_t* handle) {                               \
+    uv_loop_t* loop = handle->loop;                                           \
+                                                                              \
+    assert(handle->type == UV_##NAME);                                        \
+                                                                              \
+    if (!uv__is_active(handle))                                               \
+      return 0;                                                               \
+                                                                              \
+    /* Update loop head if needed */                                          \
+    if (loop->name##_handles == handle) {                                     \
+      loop->name##_handles = handle->name##_next;                             \
+    }                                                                         \
+                                                                              \
+    /* Update the iterator-next pointer of needed */                          \
+    if (loop->next_##name##_handle == handle) {                               \
+      loop->next_##name##_handle = handle->name##_next;                       \
+    }                                                                         \
+                                                                              \
+    if (handle->name##_prev) {                                                \
+      handle->name##_prev->name##_next = handle->name##_next;                 \
+    }                                                                         \
+    if (handle->name##_next) {                                                \
+      handle->name##_next->name##_prev = handle->name##_prev;                 \
+    }                                                                         \
+                                                                              \
+    uv__handle_stop(handle);                                                  \
+                                                                              \
+    return 0;                                                                 \
+  }                                                                           \
+                                                                              \
+                                                                              \
+  void uv_##name##_invoke(uv_loop_t* loop) {                                  \
+    uv_##name##_t* handle;                                                    \
+                                                                              \
+    (loop)->next_##name##_handle = (loop)->name##_handles;                    \
+                                                                              \
+    while ((loop)->next_##name##_handle != NULL) {                            \
+      handle = (loop)->next_##name##_handle;                                  \
+      (loop)->next_##name##_handle = handle->name##_next;                     \
+                                                                              \
+      handle->name##_cb(handle);                                              \
+    }                                                                         \
+  }
+
+UV_LOOP_WATCHER_DEFINE(prepare, PREPARE)
+UV_LOOP_WATCHER_DEFINE(check, CHECK)
+UV_LOOP_WATCHER_DEFINE(idle, IDLE)
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/pipe.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/pipe.cpp
new file mode 100644
index 0000000..80661d8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/pipe.cpp
@@ -0,0 +1,2337 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+#include <stdbool.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "stream-inl.h"
+#include "req-inl.h"
+
+#include <aclapi.h>
+#include <accctrl.h>
+
+/* A zero-size buffer for use by uv_pipe_read */
+static char uv_zero_[] = "";
+
+/* Null uv_buf_t */
+static const uv_buf_t uv_null_buf_ = { 0, NULL };
+
+/* The timeout that the pipe will wait for the remote end to write data when
+ * the local ends wants to shut it down. */
+static const int64_t eof_timeout = 50; /* ms */
+
+static const int default_pending_pipe_instances = 4;
+
+/* Pipe prefix */
+static char pipe_prefix[] = "\\\\?\\pipe";
+static const int pipe_prefix_len = sizeof(pipe_prefix) - 1;
+
+/* IPC incoming xfer queue item. */
+typedef struct {
+  uv__ipc_socket_xfer_info_t xfer_info;
+  QUEUE member;
+} uv__ipc_xfer_queue_item_t;
+
+/* IPC frame types. */
+enum { UV__IPC_DATA_FRAME = 0, UV__IPC_XFER_FRAME = 1 };
+
+/* IPC frame header. */
+typedef struct {
+  uint32_t type;
+  uint32_t payload_length;
+} uv__ipc_frame_header_t;
+
+/* Coalesced write request. */
+typedef struct {
+  uv_write_t req;       /* Internal heap-allocated write request. */
+  uv_write_t* user_req; /* Pointer to user-specified uv_write_t. */
+} uv__coalesced_write_t;
+
+
+static void eof_timer_init(uv_pipe_t* pipe);
+static void eof_timer_start(uv_pipe_t* pipe);
+static void eof_timer_stop(uv_pipe_t* pipe);
+static void eof_timer_cb(uv_timer_t* timer);
+static void eof_timer_destroy(uv_pipe_t* pipe);
+static void eof_timer_close_cb(uv_handle_t* handle);
+
+
+static void uv_unique_pipe_name(char* ptr, char* name, size_t size) {
+  snprintf(name, size, "\\\\?\\pipe\\uv\\%p-%lu", ptr, GetCurrentProcessId());
+}
+
+
+int uv_pipe_init(uv_loop_t* loop, uv_pipe_t* handle, int ipc) {
+  uv_stream_init(loop, (uv_stream_t*)handle, UV_NAMED_PIPE);
+
+  handle->reqs_pending = 0;
+  handle->handle = INVALID_HANDLE_VALUE;
+  handle->name = NULL;
+  handle->pipe.conn.ipc_remote_pid = 0;
+  handle->pipe.conn.ipc_data_frame.payload_remaining = 0;
+  QUEUE_INIT(&handle->pipe.conn.ipc_xfer_queue);
+  handle->pipe.conn.ipc_xfer_queue_length = 0;
+  handle->ipc = ipc;
+  handle->pipe.conn.non_overlapped_writes_tail = NULL;
+
+  return 0;
+}
+
+
+static void uv_pipe_connection_init(uv_pipe_t* handle) {
+  uv_connection_init((uv_stream_t*) handle);
+  handle->read_req.data = handle;
+  handle->pipe.conn.eof_timer = NULL;
+  assert(!(handle->flags & UV_HANDLE_PIPESERVER));
+  if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
+    handle->pipe.conn.readfile_thread_handle = NULL;
+    InitializeCriticalSection(&handle->pipe.conn.readfile_thread_lock);
+  }
+}
+
+
+static HANDLE open_named_pipe(const WCHAR* name, DWORD* duplex_flags) {
+  HANDLE pipeHandle;
+
+  /*
+   * Assume that we have a duplex pipe first, so attempt to
+   * connect with GENERIC_READ | GENERIC_WRITE.
+   */
+  pipeHandle = CreateFileW(name,
+                           GENERIC_READ | GENERIC_WRITE,
+                           0,
+                           NULL,
+                           OPEN_EXISTING,
+                           FILE_FLAG_OVERLAPPED,
+                           NULL);
+  if (pipeHandle != INVALID_HANDLE_VALUE) {
+    *duplex_flags = UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+    return pipeHandle;
+  }
+
+  /*
+   * If the pipe is not duplex CreateFileW fails with
+   * ERROR_ACCESS_DENIED.  In that case try to connect
+   * as a read-only or write-only.
+   */
+  if (GetLastError() == ERROR_ACCESS_DENIED) {
+    pipeHandle = CreateFileW(name,
+                             GENERIC_READ | FILE_WRITE_ATTRIBUTES,
+                             0,
+                             NULL,
+                             OPEN_EXISTING,
+                             FILE_FLAG_OVERLAPPED,
+                             NULL);
+
+    if (pipeHandle != INVALID_HANDLE_VALUE) {
+      *duplex_flags = UV_HANDLE_READABLE;
+      return pipeHandle;
+    }
+  }
+
+  if (GetLastError() == ERROR_ACCESS_DENIED) {
+    pipeHandle = CreateFileW(name,
+                             GENERIC_WRITE | FILE_READ_ATTRIBUTES,
+                             0,
+                             NULL,
+                             OPEN_EXISTING,
+                             FILE_FLAG_OVERLAPPED,
+                             NULL);
+
+    if (pipeHandle != INVALID_HANDLE_VALUE) {
+      *duplex_flags = UV_HANDLE_WRITABLE;
+      return pipeHandle;
+    }
+  }
+
+  return INVALID_HANDLE_VALUE;
+}
+
+
+static void close_pipe(uv_pipe_t* pipe) {
+  assert(pipe->u.fd == -1 || pipe->u.fd > 2);
+  if (pipe->u.fd == -1)
+    CloseHandle(pipe->handle);
+  else
+    close(pipe->u.fd);
+
+  pipe->u.fd = -1;
+  pipe->handle = INVALID_HANDLE_VALUE;
+}
+
+
+int uv_stdio_pipe_server(uv_loop_t* loop, uv_pipe_t* handle, DWORD access,
+    char* name, size_t nameSize) {
+  HANDLE pipeHandle;
+  int err;
+  char* ptr = (char*)handle;
+
+  for (;;) {
+    uv_unique_pipe_name(ptr, name, nameSize);
+
+    pipeHandle = CreateNamedPipeA(name,
+      access | FILE_FLAG_OVERLAPPED | FILE_FLAG_FIRST_PIPE_INSTANCE | WRITE_DAC,
+      PIPE_TYPE_BYTE | PIPE_READMODE_BYTE | PIPE_WAIT, 1, 65536, 65536, 0,
+      NULL);
+
+    if (pipeHandle != INVALID_HANDLE_VALUE) {
+      /* No name collisions.  We're done. */
+      break;
+    }
+
+    err = GetLastError();
+    if (err != ERROR_PIPE_BUSY && err != ERROR_ACCESS_DENIED) {
+      goto error;
+    }
+
+    /* Pipe name collision.  Increment the pointer and try again. */
+    ptr++;
+  }
+
+  if (CreateIoCompletionPort(pipeHandle,
+                             loop->iocp,
+                             (ULONG_PTR)handle,
+                             0) == NULL) {
+    err = GetLastError();
+    goto error;
+  }
+
+  uv_pipe_connection_init(handle);
+  handle->handle = pipeHandle;
+
+  return 0;
+
+ error:
+  if (pipeHandle != INVALID_HANDLE_VALUE) {
+    CloseHandle(pipeHandle);
+  }
+
+  return err;
+}
+
+
+static int uv_set_pipe_handle(uv_loop_t* loop,
+                              uv_pipe_t* handle,
+                              HANDLE pipeHandle,
+                              int fd,
+                              DWORD duplex_flags) {
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_MODE_INFORMATION mode_info;
+  DWORD mode = PIPE_READMODE_BYTE | PIPE_WAIT;
+  DWORD current_mode = 0;
+  DWORD err = 0;
+
+  if (!(handle->flags & UV_HANDLE_PIPESERVER) &&
+      handle->handle != INVALID_HANDLE_VALUE)
+    return UV_EBUSY;
+
+  if (!SetNamedPipeHandleState(pipeHandle, &mode, NULL, NULL)) {
+    err = GetLastError();
+    if (err == ERROR_ACCESS_DENIED) {
+      /*
+       * SetNamedPipeHandleState can fail if the handle doesn't have either
+       * GENERIC_WRITE  or FILE_WRITE_ATTRIBUTES.
+       * But if the handle already has the desired wait and blocking modes
+       * we can continue.
+       */
+      if (!GetNamedPipeHandleState(pipeHandle, &current_mode, NULL, NULL,
+                                   NULL, NULL, 0)) {
+        return -1;
+      } else if (current_mode & PIPE_NOWAIT) {
+        SetLastError(ERROR_ACCESS_DENIED);
+        return -1;
+      }
+    } else {
+      /* If this returns ERROR_INVALID_PARAMETER we probably opened
+       * something that is not a pipe. */
+      if (err == ERROR_INVALID_PARAMETER) {
+        SetLastError(WSAENOTSOCK);
+      }
+      return -1;
+    }
+  }
+
+  /* Check if the pipe was created with FILE_FLAG_OVERLAPPED. */
+  nt_status = pNtQueryInformationFile(pipeHandle,
+                                      &io_status,
+                                      &mode_info,
+                                      sizeof(mode_info),
+                                      FileModeInformation);
+  if (nt_status != STATUS_SUCCESS) {
+    return -1;
+  }
+
+  if (mode_info.Mode & FILE_SYNCHRONOUS_IO_ALERT ||
+      mode_info.Mode & FILE_SYNCHRONOUS_IO_NONALERT) {
+    /* Non-overlapped pipe. */
+    handle->flags |= UV_HANDLE_NON_OVERLAPPED_PIPE;
+  } else {
+    /* Overlapped pipe.  Try to associate with IOCP. */
+    if (CreateIoCompletionPort(pipeHandle,
+                               loop->iocp,
+                               (ULONG_PTR)handle,
+                               0) == NULL) {
+      handle->flags |= UV_HANDLE_EMULATE_IOCP;
+    }
+  }
+
+  handle->handle = pipeHandle;
+  handle->u.fd = fd;
+  handle->flags |= duplex_flags;
+
+  return 0;
+}
+
+
+static DWORD WINAPI pipe_shutdown_thread_proc(void* parameter) {
+  uv_loop_t* loop;
+  uv_pipe_t* handle;
+  uv_shutdown_t* req;
+
+  req = (uv_shutdown_t*) parameter;
+  assert(req);
+  handle = (uv_pipe_t*) req->handle;
+  assert(handle);
+  loop = handle->loop;
+  assert(loop);
+
+  FlushFileBuffers(handle->handle);
+
+  /* Post completed */
+  POST_COMPLETION_FOR_REQ(loop, req);
+
+  return 0;
+}
+
+
+void uv_pipe_endgame(uv_loop_t* loop, uv_pipe_t* handle) {
+  int err;
+  DWORD result;
+  uv_shutdown_t* req;
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_PIPE_LOCAL_INFORMATION pipe_info;
+  uv__ipc_xfer_queue_item_t* xfer_queue_item;
+
+  if ((handle->flags & UV_HANDLE_CONNECTION) &&
+      handle->stream.conn.shutdown_req != NULL &&
+      handle->stream.conn.write_reqs_pending == 0) {
+    req = handle->stream.conn.shutdown_req;
+
+    /* Clear the shutdown_req field so we don't go here again. */
+    handle->stream.conn.shutdown_req = NULL;
+
+    if (handle->flags & UV__HANDLE_CLOSING) {
+      UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+      /* Already closing. Cancel the shutdown. */
+      if (req->cb) {
+        req->cb(req, UV_ECANCELED);
+      }
+
+      DECREASE_PENDING_REQ_COUNT(handle);
+      return;
+    }
+
+    /* Try to avoid flushing the pipe buffer in the thread pool. */
+    nt_status = pNtQueryInformationFile(handle->handle,
+                                        &io_status,
+                                        &pipe_info,
+                                        sizeof pipe_info,
+                                        FilePipeLocalInformation);
+
+    if (nt_status != STATUS_SUCCESS) {
+      /* Failure */
+      UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+      handle->flags |= UV_HANDLE_WRITABLE; /* Questionable */
+      if (req->cb) {
+        err = pRtlNtStatusToDosError(nt_status);
+        req->cb(req, uv_translate_sys_error(err));
+      }
+
+      DECREASE_PENDING_REQ_COUNT(handle);
+      return;
+    }
+
+    if (pipe_info.OutboundQuota == pipe_info.WriteQuotaAvailable) {
+      /* Short-circuit, no need to call FlushFileBuffers. */
+      uv_insert_pending_req(loop, (uv_req_t*) req);
+      return;
+    }
+
+    /* Run FlushFileBuffers in the thread pool. */
+    result = QueueUserWorkItem(pipe_shutdown_thread_proc,
+                               req,
+                               WT_EXECUTELONGFUNCTION);
+    if (result) {
+      return;
+
+    } else {
+      /* Failure. */
+      UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+      handle->flags |= UV_HANDLE_WRITABLE; /* Questionable */
+      if (req->cb) {
+        err = GetLastError();
+        req->cb(req, uv_translate_sys_error(err));
+      }
+
+      DECREASE_PENDING_REQ_COUNT(handle);
+      return;
+    }
+  }
+
+  if (handle->flags & UV__HANDLE_CLOSING &&
+      handle->reqs_pending == 0) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+    if (handle->flags & UV_HANDLE_CONNECTION) {
+      /* Free pending sockets */
+      while (!QUEUE_EMPTY(&handle->pipe.conn.ipc_xfer_queue)) {
+        QUEUE* q;
+        SOCKET socket;
+
+        q = QUEUE_HEAD(&handle->pipe.conn.ipc_xfer_queue);
+        QUEUE_REMOVE(q);
+        xfer_queue_item = QUEUE_DATA(q, uv__ipc_xfer_queue_item_t, member);
+
+        /* Materialize socket and close it */
+        socket = WSASocketW(FROM_PROTOCOL_INFO,
+                            FROM_PROTOCOL_INFO,
+                            FROM_PROTOCOL_INFO,
+                            &xfer_queue_item->xfer_info.socket_info,
+                            0,
+                            WSA_FLAG_OVERLAPPED);
+        uv__free(xfer_queue_item);
+
+        if (socket != INVALID_SOCKET)
+          closesocket(socket);
+      }
+      handle->pipe.conn.ipc_xfer_queue_length = 0;
+
+      if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+        if (handle->read_req.wait_handle != INVALID_HANDLE_VALUE) {
+          UnregisterWait(handle->read_req.wait_handle);
+          handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
+        }
+        if (handle->read_req.event_handle) {
+          CloseHandle(handle->read_req.event_handle);
+          handle->read_req.event_handle = NULL;
+        }
+      }
+
+      if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE)
+        DeleteCriticalSection(&handle->pipe.conn.readfile_thread_lock);
+    }
+
+    if (handle->flags & UV_HANDLE_PIPESERVER) {
+      assert(handle->pipe.serv.accept_reqs);
+      uv__free(handle->pipe.serv.accept_reqs);
+      handle->pipe.serv.accept_reqs = NULL;
+    }
+
+    uv__handle_close(handle);
+  }
+}
+
+
+void uv_pipe_pending_instances(uv_pipe_t* handle, int count) {
+  if (handle->flags & UV_HANDLE_BOUND)
+    return;
+  handle->pipe.serv.pending_instances = count;
+  handle->flags |= UV_HANDLE_PIPESERVER;
+}
+
+
+/* Creates a pipe server. */
+int uv_pipe_bind(uv_pipe_t* handle, const char* name) {
+  uv_loop_t* loop = handle->loop;
+  int i, err, nameSize;
+  uv_pipe_accept_t* req;
+
+  if (handle->flags & UV_HANDLE_BOUND) {
+    return UV_EINVAL;
+  }
+
+  if (!name) {
+    return UV_EINVAL;
+  }
+
+  if (!(handle->flags & UV_HANDLE_PIPESERVER)) {
+    handle->pipe.serv.pending_instances = default_pending_pipe_instances;
+  }
+
+  handle->pipe.serv.accept_reqs = (uv_pipe_accept_t*)
+    uv__malloc(sizeof(uv_pipe_accept_t) * handle->pipe.serv.pending_instances);
+  if (!handle->pipe.serv.accept_reqs) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
+    req = &handle->pipe.serv.accept_reqs[i];
+    UV_REQ_INIT(req, UV_ACCEPT);
+    req->data = handle;
+    req->pipeHandle = INVALID_HANDLE_VALUE;
+    req->next_pending = NULL;
+  }
+
+  /* Convert name to UTF16. */
+  nameSize = MultiByteToWideChar(CP_UTF8, 0, name, -1, NULL, 0) * sizeof(WCHAR);
+  handle->name = (WCHAR*)uv__malloc(nameSize);
+  if (!handle->name) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  if (!MultiByteToWideChar(CP_UTF8,
+                           0,
+                           name,
+                           -1,
+                           handle->name,
+                           nameSize / sizeof(WCHAR))) {
+    err = GetLastError();
+    goto error;
+  }
+
+  /*
+   * Attempt to create the first pipe with FILE_FLAG_FIRST_PIPE_INSTANCE.
+   * If this fails then there's already a pipe server for the given pipe name.
+   */
+  handle->pipe.serv.accept_reqs[0].pipeHandle = CreateNamedPipeW(handle->name,
+      PIPE_ACCESS_DUPLEX | FILE_FLAG_OVERLAPPED |
+      FILE_FLAG_FIRST_PIPE_INSTANCE | WRITE_DAC,
+      PIPE_TYPE_BYTE | PIPE_READMODE_BYTE | PIPE_WAIT,
+      PIPE_UNLIMITED_INSTANCES, 65536, 65536, 0, NULL);
+
+  if (handle->pipe.serv.accept_reqs[0].pipeHandle == INVALID_HANDLE_VALUE) {
+    err = GetLastError();
+    if (err == ERROR_ACCESS_DENIED) {
+      err = WSAEADDRINUSE;  /* Translates to UV_EADDRINUSE. */
+    } else if (err == ERROR_PATH_NOT_FOUND || err == ERROR_INVALID_NAME) {
+      err = WSAEACCES;  /* Translates to UV_EACCES. */
+    }
+    goto error;
+  }
+
+  if (uv_set_pipe_handle(loop,
+                         handle,
+                         handle->pipe.serv.accept_reqs[0].pipeHandle,
+                         -1,
+                         0)) {
+    err = GetLastError();
+    goto error;
+  }
+
+  handle->pipe.serv.pending_accepts = NULL;
+  handle->flags |= UV_HANDLE_PIPESERVER;
+  handle->flags |= UV_HANDLE_BOUND;
+
+  return 0;
+
+error:
+  if (handle->name) {
+    uv__free(handle->name);
+    handle->name = NULL;
+  }
+
+  if (handle->pipe.serv.accept_reqs[0].pipeHandle != INVALID_HANDLE_VALUE) {
+    CloseHandle(handle->pipe.serv.accept_reqs[0].pipeHandle);
+    handle->pipe.serv.accept_reqs[0].pipeHandle = INVALID_HANDLE_VALUE;
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+static DWORD WINAPI pipe_connect_thread_proc(void* parameter) {
+  uv_loop_t* loop;
+  uv_pipe_t* handle;
+  uv_connect_t* req;
+  HANDLE pipeHandle = INVALID_HANDLE_VALUE;
+  DWORD duplex_flags;
+
+  req = (uv_connect_t*) parameter;
+  assert(req);
+  handle = (uv_pipe_t*) req->handle;
+  assert(handle);
+  loop = handle->loop;
+  assert(loop);
+
+  /* We're here because CreateFile on a pipe returned ERROR_PIPE_BUSY. We wait
+   * for the pipe to become available with WaitNamedPipe. */
+  while (WaitNamedPipeW(handle->name, 30000)) {
+    /* The pipe is now available, try to connect. */
+    pipeHandle = open_named_pipe(handle->name, &duplex_flags);
+    if (pipeHandle != INVALID_HANDLE_VALUE) {
+      break;
+    }
+
+    SwitchToThread();
+  }
+
+  if (pipeHandle != INVALID_HANDLE_VALUE &&
+      !uv_set_pipe_handle(loop, handle, pipeHandle, -1, duplex_flags)) {
+    SET_REQ_SUCCESS(req);
+  } else {
+    SET_REQ_ERROR(req, GetLastError());
+  }
+
+  /* Post completed */
+  POST_COMPLETION_FOR_REQ(loop, req);
+
+  return 0;
+}
+
+
+void uv_pipe_connect(uv_connect_t* req, uv_pipe_t* handle,
+    const char* name, uv_connect_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  int err, nameSize;
+  HANDLE pipeHandle = INVALID_HANDLE_VALUE;
+  DWORD duplex_flags;
+
+  UV_REQ_INIT(req, UV_CONNECT);
+  req->handle = (uv_stream_t*) handle;
+  req->cb = cb;
+
+  /* Convert name to UTF16. */
+  nameSize = MultiByteToWideChar(CP_UTF8, 0, name, -1, NULL, 0) * sizeof(WCHAR);
+  handle->name = (WCHAR*)uv__malloc(nameSize);
+  if (!handle->name) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  if (!MultiByteToWideChar(CP_UTF8,
+                           0,
+                           name,
+                           -1,
+                           handle->name,
+                           nameSize / sizeof(WCHAR))) {
+    err = GetLastError();
+    goto error;
+  }
+
+  pipeHandle = open_named_pipe(handle->name, &duplex_flags);
+  if (pipeHandle == INVALID_HANDLE_VALUE) {
+    if (GetLastError() == ERROR_PIPE_BUSY) {
+      /* Wait for the server to make a pipe instance available. */
+      if (!QueueUserWorkItem(&pipe_connect_thread_proc,
+                             req,
+                             WT_EXECUTELONGFUNCTION)) {
+        err = GetLastError();
+        goto error;
+      }
+
+      REGISTER_HANDLE_REQ(loop, handle, req);
+      handle->reqs_pending++;
+
+      return;
+    }
+
+    err = GetLastError();
+    goto error;
+  }
+
+  assert(pipeHandle != INVALID_HANDLE_VALUE);
+
+  if (uv_set_pipe_handle(loop,
+                         (uv_pipe_t*) req->handle,
+                         pipeHandle,
+                         -1,
+                         duplex_flags)) {
+    err = GetLastError();
+    goto error;
+  }
+
+  SET_REQ_SUCCESS(req);
+  uv_insert_pending_req(loop, (uv_req_t*) req);
+  handle->reqs_pending++;
+  REGISTER_HANDLE_REQ(loop, handle, req);
+  return;
+
+error:
+  if (handle->name) {
+    uv__free(handle->name);
+    handle->name = NULL;
+  }
+
+  if (pipeHandle != INVALID_HANDLE_VALUE) {
+    CloseHandle(pipeHandle);
+  }
+
+  /* Make this req pending reporting an error. */
+  SET_REQ_ERROR(req, err);
+  uv_insert_pending_req(loop, (uv_req_t*) req);
+  handle->reqs_pending++;
+  REGISTER_HANDLE_REQ(loop, handle, req);
+  return;
+}
+
+
+void uv__pipe_interrupt_read(uv_pipe_t* handle) {
+  BOOL r;
+
+  if (!(handle->flags & UV_HANDLE_READ_PENDING))
+    return; /* No pending reads. */
+  if (handle->flags & UV_HANDLE_CANCELLATION_PENDING)
+    return; /* Already cancelled. */
+  if (handle->handle == INVALID_HANDLE_VALUE)
+    return; /* Pipe handle closed. */
+
+  if (!(handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE)) {
+    /* Cancel asynchronous read. */
+    r = CancelIoEx(handle->handle, &handle->read_req.u.io.overlapped);
+    assert(r || GetLastError() == ERROR_NOT_FOUND);
+
+  } else {
+    /* Cancel synchronous read (which is happening in the thread pool). */
+    HANDLE thread;
+    volatile HANDLE* thread_ptr = &handle->pipe.conn.readfile_thread_handle;
+
+    EnterCriticalSection(&handle->pipe.conn.readfile_thread_lock);
+
+    thread = *thread_ptr;
+    if (thread == NULL) {
+      /* The thread pool thread has not yet reached the point of blocking, we
+       * can pre-empt it by setting thread_handle to INVALID_HANDLE_VALUE. */
+      *thread_ptr = INVALID_HANDLE_VALUE;
+
+    } else {
+      /* Spin until the thread has acknowledged (by setting the thread to
+       * INVALID_HANDLE_VALUE) that it is past the point of blocking. */
+      while (thread != INVALID_HANDLE_VALUE) {
+        r = CancelSynchronousIo(thread);
+        assert(r || GetLastError() == ERROR_NOT_FOUND);
+        SwitchToThread(); /* Yield thread. */
+        thread = *thread_ptr;
+      }
+    }
+
+    LeaveCriticalSection(&handle->pipe.conn.readfile_thread_lock);
+  }
+
+  /* Set flag to indicate that read has been cancelled. */
+  handle->flags |= UV_HANDLE_CANCELLATION_PENDING;
+}
+
+
+void uv__pipe_read_stop(uv_pipe_t* handle) {
+  handle->flags &= ~UV_HANDLE_READING;
+  DECREASE_ACTIVE_COUNT(handle->loop, handle);
+
+  uv__pipe_interrupt_read(handle);
+}
+
+
+/* Cleans up uv_pipe_t (server or connection) and all resources associated with
+ * it. */
+void uv_pipe_cleanup(uv_loop_t* loop, uv_pipe_t* handle) {
+  int i;
+  HANDLE pipeHandle;
+
+  uv__pipe_interrupt_read(handle);
+
+  if (handle->name) {
+    uv__free(handle->name);
+    handle->name = NULL;
+  }
+
+  if (handle->flags & UV_HANDLE_PIPESERVER) {
+    for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
+      pipeHandle = handle->pipe.serv.accept_reqs[i].pipeHandle;
+      if (pipeHandle != INVALID_HANDLE_VALUE) {
+        CloseHandle(pipeHandle);
+        handle->pipe.serv.accept_reqs[i].pipeHandle = INVALID_HANDLE_VALUE;
+      }
+    }
+    handle->handle = INVALID_HANDLE_VALUE;
+  }
+
+  if (handle->flags & UV_HANDLE_CONNECTION) {
+    handle->flags &= ~UV_HANDLE_WRITABLE;
+    eof_timer_destroy(handle);
+  }
+
+  if ((handle->flags & UV_HANDLE_CONNECTION)
+      && handle->handle != INVALID_HANDLE_VALUE)
+    close_pipe(handle);
+}
+
+
+void uv_pipe_close(uv_loop_t* loop, uv_pipe_t* handle) {
+  if (handle->flags & UV_HANDLE_READING) {
+    handle->flags &= ~UV_HANDLE_READING;
+    DECREASE_ACTIVE_COUNT(loop, handle);
+  }
+
+  if (handle->flags & UV_HANDLE_LISTENING) {
+    handle->flags &= ~UV_HANDLE_LISTENING;
+    DECREASE_ACTIVE_COUNT(loop, handle);
+  }
+
+  uv_pipe_cleanup(loop, handle);
+
+  if (handle->reqs_pending == 0) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+  }
+
+  handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+  uv__handle_closing(handle);
+}
+
+
+static void uv_pipe_queue_accept(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_pipe_accept_t* req, BOOL firstInstance) {
+  assert(handle->flags & UV_HANDLE_LISTENING);
+
+  if (!firstInstance) {
+    assert(req->pipeHandle == INVALID_HANDLE_VALUE);
+
+    req->pipeHandle = CreateNamedPipeW(handle->name,
+        PIPE_ACCESS_DUPLEX | FILE_FLAG_OVERLAPPED | WRITE_DAC,
+        PIPE_TYPE_BYTE | PIPE_READMODE_BYTE | PIPE_WAIT,
+        PIPE_UNLIMITED_INSTANCES, 65536, 65536, 0, NULL);
+
+    if (req->pipeHandle == INVALID_HANDLE_VALUE) {
+      SET_REQ_ERROR(req, GetLastError());
+      uv_insert_pending_req(loop, (uv_req_t*) req);
+      handle->reqs_pending++;
+      return;
+    }
+
+    if (uv_set_pipe_handle(loop, handle, req->pipeHandle, -1, 0)) {
+      CloseHandle(req->pipeHandle);
+      req->pipeHandle = INVALID_HANDLE_VALUE;
+      SET_REQ_ERROR(req, GetLastError());
+      uv_insert_pending_req(loop, (uv_req_t*) req);
+      handle->reqs_pending++;
+      return;
+    }
+  }
+
+  assert(req->pipeHandle != INVALID_HANDLE_VALUE);
+
+  /* Prepare the overlapped structure. */
+  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
+
+  if (!ConnectNamedPipe(req->pipeHandle, &req->u.io.overlapped) &&
+      GetLastError() != ERROR_IO_PENDING) {
+    if (GetLastError() == ERROR_PIPE_CONNECTED) {
+      SET_REQ_SUCCESS(req);
+    } else {
+      CloseHandle(req->pipeHandle);
+      req->pipeHandle = INVALID_HANDLE_VALUE;
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, GetLastError());
+    }
+    uv_insert_pending_req(loop, (uv_req_t*) req);
+    handle->reqs_pending++;
+    return;
+  }
+
+  /* Wait for completion via IOCP */
+  handle->reqs_pending++;
+}
+
+
+int uv_pipe_accept(uv_pipe_t* server, uv_stream_t* client) {
+  uv_loop_t* loop = server->loop;
+  uv_pipe_t* pipe_client;
+  uv_pipe_accept_t* req;
+  QUEUE* q;
+  uv__ipc_xfer_queue_item_t* item;
+  int err;
+
+  if (server->ipc) {
+    if (QUEUE_EMPTY(&server->pipe.conn.ipc_xfer_queue)) {
+      /* No valid pending sockets. */
+      return WSAEWOULDBLOCK;
+    }
+
+    q = QUEUE_HEAD(&server->pipe.conn.ipc_xfer_queue);
+    QUEUE_REMOVE(q);
+    server->pipe.conn.ipc_xfer_queue_length--;
+    item = QUEUE_DATA(q, uv__ipc_xfer_queue_item_t, member);
+
+    err = uv__tcp_xfer_import((uv_tcp_t*) client, &item->xfer_info);
+    if (err != 0)
+      return err;
+
+    uv__free(item);
+
+  } else {
+    pipe_client = (uv_pipe_t*)client;
+
+    /* Find a connection instance that has been connected, but not yet
+     * accepted. */
+    req = server->pipe.serv.pending_accepts;
+
+    if (!req) {
+      /* No valid connections found, so we error out. */
+      return WSAEWOULDBLOCK;
+    }
+
+    /* Initialize the client handle and copy the pipeHandle to the client */
+    uv_pipe_connection_init(pipe_client);
+    pipe_client->handle = req->pipeHandle;
+    pipe_client->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+
+    /* Prepare the req to pick up a new connection */
+    server->pipe.serv.pending_accepts = req->next_pending;
+    req->next_pending = NULL;
+    req->pipeHandle = INVALID_HANDLE_VALUE;
+
+    if (!(server->flags & UV__HANDLE_CLOSING)) {
+      uv_pipe_queue_accept(loop, server, req, FALSE);
+    }
+  }
+
+  return 0;
+}
+
+
+/* Starts listening for connections for the given pipe. */
+int uv_pipe_listen(uv_pipe_t* handle, int backlog, uv_connection_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  int i;
+
+  if (handle->flags & UV_HANDLE_LISTENING) {
+    handle->stream.serv.connection_cb = cb;
+  }
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    return WSAEINVAL;
+  }
+
+  if (handle->flags & UV_HANDLE_READING) {
+    return WSAEISCONN;
+  }
+
+  if (!(handle->flags & UV_HANDLE_PIPESERVER)) {
+    return ERROR_NOT_SUPPORTED;
+  }
+
+  handle->flags |= UV_HANDLE_LISTENING;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+  handle->stream.serv.connection_cb = cb;
+
+  /* First pipe handle should have already been created in uv_pipe_bind */
+  assert(handle->pipe.serv.accept_reqs[0].pipeHandle != INVALID_HANDLE_VALUE);
+
+  for (i = 0; i < handle->pipe.serv.pending_instances; i++) {
+    uv_pipe_queue_accept(loop, handle, &handle->pipe.serv.accept_reqs[i], i == 0);
+  }
+
+  return 0;
+}
+
+
+static DWORD WINAPI uv_pipe_zero_readfile_thread_proc(void* arg) {
+  uv_read_t* req = (uv_read_t*) arg;
+  uv_pipe_t* handle = (uv_pipe_t*) req->data;
+  uv_loop_t* loop = handle->loop;
+  volatile HANDLE* thread_ptr = &handle->pipe.conn.readfile_thread_handle;
+  CRITICAL_SECTION* lock = &handle->pipe.conn.readfile_thread_lock;
+  HANDLE thread;
+  DWORD bytes;
+  DWORD err;
+
+  assert(req->type == UV_READ);
+  assert(handle->type == UV_NAMED_PIPE);
+
+  err = 0;
+
+  /* Create a handle to the current thread. */
+  if (!DuplicateHandle(GetCurrentProcess(),
+                       GetCurrentThread(),
+                       GetCurrentProcess(),
+                       &thread,
+                       0,
+                       FALSE,
+                       DUPLICATE_SAME_ACCESS)) {
+    err = GetLastError();
+    goto out1;
+  }
+
+  /* The lock needs to be held when thread handle is modified. */
+  EnterCriticalSection(lock);
+  if (*thread_ptr == INVALID_HANDLE_VALUE) {
+    /* uv__pipe_interrupt_read() cancelled reading before we got here. */
+    err = ERROR_OPERATION_ABORTED;
+  } else {
+    /* Let main thread know which worker thread is doing the blocking read. */
+    assert(*thread_ptr == NULL);
+    *thread_ptr = thread;
+  }
+  LeaveCriticalSection(lock);
+
+  if (err)
+    goto out2;
+
+  /* Block the thread until data is available on the pipe, or the read is
+   * cancelled. */
+  if (!ReadFile(handle->handle, &uv_zero_, 0, &bytes, NULL))
+    err = GetLastError();
+
+  /* Let the main thread know the worker is past the point of blocking. */
+  assert(thread == *thread_ptr);
+  *thread_ptr = INVALID_HANDLE_VALUE;
+
+  /* Briefly acquire the mutex. Since the main thread holds the lock while it
+   * is spinning trying to cancel this thread's I/O, we will block here until
+   * it stops doing that. */
+  EnterCriticalSection(lock);
+  LeaveCriticalSection(lock);
+
+out2:
+  /* Close the handle to the current thread. */
+  CloseHandle(thread);
+
+out1:
+  /* Set request status and post a completion record to the IOCP. */
+  if (err)
+    SET_REQ_ERROR(req, err);
+  else
+    SET_REQ_SUCCESS(req);
+  POST_COMPLETION_FOR_REQ(loop, req);
+
+  return 0;
+}
+
+
+static DWORD WINAPI uv_pipe_writefile_thread_proc(void* parameter) {
+  int result;
+  DWORD bytes;
+  uv_write_t* req = (uv_write_t*) parameter;
+  uv_pipe_t* handle = (uv_pipe_t*) req->handle;
+  uv_loop_t* loop = handle->loop;
+
+  assert(req != NULL);
+  assert(req->type == UV_WRITE);
+  assert(handle->type == UV_NAMED_PIPE);
+  assert(req->write_buffer.base);
+
+  result = WriteFile(handle->handle,
+                     req->write_buffer.base,
+                     req->write_buffer.len,
+                     &bytes,
+                     NULL);
+
+  if (!result) {
+    SET_REQ_ERROR(req, GetLastError());
+  }
+
+  POST_COMPLETION_FOR_REQ(loop, req);
+  return 0;
+}
+
+
+static void CALLBACK post_completion_read_wait(void* context, BOOLEAN timed_out) {
+  uv_read_t* req;
+  uv_tcp_t* handle;
+
+  req = (uv_read_t*) context;
+  assert(req != NULL);
+  handle = (uv_tcp_t*)req->data;
+  assert(handle != NULL);
+  assert(!timed_out);
+
+  if (!PostQueuedCompletionStatus(handle->loop->iocp,
+                                  req->u.io.overlapped.InternalHigh,
+                                  0,
+                                  &req->u.io.overlapped)) {
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
+  }
+}
+
+
+static void CALLBACK post_completion_write_wait(void* context, BOOLEAN timed_out) {
+  uv_write_t* req;
+  uv_tcp_t* handle;
+
+  req = (uv_write_t*) context;
+  assert(req != NULL);
+  handle = (uv_tcp_t*)req->handle;
+  assert(handle != NULL);
+  assert(!timed_out);
+
+  if (!PostQueuedCompletionStatus(handle->loop->iocp,
+                                  req->u.io.overlapped.InternalHigh,
+                                  0,
+                                  &req->u.io.overlapped)) {
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
+  }
+}
+
+
+static void uv_pipe_queue_read(uv_loop_t* loop, uv_pipe_t* handle) {
+  uv_read_t* req;
+  int result;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+
+  assert(handle->handle != INVALID_HANDLE_VALUE);
+
+  req = &handle->read_req;
+
+  if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
+    handle->pipe.conn.readfile_thread_handle = NULL; /* Reset cancellation. */
+    if (!QueueUserWorkItem(&uv_pipe_zero_readfile_thread_proc,
+                           req,
+                           WT_EXECUTELONGFUNCTION)) {
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, GetLastError());
+      goto error;
+    }
+  } else {
+    memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      req->u.io.overlapped.hEvent = (HANDLE) ((uintptr_t) req->event_handle | 1);
+    }
+
+    /* Do 0-read */
+    result = ReadFile(handle->handle,
+                      &uv_zero_,
+                      0,
+                      NULL,
+                      &req->u.io.overlapped);
+
+    if (!result && GetLastError() != ERROR_IO_PENDING) {
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, GetLastError());
+      goto error;
+    }
+
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      if (!req->event_handle) {
+        req->event_handle = CreateEvent(NULL, 0, 0, NULL);
+        if (!req->event_handle) {
+          uv_fatal_error(GetLastError(), "CreateEvent");
+        }
+      }
+      if (req->wait_handle == INVALID_HANDLE_VALUE) {
+        if (!RegisterWaitForSingleObject(&req->wait_handle,
+            req->u.io.overlapped.hEvent, post_completion_read_wait, (void*) req,
+            INFINITE, WT_EXECUTEINWAITTHREAD)) {
+          SET_REQ_ERROR(req, GetLastError());
+          goto error;
+        }
+      }
+    }
+  }
+
+  /* Start the eof timer if there is one */
+  eof_timer_start(handle);
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+  return;
+
+error:
+  uv_insert_pending_req(loop, (uv_req_t*)req);
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+}
+
+
+int uv_pipe_read_start(uv_pipe_t* handle,
+                       uv_alloc_cb alloc_cb,
+                       uv_read_cb read_cb) {
+  uv_loop_t* loop = handle->loop;
+
+  handle->flags |= UV_HANDLE_READING;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+  handle->read_cb = read_cb;
+  handle->alloc_cb = alloc_cb;
+
+  /* If reading was stopped and then started again, there could still be a read
+   * request pending. */
+  if (!(handle->flags & UV_HANDLE_READ_PENDING))
+    uv_pipe_queue_read(loop, handle);
+
+  return 0;
+}
+
+
+static void uv_insert_non_overlapped_write_req(uv_pipe_t* handle,
+    uv_write_t* req) {
+  req->next_req = NULL;
+  if (handle->pipe.conn.non_overlapped_writes_tail) {
+    req->next_req =
+      handle->pipe.conn.non_overlapped_writes_tail->next_req;
+    handle->pipe.conn.non_overlapped_writes_tail->next_req = (uv_req_t*)req;
+    handle->pipe.conn.non_overlapped_writes_tail = req;
+  } else {
+    req->next_req = (uv_req_t*)req;
+    handle->pipe.conn.non_overlapped_writes_tail = req;
+  }
+}
+
+
+static uv_write_t* uv_remove_non_overlapped_write_req(uv_pipe_t* handle) {
+  uv_write_t* req;
+
+  if (handle->pipe.conn.non_overlapped_writes_tail) {
+    req = (uv_write_t*)handle->pipe.conn.non_overlapped_writes_tail->next_req;
+
+    if (req == handle->pipe.conn.non_overlapped_writes_tail) {
+      handle->pipe.conn.non_overlapped_writes_tail = NULL;
+    } else {
+      handle->pipe.conn.non_overlapped_writes_tail->next_req =
+        req->next_req;
+    }
+
+    return req;
+  } else {
+    /* queue empty */
+    return NULL;
+  }
+}
+
+
+static void uv_queue_non_overlapped_write(uv_pipe_t* handle) {
+  uv_write_t* req = uv_remove_non_overlapped_write_req(handle);
+  if (req) {
+    if (!QueueUserWorkItem(&uv_pipe_writefile_thread_proc,
+                           req,
+                           WT_EXECUTELONGFUNCTION)) {
+      uv_fatal_error(GetLastError(), "QueueUserWorkItem");
+    }
+  }
+}
+
+
+static int uv__build_coalesced_write_req(uv_write_t* user_req,
+                                         const uv_buf_t bufs[],
+                                         size_t nbufs,
+                                         uv_write_t** req_out,
+                                         uv_buf_t* write_buf_out) {
+  /* Pack into a single heap-allocated buffer:
+   *   (a) a uv_write_t structure where libuv stores the actual state.
+   *   (b) a pointer to the original uv_write_t.
+   *   (c) data from all `bufs` entries.
+   */
+  char* heap_buffer;
+  size_t heap_buffer_length, heap_buffer_offset;
+  uv__coalesced_write_t* coalesced_write_req; /* (a) + (b) */
+  char* data_start;                           /* (c) */
+  size_t data_length;
+  unsigned int i;
+
+  /* Compute combined size of all combined buffers from `bufs`. */
+  data_length = 0;
+  for (i = 0; i < nbufs; i++)
+    data_length += bufs[i].len;
+
+  /* The total combined size of data buffers should not exceed UINT32_MAX,
+   * because WriteFile() won't accept buffers larger than that. */
+  if (data_length > UINT32_MAX)
+    return WSAENOBUFS; /* Maps to UV_ENOBUFS. */
+
+  /* Compute heap buffer size. */
+  heap_buffer_length = sizeof *coalesced_write_req + /* (a) + (b) */
+                       data_length;                  /* (c) */
+
+  /* Allocate buffer. */
+  heap_buffer = (char*)uv__malloc(heap_buffer_length);
+  if (heap_buffer == NULL)
+    return ERROR_NOT_ENOUGH_MEMORY; /* Maps to UV_ENOMEM. */
+
+  /* Copy uv_write_t information to the buffer. */
+  coalesced_write_req = (uv__coalesced_write_t*) heap_buffer;
+  coalesced_write_req->req = *user_req; /* copy (a) */
+  coalesced_write_req->req.coalesced = 1;
+  coalesced_write_req->user_req = user_req;         /* copy (b) */
+  heap_buffer_offset = sizeof *coalesced_write_req; /* offset (a) + (b) */
+
+  /* Copy data buffers to the heap buffer. */
+  data_start = &heap_buffer[heap_buffer_offset];
+  for (i = 0; i < nbufs; i++) {
+    memcpy(&heap_buffer[heap_buffer_offset],
+           bufs[i].base,
+           bufs[i].len);               /* copy (c) */
+    heap_buffer_offset += bufs[i].len; /* offset (c) */
+  }
+  assert(heap_buffer_offset == heap_buffer_length);
+
+  /* Set out arguments and return. */
+  *req_out = &coalesced_write_req->req;
+  *write_buf_out = uv_buf_init(data_start, (unsigned int) data_length);
+  return 0;
+}
+
+
+static int uv__pipe_write_data(uv_loop_t* loop,
+                               uv_write_t* req,
+                               uv_pipe_t* handle,
+                               const uv_buf_t bufs[],
+                               size_t nbufs,
+                               uv_stream_t* send_handle,
+                               uv_write_cb cb,
+                               bool copy_always) {
+  int err;
+  int result;
+  uv_buf_t write_buf;
+
+  assert(handle->handle != INVALID_HANDLE_VALUE);
+
+  UV_REQ_INIT(req, UV_WRITE);
+  req->handle = (uv_stream_t*) handle;
+  req->send_handle = send_handle;
+  req->cb = cb;
+  /* Private fields. */
+  req->coalesced = 0;
+  req->event_handle = NULL;
+  req->wait_handle = INVALID_HANDLE_VALUE;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+  req->write_buffer = uv_null_buf_;
+
+  if (nbufs == 0) {
+    /* Write empty buffer. */
+    write_buf = uv_null_buf_;
+  } else if (nbufs == 1 && !copy_always) {
+    /* Write directly from bufs[0]. */
+    write_buf = bufs[0];
+  } else {
+    /* Coalesce all `bufs` into one big buffer. This also creates a new
+     * write-request structure that replaces the old one. */
+    err = uv__build_coalesced_write_req(req, bufs, nbufs, &req, &write_buf);
+    if (err != 0)
+      return err;
+  }
+
+  if ((handle->flags &
+      (UV_HANDLE_BLOCKING_WRITES | UV_HANDLE_NON_OVERLAPPED_PIPE)) ==
+      (UV_HANDLE_BLOCKING_WRITES | UV_HANDLE_NON_OVERLAPPED_PIPE)) {
+    DWORD bytes;
+    result =
+        WriteFile(handle->handle, write_buf.base, write_buf.len, &bytes, NULL);
+
+    if (!result) {
+      err = GetLastError();
+      return err;
+    } else {
+      /* Request completed immediately. */
+      req->u.io.queued_bytes = 0;
+    }
+
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    POST_COMPLETION_FOR_REQ(loop, req);
+    return 0;
+  } else if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
+    req->write_buffer = write_buf;
+    uv_insert_non_overlapped_write_req(handle, req);
+    if (handle->stream.conn.write_reqs_pending == 0) {
+      uv_queue_non_overlapped_write(handle);
+    }
+
+    /* Request queued by the kernel. */
+    req->u.io.queued_bytes = write_buf.len;
+    handle->write_queue_size += req->u.io.queued_bytes;
+  } else if (handle->flags & UV_HANDLE_BLOCKING_WRITES) {
+    /* Using overlapped IO, but wait for completion before returning */
+    req->u.io.overlapped.hEvent = CreateEvent(NULL, 1, 0, NULL);
+    if (!req->u.io.overlapped.hEvent) {
+      uv_fatal_error(GetLastError(), "CreateEvent");
+    }
+
+    result = WriteFile(handle->handle,
+                       write_buf.base,
+                       write_buf.len,
+                       NULL,
+                       &req->u.io.overlapped);
+
+    if (!result && GetLastError() != ERROR_IO_PENDING) {
+      err = GetLastError();
+      CloseHandle(req->u.io.overlapped.hEvent);
+      return err;
+    }
+
+    if (result) {
+      /* Request completed immediately. */
+      req->u.io.queued_bytes = 0;
+    } else {
+      /* Request queued by the kernel. */
+      req->u.io.queued_bytes = write_buf.len;
+      handle->write_queue_size += req->u.io.queued_bytes;
+      if (WaitForSingleObject(req->u.io.overlapped.hEvent, INFINITE) !=
+          WAIT_OBJECT_0) {
+        err = GetLastError();
+        CloseHandle(req->u.io.overlapped.hEvent);
+        return err;
+      }
+    }
+    CloseHandle(req->u.io.overlapped.hEvent);
+
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    return 0;
+  } else {
+    result = WriteFile(handle->handle,
+                       write_buf.base,
+                       write_buf.len,
+                       NULL,
+                       &req->u.io.overlapped);
+
+    if (!result && GetLastError() != ERROR_IO_PENDING) {
+      return GetLastError();
+    }
+
+    if (result) {
+      /* Request completed immediately. */
+      req->u.io.queued_bytes = 0;
+    } else {
+      /* Request queued by the kernel. */
+      req->u.io.queued_bytes = write_buf.len;
+      handle->write_queue_size += req->u.io.queued_bytes;
+    }
+
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      req->event_handle = CreateEvent(NULL, 0, 0, NULL);
+      if (!req->event_handle) {
+        uv_fatal_error(GetLastError(), "CreateEvent");
+      }
+      if (!RegisterWaitForSingleObject(&req->wait_handle,
+          req->u.io.overlapped.hEvent, post_completion_write_wait, (void*) req,
+          INFINITE, WT_EXECUTEINWAITTHREAD)) {
+        return GetLastError();
+      }
+    }
+  }
+
+  REGISTER_HANDLE_REQ(loop, handle, req);
+  handle->reqs_pending++;
+  handle->stream.conn.write_reqs_pending++;
+
+  return 0;
+}
+
+
+static DWORD uv__pipe_get_ipc_remote_pid(uv_pipe_t* handle) {
+  DWORD* pid = &handle->pipe.conn.ipc_remote_pid;
+
+  /* If the both ends of the IPC pipe are owned by the same process,
+   * the remote end pid may not yet be set. If so, do it here.
+   * TODO: this is weird; it'd probably better to use a handshake. */
+  if (*pid == 0)
+    *pid = GetCurrentProcessId();
+
+  return *pid;
+}
+
+
+int uv__pipe_write_ipc(uv_loop_t* loop,
+                       uv_write_t* req,
+                       uv_pipe_t* handle,
+                       const uv_buf_t data_bufs[],
+                       size_t data_buf_count,
+                       uv_stream_t* send_handle,
+                       uv_write_cb cb) {
+  uv_buf_t stack_bufs[6];
+  uv_buf_t* bufs;
+  size_t buf_count, buf_index;
+  uv__ipc_frame_header_t xfer_frame_header;
+  uv__ipc_socket_xfer_info_t xfer_info;
+  uv__ipc_frame_header_t data_frame_header;
+  size_t data_length;
+  size_t i;
+  int err;
+
+  /* Compute the combined size of data buffers. */
+  data_length = 0;
+  for (i = 0; i < data_buf_count; i++)
+    data_length += data_bufs[i].len;
+  if (data_length > UINT32_MAX)
+    return WSAENOBUFS; /* Maps to UV_ENOBUFS. */
+
+  /* Prepare xfer frame payload. */
+  if (send_handle) {
+    uv_tcp_t* send_tcp_handle = (uv_tcp_t*) send_handle;
+
+    /* Verify that `send_handle` it is indeed a tcp handle. */
+    if (send_tcp_handle->type != UV_TCP)
+      return ERROR_NOT_SUPPORTED;
+
+    /* Export the tcp handle. */
+    err = uv__tcp_xfer_export(
+        send_tcp_handle, uv__pipe_get_ipc_remote_pid(handle), &xfer_info);
+    if (err != 0)
+      return err;
+  }
+
+  /* Compute the number of uv_buf_t's required. */
+  buf_count = 0;
+  if (send_handle != NULL) {
+    buf_count += 2; /* One for the frame header, one for the payload. */
+  }
+  if (data_buf_count > 0) {
+    buf_count += 1 + data_buf_count; /* One extra for the frame header. */
+  }
+
+  /* Use the on-stack buffer array if it is big enough; otherwise allocate
+   * space for it on the heap. */
+  if (buf_count < ARRAY_SIZE(stack_bufs)) {
+    /* Use on-stack buffer array. */
+    bufs = stack_bufs;
+  } else {
+    /* Use heap-allocated buffer array. */
+    bufs = (uv_buf_t*)uv__calloc(buf_count, sizeof(uv_buf_t));
+    if (bufs == NULL)
+      return ERROR_NOT_ENOUGH_MEMORY; /* Maps to UV_ENOMEM. */
+  }
+  buf_index = 0;
+
+  if (send_handle != NULL) {
+    /* Add xfer frame header. */
+    xfer_frame_header.type = UV__IPC_XFER_FRAME;
+    xfer_frame_header.payload_length = sizeof xfer_info;
+    bufs[buf_index++] =
+        uv_buf_init((char*) &xfer_frame_header, sizeof xfer_frame_header);
+
+    /* Add xfer frame payload. */
+    bufs[buf_index++] = uv_buf_init((char*) &xfer_info, sizeof xfer_info);
+  }
+
+  if (data_length > 0) {
+    /* Add data frame header. */
+    data_frame_header.type = UV__IPC_DATA_FRAME;
+    data_frame_header.payload_length = (uint32_t) data_length;
+    bufs[buf_index++] =
+        uv_buf_init((char*) &data_frame_header, sizeof data_frame_header);
+
+    /* Add data buffers. */
+    for (i = 0; i < data_buf_count; i++)
+      bufs[buf_index++] = data_bufs[i];
+  }
+
+  /* Write buffers. We set the `always_copy` flag, so it is not a problem that
+   * some of the written data lives on the stack. */
+  err = uv__pipe_write_data(
+      loop, req, handle, bufs, buf_count, send_handle, cb, true);
+
+  /* If we had to heap-allocate the bufs array, free it now. */
+  if (bufs != stack_bufs) {
+    uv__free(bufs);
+  }
+
+  return err;
+}
+
+
+int uv__pipe_write(uv_loop_t* loop,
+                   uv_write_t* req,
+                   uv_pipe_t* handle,
+                   const uv_buf_t bufs[],
+                   size_t nbufs,
+                   uv_stream_t* send_handle,
+                   uv_write_cb cb) {
+  if (handle->ipc) {
+    /* IPC pipe write: use framing protocol. */
+    return uv__pipe_write_ipc(loop, req, handle, bufs, nbufs, send_handle, cb);
+  } else {
+    /* Non-IPC pipe write: put data on the wire directly. */
+    assert(send_handle == NULL);
+    return uv__pipe_write_data(
+        loop, req, handle, bufs, nbufs, NULL, cb, false);
+  }
+}
+
+
+static void uv_pipe_read_eof(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_buf_t buf) {
+  /* If there is an eof timer running, we don't need it any more, so discard
+   * it. */
+  eof_timer_destroy(handle);
+
+  handle->flags &= ~UV_HANDLE_READABLE;
+  uv_read_stop((uv_stream_t*) handle);
+
+  handle->read_cb((uv_stream_t*) handle, UV_EOF, &buf);
+}
+
+
+static void uv_pipe_read_error(uv_loop_t* loop, uv_pipe_t* handle, int error,
+    uv_buf_t buf) {
+  /* If there is an eof timer running, we don't need it any more, so discard
+   * it. */
+  eof_timer_destroy(handle);
+
+  uv_read_stop((uv_stream_t*) handle);
+
+  handle->read_cb((uv_stream_t*)handle, uv_translate_sys_error(error), &buf);
+}
+
+
+static void uv_pipe_read_error_or_eof(uv_loop_t* loop, uv_pipe_t* handle,
+    int error, uv_buf_t buf) {
+  if (error == ERROR_BROKEN_PIPE) {
+    uv_pipe_read_eof(loop, handle, buf);
+  } else {
+    uv_pipe_read_error(loop, handle, error, buf);
+  }
+}
+
+
+static void uv__pipe_queue_ipc_xfer_info(
+    uv_pipe_t* handle, uv__ipc_socket_xfer_info_t* xfer_info) {
+  uv__ipc_xfer_queue_item_t* item;
+
+  item = (uv__ipc_xfer_queue_item_t*) uv__malloc(sizeof(*item));
+  if (item == NULL)
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+
+  memcpy(&item->xfer_info, xfer_info, sizeof(item->xfer_info));
+  QUEUE_INSERT_TAIL(&handle->pipe.conn.ipc_xfer_queue, &item->member);
+  handle->pipe.conn.ipc_xfer_queue_length++;
+}
+
+
+/* Read an exact number of bytes from a pipe. If an error or end-of-file is
+ * encountered before the requested number of bytes are read, an error is
+ * returned. */
+static int uv__pipe_read_exactly(HANDLE h, void* buffer, DWORD count) {
+  DWORD bytes_read, bytes_read_now;
+
+  bytes_read = 0;
+  while (bytes_read < count) {
+    if (!ReadFile(h,
+                  (char*) buffer + bytes_read,
+                  count - bytes_read,
+                  &bytes_read_now,
+                  NULL)) {
+      return GetLastError();
+    }
+
+    bytes_read += bytes_read_now;
+  }
+
+  assert(bytes_read == count);
+  return 0;
+}
+
+
+static DWORD uv__pipe_read_data(uv_loop_t* loop,
+                                uv_pipe_t* handle,
+                                DWORD suggested_bytes,
+                                DWORD max_bytes) {
+  DWORD bytes_read;
+  uv_buf_t buf;
+
+  /* Ask the user for a buffer to read data into. */
+  buf = uv_buf_init(NULL, 0);
+  handle->alloc_cb((uv_handle_t*) handle, suggested_bytes, &buf);
+  if (buf.base == NULL || buf.len == 0) {
+    handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
+    return 0; /* Break out of read loop. */
+  }
+
+  /* Ensure we read at most the smaller of:
+   *   (a) the length of the user-allocated buffer.
+   *   (b) the maximum data length as specified by the `max_bytes` argument.
+   */
+  if (max_bytes > buf.len)
+    max_bytes = buf.len;
+
+  /* Read into the user buffer. */
+  if (!ReadFile(handle->handle, buf.base, max_bytes, &bytes_read, NULL)) {
+    uv_pipe_read_error_or_eof(loop, handle, GetLastError(), buf);
+    return 0; /* Break out of read loop. */
+  }
+
+  /* Call the read callback. */
+  handle->read_cb((uv_stream_t*) handle, bytes_read, &buf);
+
+  return bytes_read;
+}
+
+
+static DWORD uv__pipe_read_ipc(uv_loop_t* loop, uv_pipe_t* handle) {
+  DWORD* data_remaining =
+      (DWORD*)&handle->pipe.conn.ipc_data_frame.payload_remaining;
+  int err;
+
+  if (*data_remaining > 0) {
+    /* Read data frame payload. */
+    DWORD bytes_read =
+        uv__pipe_read_data(loop, handle, *data_remaining, *data_remaining);
+    *data_remaining -= bytes_read;
+    return bytes_read;
+
+  } else {
+    /* Start of a new IPC frame. */
+    uv__ipc_frame_header_t frame_header;
+    uv__ipc_socket_xfer_info_t xfer_info;
+
+    /* Read the IPC frame header. */
+    err = uv__pipe_read_exactly(
+        handle->handle, &frame_header, sizeof frame_header);
+    if (err)
+      goto error;
+
+    if (frame_header.type == UV__IPC_DATA_FRAME) {
+      /* Data frame: capture payload length. Actual data will be read in
+       * subsequent call to uv__pipe_read_ipc(). */
+      *data_remaining = frame_header.payload_length;
+
+      /* Return number of bytes read. */
+      return sizeof frame_header;
+
+    } else if (frame_header.type == UV__IPC_XFER_FRAME) {
+      /* Xfer frame: read the payload. */
+      assert(frame_header.payload_length == sizeof xfer_info);
+      err =
+          uv__pipe_read_exactly(handle->handle, &xfer_info, sizeof xfer_info);
+      if (err)
+        goto error;
+
+      /* Store the pending socket info. */
+      uv__pipe_queue_ipc_xfer_info(handle, &xfer_info);
+
+      /* Return number of bytes read. */
+      return sizeof frame_header + sizeof xfer_info;
+    }
+
+    /* Invalid frame. */
+    err = WSAECONNABORTED; /* Maps to UV_ECONNABORTED. */
+  }
+
+error:
+  uv_pipe_read_error_or_eof(loop, handle, err, uv_null_buf_);
+  return 0; /* Break out of read loop. */
+}
+
+
+void uv_process_pipe_read_req(uv_loop_t* loop,
+                              uv_pipe_t* handle,
+                              uv_req_t* req) {
+  assert(handle->type == UV_NAMED_PIPE);
+
+  handle->flags &= ~(UV_HANDLE_READ_PENDING | UV_HANDLE_CANCELLATION_PENDING);
+  DECREASE_PENDING_REQ_COUNT(handle);
+  eof_timer_stop(handle);
+
+  /* At this point, we're done with bookkeeping. If the user has stopped
+   * reading the pipe in the meantime, there is nothing left to do, since there
+   * is no callback that we can call. */
+  if (!(handle->flags & UV_HANDLE_READING))
+    return;
+
+  if (!REQ_SUCCESS(req)) {
+    /* An error occurred doing the zero-read. */
+    DWORD err = GET_REQ_ERROR(req);
+
+    /* If the read was cancelled by uv__pipe_interrupt_read(), the request may
+     * indicate an ERROR_OPERATION_ABORTED error. This error isn't relevant to
+     * the user; we'll start a new zero-read at the end of this function. */
+    if (err != ERROR_OPERATION_ABORTED)
+      uv_pipe_read_error_or_eof(loop, handle, err, uv_null_buf_);
+
+  } else {
+    /* The zero-read completed without error, indicating there is data
+     * available in the kernel buffer. */
+    DWORD avail;
+
+    /* Get the number of bytes available. */
+    avail = 0;
+    if (!PeekNamedPipe(handle->handle, NULL, 0, NULL, &avail, NULL))
+      uv_pipe_read_error_or_eof(loop, handle, GetLastError(), uv_null_buf_);
+
+    /* Read until we've either read all the bytes available, or the 'reading'
+     * flag is cleared. */
+    while (avail > 0 && handle->flags & UV_HANDLE_READING) {
+      /* Depending on the type of pipe, read either IPC frames or raw data. */
+      DWORD bytes_read =
+          handle->ipc ? uv__pipe_read_ipc(loop, handle)
+                      : uv__pipe_read_data(loop, handle, avail, (DWORD) -1);
+
+      /* If no bytes were read, treat this as an indication that an error
+       * occurred, and break out of the read loop. */
+      if (bytes_read == 0)
+        break;
+
+      /* It is possible that more bytes were read than we thought were
+       * available. To prevent `avail` from underflowing, break out of the loop
+       * if this is the case. */
+      if (bytes_read > avail)
+        break;
+
+      /* Recompute the number of bytes available. */
+      avail -= bytes_read;
+    }
+  }
+
+  /* Start another zero-read request if necessary. */
+  if ((handle->flags & UV_HANDLE_READING) &&
+      !(handle->flags & UV_HANDLE_READ_PENDING)) {
+    uv_pipe_queue_read(loop, handle);
+  }
+}
+
+
+void uv_process_pipe_write_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_write_t* req) {
+  int err;
+
+  assert(handle->type == UV_NAMED_PIPE);
+
+  assert(handle->write_queue_size >= req->u.io.queued_bytes);
+  handle->write_queue_size -= req->u.io.queued_bytes;
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    if (req->wait_handle != INVALID_HANDLE_VALUE) {
+      UnregisterWait(req->wait_handle);
+      req->wait_handle = INVALID_HANDLE_VALUE;
+    }
+    if (req->event_handle) {
+      CloseHandle(req->event_handle);
+      req->event_handle = NULL;
+    }
+  }
+
+  err = GET_REQ_ERROR(req);
+
+  /* If this was a coalesced write, extract pointer to the user_provided
+   * uv_write_t structure so we can pass the expected pointer to the callback,
+   * then free the heap-allocated write req. */
+  if (req->coalesced) {
+    uv__coalesced_write_t* coalesced_write =
+        container_of(req, uv__coalesced_write_t, req);
+    req = coalesced_write->user_req;
+    uv__free(coalesced_write);
+  }
+  if (req->cb) {
+    req->cb(req, uv_translate_sys_error(err));
+  }
+
+  handle->stream.conn.write_reqs_pending--;
+
+  if (handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE &&
+      handle->pipe.conn.non_overlapped_writes_tail) {
+    assert(handle->stream.conn.write_reqs_pending > 0);
+    uv_queue_non_overlapped_write(handle);
+  }
+
+  if (handle->stream.conn.shutdown_req != NULL &&
+      handle->stream.conn.write_reqs_pending == 0) {
+    uv_want_endgame(loop, (uv_handle_t*)handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_process_pipe_accept_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_req_t* raw_req) {
+  uv_pipe_accept_t* req = (uv_pipe_accept_t*) raw_req;
+
+  assert(handle->type == UV_NAMED_PIPE);
+
+  if (handle->flags & UV__HANDLE_CLOSING) {
+    /* The req->pipeHandle should be freed already in uv_pipe_cleanup(). */
+    assert(req->pipeHandle == INVALID_HANDLE_VALUE);
+    DECREASE_PENDING_REQ_COUNT(handle);
+    return;
+  }
+
+  if (REQ_SUCCESS(req)) {
+    assert(req->pipeHandle != INVALID_HANDLE_VALUE);
+    req->next_pending = handle->pipe.serv.pending_accepts;
+    handle->pipe.serv.pending_accepts = req;
+
+    if (handle->stream.serv.connection_cb) {
+      handle->stream.serv.connection_cb((uv_stream_t*)handle, 0);
+    }
+  } else {
+    if (req->pipeHandle != INVALID_HANDLE_VALUE) {
+      CloseHandle(req->pipeHandle);
+      req->pipeHandle = INVALID_HANDLE_VALUE;
+    }
+    if (!(handle->flags & UV__HANDLE_CLOSING)) {
+      uv_pipe_queue_accept(loop, handle, req, FALSE);
+    }
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_process_pipe_connect_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_connect_t* req) {
+  int err;
+
+  assert(handle->type == UV_NAMED_PIPE);
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (req->cb) {
+    err = 0;
+    if (REQ_SUCCESS(req)) {
+      uv_pipe_connection_init(handle);
+    } else {
+      err = GET_REQ_ERROR(req);
+    }
+    req->cb(req, uv_translate_sys_error(err));
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_process_pipe_shutdown_req(uv_loop_t* loop, uv_pipe_t* handle,
+    uv_shutdown_t* req) {
+  assert(handle->type == UV_NAMED_PIPE);
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (handle->flags & UV_HANDLE_READABLE) {
+    /* Initialize and optionally start the eof timer. Only do this if the pipe
+     * is readable and we haven't seen EOF come in ourselves. */
+    eof_timer_init(handle);
+
+    /* If reading start the timer right now. Otherwise uv_pipe_queue_read will
+     * start it. */
+    if (handle->flags & UV_HANDLE_READ_PENDING) {
+      eof_timer_start(handle);
+    }
+
+  } else {
+    /* This pipe is not readable. We can just close it to let the other end
+     * know that we're done writing. */
+    close_pipe(handle);
+  }
+
+  if (req->cb) {
+    req->cb(req, 0);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+static void eof_timer_init(uv_pipe_t* pipe) {
+  int r;
+
+  assert(pipe->pipe.conn.eof_timer == NULL);
+  assert(pipe->flags & UV_HANDLE_CONNECTION);
+
+  pipe->pipe.conn.eof_timer = (uv_timer_t*) uv__malloc(sizeof *pipe->pipe.conn.eof_timer);
+
+  r = uv_timer_init(pipe->loop, pipe->pipe.conn.eof_timer);
+  assert(r == 0); /* timers can't fail */
+  pipe->pipe.conn.eof_timer->data = pipe;
+  uv_unref((uv_handle_t*) pipe->pipe.conn.eof_timer);
+}
+
+
+static void eof_timer_start(uv_pipe_t* pipe) {
+  assert(pipe->flags & UV_HANDLE_CONNECTION);
+
+  if (pipe->pipe.conn.eof_timer != NULL) {
+    uv_timer_start(pipe->pipe.conn.eof_timer, eof_timer_cb, eof_timeout, 0);
+  }
+}
+
+
+static void eof_timer_stop(uv_pipe_t* pipe) {
+  assert(pipe->flags & UV_HANDLE_CONNECTION);
+
+  if (pipe->pipe.conn.eof_timer != NULL) {
+    uv_timer_stop(pipe->pipe.conn.eof_timer);
+  }
+}
+
+
+static void eof_timer_cb(uv_timer_t* timer) {
+  uv_pipe_t* pipe = (uv_pipe_t*) timer->data;
+  uv_loop_t* loop = timer->loop;
+
+  assert(pipe->type == UV_NAMED_PIPE);
+
+  /* This should always be true, since we start the timer only in
+   * uv_pipe_queue_read after successfully calling ReadFile, or in
+   * uv_process_pipe_shutdown_req if a read is pending, and we always
+   * immediately stop the timer in uv_process_pipe_read_req. */
+  assert(pipe->flags & UV_HANDLE_READ_PENDING);
+
+  /* If there are many packets coming off the iocp then the timer callback may
+   * be called before the read request is coming off the queue. Therefore we
+   * check here if the read request has completed but will be processed later.
+   */
+  if ((pipe->flags & UV_HANDLE_READ_PENDING) &&
+      HasOverlappedIoCompleted(&pipe->read_req.u.io.overlapped)) {
+    return;
+  }
+
+  /* Force both ends off the pipe. */
+  close_pipe(pipe);
+
+  /* Stop reading, so the pending read that is going to fail will not be
+   * reported to the user. */
+  uv_read_stop((uv_stream_t*) pipe);
+
+  /* Report the eof and update flags. This will get reported even if the user
+   * stopped reading in the meantime. TODO: is that okay? */
+  uv_pipe_read_eof(loop, pipe, uv_null_buf_);
+}
+
+
+static void eof_timer_destroy(uv_pipe_t* pipe) {
+  assert(pipe->flags & UV_HANDLE_CONNECTION);
+
+  if (pipe->pipe.conn.eof_timer) {
+    uv_close((uv_handle_t*) pipe->pipe.conn.eof_timer, eof_timer_close_cb);
+    pipe->pipe.conn.eof_timer = NULL;
+  }
+}
+
+
+static void eof_timer_close_cb(uv_handle_t* handle) {
+  assert(handle->type == UV_TIMER);
+  uv__free(handle);
+}
+
+
+int uv_pipe_open(uv_pipe_t* pipe, uv_file file) {
+  HANDLE os_handle = uv__get_osfhandle(file);
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_ACCESS_INFORMATION access;
+  DWORD duplex_flags = 0;
+
+  if (os_handle == INVALID_HANDLE_VALUE)
+    return UV_EBADF;
+
+  uv__once_init();
+  /* In order to avoid closing a stdio file descriptor 0-2, duplicate the
+   * underlying OS handle and forget about the original fd.
+   * We could also opt to use the original OS handle and just never close it,
+   * but then there would be no reliable way to cancel pending read operations
+   * upon close.
+   */
+  if (file <= 2) {
+    if (!DuplicateHandle(INVALID_HANDLE_VALUE,
+                         os_handle,
+                         INVALID_HANDLE_VALUE,
+                         &os_handle,
+                         0,
+                         FALSE,
+                         DUPLICATE_SAME_ACCESS))
+      return uv_translate_sys_error(GetLastError());
+    file = -1;
+  }
+
+  /* Determine what kind of permissions we have on this handle.
+   * Cygwin opens the pipe in message mode, but we can support it,
+   * just query the access flags and set the stream flags accordingly.
+   */
+  nt_status = pNtQueryInformationFile(os_handle,
+                                      &io_status,
+                                      &access,
+                                      sizeof(access),
+                                      FileAccessInformation);
+  if (nt_status != STATUS_SUCCESS)
+    return UV_EINVAL;
+
+  if (pipe->ipc) {
+    if (!(access.AccessFlags & FILE_WRITE_DATA) ||
+        !(access.AccessFlags & FILE_READ_DATA)) {
+      return UV_EINVAL;
+    }
+  }
+
+  if (access.AccessFlags & FILE_WRITE_DATA)
+    duplex_flags |= UV_HANDLE_WRITABLE;
+  if (access.AccessFlags & FILE_READ_DATA)
+    duplex_flags |= UV_HANDLE_READABLE;
+
+  if (os_handle == INVALID_HANDLE_VALUE ||
+      uv_set_pipe_handle(pipe->loop,
+                         pipe,
+                         os_handle,
+                         file,
+                         duplex_flags) == -1) {
+    return UV_EINVAL;
+  }
+
+  uv_pipe_connection_init(pipe);
+
+  if (pipe->ipc) {
+    assert(!(pipe->flags & UV_HANDLE_NON_OVERLAPPED_PIPE));
+    pipe->pipe.conn.ipc_remote_pid = uv_os_getppid();
+    assert(pipe->pipe.conn.ipc_remote_pid != -1);
+  }
+  return 0;
+}
+
+
+static int uv__pipe_getname(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  NTSTATUS nt_status;
+  IO_STATUS_BLOCK io_status;
+  FILE_NAME_INFORMATION tmp_name_info;
+  FILE_NAME_INFORMATION* name_info;
+  WCHAR* name_buf;
+  unsigned int addrlen;
+  unsigned int name_size;
+  unsigned int name_len;
+  int err;
+
+  uv__once_init();
+  name_info = NULL;
+
+  if (handle->handle == INVALID_HANDLE_VALUE) {
+    *size = 0;
+    return UV_EINVAL;
+  }
+
+  /* NtQueryInformationFile will block if another thread is performing a
+   * blocking operation on the queried handle. If the pipe handle is
+   * synchronous, there may be a worker thread currently calling ReadFile() on
+   * the pipe handle, which could cause a deadlock. To avoid this, interrupt
+   * the read. */
+  if (handle->flags & UV_HANDLE_CONNECTION &&
+      handle->flags & UV_HANDLE_NON_OVERLAPPED_PIPE) {
+    uv__pipe_interrupt_read((uv_pipe_t*) handle); /* cast away const warning */
+  }
+
+  nt_status = pNtQueryInformationFile(handle->handle,
+                                      &io_status,
+                                      &tmp_name_info,
+                                      sizeof tmp_name_info,
+                                      FileNameInformation);
+  if (nt_status == STATUS_BUFFER_OVERFLOW) {
+    name_size = sizeof(*name_info) + tmp_name_info.FileNameLength;
+    name_info = (FILE_NAME_INFORMATION*)uv__malloc(name_size);
+    if (!name_info) {
+      *size = 0;
+      err = UV_ENOMEM;
+      goto cleanup;
+    }
+
+    nt_status = pNtQueryInformationFile(handle->handle,
+                                        &io_status,
+                                        name_info,
+                                        name_size,
+                                        FileNameInformation);
+  }
+
+  if (nt_status != STATUS_SUCCESS) {
+    *size = 0;
+    err = uv_translate_sys_error(pRtlNtStatusToDosError(nt_status));
+    goto error;
+  }
+
+  if (!name_info) {
+    /* the struct on stack was used */
+    name_buf = tmp_name_info.FileName;
+    name_len = tmp_name_info.FileNameLength;
+  } else {
+    name_buf = name_info->FileName;
+    name_len = name_info->FileNameLength;
+  }
+
+  if (name_len == 0) {
+    *size = 0;
+    err = 0;
+    goto error;
+  }
+
+  name_len /= sizeof(WCHAR);
+
+  /* check how much space we need */
+  addrlen = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                name_buf,
+                                name_len,
+                                NULL,
+                                0,
+                                NULL,
+                                NULL);
+  if (!addrlen) {
+    *size = 0;
+    err = uv_translate_sys_error(GetLastError());
+    goto error;
+  } else if (pipe_prefix_len + addrlen >= *size) {
+    /* "\\\\.\\pipe" + name */
+    *size = pipe_prefix_len + addrlen + 1;
+    err = UV_ENOBUFS;
+    goto error;
+  }
+
+  memcpy(buffer, pipe_prefix, pipe_prefix_len);
+  addrlen = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                name_buf,
+                                name_len,
+                                buffer+pipe_prefix_len,
+                                *size-pipe_prefix_len,
+                                NULL,
+                                NULL);
+  if (!addrlen) {
+    *size = 0;
+    err = uv_translate_sys_error(GetLastError());
+    goto error;
+  }
+
+  addrlen += pipe_prefix_len;
+  *size = addrlen;
+  buffer[addrlen] = '\0';
+
+  err = 0;
+
+error:
+  uv__free(name_info);
+
+cleanup:
+  return err;
+}
+
+
+int uv_pipe_pending_count(uv_pipe_t* handle) {
+  if (!handle->ipc)
+    return 0;
+  return handle->pipe.conn.ipc_xfer_queue_length;
+}
+
+
+int uv_pipe_getsockname(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  if (handle->flags & UV_HANDLE_BOUND)
+    return uv__pipe_getname(handle, buffer, size);
+
+  if (handle->flags & UV_HANDLE_CONNECTION ||
+      handle->handle != INVALID_HANDLE_VALUE) {
+    *size = 0;
+    return 0;
+  }
+
+  return UV_EBADF;
+}
+
+
+int uv_pipe_getpeername(const uv_pipe_t* handle, char* buffer, size_t* size) {
+  /* emulate unix behaviour */
+  if (handle->flags & UV_HANDLE_BOUND)
+    return UV_ENOTCONN;
+
+  if (handle->handle != INVALID_HANDLE_VALUE)
+    return uv__pipe_getname(handle, buffer, size);
+
+  return UV_EBADF;
+}
+
+
+uv_handle_type uv_pipe_pending_type(uv_pipe_t* handle) {
+  if (!handle->ipc)
+    return UV_UNKNOWN_HANDLE;
+  if (handle->pipe.conn.ipc_xfer_queue_length == 0)
+    return UV_UNKNOWN_HANDLE;
+  else
+    return UV_TCP;
+}
+
+int uv_pipe_chmod(uv_pipe_t* handle, int mode) {
+  SID_IDENTIFIER_AUTHORITY sid_world = SECURITY_WORLD_SID_AUTHORITY;
+  PACL old_dacl, new_dacl;
+  PSECURITY_DESCRIPTOR sd;
+  EXPLICIT_ACCESS ea;
+  PSID everyone;
+  int error;
+
+  if (handle == NULL || handle->handle == INVALID_HANDLE_VALUE)
+    return UV_EBADF;
+
+  if (mode != UV_READABLE &&
+      mode != UV_WRITABLE &&
+      mode != (UV_WRITABLE | UV_READABLE))
+    return UV_EINVAL;
+
+  if (!AllocateAndInitializeSid(&sid_world,
+                                1,
+                                SECURITY_WORLD_RID,
+                                0, 0, 0, 0, 0, 0, 0,
+                                &everyone)) {
+    error = GetLastError();
+    goto done;
+  }
+
+  if (GetSecurityInfo(handle->handle,
+                      SE_KERNEL_OBJECT,
+                      DACL_SECURITY_INFORMATION,
+                      NULL,
+                      NULL,
+                      &old_dacl,
+                      NULL,
+                      &sd)) {
+    error = GetLastError();
+    goto clean_sid;
+  }
+ 
+  memset(&ea, 0, sizeof(EXPLICIT_ACCESS));
+  if (mode & UV_READABLE)
+    ea.grfAccessPermissions |= GENERIC_READ | FILE_WRITE_ATTRIBUTES;
+  if (mode & UV_WRITABLE)
+    ea.grfAccessPermissions |= GENERIC_WRITE | FILE_READ_ATTRIBUTES;
+  ea.grfAccessPermissions |= SYNCHRONIZE;
+  ea.grfAccessMode = SET_ACCESS;
+  ea.grfInheritance = NO_INHERITANCE;
+  ea.Trustee.TrusteeForm = TRUSTEE_IS_SID;
+  ea.Trustee.TrusteeType = TRUSTEE_IS_WELL_KNOWN_GROUP;
+  ea.Trustee.ptstrName = (LPTSTR)everyone;
+
+  if (SetEntriesInAcl(1, &ea, old_dacl, &new_dacl)) {
+    error = GetLastError();
+    goto clean_sd;
+  }
+
+  if (SetSecurityInfo(handle->handle,
+                      SE_KERNEL_OBJECT,
+                      DACL_SECURITY_INFORMATION,
+                      NULL,
+                      NULL,
+                      new_dacl,
+                      NULL)) {
+    error = GetLastError();
+    goto clean_dacl;
+  }
+
+  error = 0;
+
+clean_dacl:
+  LocalFree((HLOCAL) new_dacl);
+clean_sd:
+  LocalFree((HLOCAL) sd);
+clean_sid:
+  FreeSid(everyone);
+done:
+  return uv_translate_sys_error(error);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/poll.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/poll.cpp
new file mode 100644
index 0000000..b1369df
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/poll.cpp
@@ -0,0 +1,643 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+static const GUID uv_msafd_provider_ids[UV_MSAFD_PROVIDER_COUNT] = {
+  {0xe70f1aa0, 0xab8b, 0x11cf,
+      {0x8c, 0xa3, 0x00, 0x80, 0x5f, 0x48, 0xa1, 0x92}},
+  {0xf9eab0c0, 0x26d4, 0x11d0,
+      {0xbb, 0xbf, 0x00, 0xaa, 0x00, 0x6c, 0x34, 0xe4}},
+  {0x9fc48064, 0x7298, 0x43e4,
+      {0xb7, 0xbd, 0x18, 0x1f, 0x20, 0x89, 0x79, 0x2a}}
+};
+
+typedef struct uv_single_fd_set_s {
+  unsigned int fd_count;
+  SOCKET fd_array[1];
+} uv_single_fd_set_t;
+
+
+static OVERLAPPED overlapped_dummy_;
+static uv_once_t overlapped_dummy_init_guard_ = UV_ONCE_INIT;
+
+static AFD_POLL_INFO afd_poll_info_dummy_;
+
+
+static void uv__init_overlapped_dummy(void) {
+  HANDLE event;
+
+  event = CreateEvent(NULL, TRUE, TRUE, NULL);
+  if (event == NULL)
+    uv_fatal_error(GetLastError(), "CreateEvent");
+
+  memset(&overlapped_dummy_, 0, sizeof overlapped_dummy_);
+  overlapped_dummy_.hEvent = (HANDLE) ((uintptr_t) event | 1);
+}
+
+
+static OVERLAPPED* uv__get_overlapped_dummy(void) {
+  uv_once(&overlapped_dummy_init_guard_, uv__init_overlapped_dummy);
+  return &overlapped_dummy_;
+}
+
+
+static AFD_POLL_INFO* uv__get_afd_poll_info_dummy(void) {
+  return &afd_poll_info_dummy_;
+}
+
+
+static void uv__fast_poll_submit_poll_req(uv_loop_t* loop, uv_poll_t* handle) {
+  uv_req_t* req;
+  AFD_POLL_INFO* afd_poll_info;
+  DWORD result;
+
+  /* Find a yet unsubmitted req to submit. */
+  if (handle->submitted_events_1 == 0) {
+    req = &handle->poll_req_1;
+    afd_poll_info = &handle->afd_poll_info_1;
+    handle->submitted_events_1 = handle->events;
+    handle->mask_events_1 = 0;
+    handle->mask_events_2 = handle->events;
+  } else if (handle->submitted_events_2 == 0) {
+    req = &handle->poll_req_2;
+    afd_poll_info = &handle->afd_poll_info_2;
+    handle->submitted_events_2 = handle->events;
+    handle->mask_events_1 = handle->events;
+    handle->mask_events_2 = 0;
+  } else {
+    /* Just wait until there's an unsubmitted req. This will happen almost
+     * immediately as one of the 2 outstanding requests is about to return.
+     * When this happens, uv__fast_poll_process_poll_req will be called, and
+     * the pending events, if needed, will be processed in a subsequent
+     * request. */
+    return;
+  }
+
+  /* Setting Exclusive to TRUE makes the other poll request return if there is
+   * any. */
+  afd_poll_info->Exclusive = TRUE;
+  afd_poll_info->NumberOfHandles = 1;
+  afd_poll_info->Timeout.QuadPart = INT64_MAX;
+  afd_poll_info->Handles[0].Handle = (HANDLE) handle->socket;
+  afd_poll_info->Handles[0].Status = 0;
+  afd_poll_info->Handles[0].Events = 0;
+
+  if (handle->events & UV_READABLE) {
+    afd_poll_info->Handles[0].Events |= AFD_POLL_RECEIVE |
+        AFD_POLL_DISCONNECT | AFD_POLL_ACCEPT | AFD_POLL_ABORT;
+  } else {
+    if (handle->events & UV_DISCONNECT) {
+      afd_poll_info->Handles[0].Events |= AFD_POLL_DISCONNECT;
+    }
+  }
+  if (handle->events & UV_WRITABLE) {
+    afd_poll_info->Handles[0].Events |= AFD_POLL_SEND | AFD_POLL_CONNECT_FAIL;
+  }
+
+  memset(&req->u.io.overlapped, 0, sizeof req->u.io.overlapped);
+
+  result = uv_msafd_poll((SOCKET) handle->peer_socket,
+                         afd_poll_info,
+                         afd_poll_info,
+                         &req->u.io.overlapped);
+  if (result != 0 && WSAGetLastError() != WSA_IO_PENDING) {
+    /* Queue this req, reporting an error. */
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv_insert_pending_req(loop, req);
+  }
+}
+
+
+static int uv__fast_poll_cancel_poll_req(uv_loop_t* loop, uv_poll_t* handle) {
+  AFD_POLL_INFO afd_poll_info;
+  DWORD result;
+
+  afd_poll_info.Exclusive = TRUE;
+  afd_poll_info.NumberOfHandles = 1;
+  afd_poll_info.Timeout.QuadPart = INT64_MAX;
+  afd_poll_info.Handles[0].Handle = (HANDLE) handle->socket;
+  afd_poll_info.Handles[0].Status = 0;
+  afd_poll_info.Handles[0].Events = AFD_POLL_ALL;
+
+  result = uv_msafd_poll(handle->socket,
+                         &afd_poll_info,
+                         uv__get_afd_poll_info_dummy(),
+                         uv__get_overlapped_dummy());
+
+  if (result == SOCKET_ERROR) {
+    DWORD error = WSAGetLastError();
+    if (error != WSA_IO_PENDING)
+      return error;
+  }
+
+  return 0;
+}
+
+
+static void uv__fast_poll_process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
+    uv_req_t* req) {
+  unsigned char mask_events;
+  AFD_POLL_INFO* afd_poll_info;
+
+  if (req == &handle->poll_req_1) {
+    afd_poll_info = &handle->afd_poll_info_1;
+    handle->submitted_events_1 = 0;
+    mask_events = handle->mask_events_1;
+  } else if (req == &handle->poll_req_2) {
+    afd_poll_info = &handle->afd_poll_info_2;
+    handle->submitted_events_2 = 0;
+    mask_events = handle->mask_events_2;
+  } else {
+    assert(0);
+    return;
+  }
+
+  /* Report an error unless the select was just interrupted. */
+  if (!REQ_SUCCESS(req)) {
+    DWORD error = GET_REQ_SOCK_ERROR(req);
+    if (error != WSAEINTR && handle->events != 0) {
+      handle->events = 0; /* Stop the watcher */
+      handle->poll_cb(handle, uv_translate_sys_error(error), 0);
+    }
+
+  } else if (afd_poll_info->NumberOfHandles >= 1) {
+    unsigned char events = 0;
+
+    if ((afd_poll_info->Handles[0].Events & (AFD_POLL_RECEIVE |
+        AFD_POLL_DISCONNECT | AFD_POLL_ACCEPT | AFD_POLL_ABORT)) != 0) {
+      events |= UV_READABLE;
+      if ((afd_poll_info->Handles[0].Events & AFD_POLL_DISCONNECT) != 0) {
+        events |= UV_DISCONNECT;
+      }
+    }
+    if ((afd_poll_info->Handles[0].Events & (AFD_POLL_SEND |
+        AFD_POLL_CONNECT_FAIL)) != 0) {
+      events |= UV_WRITABLE;
+    }
+
+    events &= handle->events & ~mask_events;
+
+    if (afd_poll_info->Handles[0].Events & AFD_POLL_LOCAL_CLOSE) {
+      /* Stop polling. */
+      handle->events = 0;
+      if (uv__is_active(handle))
+        uv__handle_stop(handle);
+    }
+
+    if (events != 0) {
+      handle->poll_cb(handle, 0, events);
+    }
+  }
+
+  if ((handle->events & ~(handle->submitted_events_1 |
+      handle->submitted_events_2)) != 0) {
+    uv__fast_poll_submit_poll_req(loop, handle);
+  } else if ((handle->flags & UV__HANDLE_CLOSING) &&
+             handle->submitted_events_1 == 0 &&
+             handle->submitted_events_2 == 0) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+static int uv__fast_poll_set(uv_loop_t* loop, uv_poll_t* handle, int events) {
+  assert(handle->type == UV_POLL);
+  assert(!(handle->flags & UV__HANDLE_CLOSING));
+  assert((events & ~(UV_READABLE | UV_WRITABLE | UV_DISCONNECT)) == 0);
+
+  handle->events = events;
+
+  if (handle->events != 0) {
+    uv__handle_start(handle);
+  } else {
+    uv__handle_stop(handle);
+  }
+
+  if ((handle->events & ~(handle->submitted_events_1 |
+      handle->submitted_events_2)) != 0) {
+    uv__fast_poll_submit_poll_req(handle->loop, handle);
+  }
+
+  return 0;
+}
+
+
+static int uv__fast_poll_close(uv_loop_t* loop, uv_poll_t* handle) {
+  handle->events = 0;
+  uv__handle_closing(handle);
+
+  if (handle->submitted_events_1 == 0 &&
+      handle->submitted_events_2 == 0) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+    return 0;
+  } else {
+    /* Cancel outstanding poll requests by executing another, unique poll
+     * request that forces the outstanding ones to return. */
+    return uv__fast_poll_cancel_poll_req(loop, handle);
+  }
+}
+
+
+static SOCKET uv__fast_poll_create_peer_socket(HANDLE iocp,
+    WSAPROTOCOL_INFOW* protocol_info) {
+  SOCKET sock = 0;
+
+  sock = WSASocketW(protocol_info->iAddressFamily,
+                    protocol_info->iSocketType,
+                    protocol_info->iProtocol,
+                    protocol_info,
+                    0,
+                    WSA_FLAG_OVERLAPPED);
+  if (sock == INVALID_SOCKET) {
+    return INVALID_SOCKET;
+  }
+
+  if (!SetHandleInformation((HANDLE) sock, HANDLE_FLAG_INHERIT, 0)) {
+    goto error;
+  };
+
+  if (CreateIoCompletionPort((HANDLE) sock,
+                             iocp,
+                             (ULONG_PTR) sock,
+                             0) == NULL) {
+    goto error;
+  }
+
+  return sock;
+
+ error:
+  closesocket(sock);
+  return INVALID_SOCKET;
+}
+
+
+static SOCKET uv__fast_poll_get_peer_socket(uv_loop_t* loop,
+    WSAPROTOCOL_INFOW* protocol_info) {
+  int index, i;
+  SOCKET peer_socket;
+
+  index = -1;
+  for (i = 0; (size_t) i < ARRAY_SIZE(uv_msafd_provider_ids); i++) {
+    if (memcmp((void*) &protocol_info->ProviderId,
+               (void*) &uv_msafd_provider_ids[i],
+               sizeof protocol_info->ProviderId) == 0) {
+      index = i;
+    }
+  }
+
+  /* Check if the protocol uses an msafd socket. */
+  if (index < 0) {
+    return INVALID_SOCKET;
+  }
+
+  /* If we didn't (try) to create a peer socket yet, try to make one. Don't try
+   * again if the peer socket creation failed earlier for the same protocol. */
+  peer_socket = loop->poll_peer_sockets[index];
+  if (peer_socket == 0) {
+    peer_socket = uv__fast_poll_create_peer_socket(loop->iocp, protocol_info);
+    loop->poll_peer_sockets[index] = peer_socket;
+  }
+
+  return peer_socket;
+}
+
+
+static DWORD WINAPI uv__slow_poll_thread_proc(void* arg) {
+  uv_req_t* req = (uv_req_t*) arg;
+  uv_poll_t* handle = (uv_poll_t*) req->data;
+  unsigned char reported_events;
+  int r;
+  uv_single_fd_set_t rfds, wfds, efds;
+  struct timeval timeout;
+
+  assert(handle->type == UV_POLL);
+  assert(req->type == UV_POLL_REQ);
+
+  if (handle->events & UV_READABLE) {
+    rfds.fd_count = 1;
+    rfds.fd_array[0] = handle->socket;
+  } else {
+    rfds.fd_count = 0;
+  }
+
+  if (handle->events & UV_WRITABLE) {
+    wfds.fd_count = 1;
+    wfds.fd_array[0] = handle->socket;
+    efds.fd_count = 1;
+    efds.fd_array[0] = handle->socket;
+  } else {
+    wfds.fd_count = 0;
+    efds.fd_count = 0;
+  }
+
+  /* Make the select() time out after 3 minutes. If select() hangs because the
+   * user closed the socket, we will at least not hang indefinitely. */
+  timeout.tv_sec = 3 * 60;
+  timeout.tv_usec = 0;
+
+  r = select(1, (fd_set*) &rfds, (fd_set*) &wfds, (fd_set*) &efds, &timeout);
+  if (r == SOCKET_ERROR) {
+    /* Queue this req, reporting an error. */
+    SET_REQ_ERROR(&handle->poll_req_1, WSAGetLastError());
+    POST_COMPLETION_FOR_REQ(handle->loop, req);
+    return 0;
+  }
+
+  reported_events = 0;
+
+  if (r > 0) {
+    if (rfds.fd_count > 0) {
+      assert(rfds.fd_count == 1);
+      assert(rfds.fd_array[0] == handle->socket);
+      reported_events |= UV_READABLE;
+    }
+
+    if (wfds.fd_count > 0) {
+      assert(wfds.fd_count == 1);
+      assert(wfds.fd_array[0] == handle->socket);
+      reported_events |= UV_WRITABLE;
+    } else if (efds.fd_count > 0) {
+      assert(efds.fd_count == 1);
+      assert(efds.fd_array[0] == handle->socket);
+      reported_events |= UV_WRITABLE;
+    }
+  }
+
+  SET_REQ_SUCCESS(req);
+  req->u.io.overlapped.InternalHigh = (DWORD) reported_events;
+  POST_COMPLETION_FOR_REQ(handle->loop, req);
+
+  return 0;
+}
+
+
+static void uv__slow_poll_submit_poll_req(uv_loop_t* loop, uv_poll_t* handle) {
+  uv_req_t* req;
+
+  /* Find a yet unsubmitted req to submit. */
+  if (handle->submitted_events_1 == 0) {
+    req = &handle->poll_req_1;
+    handle->submitted_events_1 = handle->events;
+    handle->mask_events_1 = 0;
+    handle->mask_events_2 = handle->events;
+  } else if (handle->submitted_events_2 == 0) {
+    req = &handle->poll_req_2;
+    handle->submitted_events_2 = handle->events;
+    handle->mask_events_1 = handle->events;
+    handle->mask_events_2 = 0;
+  } else {
+    assert(0);
+    return;
+  }
+
+  if (!QueueUserWorkItem(uv__slow_poll_thread_proc,
+                         (void*) req,
+                         WT_EXECUTELONGFUNCTION)) {
+    /* Make this req pending, reporting an error. */
+    SET_REQ_ERROR(req, GetLastError());
+    uv_insert_pending_req(loop, req);
+  }
+}
+
+
+
+static void uv__slow_poll_process_poll_req(uv_loop_t* loop, uv_poll_t* handle,
+    uv_req_t* req) {
+  unsigned char mask_events;
+  int err;
+
+  if (req == &handle->poll_req_1) {
+    handle->submitted_events_1 = 0;
+    mask_events = handle->mask_events_1;
+  } else if (req == &handle->poll_req_2) {
+    handle->submitted_events_2 = 0;
+    mask_events = handle->mask_events_2;
+  } else {
+    assert(0);
+    return;
+  }
+
+  if (!REQ_SUCCESS(req)) {
+    /* Error. */
+    if (handle->events != 0) {
+      err = GET_REQ_ERROR(req);
+      handle->events = 0; /* Stop the watcher */
+      handle->poll_cb(handle, uv_translate_sys_error(err), 0);
+    }
+  } else {
+    /* Got some events. */
+    int events = req->u.io.overlapped.InternalHigh & handle->events & ~mask_events;
+    if (events != 0) {
+      handle->poll_cb(handle, 0, events);
+    }
+  }
+
+  if ((handle->events & ~(handle->submitted_events_1 |
+      handle->submitted_events_2)) != 0) {
+    uv__slow_poll_submit_poll_req(loop, handle);
+  } else if ((handle->flags & UV__HANDLE_CLOSING) &&
+             handle->submitted_events_1 == 0 &&
+             handle->submitted_events_2 == 0) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+static int uv__slow_poll_set(uv_loop_t* loop, uv_poll_t* handle, int events) {
+  assert(handle->type == UV_POLL);
+  assert(!(handle->flags & UV__HANDLE_CLOSING));
+  assert((events & ~(UV_READABLE | UV_WRITABLE)) == 0);
+
+  handle->events = events;
+
+  if (handle->events != 0) {
+    uv__handle_start(handle);
+  } else {
+    uv__handle_stop(handle);
+  }
+
+  if ((handle->events &
+      ~(handle->submitted_events_1 | handle->submitted_events_2)) != 0) {
+    uv__slow_poll_submit_poll_req(handle->loop, handle);
+  }
+
+  return 0;
+}
+
+
+static int uv__slow_poll_close(uv_loop_t* loop, uv_poll_t* handle) {
+  handle->events = 0;
+  uv__handle_closing(handle);
+
+  if (handle->submitted_events_1 == 0 &&
+      handle->submitted_events_2 == 0) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+  }
+
+  return 0;
+}
+
+
+int uv_poll_init(uv_loop_t* loop, uv_poll_t* handle, int fd) {
+  return uv_poll_init_socket(loop, handle, (SOCKET) uv__get_osfhandle(fd));
+}
+
+
+int uv_poll_init_socket(uv_loop_t* loop, uv_poll_t* handle,
+    uv_os_sock_t socket) {
+  WSAPROTOCOL_INFOW protocol_info;
+  int len;
+  SOCKET peer_socket, base_socket;
+  DWORD bytes;
+  DWORD yes = 1;
+
+  /* Set the socket to nonblocking mode */
+  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR)
+    return uv_translate_sys_error(WSAGetLastError());
+
+/* Try to obtain a base handle for the socket. This increases this chances that
+ * we find an AFD handle and are able to use the fast poll mechanism. This will
+ * always fail on windows XP/2k3, since they don't support the. SIO_BASE_HANDLE
+ * ioctl. */
+#ifndef NDEBUG
+  base_socket = INVALID_SOCKET;
+#endif
+
+  if (WSAIoctl(socket,
+               SIO_BASE_HANDLE,
+               NULL,
+               0,
+               &base_socket,
+               sizeof base_socket,
+               &bytes,
+               NULL,
+               NULL) == 0) {
+    assert(base_socket != 0 && base_socket != INVALID_SOCKET);
+    socket = base_socket;
+  }
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_POLL);
+  handle->socket = socket;
+  handle->events = 0;
+
+  /* Obtain protocol information about the socket. */
+  len = sizeof protocol_info;
+  if (getsockopt(socket,
+                 SOL_SOCKET,
+                 SO_PROTOCOL_INFOW,
+                 (char*) &protocol_info,
+                 &len) != 0) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  /* Get the peer socket that is needed to enable fast poll. If the returned
+   * value is NULL, the protocol is not implemented by MSAFD and we'll have to
+   * use slow mode. */
+  peer_socket = uv__fast_poll_get_peer_socket(loop, &protocol_info);
+
+  if (peer_socket != INVALID_SOCKET) {
+    /* Initialize fast poll specific fields. */
+    handle->peer_socket = peer_socket;
+  } else {
+    /* Initialize slow poll specific fields. */
+    handle->flags |= UV_HANDLE_POLL_SLOW;
+  }
+
+  /* Initialize 2 poll reqs. */
+  handle->submitted_events_1 = 0;
+  UV_REQ_INIT(&handle->poll_req_1, UV_POLL_REQ);
+  handle->poll_req_1.data = handle;
+
+  handle->submitted_events_2 = 0;
+  UV_REQ_INIT(&handle->poll_req_2, UV_POLL_REQ);
+  handle->poll_req_2.data = handle;
+
+  return 0;
+}
+
+
+int uv_poll_start(uv_poll_t* handle, int events, uv_poll_cb cb) {
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
+    err = uv__fast_poll_set(handle->loop, handle, events);
+  } else {
+    err = uv__slow_poll_set(handle->loop, handle, events);
+  }
+
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  handle->poll_cb = cb;
+
+  return 0;
+}
+
+
+int uv_poll_stop(uv_poll_t* handle) {
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
+    err = uv__fast_poll_set(handle->loop, handle, 0);
+  } else {
+    err = uv__slow_poll_set(handle->loop, handle, 0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+void uv_process_poll_req(uv_loop_t* loop, uv_poll_t* handle, uv_req_t* req) {
+  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
+    uv__fast_poll_process_poll_req(loop, handle, req);
+  } else {
+    uv__slow_poll_process_poll_req(loop, handle, req);
+  }
+}
+
+
+int uv_poll_close(uv_loop_t* loop, uv_poll_t* handle) {
+  if (!(handle->flags & UV_HANDLE_POLL_SLOW)) {
+    return uv__fast_poll_close(loop, handle);
+  } else {
+    return uv__slow_poll_close(loop, handle);
+  }
+}
+
+
+void uv_poll_endgame(uv_loop_t* loop, uv_poll_t* handle) {
+  assert(handle->flags & UV__HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+  assert(handle->submitted_events_1 == 0);
+  assert(handle->submitted_events_2 == 0);
+
+  uv__handle_close(handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/process-stdio.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/process-stdio.cpp
new file mode 100644
index 0000000..0ae9f06
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/process-stdio.cpp
@@ -0,0 +1,511 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+#include <stdio.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+
+
+/*
+ * The `child_stdio_buffer` buffer has the following layout:
+ *   int number_of_fds
+ *   unsigned char crt_flags[number_of_fds]
+ *   HANDLE os_handle[number_of_fds]
+ */
+#define CHILD_STDIO_SIZE(count)                     \
+    (sizeof(int) +                                  \
+     sizeof(unsigned char) * (count) +              \
+     sizeof(uintptr_t) * (count))
+
+#define CHILD_STDIO_COUNT(buffer)                   \
+    *((unsigned int*) (buffer))
+
+#define CHILD_STDIO_CRT_FLAGS(buffer, fd)           \
+    *((unsigned char*) (buffer) + sizeof(int) + fd)
+
+#define CHILD_STDIO_HANDLE(buffer, fd)              \
+    *((HANDLE*) ((unsigned char*) (buffer) +        \
+                 sizeof(int) +                      \
+                 sizeof(unsigned char) *            \
+                 CHILD_STDIO_COUNT((buffer)) +      \
+                 sizeof(HANDLE) * (fd)))
+
+
+/* CRT file descriptor mode flags */
+#define FOPEN       0x01
+#define FEOFLAG     0x02
+#define FCRLF       0x04
+#define FPIPE       0x08
+#define FNOINHERIT  0x10
+#define FAPPEND     0x20
+#define FDEV        0x40
+#define FTEXT       0x80
+
+
+/*
+ * Clear the HANDLE_FLAG_INHERIT flag from all HANDLEs that were inherited
+ * the parent process. Don't check for errors - the stdio handles may not be
+ * valid, or may be closed already. There is no guarantee that this function
+ * does a perfect job.
+ */
+void uv_disable_stdio_inheritance(void) {
+  HANDLE handle;
+  STARTUPINFOW si;
+
+  /* Make the windows stdio handles non-inheritable. */
+  handle = GetStdHandle(STD_INPUT_HANDLE);
+  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
+    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
+
+  handle = GetStdHandle(STD_OUTPUT_HANDLE);
+  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
+    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
+
+  handle = GetStdHandle(STD_ERROR_HANDLE);
+  if (handle != NULL && handle != INVALID_HANDLE_VALUE)
+    SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
+
+  /* Make inherited CRT FDs non-inheritable. */
+  GetStartupInfoW(&si);
+  if (uv__stdio_verify(si.lpReserved2, si.cbReserved2))
+    uv__stdio_noinherit(si.lpReserved2);
+}
+
+
+static int uv__create_stdio_pipe_pair(uv_loop_t* loop,
+    uv_pipe_t* server_pipe, HANDLE* child_pipe_ptr, unsigned int flags) {
+  char pipe_name[64];
+  SECURITY_ATTRIBUTES sa;
+  DWORD server_access = 0;
+  DWORD client_access = 0;
+  HANDLE child_pipe = INVALID_HANDLE_VALUE;
+  int err;
+
+  if (flags & UV_READABLE_PIPE) {
+    /* The server needs inbound access too, otherwise CreateNamedPipe() won't
+     * give us the FILE_READ_ATTRIBUTES permission. We need that to probe the
+     * state of the write buffer when we're trying to shutdown the pipe. */
+    server_access |= PIPE_ACCESS_OUTBOUND | PIPE_ACCESS_INBOUND;
+    client_access |= GENERIC_READ | FILE_WRITE_ATTRIBUTES;
+  }
+  if (flags & UV_WRITABLE_PIPE) {
+    server_access |= PIPE_ACCESS_INBOUND;
+    client_access |= GENERIC_WRITE | FILE_READ_ATTRIBUTES;
+  }
+
+  /* Create server pipe handle. */
+  err = uv_stdio_pipe_server(loop,
+                             server_pipe,
+                             server_access,
+                             pipe_name,
+                             sizeof(pipe_name));
+  if (err)
+    goto error;
+
+  /* Create child pipe handle. */
+  sa.nLength = sizeof sa;
+  sa.lpSecurityDescriptor = NULL;
+  sa.bInheritHandle = TRUE;
+
+  BOOL overlap = server_pipe->ipc || (flags & UV_OVERLAPPED_PIPE);
+  child_pipe = CreateFileA(pipe_name,
+                           client_access,
+                           0,
+                           &sa,
+                           OPEN_EXISTING,
+                           overlap ? FILE_FLAG_OVERLAPPED : 0,
+                           NULL);
+  if (child_pipe == INVALID_HANDLE_VALUE) {
+    err = GetLastError();
+    goto error;
+  }
+
+#ifndef NDEBUG
+  /* Validate that the pipe was opened in the right mode. */
+  {
+    DWORD mode;
+    BOOL r = GetNamedPipeHandleState(child_pipe,
+                                     &mode,
+                                     NULL,
+                                     NULL,
+                                     NULL,
+                                     NULL,
+                                     0);
+    assert(r == TRUE);
+    assert(mode == (PIPE_READMODE_BYTE | PIPE_WAIT));
+  }
+#endif
+
+  /* Do a blocking ConnectNamedPipe. This should not block because we have both
+   * ends of the pipe created. */
+  if (!ConnectNamedPipe(server_pipe->handle, NULL)) {
+    if (GetLastError() != ERROR_PIPE_CONNECTED) {
+      err = GetLastError();
+      goto error;
+    }
+  }
+
+  /* The server end is now readable and/or writable. */
+  if (flags & UV_READABLE_PIPE)
+    server_pipe->flags |= UV_HANDLE_WRITABLE;
+  if (flags & UV_WRITABLE_PIPE)
+    server_pipe->flags |= UV_HANDLE_READABLE;
+
+  *child_pipe_ptr = child_pipe;
+  return 0;
+
+ error:
+  if (server_pipe->handle != INVALID_HANDLE_VALUE) {
+    uv_pipe_cleanup(loop, server_pipe);
+  }
+
+  if (child_pipe != INVALID_HANDLE_VALUE) {
+    CloseHandle(child_pipe);
+  }
+
+  return err;
+}
+
+
+static int uv__duplicate_handle(uv_loop_t* loop, HANDLE handle, HANDLE* dup) {
+  HANDLE current_process;
+
+
+  /* _get_osfhandle will sometimes return -2 in case of an error. This seems to
+   * happen when fd <= 2 and the process' corresponding stdio handle is set to
+   * NULL. Unfortunately DuplicateHandle will happily duplicate (HANDLE) -2, so
+   * this situation goes unnoticed until someone tries to use the duplicate.
+   * Therefore we filter out known-invalid handles here. */
+  if (handle == INVALID_HANDLE_VALUE ||
+      handle == NULL ||
+      handle == (HANDLE) -2) {
+    *dup = INVALID_HANDLE_VALUE;
+    return ERROR_INVALID_HANDLE;
+  }
+
+  current_process = GetCurrentProcess();
+
+  if (!DuplicateHandle(current_process,
+                       handle,
+                       current_process,
+                       dup,
+                       0,
+                       TRUE,
+                       DUPLICATE_SAME_ACCESS)) {
+    *dup = INVALID_HANDLE_VALUE;
+    return GetLastError();
+  }
+
+  return 0;
+}
+
+
+static int uv__duplicate_fd(uv_loop_t* loop, int fd, HANDLE* dup) {
+  HANDLE handle;
+
+  if (fd == -1) {
+    *dup = INVALID_HANDLE_VALUE;
+    return ERROR_INVALID_HANDLE;
+  }
+
+  handle = uv__get_osfhandle(fd);
+  return uv__duplicate_handle(loop, handle, dup);
+}
+
+
+int uv__create_nul_handle(HANDLE* handle_ptr,
+    DWORD access) {
+  HANDLE handle;
+  SECURITY_ATTRIBUTES sa;
+
+  sa.nLength = sizeof sa;
+  sa.lpSecurityDescriptor = NULL;
+  sa.bInheritHandle = TRUE;
+
+  handle = CreateFileW(L"NUL",
+                       access,
+                       FILE_SHARE_READ | FILE_SHARE_WRITE,
+                       &sa,
+                       OPEN_EXISTING,
+                       0,
+                       NULL);
+  if (handle == INVALID_HANDLE_VALUE) {
+    return GetLastError();
+  }
+
+  *handle_ptr = handle;
+  return 0;
+}
+
+
+int uv__stdio_create(uv_loop_t* loop,
+                     const uv_process_options_t* options,
+                     BYTE** buffer_ptr) {
+  BYTE* buffer;
+  int count, i;
+  int err;
+
+  count = options->stdio_count;
+
+  if (count < 0 || count > 255) {
+    /* Only support FDs 0-255 */
+    return ERROR_NOT_SUPPORTED;
+  } else if (count < 3) {
+    /* There should always be at least 3 stdio handles. */
+    count = 3;
+  }
+
+  /* Allocate the child stdio buffer */
+  buffer = (BYTE*) uv__malloc(CHILD_STDIO_SIZE(count));
+  if (buffer == NULL) {
+    return ERROR_OUTOFMEMORY;
+  }
+
+  /* Prepopulate the buffer with INVALID_HANDLE_VALUE handles so we can clean
+   * up on failure. */
+  CHILD_STDIO_COUNT(buffer) = count;
+  for (i = 0; i < count; i++) {
+    CHILD_STDIO_CRT_FLAGS(buffer, i) = 0;
+    CHILD_STDIO_HANDLE(buffer, i) = INVALID_HANDLE_VALUE;
+  }
+
+  for (i = 0; i < count; i++) {
+    uv_stdio_container_t fdopt;
+    if (i < options->stdio_count) {
+      fdopt = options->stdio[i];
+    } else {
+      fdopt.flags = UV_IGNORE;
+    }
+
+    switch (fdopt.flags & (UV_IGNORE | UV_CREATE_PIPE | UV_INHERIT_FD |
+            UV_INHERIT_STREAM)) {
+      case UV_IGNORE:
+        /* Starting a process with no stdin/stout/stderr can confuse it. So no
+         * matter what the user specified, we make sure the first three FDs are
+         * always open in their typical modes, e. g. stdin be readable and
+         * stdout/err should be writable. For FDs > 2, don't do anything - all
+         * handles in the stdio buffer are initialized with.
+         * INVALID_HANDLE_VALUE, which should be okay. */
+        if (i <= 2) {
+          DWORD access = (i == 0) ? FILE_GENERIC_READ :
+                                    FILE_GENERIC_WRITE | FILE_READ_ATTRIBUTES;
+
+          err = uv__create_nul_handle(&CHILD_STDIO_HANDLE(buffer, i),
+                                      access);
+          if (err)
+            goto error;
+
+          CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
+        }
+        break;
+
+      case UV_CREATE_PIPE: {
+        /* Create a pair of two connected pipe ends; one end is turned into an
+         * uv_pipe_t for use by the parent. The other one is given to the
+         * child. */
+        uv_pipe_t* parent_pipe = (uv_pipe_t*) fdopt.data.stream;
+        HANDLE child_pipe = INVALID_HANDLE_VALUE;
+
+        /* Create a new, connected pipe pair. stdio[i]. stream should point to
+         * an uninitialized, but not connected pipe handle. */
+        assert(fdopt.data.stream->type == UV_NAMED_PIPE);
+        assert(!(fdopt.data.stream->flags & UV_HANDLE_CONNECTION));
+        assert(!(fdopt.data.stream->flags & UV_HANDLE_PIPESERVER));
+
+        err = uv__create_stdio_pipe_pair(loop,
+                                         parent_pipe,
+                                         &child_pipe,
+                                         fdopt.flags);
+        if (err)
+          goto error;
+
+        CHILD_STDIO_HANDLE(buffer, i) = child_pipe;
+        CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FPIPE;
+        break;
+      }
+
+      case UV_INHERIT_FD: {
+        /* Inherit a raw FD. */
+        HANDLE child_handle;
+
+        /* Make an inheritable duplicate of the handle. */
+        err = uv__duplicate_fd(loop, fdopt.data.fd, &child_handle);
+        if (err) {
+          /* If fdopt. data. fd is not valid and fd <= 2, then ignore the
+           * error. */
+          if (fdopt.data.fd <= 2 && err == ERROR_INVALID_HANDLE) {
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = 0;
+            CHILD_STDIO_HANDLE(buffer, i) = INVALID_HANDLE_VALUE;
+            break;
+          }
+          goto error;
+        }
+
+        /* Figure out what the type is. */
+        switch (GetFileType(child_handle)) {
+          case FILE_TYPE_DISK:
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN;
+            break;
+
+          case FILE_TYPE_PIPE:
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FPIPE;
+            break;
+
+          case FILE_TYPE_CHAR:
+          case FILE_TYPE_REMOTE:
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
+            break;
+
+          case FILE_TYPE_UNKNOWN:
+            if (GetLastError() != 0) {
+              err = GetLastError();
+              CloseHandle(child_handle);
+              goto error;
+            }
+            CHILD_STDIO_CRT_FLAGS(buffer, i) = FOPEN | FDEV;
+            break;
+
+          default:
+            assert(0);
+            return -1;
+        }
+
+        CHILD_STDIO_HANDLE(buffer, i) = child_handle;
+        break;
+      }
+
+      case UV_INHERIT_STREAM: {
+        /* Use an existing stream as the stdio handle for the child. */
+        HANDLE stream_handle, child_handle;
+        unsigned char crt_flags;
+        uv_stream_t* stream = fdopt.data.stream;
+
+        /* Leech the handle out of the stream. */
+        if (stream->type == UV_TTY) {
+          stream_handle = ((uv_tty_t*) stream)->handle;
+          crt_flags = FOPEN | FDEV;
+        } else if (stream->type == UV_NAMED_PIPE &&
+                   stream->flags & UV_HANDLE_CONNECTION) {
+          stream_handle = ((uv_pipe_t*) stream)->handle;
+          crt_flags = FOPEN | FPIPE;
+        } else {
+          stream_handle = INVALID_HANDLE_VALUE;
+          crt_flags = 0;
+        }
+
+        if (stream_handle == NULL ||
+            stream_handle == INVALID_HANDLE_VALUE) {
+          /* The handle is already closed, or not yet created, or the stream
+           * type is not supported. */
+          err = ERROR_NOT_SUPPORTED;
+          goto error;
+        }
+
+        /* Make an inheritable copy of the handle. */
+        err = uv__duplicate_handle(loop, stream_handle, &child_handle);
+        if (err)
+          goto error;
+
+        CHILD_STDIO_HANDLE(buffer, i) = child_handle;
+        CHILD_STDIO_CRT_FLAGS(buffer, i) = crt_flags;
+        break;
+      }
+
+      default:
+        assert(0);
+        return -1;
+    }
+  }
+
+  *buffer_ptr  = buffer;
+  return 0;
+
+ error:
+  uv__stdio_destroy(buffer);
+  return err;
+}
+
+
+void uv__stdio_destroy(BYTE* buffer) {
+  int i, count;
+
+  count = CHILD_STDIO_COUNT(buffer);
+  for (i = 0; i < count; i++) {
+    HANDLE handle = CHILD_STDIO_HANDLE(buffer, i);
+    if (handle != INVALID_HANDLE_VALUE) {
+      CloseHandle(handle);
+    }
+  }
+
+  uv__free(buffer);
+}
+
+
+void uv__stdio_noinherit(BYTE* buffer) {
+  int i, count;
+
+  count = CHILD_STDIO_COUNT(buffer);
+  for (i = 0; i < count; i++) {
+    HANDLE handle = CHILD_STDIO_HANDLE(buffer, i);
+    if (handle != INVALID_HANDLE_VALUE) {
+      SetHandleInformation(handle, HANDLE_FLAG_INHERIT, 0);
+    }
+  }
+}
+
+
+int uv__stdio_verify(BYTE* buffer, WORD size) {
+  unsigned int count;
+
+  /* Check the buffer pointer. */
+  if (buffer == NULL)
+    return 0;
+
+  /* Verify that the buffer is at least big enough to hold the count. */
+  if (size < CHILD_STDIO_SIZE(0))
+    return 0;
+
+  /* Verify if the count is within range. */
+  count = CHILD_STDIO_COUNT(buffer);
+  if (count > 256)
+    return 0;
+
+  /* Verify that the buffer size is big enough to hold info for N FDs. */
+  if (size < CHILD_STDIO_SIZE(count))
+    return 0;
+
+  return 1;
+}
+
+
+WORD uv__stdio_size(BYTE* buffer) {
+  return (WORD) CHILD_STDIO_SIZE(CHILD_STDIO_COUNT((buffer)));
+}
+
+
+HANDLE uv__stdio_handle(BYTE* buffer, int fd) {
+  return CHILD_STDIO_HANDLE(buffer, fd);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/process.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/process.cpp
new file mode 100644
index 0000000..c47a3c4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/process.cpp
@@ -0,0 +1,1278 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <signal.h>
+#include <limits.h>
+#include <wchar.h>
+#include <malloc.h>    /* alloca */
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+#define SIGKILL         9
+
+
+typedef struct env_var {
+  const WCHAR* const wide;
+  const WCHAR* const wide_eq;
+  const size_t len; /* including null or '=' */
+} env_var_t;
+
+#define E_V(str) { L##str, L##str L"=", sizeof(str) }
+
+static const env_var_t required_vars[] = { /* keep me sorted */
+  E_V("HOMEDRIVE"),
+  E_V("HOMEPATH"),
+  E_V("LOGONSERVER"),
+  E_V("PATH"),
+  E_V("SYSTEMDRIVE"),
+  E_V("SYSTEMROOT"),
+  E_V("TEMP"),
+  E_V("USERDOMAIN"),
+  E_V("USERNAME"),
+  E_V("USERPROFILE"),
+  E_V("WINDIR"),
+};
+static size_t n_required_vars = ARRAY_SIZE(required_vars);
+
+
+static HANDLE uv_global_job_handle_;
+static uv_once_t uv_global_job_handle_init_guard_ = UV_ONCE_INIT;
+
+
+static void uv__init_global_job_handle(void) {
+  /* Create a job object and set it up to kill all contained processes when
+   * it's closed. Since this handle is made non-inheritable and we're not
+   * giving it to anyone, we're the only process holding a reference to it.
+   * That means that if this process exits it is closed and all the processes
+   * it contains are killed. All processes created with uv_spawn that are not
+   * spawned with the UV_PROCESS_DETACHED flag are assigned to this job.
+   *
+   * We're setting the JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK flag so only the
+   * processes that we explicitly add are affected, and *their* subprocesses
+   * are not. This ensures that our child processes are not limited in their
+   * ability to use job control on Windows versions that don't deal with
+   * nested jobs (prior to Windows 8 / Server 2012). It also lets our child
+   * processes created detached processes without explicitly breaking away
+   * from job control (which uv_spawn doesn't, either).
+   */
+  SECURITY_ATTRIBUTES attr;
+  JOBOBJECT_EXTENDED_LIMIT_INFORMATION info;
+
+  memset(&attr, 0, sizeof attr);
+  attr.bInheritHandle = FALSE;
+
+  memset(&info, 0, sizeof info);
+  info.BasicLimitInformation.LimitFlags =
+      JOB_OBJECT_LIMIT_BREAKAWAY_OK |
+      JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK |
+      JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION |
+      JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE;
+
+  uv_global_job_handle_ = CreateJobObjectW(&attr, NULL);
+  if (uv_global_job_handle_ == NULL)
+    uv_fatal_error(GetLastError(), "CreateJobObjectW");
+
+  if (!SetInformationJobObject(uv_global_job_handle_,
+                               JobObjectExtendedLimitInformation,
+                               &info,
+                               sizeof info))
+    uv_fatal_error(GetLastError(), "SetInformationJobObject");
+}
+
+
+static int uv_utf8_to_utf16_alloc(const char* s, WCHAR** ws_ptr) {
+  int ws_len, r;
+  WCHAR* ws;
+
+  ws_len = MultiByteToWideChar(CP_UTF8,
+                               0,
+                               s,
+                               -1,
+                               NULL,
+                               0);
+  if (ws_len <= 0) {
+    return GetLastError();
+  }
+
+  ws = (WCHAR*) uv__malloc(ws_len * sizeof(WCHAR));
+  if (ws == NULL) {
+    return ERROR_OUTOFMEMORY;
+  }
+
+  r = MultiByteToWideChar(CP_UTF8,
+                          0,
+                          s,
+                          -1,
+                          ws,
+                          ws_len);
+  assert(r == ws_len);
+
+  *ws_ptr = ws;
+  return 0;
+}
+
+
+static void uv_process_init(uv_loop_t* loop, uv_process_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_PROCESS);
+  handle->exit_cb = NULL;
+  handle->pid = 0;
+  handle->exit_signal = 0;
+  handle->wait_handle = INVALID_HANDLE_VALUE;
+  handle->process_handle = INVALID_HANDLE_VALUE;
+  handle->child_stdio_buffer = NULL;
+  handle->exit_cb_pending = 0;
+
+  UV_REQ_INIT(&handle->exit_req, UV_PROCESS_EXIT);
+  handle->exit_req.data = handle;
+}
+
+
+/*
+ * Path search functions
+ */
+
+/*
+ * Helper function for search_path
+ */
+static WCHAR* search_path_join_test(const WCHAR* dir,
+                                    size_t dir_len,
+                                    const WCHAR* name,
+                                    size_t name_len,
+                                    const WCHAR* ext,
+                                    size_t ext_len,
+                                    const WCHAR* cwd,
+                                    size_t cwd_len) {
+  WCHAR *result, *result_pos;
+  DWORD attrs;
+  if (dir_len > 2 && dir[0] == L'\\' && dir[1] == L'\\') {
+    /* It's a UNC path so ignore cwd */
+    cwd_len = 0;
+  } else if (dir_len >= 1 && (dir[0] == L'/' || dir[0] == L'\\')) {
+    /* It's a full path without drive letter, use cwd's drive letter only */
+    cwd_len = 2;
+  } else if (dir_len >= 2 && dir[1] == L':' &&
+      (dir_len < 3 || (dir[2] != L'/' && dir[2] != L'\\'))) {
+    /* It's a relative path with drive letter (ext.g. D:../some/file)
+     * Replace drive letter in dir by full cwd if it points to the same drive,
+     * otherwise use the dir only.
+     */
+    if (cwd_len < 2 || _wcsnicmp(cwd, dir, 2) != 0) {
+      cwd_len = 0;
+    } else {
+      dir += 2;
+      dir_len -= 2;
+    }
+  } else if (dir_len > 2 && dir[1] == L':') {
+    /* It's an absolute path with drive letter
+     * Don't use the cwd at all
+     */
+    cwd_len = 0;
+  }
+
+  /* Allocate buffer for output */
+  result = result_pos = (WCHAR*)uv__malloc(sizeof(WCHAR) *
+      (cwd_len + 1 + dir_len + 1 + name_len + 1 + ext_len + 1));
+
+  /* Copy cwd */
+  wcsncpy(result_pos, cwd, cwd_len);
+  result_pos += cwd_len;
+
+  /* Add a path separator if cwd didn't end with one */
+  if (cwd_len && wcsrchr(L"\\/:", result_pos[-1]) == NULL) {
+    result_pos[0] = L'\\';
+    result_pos++;
+  }
+
+  /* Copy dir */
+  wcsncpy(result_pos, dir, dir_len);
+  result_pos += dir_len;
+
+  /* Add a separator if the dir didn't end with one */
+  if (dir_len && wcsrchr(L"\\/:", result_pos[-1]) == NULL) {
+    result_pos[0] = L'\\';
+    result_pos++;
+  }
+
+  /* Copy filename */
+  wcsncpy(result_pos, name, name_len);
+  result_pos += name_len;
+
+  if (ext_len) {
+    /* Add a dot if the filename didn't end with one */
+    if (name_len && result_pos[-1] != '.') {
+      result_pos[0] = L'.';
+      result_pos++;
+    }
+
+    /* Copy extension */
+    wcsncpy(result_pos, ext, ext_len);
+    result_pos += ext_len;
+  }
+
+  /* Null terminator */
+  result_pos[0] = L'\0';
+
+  attrs = GetFileAttributesW(result);
+
+  if (attrs != INVALID_FILE_ATTRIBUTES &&
+      !(attrs & FILE_ATTRIBUTE_DIRECTORY)) {
+    return result;
+  }
+
+  uv__free(result);
+  return NULL;
+}
+
+
+/*
+ * Helper function for search_path
+ */
+static WCHAR* path_search_walk_ext(const WCHAR *dir,
+                                   size_t dir_len,
+                                   const WCHAR *name,
+                                   size_t name_len,
+                                   WCHAR *cwd,
+                                   size_t cwd_len,
+                                   int name_has_ext) {
+  WCHAR* result;
+
+  /* If the name itself has a nonempty extension, try this extension first */
+  if (name_has_ext) {
+    result = search_path_join_test(dir, dir_len,
+                                   name, name_len,
+                                   L"", 0,
+                                   cwd, cwd_len);
+    if (result != NULL) {
+      return result;
+    }
+  }
+
+  /* Try .com extension */
+  result = search_path_join_test(dir, dir_len,
+                                 name, name_len,
+                                 L"com", 3,
+                                 cwd, cwd_len);
+  if (result != NULL) {
+    return result;
+  }
+
+  /* Try .exe extension */
+  result = search_path_join_test(dir, dir_len,
+                                 name, name_len,
+                                 L"exe", 3,
+                                 cwd, cwd_len);
+  if (result != NULL) {
+    return result;
+  }
+
+  return NULL;
+}
+
+
+/*
+ * search_path searches the system path for an executable filename -
+ * the windows API doesn't provide this as a standalone function nor as an
+ * option to CreateProcess.
+ *
+ * It tries to return an absolute filename.
+ *
+ * Furthermore, it tries to follow the semantics that cmd.exe, with this
+ * exception that PATHEXT environment variable isn't used. Since CreateProcess
+ * can start only .com and .exe files, only those extensions are tried. This
+ * behavior equals that of msvcrt's spawn functions.
+ *
+ * - Do not search the path if the filename already contains a path (either
+ *   relative or absolute).
+ *
+ * - If there's really only a filename, check the current directory for file,
+ *   then search all path directories.
+ *
+ * - If filename specified has *any* extension, search for the file with the
+ *   specified extension first.
+ *
+ * - If the literal filename is not found in a directory, try *appending*
+ *   (not replacing) .com first and then .exe.
+ *
+ * - The path variable may contain relative paths; relative paths are relative
+ *   to the cwd.
+ *
+ * - Directories in path may or may not end with a trailing backslash.
+ *
+ * - CMD does not trim leading/trailing whitespace from path/pathex entries
+ *   nor from the environment variables as a whole.
+ *
+ * - When cmd.exe cannot read a directory, it will just skip it and go on
+ *   searching. However, unlike posix-y systems, it will happily try to run a
+ *   file that is not readable/executable; if the spawn fails it will not
+ *   continue searching.
+ *
+ * UNC path support: we are dealing with UNC paths in both the path and the
+ * filename. This is a deviation from what cmd.exe does (it does not let you
+ * start a program by specifying an UNC path on the command line) but this is
+ * really a pointless restriction.
+ *
+ */
+static WCHAR* search_path(const WCHAR *file,
+                            WCHAR *cwd,
+                            const WCHAR *path) {
+  int file_has_dir;
+  WCHAR* result = NULL;
+  WCHAR *file_name_start;
+  WCHAR *dot;
+  const WCHAR *dir_start, *dir_end, *dir_path;
+  size_t dir_len;
+  int name_has_ext;
+
+  size_t file_len = wcslen(file);
+  size_t cwd_len = wcslen(cwd);
+
+  /* If the caller supplies an empty filename,
+   * we're not gonna return c:\windows\.exe -- GFY!
+   */
+  if (file_len == 0
+      || (file_len == 1 && file[0] == L'.')) {
+    return NULL;
+  }
+
+  /* Find the start of the filename so we can split the directory from the
+   * name. */
+  for (file_name_start = (WCHAR*)file + file_len;
+       file_name_start > file
+           && file_name_start[-1] != L'\\'
+           && file_name_start[-1] != L'/'
+           && file_name_start[-1] != L':';
+       file_name_start--);
+
+  file_has_dir = file_name_start != file;
+
+  /* Check if the filename includes an extension */
+  dot = wcschr(file_name_start, L'.');
+  name_has_ext = (dot != NULL && dot[1] != L'\0');
+
+  if (file_has_dir) {
+    /* The file has a path inside, don't use path */
+    result = path_search_walk_ext(
+        file, file_name_start - file,
+        file_name_start, file_len - (file_name_start - file),
+        cwd, cwd_len,
+        name_has_ext);
+
+  } else {
+    dir_end = path;
+
+    /* The file is really only a name; look in cwd first, then scan path */
+    result = path_search_walk_ext(L"", 0,
+                                  file, file_len,
+                                  cwd, cwd_len,
+                                  name_has_ext);
+
+    while (result == NULL) {
+      if (*dir_end == L'\0') {
+        break;
+      }
+
+      /* Skip the separator that dir_end now points to */
+      if (dir_end != path || *path == L';') {
+        dir_end++;
+      }
+
+      /* Next slice starts just after where the previous one ended */
+      dir_start = dir_end;
+
+      /* If path is quoted, find quote end */
+      if (*dir_start == L'"' || *dir_start == L'\'') {
+        dir_end = wcschr(dir_start + 1, *dir_start);
+        if (dir_end == NULL) {
+          dir_end = wcschr(dir_start, L'\0');
+        }
+      }
+      /* Slice until the next ; or \0 is found */
+      dir_end = wcschr(dir_end, L';');
+      if (dir_end == NULL) {
+        dir_end = wcschr(dir_start, L'\0');
+      }
+
+      /* If the slice is zero-length, don't bother */
+      if (dir_end - dir_start == 0) {
+        continue;
+      }
+
+      dir_path = dir_start;
+      dir_len = dir_end - dir_start;
+
+      /* Adjust if the path is quoted. */
+      if (dir_path[0] == '"' || dir_path[0] == '\'') {
+        ++dir_path;
+        --dir_len;
+      }
+
+      if (dir_path[dir_len - 1] == '"' || dir_path[dir_len - 1] == '\'') {
+        --dir_len;
+      }
+
+      result = path_search_walk_ext(dir_path, dir_len,
+                                    file, file_len,
+                                    cwd, cwd_len,
+                                    name_has_ext);
+    }
+  }
+
+  return result;
+}
+
+
+/*
+ * Quotes command line arguments
+ * Returns a pointer to the end (next char to be written) of the buffer
+ */
+WCHAR* quote_cmd_arg(const WCHAR *source, WCHAR *target) {
+  size_t len = wcslen(source);
+  size_t i;
+  int quote_hit;
+  WCHAR* start;
+
+  if (len == 0) {
+    /* Need double quotation for empty argument */
+    *(target++) = L'"';
+    *(target++) = L'"';
+    return target;
+  }
+
+  if (NULL == wcspbrk(source, L" \t\"")) {
+    /* No quotation needed */
+    wcsncpy(target, source, len);
+    target += len;
+    return target;
+  }
+
+  if (NULL == wcspbrk(source, L"\"\\")) {
+    /*
+     * No embedded double quotes or backlashes, so I can just wrap
+     * quote marks around the whole thing.
+     */
+    *(target++) = L'"';
+    wcsncpy(target, source, len);
+    target += len;
+    *(target++) = L'"';
+    return target;
+  }
+
+  /*
+   * Expected input/output:
+   *   input : hello"world
+   *   output: "hello\"world"
+   *   input : hello""world
+   *   output: "hello\"\"world"
+   *   input : hello\world
+   *   output: hello\world
+   *   input : hello\\world
+   *   output: hello\\world
+   *   input : hello\"world
+   *   output: "hello\\\"world"
+   *   input : hello\\"world
+   *   output: "hello\\\\\"world"
+   *   input : hello world\
+   *   output: "hello world\\"
+   */
+
+  *(target++) = L'"';
+  start = target;
+  quote_hit = 1;
+
+  for (i = len; i > 0; --i) {
+    *(target++) = source[i - 1];
+
+    if (quote_hit && source[i - 1] == L'\\') {
+      *(target++) = L'\\';
+    } else if(source[i - 1] == L'"') {
+      quote_hit = 1;
+      *(target++) = L'\\';
+    } else {
+      quote_hit = 0;
+    }
+  }
+  target[0] = L'\0';
+  wcsrev(start);
+  *(target++) = L'"';
+  return target;
+}
+
+
+int make_program_args(char** args, int verbatim_arguments, WCHAR** dst_ptr) {
+  char** arg;
+  WCHAR* dst = NULL;
+  WCHAR* temp_buffer = NULL;
+  size_t dst_len = 0;
+  size_t temp_buffer_len = 0;
+  WCHAR* pos;
+  int arg_count = 0;
+  int err = 0;
+
+  /* Count the required size. */
+  for (arg = args; *arg; arg++) {
+    DWORD arg_len;
+
+    arg_len = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  *arg,
+                                  -1,
+                                  NULL,
+                                  0);
+    if (arg_len == 0) {
+      return GetLastError();
+    }
+
+    dst_len += arg_len;
+
+    if (arg_len > temp_buffer_len)
+      temp_buffer_len = arg_len;
+
+    arg_count++;
+  }
+
+  /* Adjust for potential quotes. Also assume the worst-case scenario that
+   * every character needs escaping, so we need twice as much space. */
+  dst_len = dst_len * 2 + arg_count * 2;
+
+  /* Allocate buffer for the final command line. */
+  dst = (WCHAR*) uv__malloc(dst_len * sizeof(WCHAR));
+  if (dst == NULL) {
+    err = ERROR_OUTOFMEMORY;
+    goto error;
+  }
+
+  /* Allocate temporary working buffer. */
+  temp_buffer = (WCHAR*) uv__malloc(temp_buffer_len * sizeof(WCHAR));
+  if (temp_buffer == NULL) {
+    err = ERROR_OUTOFMEMORY;
+    goto error;
+  }
+
+  pos = dst;
+  for (arg = args; *arg; arg++) {
+    DWORD arg_len;
+
+    /* Convert argument to wide char. */
+    arg_len = MultiByteToWideChar(CP_UTF8,
+                                  0,
+                                  *arg,
+                                  -1,
+                                  temp_buffer,
+                                  (int) (dst + dst_len - pos));
+    if (arg_len == 0) {
+      err = GetLastError();
+      goto error;
+    }
+
+    if (verbatim_arguments) {
+      /* Copy verbatim. */
+      wcscpy(pos, temp_buffer);
+      pos += arg_len - 1;
+    } else {
+      /* Quote/escape, if needed. */
+      pos = quote_cmd_arg(temp_buffer, pos);
+    }
+
+    *pos++ = *(arg + 1) ? L' ' : L'\0';
+  }
+
+  uv__free(temp_buffer);
+
+  *dst_ptr = dst;
+  return 0;
+
+error:
+  uv__free(dst);
+  uv__free(temp_buffer);
+  return err;
+}
+
+
+int env_strncmp(const wchar_t* a, int na, const wchar_t* b) {
+  const wchar_t* a_eq;
+  const wchar_t* b_eq;
+  wchar_t* A;
+  wchar_t* B;
+  int nb;
+  int r;
+
+  if (na < 0) {
+    a_eq = wcschr(a, L'=');
+    assert(a_eq);
+    na = (int)(long)(a_eq - a);
+  } else {
+    na--;
+  }
+  b_eq = wcschr(b, L'=');
+  assert(b_eq);
+  nb = b_eq - b;
+
+  A = (wchar_t*)alloca((na+1) * sizeof(wchar_t));
+  B = (wchar_t*)alloca((nb+1) * sizeof(wchar_t));
+
+  r = LCMapStringW(LOCALE_INVARIANT, LCMAP_UPPERCASE, a, na, A, na);
+  assert(r==na);
+  A[na] = L'\0';
+  r = LCMapStringW(LOCALE_INVARIANT, LCMAP_UPPERCASE, b, nb, B, nb);
+  assert(r==nb);
+  B[nb] = L'\0';
+
+  while (1) {
+    wchar_t AA = *A++;
+    wchar_t BB = *B++;
+    if (AA < BB) {
+      return -1;
+    } else if (AA > BB) {
+      return 1;
+    } else if (!AA && !BB) {
+      return 0;
+    }
+  }
+}
+
+
+static int qsort_wcscmp(const void *a, const void *b) {
+  wchar_t* astr = *(wchar_t* const*)a;
+  wchar_t* bstr = *(wchar_t* const*)b;
+  return env_strncmp(astr, -1, bstr);
+}
+
+
+/*
+ * The way windows takes environment variables is different than what C does;
+ * Windows wants a contiguous block of null-terminated strings, terminated
+ * with an additional null.
+ *
+ * Windows has a few "essential" environment variables. winsock will fail
+ * to initialize if SYSTEMROOT is not defined; some APIs make reference to
+ * TEMP. SYSTEMDRIVE is probably also important. We therefore ensure that
+ * these get defined if the input environment block does not contain any
+ * values for them.
+ *
+ * Also add variables known to Cygwin to be required for correct
+ * subprocess operation in many cases:
+ * https://github.com/Alexpux/Cygwin/blob/b266b04fbbd3a595f02ea149e4306d3ab9b1fe3d/winsup/cygwin/environ.cc#L955
+ *
+ */
+int make_program_env(char* env_block[], WCHAR** dst_ptr) {
+  WCHAR* dst;
+  WCHAR* ptr;
+  char** env;
+  size_t env_len = 0;
+  int len;
+  size_t i;
+  DWORD var_size;
+  size_t env_block_count = 1; /* 1 for null-terminator */
+  WCHAR* dst_copy;
+  WCHAR** ptr_copy;
+  WCHAR** env_copy;
+  DWORD* required_vars_value_len =
+      (DWORD*)alloca(n_required_vars * sizeof(DWORD*));
+
+  /* first pass: determine size in UTF-16 */
+  for (env = env_block; *env; env++) {
+    int len;
+    if (strchr(*env, '=')) {
+      len = MultiByteToWideChar(CP_UTF8,
+                                0,
+                                *env,
+                                -1,
+                                NULL,
+                                0);
+      if (len <= 0) {
+        return GetLastError();
+      }
+      env_len += len;
+      env_block_count++;
+    }
+  }
+
+  /* second pass: copy to UTF-16 environment block */
+  dst_copy = (WCHAR*)uv__malloc(env_len * sizeof(WCHAR));
+  if (!dst_copy) {
+    return ERROR_OUTOFMEMORY;
+  }
+  env_copy = (WCHAR**)alloca(env_block_count * sizeof(WCHAR*));
+
+  ptr = dst_copy;
+  ptr_copy = env_copy;
+  for (env = env_block; *env; env++) {
+    if (strchr(*env, '=')) {
+      len = MultiByteToWideChar(CP_UTF8,
+                                0,
+                                *env,
+                                -1,
+                                ptr,
+                                (int) (env_len - (ptr - dst_copy)));
+      if (len <= 0) {
+        DWORD err = GetLastError();
+        uv__free(dst_copy);
+        return err;
+      }
+      *ptr_copy++ = ptr;
+      ptr += len;
+    }
+  }
+  *ptr_copy = NULL;
+  assert(env_len == ptr - dst_copy);
+
+  /* sort our (UTF-16) copy */
+  qsort(env_copy, env_block_count-1, sizeof(wchar_t*), qsort_wcscmp);
+
+  /* third pass: check for required variables */
+  for (ptr_copy = env_copy, i = 0; i < n_required_vars; ) {
+    int cmp;
+    if (!*ptr_copy) {
+      cmp = -1;
+    } else {
+      cmp = env_strncmp(required_vars[i].wide_eq,
+                       required_vars[i].len,
+                        *ptr_copy);
+    }
+    if (cmp < 0) {
+      /* missing required var */
+      var_size = GetEnvironmentVariableW(required_vars[i].wide, NULL, 0);
+      required_vars_value_len[i] = var_size;
+      if (var_size != 0) {
+        env_len += required_vars[i].len;
+        env_len += var_size;
+      }
+      i++;
+    } else {
+      ptr_copy++;
+      if (cmp == 0)
+        i++;
+    }
+  }
+
+  /* final pass: copy, in sort order, and inserting required variables */
+  dst = (WCHAR*)uv__malloc((1+env_len) * sizeof(WCHAR));
+  if (!dst) {
+    uv__free(dst_copy);
+    return ERROR_OUTOFMEMORY;
+  }
+
+  for (ptr = dst, ptr_copy = env_copy, i = 0;
+       *ptr_copy || i < n_required_vars;
+       ptr += len) {
+    int cmp;
+    if (i >= n_required_vars) {
+      cmp = 1;
+    } else if (!*ptr_copy) {
+      cmp = -1;
+    } else {
+      cmp = env_strncmp(required_vars[i].wide_eq,
+                        required_vars[i].len,
+                        *ptr_copy);
+    }
+    if (cmp < 0) {
+      /* missing required var */
+      len = required_vars_value_len[i];
+      if (len) {
+        wcscpy(ptr, required_vars[i].wide_eq);
+        ptr += required_vars[i].len;
+        var_size = GetEnvironmentVariableW(required_vars[i].wide,
+                                           ptr,
+                                           (int) (env_len - (ptr - dst)));
+        if (var_size != len-1) { /* race condition? */
+          uv_fatal_error(GetLastError(), "GetEnvironmentVariableW");
+        }
+      }
+      i++;
+    } else {
+      /* copy var from env_block */
+      len = wcslen(*ptr_copy) + 1;
+      wmemcpy(ptr, *ptr_copy, len);
+      ptr_copy++;
+      if (cmp == 0)
+        i++;
+    }
+  }
+
+  /* Terminate with an extra NULL. */
+  assert(env_len == (ptr - dst));
+  *ptr = L'\0';
+
+  uv__free(dst_copy);
+  *dst_ptr = dst;
+  return 0;
+}
+
+/*
+ * Attempt to find the value of the PATH environment variable in the child's
+ * preprocessed environment.
+ *
+ * If found, a pointer into `env` is returned. If not found, NULL is returned.
+ */
+static WCHAR* find_path(WCHAR *env) {
+  for (; env != NULL && *env != 0; env += wcslen(env) + 1) {
+    if ((env[0] == L'P' || env[0] == L'p') &&
+        (env[1] == L'A' || env[1] == L'a') &&
+        (env[2] == L'T' || env[2] == L't') &&
+        (env[3] == L'H' || env[3] == L'h') &&
+        (env[4] == L'=')) {
+      return &env[5];
+    }
+  }
+
+  return NULL;
+}
+
+/*
+ * Called on Windows thread-pool thread to indicate that
+ * a child process has exited.
+ */
+static void CALLBACK exit_wait_callback(void* data, BOOLEAN didTimeout) {
+  uv_process_t* process = (uv_process_t*) data;
+  uv_loop_t* loop = process->loop;
+
+  assert(didTimeout == FALSE);
+  assert(process);
+  assert(!process->exit_cb_pending);
+
+  process->exit_cb_pending = 1;
+
+  /* Post completed */
+  POST_COMPLETION_FOR_REQ(loop, &process->exit_req);
+}
+
+
+/* Called on main thread after a child process has exited. */
+void uv_process_proc_exit(uv_loop_t* loop, uv_process_t* handle) {
+  int64_t exit_code;
+  DWORD status;
+
+  assert(handle->exit_cb_pending);
+  handle->exit_cb_pending = 0;
+
+  /* If we're closing, don't call the exit callback. Just schedule a close
+   * callback now. */
+  if (handle->flags & UV__HANDLE_CLOSING) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+    return;
+  }
+
+  /* Unregister from process notification. */
+  if (handle->wait_handle != INVALID_HANDLE_VALUE) {
+    UnregisterWait(handle->wait_handle);
+    handle->wait_handle = INVALID_HANDLE_VALUE;
+  }
+
+  /* Set the handle to inactive: no callbacks will be made after the exit
+   * callback. */
+  uv__handle_stop(handle);
+
+  if (GetExitCodeProcess(handle->process_handle, &status)) {
+    exit_code = status;
+  } else {
+    /* Unable to obtain the exit code. This should never happen. */
+    exit_code = uv_translate_sys_error(GetLastError());
+  }
+
+  /* Fire the exit callback. */
+  if (handle->exit_cb) {
+    handle->exit_cb(handle, exit_code, handle->exit_signal);
+  }
+}
+
+
+void uv_process_close(uv_loop_t* loop, uv_process_t* handle) {
+  uv__handle_closing(handle);
+
+  if (handle->wait_handle != INVALID_HANDLE_VALUE) {
+    /* This blocks until either the wait was cancelled, or the callback has
+     * completed. */
+    BOOL r = UnregisterWaitEx(handle->wait_handle, INVALID_HANDLE_VALUE);
+    if (!r) {
+      /* This should never happen, and if it happens, we can't recover... */
+      uv_fatal_error(GetLastError(), "UnregisterWaitEx");
+    }
+
+    handle->wait_handle = INVALID_HANDLE_VALUE;
+  }
+
+  if (!handle->exit_cb_pending) {
+    uv_want_endgame(loop, (uv_handle_t*)handle);
+  }
+}
+
+
+void uv_process_endgame(uv_loop_t* loop, uv_process_t* handle) {
+  assert(!handle->exit_cb_pending);
+  assert(handle->flags & UV__HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+  /* Clean-up the process handle. */
+  CloseHandle(handle->process_handle);
+
+  uv__handle_close(handle);
+}
+
+
+int uv_spawn(uv_loop_t* loop,
+             uv_process_t* process,
+             const uv_process_options_t* options) {
+  int i;
+  int err = 0;
+  WCHAR* path = NULL, *alloc_path = NULL;
+  BOOL result;
+  WCHAR* application_path = NULL, *application = NULL, *arguments = NULL,
+         *env = NULL, *cwd = NULL;
+  STARTUPINFOW startup;
+  PROCESS_INFORMATION info;
+  DWORD process_flags;
+
+  uv_process_init(loop, process);
+  process->exit_cb = options->exit_cb;
+
+  if (options->flags & (UV_PROCESS_SETGID | UV_PROCESS_SETUID)) {
+    return UV_ENOTSUP;
+  }
+
+  if (options->file == NULL ||
+      options->args == NULL) {
+    return UV_EINVAL;
+  }
+
+  assert(options->file != NULL);
+  assert(!(options->flags & ~(UV_PROCESS_DETACHED |
+                              UV_PROCESS_SETGID |
+                              UV_PROCESS_SETUID |
+                              UV_PROCESS_WINDOWS_HIDE |
+                              UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS)));
+
+  err = uv_utf8_to_utf16_alloc(options->file, &application);
+  if (err)
+    goto done;
+
+  err = make_program_args(
+      options->args,
+      options->flags & UV_PROCESS_WINDOWS_VERBATIM_ARGUMENTS,
+      &arguments);
+  if (err)
+    goto done;
+
+  if (options->env) {
+     err = make_program_env(options->env, &env);
+     if (err)
+       goto done;
+  }
+
+  if (options->cwd) {
+    /* Explicit cwd */
+    err = uv_utf8_to_utf16_alloc(options->cwd, &cwd);
+    if (err)
+      goto done;
+
+  } else {
+    /* Inherit cwd */
+    DWORD cwd_len, r;
+
+    cwd_len = GetCurrentDirectoryW(0, NULL);
+    if (!cwd_len) {
+      err = GetLastError();
+      goto done;
+    }
+
+    cwd = (WCHAR*) uv__malloc(cwd_len * sizeof(WCHAR));
+    if (cwd == NULL) {
+      err = ERROR_OUTOFMEMORY;
+      goto done;
+    }
+
+    r = GetCurrentDirectoryW(cwd_len, cwd);
+    if (r == 0 || r >= cwd_len) {
+      err = GetLastError();
+      goto done;
+    }
+  }
+
+  /* Get PATH environment variable. */
+  path = find_path(env);
+  if (path == NULL) {
+    DWORD path_len, r;
+
+    path_len = GetEnvironmentVariableW(L"PATH", NULL, 0);
+    if (path_len == 0) {
+      err = GetLastError();
+      goto done;
+    }
+
+    alloc_path = (WCHAR*) uv__malloc(path_len * sizeof(WCHAR));
+    if (alloc_path == NULL) {
+      err = ERROR_OUTOFMEMORY;
+      goto done;
+    }
+    path = alloc_path;
+
+    r = GetEnvironmentVariableW(L"PATH", path, path_len);
+    if (r == 0 || r >= path_len) {
+      err = GetLastError();
+      goto done;
+    }
+  }
+
+  err = uv__stdio_create(loop, options, &process->child_stdio_buffer);
+  if (err)
+    goto done;
+
+  application_path = search_path(application,
+                                 cwd,
+                                 path);
+  if (application_path == NULL) {
+    /* Not found. */
+    err = ERROR_FILE_NOT_FOUND;
+    goto done;
+  }
+
+  startup.cb = sizeof(startup);
+  startup.lpReserved = NULL;
+  startup.lpDesktop = NULL;
+  startup.lpTitle = NULL;
+  startup.dwFlags = STARTF_USESTDHANDLES | STARTF_USESHOWWINDOW;
+
+  startup.cbReserved2 = uv__stdio_size(process->child_stdio_buffer);
+  startup.lpReserved2 = (BYTE*) process->child_stdio_buffer;
+
+  startup.hStdInput = uv__stdio_handle(process->child_stdio_buffer, 0);
+  startup.hStdOutput = uv__stdio_handle(process->child_stdio_buffer, 1);
+  startup.hStdError = uv__stdio_handle(process->child_stdio_buffer, 2);
+
+  process_flags = CREATE_UNICODE_ENVIRONMENT;
+
+  if (options->flags & UV_PROCESS_WINDOWS_HIDE) {
+    /* Avoid creating console window if stdio is not inherited. */
+    for (i = 0; i < options->stdio_count; i++) {
+      if (options->stdio[i].flags & UV_INHERIT_FD)
+        break;
+      if (i == options->stdio_count - 1)
+        process_flags |= CREATE_NO_WINDOW;
+    }
+
+    /* Use SW_HIDE to avoid any potential process window. */
+    startup.wShowWindow = SW_HIDE;
+  } else {
+    startup.wShowWindow = SW_SHOWDEFAULT;
+  }
+
+  if (options->flags & UV_PROCESS_DETACHED) {
+    /* Note that we're not setting the CREATE_BREAKAWAY_FROM_JOB flag. That
+     * means that libuv might not let you create a fully daemonized process
+     * when run under job control. However the type of job control that libuv
+     * itself creates doesn't trickle down to subprocesses so they can still
+     * daemonize.
+     *
+     * A reason to not do this is that CREATE_BREAKAWAY_FROM_JOB makes the
+     * CreateProcess call fail if we're under job control that doesn't allow
+     * breakaway.
+     */
+    process_flags |= DETACHED_PROCESS | CREATE_NEW_PROCESS_GROUP;
+  }
+
+  if (!CreateProcessW(application_path,
+                     arguments,
+                     NULL,
+                     NULL,
+                     1,
+                     process_flags,
+                     env,
+                     cwd,
+                     &startup,
+                     &info)) {
+    /* CreateProcessW failed. */
+    err = GetLastError();
+    goto done;
+  }
+
+  /* Spawn succeeded. Beyond this point, failure is reported asynchronously. */
+
+  process->process_handle = info.hProcess;
+  process->pid = info.dwProcessId;
+
+  /* If the process isn't spawned as detached, assign to the global job object
+   * so windows will kill it when the parent process dies. */
+  if (!(options->flags & UV_PROCESS_DETACHED)) {
+    uv_once(&uv_global_job_handle_init_guard_, uv__init_global_job_handle);
+
+    if (!AssignProcessToJobObject(uv_global_job_handle_, info.hProcess)) {
+      /* AssignProcessToJobObject might fail if this process is under job
+       * control and the job doesn't have the
+       * JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK flag set, on a Windows version
+       * that doesn't support nested jobs.
+       *
+       * When that happens we just swallow the error and continue without
+       * establishing a kill-child-on-parent-exit relationship, otherwise
+       * there would be no way for libuv applications run under job control
+       * to spawn processes at all.
+       */
+      DWORD err = GetLastError();
+      if (err != ERROR_ACCESS_DENIED)
+        uv_fatal_error(err, "AssignProcessToJobObject");
+    }
+  }
+
+  /* Set IPC pid to all IPC pipes. */
+  for (i = 0; i < options->stdio_count; i++) {
+    const uv_stdio_container_t* fdopt = &options->stdio[i];
+    if (fdopt->flags & UV_CREATE_PIPE &&
+        fdopt->data.stream->type == UV_NAMED_PIPE &&
+        ((uv_pipe_t*) fdopt->data.stream)->ipc) {
+      ((uv_pipe_t*) fdopt->data.stream)->pipe.conn.ipc_remote_pid =
+          info.dwProcessId;
+    }
+  }
+
+  /* Setup notifications for when the child process exits. */
+  result = RegisterWaitForSingleObject(&process->wait_handle,
+      process->process_handle, exit_wait_callback, (void*)process, INFINITE,
+      WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE);
+  if (!result) {
+    uv_fatal_error(GetLastError(), "RegisterWaitForSingleObject");
+  }
+
+  CloseHandle(info.hThread);
+
+  assert(!err);
+
+  /* Make the handle active. It will remain active until the exit callback is
+   * made or the handle is closed, whichever happens first. */
+  uv__handle_start(process);
+
+  /* Cleanup, whether we succeeded or failed. */
+ done:
+  uv__free(application);
+  uv__free(application_path);
+  uv__free(arguments);
+  uv__free(cwd);
+  uv__free(env);
+  uv__free(alloc_path);
+
+  if (process->child_stdio_buffer != NULL) {
+    /* Clean up child stdio handles. */
+    uv__stdio_destroy(process->child_stdio_buffer);
+    process->child_stdio_buffer = NULL;
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+static int uv__kill(HANDLE process_handle, int signum) {
+  if (signum < 0 || signum >= NSIG) {
+    return UV_EINVAL;
+  }
+
+  switch (signum) {
+    case SIGTERM:
+    case SIGKILL:
+    case SIGINT: {
+      /* Unconditionally terminate the process. On Windows, killed processes
+       * normally return 1. */
+      DWORD status;
+      int err;
+
+      if (TerminateProcess(process_handle, 1))
+        return 0;
+
+      /* If the process already exited before TerminateProcess was called,.
+       * TerminateProcess will fail with ERROR_ACCESS_DENIED. */
+      err = GetLastError();
+      if (err == ERROR_ACCESS_DENIED &&
+          GetExitCodeProcess(process_handle, &status) &&
+          status != STILL_ACTIVE) {
+        return UV_ESRCH;
+      }
+
+      return uv_translate_sys_error(err);
+    }
+
+    case 0: {
+      /* Health check: is the process still alive? */
+      DWORD status;
+
+      if (!GetExitCodeProcess(process_handle, &status))
+        return uv_translate_sys_error(GetLastError());
+
+      if (status != STILL_ACTIVE)
+        return UV_ESRCH;
+
+      return 0;
+    }
+
+    default:
+      /* Unsupported signal. */
+      return UV_ENOSYS;
+  }
+}
+
+
+int uv_process_kill(uv_process_t* process, int signum) {
+  int err;
+
+  if (process->process_handle == INVALID_HANDLE_VALUE) {
+    return UV_EINVAL;
+  }
+
+  err = uv__kill(process->process_handle, signum);
+  if (err) {
+    return err;  /* err is already translated. */
+  }
+
+  process->exit_signal = signum;
+
+  return 0;
+}
+
+
+int uv_kill(int pid, int signum) {
+  int err;
+  HANDLE process_handle;
+
+  if (pid == 0) {
+    process_handle = GetCurrentProcess();
+  } else {
+    process_handle = OpenProcess(PROCESS_TERMINATE | PROCESS_QUERY_INFORMATION,
+                                 FALSE,
+                                 pid);
+  }
+
+  if (process_handle == NULL) {
+    err = GetLastError();
+    if (err == ERROR_INVALID_PARAMETER) {
+      return UV_ESRCH;
+    } else {
+      return uv_translate_sys_error(err);
+    }
+  }
+
+  err = uv__kill(process_handle, signum);
+  CloseHandle(process_handle);
+
+  return err;  /* err is already translated. */
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/req-inl.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/req-inl.h
new file mode 100644
index 0000000..f2513b7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/req-inl.h
@@ -0,0 +1,221 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_REQ_INL_H_
+#define UV_WIN_REQ_INL_H_
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+#define SET_REQ_STATUS(req, status)                                     \
+   (req)->u.io.overlapped.Internal = (ULONG_PTR) (status)
+
+#define SET_REQ_ERROR(req, error)                                       \
+  SET_REQ_STATUS((req), NTSTATUS_FROM_WIN32((error)))
+
+/* Note: used open-coded in UV_REQ_INIT() because of a circular dependency
+ * between src/uv-common.h and src/win/internal.h.
+ */
+#define SET_REQ_SUCCESS(req)                                            \
+  SET_REQ_STATUS((req), STATUS_SUCCESS)
+
+#define GET_REQ_STATUS(req)                                             \
+  ((NTSTATUS) (req)->u.io.overlapped.Internal)
+
+#define REQ_SUCCESS(req)                                                \
+  (NT_SUCCESS(GET_REQ_STATUS((req))))
+
+#define GET_REQ_ERROR(req)                                              \
+  (pRtlNtStatusToDosError(GET_REQ_STATUS((req))))
+
+#define GET_REQ_SOCK_ERROR(req)                                         \
+  (uv_ntstatus_to_winsock_error(GET_REQ_STATUS((req))))
+
+
+#define REGISTER_HANDLE_REQ(loop, handle, req)                          \
+  do {                                                                  \
+    INCREASE_ACTIVE_COUNT((loop), (handle));                            \
+    uv__req_register((loop), (req));                                    \
+  } while (0)
+
+#define UNREGISTER_HANDLE_REQ(loop, handle, req)                        \
+  do {                                                                  \
+    DECREASE_ACTIVE_COUNT((loop), (handle));                            \
+    uv__req_unregister((loop), (req));                                  \
+  } while (0)
+
+
+#define UV_SUCCEEDED_WITHOUT_IOCP(result)                               \
+  ((result) && (handle->flags & UV_HANDLE_SYNC_BYPASS_IOCP))
+
+#define UV_SUCCEEDED_WITH_IOCP(result)                                  \
+  ((result) || (GetLastError() == ERROR_IO_PENDING))
+
+
+#define POST_COMPLETION_FOR_REQ(loop, req)                              \
+  if (!PostQueuedCompletionStatus((loop)->iocp,                         \
+                                  0,                                    \
+                                  0,                                    \
+                                  &((req)->u.io.overlapped))) {         \
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");       \
+  }
+
+
+INLINE static uv_req_t* uv_overlapped_to_req(OVERLAPPED* overlapped) {
+  return CONTAINING_RECORD(overlapped, uv_req_t, u.io.overlapped);
+}
+
+
+INLINE static void uv_insert_pending_req(uv_loop_t* loop, uv_req_t* req) {
+  req->next_req = NULL;
+  if (loop->pending_reqs_tail) {
+#ifdef _DEBUG
+    /* Ensure the request is not already in the queue, or the queue
+     * will get corrupted.
+     */
+    uv_req_t* current = loop->pending_reqs_tail;
+    do {
+      assert(req != current);
+      current = current->next_req;
+    } while(current != loop->pending_reqs_tail);
+#endif
+
+    req->next_req = loop->pending_reqs_tail->next_req;
+    loop->pending_reqs_tail->next_req = req;
+    loop->pending_reqs_tail = req;
+  } else {
+    req->next_req = req;
+    loop->pending_reqs_tail = req;
+  }
+}
+
+
+#define DELEGATE_STREAM_REQ(loop, req, method, handle_at)                     \
+  do {                                                                        \
+    switch (((uv_handle_t*) (req)->handle_at)->type) {                        \
+      case UV_TCP:                                                            \
+        uv_process_tcp_##method##_req(loop,                                   \
+                                      (uv_tcp_t*) ((req)->handle_at),         \
+                                      req);                                   \
+        break;                                                                \
+                                                                              \
+      case UV_NAMED_PIPE:                                                     \
+        uv_process_pipe_##method##_req(loop,                                  \
+                                       (uv_pipe_t*) ((req)->handle_at),       \
+                                       req);                                  \
+        break;                                                                \
+                                                                              \
+      case UV_TTY:                                                            \
+        uv_process_tty_##method##_req(loop,                                   \
+                                      (uv_tty_t*) ((req)->handle_at),         \
+                                      req);                                   \
+        break;                                                                \
+                                                                              \
+      default:                                                                \
+        assert(0);                                                            \
+    }                                                                         \
+  } while (0)
+
+
+INLINE static int uv_process_reqs(uv_loop_t* loop) {
+  uv_req_t* req;
+  uv_req_t* first;
+  uv_req_t* next;
+
+  if (loop->pending_reqs_tail == NULL)
+    return 0;
+
+  first = loop->pending_reqs_tail->next_req;
+  next = first;
+  loop->pending_reqs_tail = NULL;
+
+  while (next != NULL) {
+    req = next;
+    next = req->next_req != first ? req->next_req : NULL;
+
+    switch (req->type) {
+      case UV_READ:
+        DELEGATE_STREAM_REQ(loop, req, read, data);
+        break;
+
+      case UV_WRITE:
+        DELEGATE_STREAM_REQ(loop, (uv_write_t*) req, write, handle);
+        break;
+
+      case UV_ACCEPT:
+        DELEGATE_STREAM_REQ(loop, req, accept, data);
+        break;
+
+      case UV_CONNECT:
+        DELEGATE_STREAM_REQ(loop, (uv_connect_t*) req, connect, handle);
+        break;
+
+      case UV_SHUTDOWN:
+        /* Tcp shutdown requests don't come here. */
+        assert(((uv_shutdown_t*) req)->handle->type == UV_NAMED_PIPE);
+        uv_process_pipe_shutdown_req(
+            loop,
+            (uv_pipe_t*) ((uv_shutdown_t*) req)->handle,
+            (uv_shutdown_t*) req);
+        break;
+
+      case UV_UDP_RECV:
+        uv_process_udp_recv_req(loop, (uv_udp_t*) req->data, req);
+        break;
+
+      case UV_UDP_SEND:
+        uv_process_udp_send_req(loop,
+                                ((uv_udp_send_t*) req)->handle,
+                                (uv_udp_send_t*) req);
+        break;
+
+      case UV_WAKEUP:
+        uv_process_async_wakeup_req(loop, (uv_async_t*) req->data, req);
+        break;
+
+      case UV_SIGNAL_REQ:
+        uv_process_signal_req(loop, (uv_signal_t*) req->data, req);
+        break;
+
+      case UV_POLL_REQ:
+        uv_process_poll_req(loop, (uv_poll_t*) req->data, req);
+        break;
+
+      case UV_PROCESS_EXIT:
+        uv_process_proc_exit(loop, (uv_process_t*) req->data);
+        break;
+
+      case UV_FS_EVENT_REQ:
+        uv_process_fs_event_req(loop, req, (uv_fs_event_t*) req->data);
+        break;
+
+      default:
+        assert(0);
+    }
+  }
+
+  return 1;
+}
+
+#endif /* UV_WIN_REQ_INL_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/req.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/req.cpp
new file mode 100644
index 0000000..111cc5e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/req.cpp
@@ -0,0 +1,25 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/signal.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/signal.cpp
new file mode 100644
index 0000000..750c1b3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/signal.cpp
@@ -0,0 +1,277 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <signal.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+RB_HEAD(uv_signal_tree_s, uv_signal_s);
+
+static struct uv_signal_tree_s uv__signal_tree = RB_INITIALIZER(uv__signal_tree);
+static CRITICAL_SECTION uv__signal_lock;
+
+static BOOL WINAPI uv__signal_control_handler(DWORD type);
+
+int uv__signal_start(uv_signal_t* handle,
+                     uv_signal_cb signal_cb,
+                     int signum,
+                     int oneshot);
+
+void uv_signals_init(void) {
+  InitializeCriticalSection(&uv__signal_lock);
+  if (!SetConsoleCtrlHandler(uv__signal_control_handler, TRUE))
+    abort();
+}
+
+
+static int uv__signal_compare(uv_signal_t* w1, uv_signal_t* w2) {
+  /* Compare signums first so all watchers with the same signnum end up
+   * adjacent. */
+  if (w1->signum < w2->signum) return -1;
+  if (w1->signum > w2->signum) return 1;
+
+  /* Sort by loop pointer, so we can easily look up the first item after
+   * { .signum = x, .loop = NULL }. */
+  if ((uintptr_t) w1->loop < (uintptr_t) w2->loop) return -1;
+  if ((uintptr_t) w1->loop > (uintptr_t) w2->loop) return 1;
+
+  if ((uintptr_t) w1 < (uintptr_t) w2) return -1;
+  if ((uintptr_t) w1 > (uintptr_t) w2) return 1;
+
+  return 0;
+}
+
+
+RB_GENERATE_STATIC(uv_signal_tree_s, uv_signal_s, tree_entry, uv__signal_compare)
+
+
+/*
+ * Dispatches signal {signum} to all active uv_signal_t watchers in all loops.
+ * Returns 1 if the signal was dispatched to any watcher, or 0 if there were
+ * no active signal watchers observing this signal.
+ */
+int uv__signal_dispatch(int signum) {
+  uv_signal_t lookup;
+  uv_signal_t* handle;
+  int dispatched;
+
+  dispatched = 0;
+
+  EnterCriticalSection(&uv__signal_lock);
+
+  lookup.signum = signum;
+  lookup.loop = NULL;
+
+  for (handle = RB_NFIND(uv_signal_tree_s, &uv__signal_tree, &lookup);
+       handle != NULL && handle->signum == signum;
+       handle = RB_NEXT(uv_signal_tree_s, &uv__signal_tree, handle)) {
+    unsigned long previous = InterlockedExchange(
+            (volatile LONG*) &handle->pending_signum, signum);
+
+    if (handle->flags & UV__SIGNAL_ONE_SHOT_DISPATCHED)
+      continue;
+
+    if (!previous) {
+      POST_COMPLETION_FOR_REQ(handle->loop, &handle->signal_req);
+    }
+
+    dispatched = 1;
+    if (handle->flags & UV__SIGNAL_ONE_SHOT)
+      handle->flags |= UV__SIGNAL_ONE_SHOT_DISPATCHED;
+  }
+
+  LeaveCriticalSection(&uv__signal_lock);
+
+  return dispatched;
+}
+
+
+static BOOL WINAPI uv__signal_control_handler(DWORD type) {
+  switch (type) {
+    case CTRL_C_EVENT:
+      return uv__signal_dispatch(SIGINT);
+
+    case CTRL_BREAK_EVENT:
+      return uv__signal_dispatch(SIGBREAK);
+
+    case CTRL_CLOSE_EVENT:
+      if (uv__signal_dispatch(SIGHUP)) {
+        /* Windows will terminate the process after the control handler
+         * returns. After that it will just terminate our process. Therefore
+         * block the signal handler so the main loop has some time to pick up
+         * the signal and do something for a few seconds. */
+        Sleep(INFINITE);
+        return TRUE;
+      }
+      return FALSE;
+
+    case CTRL_LOGOFF_EVENT:
+    case CTRL_SHUTDOWN_EVENT:
+      /* These signals are only sent to services. Services have their own
+       * notification mechanism, so there's no point in handling these. */
+
+    default:
+      /* We don't handle these. */
+      return FALSE;
+  }
+}
+
+
+int uv_signal_init(uv_loop_t* loop, uv_signal_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_SIGNAL);
+  handle->pending_signum = 0;
+  handle->signum = 0;
+  handle->signal_cb = NULL;
+
+  UV_REQ_INIT(&handle->signal_req, UV_SIGNAL_REQ);
+  handle->signal_req.data = handle;
+
+  return 0;
+}
+
+
+int uv_signal_stop(uv_signal_t* handle) {
+  uv_signal_t* removed_handle;
+
+  /* If the watcher wasn't started, this is a no-op. */
+  if (handle->signum == 0)
+    return 0;
+
+  EnterCriticalSection(&uv__signal_lock);
+
+  removed_handle = RB_REMOVE(uv_signal_tree_s, &uv__signal_tree, handle);
+  assert(removed_handle == handle);
+
+  LeaveCriticalSection(&uv__signal_lock);
+
+  handle->signum = 0;
+  uv__handle_stop(handle);
+
+  return 0;
+}
+
+
+int uv_signal_start(uv_signal_t* handle, uv_signal_cb signal_cb, int signum) {
+  return uv__signal_start(handle, signal_cb, signum, 0);
+}
+
+
+int uv_signal_start_oneshot(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum) {
+  return uv__signal_start(handle, signal_cb, signum, 1);
+}
+
+
+int uv__signal_start(uv_signal_t* handle,
+                            uv_signal_cb signal_cb,
+                            int signum,
+                            int oneshot) {
+  /* Test for invalid signal values. */
+  if (signum != SIGWINCH && (signum <= 0 || signum >= NSIG))
+    return UV_EINVAL;
+
+  /* Short circuit: if the signal watcher is already watching {signum} don't go
+   * through the process of deregistering and registering the handler.
+   * Additionally, this avoids pending signals getting lost in the (small) time
+   * frame that handle->signum == 0. */
+  if (signum == handle->signum) {
+    handle->signal_cb = signal_cb;
+    return 0;
+  }
+
+  /* If the signal handler was already active, stop it first. */
+  if (handle->signum != 0) {
+    int r = uv_signal_stop(handle);
+    /* uv_signal_stop is infallible. */
+    assert(r == 0);
+  }
+
+  EnterCriticalSection(&uv__signal_lock);
+
+  handle->signum = signum;
+  if (oneshot)
+    handle->flags |= UV__SIGNAL_ONE_SHOT;
+
+  RB_INSERT(uv_signal_tree_s, &uv__signal_tree, handle);
+
+  LeaveCriticalSection(&uv__signal_lock);
+
+  handle->signal_cb = signal_cb;
+  uv__handle_start(handle);
+
+  return 0;
+}
+
+
+void uv_process_signal_req(uv_loop_t* loop, uv_signal_t* handle,
+    uv_req_t* req) {
+  long dispatched_signum;
+
+  assert(handle->type == UV_SIGNAL);
+  assert(req->type == UV_SIGNAL_REQ);
+
+  dispatched_signum = InterlockedExchange(
+          (volatile LONG*) &handle->pending_signum, 0);
+  assert(dispatched_signum != 0);
+
+  /* Check if the pending signal equals the signum that we are watching for.
+   * These can get out of sync when the handler is stopped and restarted while
+   * the signal_req is pending. */
+  if (dispatched_signum == handle->signum)
+    handle->signal_cb(handle, dispatched_signum);
+
+  if (handle->flags & UV__SIGNAL_ONE_SHOT)
+    uv_signal_stop(handle);
+
+  if (handle->flags & UV__HANDLE_CLOSING) {
+    /* When it is closing, it must be stopped at this point. */
+    assert(handle->signum == 0);
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+void uv_signal_close(uv_loop_t* loop, uv_signal_t* handle) {
+  uv_signal_stop(handle);
+  uv__handle_closing(handle);
+
+  if (handle->pending_signum == 0) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+void uv_signal_endgame(uv_loop_t* loop, uv_signal_t* handle) {
+  assert(handle->flags & UV__HANDLE_CLOSING);
+  assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+  assert(handle->signum == 0);
+  assert(handle->pending_signum == 0);
+
+  handle->flags |= UV_HANDLE_CLOSED;
+
+  uv__handle_close(handle);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/snprintf.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/snprintf.cpp
new file mode 100644
index 0000000..776c0e3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/snprintf.cpp
@@ -0,0 +1,42 @@
+/* Copyright the libuv project contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#if defined(_MSC_VER) && _MSC_VER < 1900
+
+#include <stdio.h>
+#include <stdarg.h>
+
+/* Emulate snprintf() on MSVC<2015, _snprintf() doesn't zero-terminate the buffer
+ * on overflow...
+ */
+int snprintf(char* buf, size_t len, const char* fmt, ...) {
+  int n;
+  va_list ap;
+  va_start(ap, fmt);
+
+  n = _vscprintf(fmt, ap);
+  vsnprintf_s(buf, len, _TRUNCATE, fmt, ap);
+
+  va_end(ap);
+  return n;
+}
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/stream-inl.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/stream-inl.h
new file mode 100644
index 0000000..40f5ddd
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/stream-inl.h
@@ -0,0 +1,54 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_STREAM_INL_H_
+#define UV_WIN_STREAM_INL_H_
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+INLINE static void uv_stream_init(uv_loop_t* loop,
+                                  uv_stream_t* handle,
+                                  uv_handle_type type) {
+  uv__handle_init(loop, (uv_handle_t*) handle, type);
+  handle->write_queue_size = 0;
+  handle->activecnt = 0;
+  handle->stream.conn.shutdown_req = NULL;
+  handle->stream.conn.write_reqs_pending = 0;
+
+  UV_REQ_INIT(&handle->read_req, UV_READ);
+  handle->read_req.event_handle = NULL;
+  handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
+  handle->read_req.data = handle;
+}
+
+
+INLINE static void uv_connection_init(uv_stream_t* handle) {
+  handle->flags |= UV_HANDLE_CONNECTION;
+}
+
+
+#endif /* UV_WIN_STREAM_INL_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/stream.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/stream.cpp
new file mode 100644
index 0000000..3273a03
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/stream.cpp
@@ -0,0 +1,240 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "req-inl.h"
+
+
+int uv_listen(uv_stream_t* stream, int backlog, uv_connection_cb cb) {
+  int err;
+
+  err = ERROR_INVALID_PARAMETER;
+  switch (stream->type) {
+    case UV_TCP:
+      err = uv_tcp_listen((uv_tcp_t*)stream, backlog, cb);
+      break;
+    case UV_NAMED_PIPE:
+      err = uv_pipe_listen((uv_pipe_t*)stream, backlog, cb);
+      break;
+    default:
+      assert(0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_accept(uv_stream_t* server, uv_stream_t* client) {
+  int err;
+
+  err = ERROR_INVALID_PARAMETER;
+  switch (server->type) {
+    case UV_TCP:
+      err = uv_tcp_accept((uv_tcp_t*)server, (uv_tcp_t*)client);
+      break;
+    case UV_NAMED_PIPE:
+      err = uv_pipe_accept((uv_pipe_t*)server, client);
+      break;
+    default:
+      assert(0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_read_start(uv_stream_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb) {
+  int err;
+
+  if (handle->flags & UV_HANDLE_READING) {
+    return UV_EALREADY;
+  }
+
+  if (!(handle->flags & UV_HANDLE_READABLE)) {
+    return UV_ENOTCONN;
+  }
+
+  err = ERROR_INVALID_PARAMETER;
+  switch (handle->type) {
+    case UV_TCP:
+      err = uv_tcp_read_start((uv_tcp_t*)handle, alloc_cb, read_cb);
+      break;
+    case UV_NAMED_PIPE:
+      err = uv_pipe_read_start((uv_pipe_t*)handle, alloc_cb, read_cb);
+      break;
+    case UV_TTY:
+      err = uv_tty_read_start((uv_tty_t*) handle, alloc_cb, read_cb);
+      break;
+    default:
+      assert(0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_read_stop(uv_stream_t* handle) {
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_READING))
+    return 0;
+
+  err = 0;
+  if (handle->type == UV_TTY) {
+    err = uv_tty_read_stop((uv_tty_t*) handle);
+  } else if (handle->type == UV_NAMED_PIPE) {
+    uv__pipe_read_stop((uv_pipe_t*) handle);
+  } else {
+    handle->flags &= ~UV_HANDLE_READING;
+    DECREASE_ACTIVE_COUNT(handle->loop, handle);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_write(uv_write_t* req,
+             uv_stream_t* handle,
+             const uv_buf_t bufs[],
+             unsigned int nbufs,
+             uv_write_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_WRITABLE)) {
+    return UV_EPIPE;
+  }
+
+  err = ERROR_INVALID_PARAMETER;
+  switch (handle->type) {
+    case UV_TCP:
+      err = uv_tcp_write(loop, req, (uv_tcp_t*) handle, bufs, nbufs, cb);
+      break;
+    case UV_NAMED_PIPE:
+      err = uv__pipe_write(
+          loop, req, (uv_pipe_t*) handle, bufs, nbufs, NULL, cb);
+      break;
+    case UV_TTY:
+      err = uv_tty_write(loop, req, (uv_tty_t*) handle, bufs, nbufs, cb);
+      break;
+    default:
+      assert(0);
+  }
+
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_write2(uv_write_t* req,
+              uv_stream_t* handle,
+              const uv_buf_t bufs[],
+              unsigned int nbufs,
+              uv_stream_t* send_handle,
+              uv_write_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  int err;
+
+  if (send_handle == NULL) {
+    return uv_write(req, handle, bufs, nbufs, cb);
+  }
+
+  if (handle->type != UV_NAMED_PIPE || !((uv_pipe_t*) handle)->ipc) {
+    return UV_EINVAL;
+  } else if (!(handle->flags & UV_HANDLE_WRITABLE)) {
+    return UV_EPIPE;
+  }
+
+  err = uv__pipe_write(
+      loop, req, (uv_pipe_t*) handle, bufs, nbufs, send_handle, cb);
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_try_write(uv_stream_t* stream,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs) {
+  if (stream->flags & UV__HANDLE_CLOSING)
+    return UV_EBADF;
+  if (!(stream->flags & UV_HANDLE_WRITABLE))
+    return UV_EPIPE;
+
+  switch (stream->type) {
+    case UV_TCP:
+      return uv__tcp_try_write((uv_tcp_t*) stream, bufs, nbufs);
+    case UV_TTY:
+      return uv__tty_try_write((uv_tty_t*) stream, bufs, nbufs);
+    case UV_NAMED_PIPE:
+      return UV_EAGAIN;
+    default:
+      assert(0);
+      return UV_ENOSYS;
+  }
+}
+
+
+int uv_shutdown(uv_shutdown_t* req, uv_stream_t* handle, uv_shutdown_cb cb) {
+  uv_loop_t* loop = handle->loop;
+
+  if (!(handle->flags & UV_HANDLE_WRITABLE)) {
+    return UV_EPIPE;
+  }
+
+  UV_REQ_INIT(req, UV_SHUTDOWN);
+  req->handle = handle;
+  req->cb = cb;
+
+  handle->flags &= ~UV_HANDLE_WRITABLE;
+  handle->stream.conn.shutdown_req = req;
+  handle->reqs_pending++;
+  REGISTER_HANDLE_REQ(loop, handle, req);
+
+  uv_want_endgame(loop, (uv_handle_t*)handle);
+
+  return 0;
+}
+
+
+int uv_is_readable(const uv_stream_t* handle) {
+  return !!(handle->flags & UV_HANDLE_READABLE);
+}
+
+
+int uv_is_writable(const uv_stream_t* handle) {
+  return !!(handle->flags & UV_HANDLE_WRITABLE);
+}
+
+
+int uv_stream_set_blocking(uv_stream_t* handle, int blocking) {
+  if (handle->type != UV_NAMED_PIPE)
+    return UV_EINVAL;
+
+  if (blocking != 0)
+    handle->flags |= UV_HANDLE_BLOCKING_WRITES;
+  else
+    handle->flags &= ~UV_HANDLE_BLOCKING_WRITES;
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/tcp.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/tcp.cpp
new file mode 100644
index 0000000..38cd73e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/tcp.cpp
@@ -0,0 +1,1515 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "stream-inl.h"
+#include "req-inl.h"
+
+
+/*
+ * Threshold of active tcp streams for which to preallocate tcp read buffers.
+ * (Due to node slab allocator performing poorly under this pattern,
+ *  the optimization is temporarily disabled (threshold=0).  This will be
+ *  revisited once node allocator is improved.)
+ */
+const unsigned int uv_active_tcp_streams_threshold = 0;
+
+/*
+ * Number of simultaneous pending AcceptEx calls.
+ */
+const unsigned int uv_simultaneous_server_accepts = 32;
+
+/* A zero-size buffer for use by uv_tcp_read */
+static char uv_zero_[] = "";
+
+static int uv__tcp_nodelay(uv_tcp_t* handle, SOCKET socket, int enable) {
+  if (setsockopt(socket,
+                 IPPROTO_TCP,
+                 TCP_NODELAY,
+                 (const char*)&enable,
+                 sizeof enable) == -1) {
+    return WSAGetLastError();
+  }
+  return 0;
+}
+
+
+static int uv__tcp_keepalive(uv_tcp_t* handle, SOCKET socket, int enable, unsigned int delay) {
+  if (setsockopt(socket,
+                 SOL_SOCKET,
+                 SO_KEEPALIVE,
+                 (const char*)&enable,
+                 sizeof enable) == -1) {
+    return WSAGetLastError();
+  }
+
+  if (enable && setsockopt(socket,
+                           IPPROTO_TCP,
+                           TCP_KEEPALIVE,
+                           (const char*)&delay,
+                           sizeof delay) == -1) {
+    return WSAGetLastError();
+  }
+
+  return 0;
+}
+
+
+static int uv_tcp_set_socket(uv_loop_t* loop,
+                             uv_tcp_t* handle,
+                             SOCKET socket,
+                             int family,
+                             int imported) {
+  DWORD yes = 1;
+  int non_ifs_lsp;
+  int err;
+
+  if (handle->socket != INVALID_SOCKET)
+    return UV_EBUSY;
+
+  /* Set the socket to nonblocking mode */
+  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR) {
+    return WSAGetLastError();
+  }
+
+  /* Make the socket non-inheritable */
+  if (!SetHandleInformation((HANDLE) socket, HANDLE_FLAG_INHERIT, 0))
+    return GetLastError();
+
+  /* Associate it with the I/O completion port. Use uv_handle_t pointer as
+   * completion key. */
+  if (CreateIoCompletionPort((HANDLE)socket,
+                             loop->iocp,
+                             (ULONG_PTR)socket,
+                             0) == NULL) {
+    if (imported) {
+      handle->flags |= UV_HANDLE_EMULATE_IOCP;
+    } else {
+      return GetLastError();
+    }
+  }
+
+  if (family == AF_INET6) {
+    non_ifs_lsp = uv_tcp_non_ifs_lsp_ipv6;
+  } else {
+    non_ifs_lsp = uv_tcp_non_ifs_lsp_ipv4;
+  }
+
+  if (!(handle->flags & UV_HANDLE_EMULATE_IOCP) && !non_ifs_lsp) {
+    UCHAR sfcnm_flags =
+        FILE_SKIP_SET_EVENT_ON_HANDLE | FILE_SKIP_COMPLETION_PORT_ON_SUCCESS;
+    if (!SetFileCompletionNotificationModes((HANDLE) socket, sfcnm_flags))
+      return GetLastError();
+    handle->flags |= UV_HANDLE_SYNC_BYPASS_IOCP;
+  }
+
+  if (handle->flags & UV_HANDLE_TCP_NODELAY) {
+    err = uv__tcp_nodelay(handle, socket, 1);
+    if (err)
+      return err;
+  }
+
+  /* TODO: Use stored delay. */
+  if (handle->flags & UV_HANDLE_TCP_KEEPALIVE) {
+    err = uv__tcp_keepalive(handle, socket, 1, 60);
+    if (err)
+      return err;
+  }
+
+  handle->socket = socket;
+
+  if (family == AF_INET6) {
+    handle->flags |= UV_HANDLE_IPV6;
+  } else {
+    assert(!(handle->flags & UV_HANDLE_IPV6));
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_init_ex(uv_loop_t* loop, uv_tcp_t* handle, unsigned int flags) {
+  int domain;
+
+  /* Use the lower 8 bits for the domain */
+  domain = flags & 0xFF;
+  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
+    return UV_EINVAL;
+
+  if (flags & ~0xFF)
+    return UV_EINVAL;
+
+  uv_stream_init(loop, (uv_stream_t*) handle, UV_TCP);
+  handle->tcp.serv.accept_reqs = NULL;
+  handle->tcp.serv.pending_accepts = NULL;
+  handle->socket = INVALID_SOCKET;
+  handle->reqs_pending = 0;
+  handle->tcp.serv.func_acceptex = NULL;
+  handle->tcp.conn.func_connectex = NULL;
+  handle->tcp.serv.processed_accepts = 0;
+  handle->delayed_error = 0;
+
+  /* If anything fails beyond this point we need to remove the handle from
+   * the handle queue, since it was added by uv__handle_init in uv_stream_init.
+   */
+
+  if (domain != AF_UNSPEC) {
+    SOCKET sock;
+    DWORD err;
+
+    sock = socket(domain, SOCK_STREAM, 0);
+    if (sock == INVALID_SOCKET) {
+      err = WSAGetLastError();
+      QUEUE_REMOVE(&handle->handle_queue);
+      return uv_translate_sys_error(err);
+    }
+
+    err = uv_tcp_set_socket(handle->loop, handle, sock, domain, 0);
+    if (err) {
+      closesocket(sock);
+      QUEUE_REMOVE(&handle->handle_queue);
+      return uv_translate_sys_error(err);
+    }
+
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_init(uv_loop_t* loop, uv_tcp_t* handle) {
+  return uv_tcp_init_ex(loop, handle, AF_UNSPEC);
+}
+
+
+void uv_tcp_endgame(uv_loop_t* loop, uv_tcp_t* handle) {
+  int err;
+  unsigned int i;
+  uv_tcp_accept_t* req;
+
+  if (handle->flags & UV_HANDLE_CONNECTION &&
+      handle->stream.conn.shutdown_req != NULL &&
+      handle->stream.conn.write_reqs_pending == 0) {
+
+    UNREGISTER_HANDLE_REQ(loop, handle, handle->stream.conn.shutdown_req);
+
+    err = 0;
+    if (handle->flags & UV__HANDLE_CLOSING) {
+      err = ERROR_OPERATION_ABORTED;
+    } else if (shutdown(handle->socket, SD_SEND) == SOCKET_ERROR) {
+      err = WSAGetLastError();
+    }
+
+    if (handle->stream.conn.shutdown_req->cb) {
+      handle->stream.conn.shutdown_req->cb(handle->stream.conn.shutdown_req,
+                               uv_translate_sys_error(err));
+    }
+
+    handle->stream.conn.shutdown_req = NULL;
+    DECREASE_PENDING_REQ_COUNT(handle);
+    return;
+  }
+
+  if (handle->flags & UV__HANDLE_CLOSING &&
+      handle->reqs_pending == 0) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+
+    if (!(handle->flags & UV_HANDLE_TCP_SOCKET_CLOSED)) {
+      closesocket(handle->socket);
+      handle->socket = INVALID_SOCKET;
+      handle->flags |= UV_HANDLE_TCP_SOCKET_CLOSED;
+    }
+
+    if (!(handle->flags & UV_HANDLE_CONNECTION) && handle->tcp.serv.accept_reqs) {
+      if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+        for (i = 0; i < uv_simultaneous_server_accepts; i++) {
+          req = &handle->tcp.serv.accept_reqs[i];
+          if (req->wait_handle != INVALID_HANDLE_VALUE) {
+            UnregisterWait(req->wait_handle);
+            req->wait_handle = INVALID_HANDLE_VALUE;
+          }
+          if (req->event_handle) {
+            CloseHandle(req->event_handle);
+            req->event_handle = NULL;
+          }
+        }
+      }
+
+      uv__free(handle->tcp.serv.accept_reqs);
+      handle->tcp.serv.accept_reqs = NULL;
+    }
+
+    if (handle->flags & UV_HANDLE_CONNECTION &&
+        handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      if (handle->read_req.wait_handle != INVALID_HANDLE_VALUE) {
+        UnregisterWait(handle->read_req.wait_handle);
+        handle->read_req.wait_handle = INVALID_HANDLE_VALUE;
+      }
+      if (handle->read_req.event_handle) {
+        CloseHandle(handle->read_req.event_handle);
+        handle->read_req.event_handle = NULL;
+      }
+    }
+
+    uv__handle_close(handle);
+    loop->active_tcp_streams--;
+  }
+}
+
+
+/* Unlike on Unix, here we don't set SO_REUSEADDR, because it doesn't just
+ * allow binding to addresses that are in use by sockets in TIME_WAIT, it
+ * effectively allows 'stealing' a port which is in use by another application.
+ *
+ * SO_EXCLUSIVEADDRUSE is also not good here because it does check all sockets,
+ * regardless of state, so we'd get an error even if the port is in use by a
+ * socket in TIME_WAIT state.
+ *
+ * See issue #1360.
+ *
+ */
+static int uv_tcp_try_bind(uv_tcp_t* handle,
+                           const struct sockaddr* addr,
+                           unsigned int addrlen,
+                           unsigned int flags) {
+  DWORD err;
+  int r;
+
+  if (handle->socket == INVALID_SOCKET) {
+    SOCKET sock;
+
+    /* Cannot set IPv6-only mode on non-IPv6 socket. */
+    if ((flags & UV_TCP_IPV6ONLY) && addr->sa_family != AF_INET6)
+      return ERROR_INVALID_PARAMETER;
+
+    sock = socket(addr->sa_family, SOCK_STREAM, 0);
+    if (sock == INVALID_SOCKET) {
+      return WSAGetLastError();
+    }
+
+    err = uv_tcp_set_socket(handle->loop, handle, sock, addr->sa_family, 0);
+    if (err) {
+      closesocket(sock);
+      return err;
+    }
+  }
+
+#ifdef IPV6_V6ONLY
+  if (addr->sa_family == AF_INET6) {
+    int on;
+
+    on = (flags & UV_TCP_IPV6ONLY) != 0;
+
+    /* TODO: how to handle errors? This may fail if there is no ipv4 stack
+     * available, or when run on XP/2003 which have no support for dualstack
+     * sockets. For now we're silently ignoring the error. */
+    setsockopt(handle->socket,
+               IPPROTO_IPV6,
+               IPV6_V6ONLY,
+               (const char*)&on,
+               sizeof on);
+  }
+#endif
+
+  r = bind(handle->socket, addr, addrlen);
+
+  if (r == SOCKET_ERROR) {
+    err = WSAGetLastError();
+    if (err == WSAEADDRINUSE) {
+      /* Some errors are not to be reported until connect() or listen() */
+      handle->delayed_error = err;
+    } else {
+      return err;
+    }
+  }
+
+  handle->flags |= UV_HANDLE_BOUND;
+
+  return 0;
+}
+
+
+static void CALLBACK post_completion(void* context, BOOLEAN timed_out) {
+  uv_req_t* req;
+  uv_tcp_t* handle;
+
+  req = (uv_req_t*) context;
+  assert(req != NULL);
+  handle = (uv_tcp_t*)req->data;
+  assert(handle != NULL);
+  assert(!timed_out);
+
+  if (!PostQueuedCompletionStatus(handle->loop->iocp,
+                                  req->u.io.overlapped.InternalHigh,
+                                  0,
+                                  &req->u.io.overlapped)) {
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
+  }
+}
+
+
+static void CALLBACK post_write_completion(void* context, BOOLEAN timed_out) {
+  uv_write_t* req;
+  uv_tcp_t* handle;
+
+  req = (uv_write_t*) context;
+  assert(req != NULL);
+  handle = (uv_tcp_t*)req->handle;
+  assert(handle != NULL);
+  assert(!timed_out);
+
+  if (!PostQueuedCompletionStatus(handle->loop->iocp,
+                                  req->u.io.overlapped.InternalHigh,
+                                  0,
+                                  &req->u.io.overlapped)) {
+    uv_fatal_error(GetLastError(), "PostQueuedCompletionStatus");
+  }
+}
+
+
+static void uv_tcp_queue_accept(uv_tcp_t* handle, uv_tcp_accept_t* req) {
+  uv_loop_t* loop = handle->loop;
+  BOOL success;
+  DWORD bytes;
+  SOCKET accept_socket;
+  short family;
+
+  assert(handle->flags & UV_HANDLE_LISTENING);
+  assert(req->accept_socket == INVALID_SOCKET);
+
+  /* choose family and extension function */
+  if (handle->flags & UV_HANDLE_IPV6) {
+    family = AF_INET6;
+  } else {
+    family = AF_INET;
+  }
+
+  /* Open a socket for the accepted connection. */
+  accept_socket = socket(family, SOCK_STREAM, 0);
+  if (accept_socket == INVALID_SOCKET) {
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+    handle->reqs_pending++;
+    return;
+  }
+
+  /* Make the socket non-inheritable */
+  if (!SetHandleInformation((HANDLE) accept_socket, HANDLE_FLAG_INHERIT, 0)) {
+    SET_REQ_ERROR(req, GetLastError());
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+    handle->reqs_pending++;
+    closesocket(accept_socket);
+    return;
+  }
+
+  /* Prepare the overlapped structure. */
+  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
+  }
+
+  success = handle->tcp.serv.func_acceptex(handle->socket,
+                                          accept_socket,
+                                          (void*)req->accept_buffer,
+                                          0,
+                                          sizeof(struct sockaddr_storage),
+                                          sizeof(struct sockaddr_storage),
+                                          &bytes,
+                                          &req->u.io.overlapped);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(success)) {
+    /* Process the req without IOCP. */
+    req->accept_socket = accept_socket;
+    handle->reqs_pending++;
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(success)) {
+    /* The req will be processed with IOCP. */
+    req->accept_socket = accept_socket;
+    handle->reqs_pending++;
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        req->wait_handle == INVALID_HANDLE_VALUE &&
+        !RegisterWaitForSingleObject(&req->wait_handle,
+          req->event_handle, post_completion, (void*) req,
+          INFINITE, WT_EXECUTEINWAITTHREAD)) {
+      SET_REQ_ERROR(req, GetLastError());
+      uv_insert_pending_req(loop, (uv_req_t*)req);
+    }
+  } else {
+    /* Make this req pending reporting an error. */
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+    handle->reqs_pending++;
+    /* Destroy the preallocated client socket. */
+    closesocket(accept_socket);
+    /* Destroy the event handle */
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+      CloseHandle(req->u.io.overlapped.hEvent);
+      req->event_handle = NULL;
+    }
+  }
+}
+
+
+static void uv_tcp_queue_read(uv_loop_t* loop, uv_tcp_t* handle) {
+  uv_read_t* req;
+  uv_buf_t buf;
+  int result;
+  DWORD bytes, flags;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+
+  req = &handle->read_req;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  /*
+   * Preallocate a read buffer if the number of active streams is below
+   * the threshold.
+  */
+  if (loop->active_tcp_streams < uv_active_tcp_streams_threshold) {
+    handle->flags &= ~UV_HANDLE_ZERO_READ;
+    handle->tcp.conn.read_buffer = uv_buf_init(NULL, 0);
+    handle->alloc_cb((uv_handle_t*) handle, 65536, &handle->tcp.conn.read_buffer);
+    if (handle->tcp.conn.read_buffer.base == NULL ||
+        handle->tcp.conn.read_buffer.len == 0) {
+      handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &handle->tcp.conn.read_buffer);
+      return;
+    }
+    assert(handle->tcp.conn.read_buffer.base != NULL);
+    buf = handle->tcp.conn.read_buffer;
+  } else {
+    handle->flags |= UV_HANDLE_ZERO_READ;
+    buf.base = (char*) &uv_zero_;
+    buf.len = 0;
+  }
+
+  /* Prepare the overlapped structure. */
+  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    assert(req->event_handle);
+    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
+  }
+
+  flags = 0;
+  result = WSARecv(handle->socket,
+                   (WSABUF*)&buf,
+                   1,
+                   &bytes,
+                   &flags,
+                   &req->u.io.overlapped,
+                   NULL);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+    /* Process the req without IOCP. */
+    handle->flags |= UV_HANDLE_READ_PENDING;
+    req->u.io.overlapped.InternalHigh = bytes;
+    handle->reqs_pending++;
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+    /* The req will be processed with IOCP. */
+    handle->flags |= UV_HANDLE_READ_PENDING;
+    handle->reqs_pending++;
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        req->wait_handle == INVALID_HANDLE_VALUE &&
+        !RegisterWaitForSingleObject(&req->wait_handle,
+          req->event_handle, post_completion, (void*) req,
+          INFINITE, WT_EXECUTEINWAITTHREAD)) {
+      SET_REQ_ERROR(req, GetLastError());
+      uv_insert_pending_req(loop, (uv_req_t*)req);
+    }
+  } else {
+    /* Make this req pending reporting an error. */
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+    handle->reqs_pending++;
+  }
+}
+
+
+int uv_tcp_listen(uv_tcp_t* handle, int backlog, uv_connection_cb cb) {
+  unsigned int i, simultaneous_accepts;
+  uv_tcp_accept_t* req;
+  int err;
+
+  assert(backlog > 0);
+
+  if (handle->flags & UV_HANDLE_LISTENING) {
+    handle->stream.serv.connection_cb = cb;
+  }
+
+  if (handle->flags & UV_HANDLE_READING) {
+    return WSAEISCONN;
+  }
+
+  if (handle->delayed_error) {
+    return handle->delayed_error;
+  }
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    err = uv_tcp_try_bind(handle,
+                          (const struct sockaddr*) &uv_addr_ip4_any_,
+                          sizeof(uv_addr_ip4_any_),
+                          0);
+    if (err)
+      return err;
+    if (handle->delayed_error)
+      return handle->delayed_error;
+  }
+
+  if (!handle->tcp.serv.func_acceptex) {
+    if (!uv_get_acceptex_function(handle->socket, &handle->tcp.serv.func_acceptex)) {
+      return WSAEAFNOSUPPORT;
+    }
+  }
+
+  if (!(handle->flags & UV_HANDLE_SHARED_TCP_SOCKET) &&
+      listen(handle->socket, backlog) == SOCKET_ERROR) {
+    return WSAGetLastError();
+  }
+
+  handle->flags |= UV_HANDLE_LISTENING;
+  handle->stream.serv.connection_cb = cb;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+
+  simultaneous_accepts = handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT ? 1
+    : uv_simultaneous_server_accepts;
+
+  if(!handle->tcp.serv.accept_reqs) {
+    handle->tcp.serv.accept_reqs = (uv_tcp_accept_t*)
+      uv__malloc(uv_simultaneous_server_accepts * sizeof(uv_tcp_accept_t));
+    if (!handle->tcp.serv.accept_reqs) {
+      uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+    }
+
+    for (i = 0; i < simultaneous_accepts; i++) {
+      req = &handle->tcp.serv.accept_reqs[i];
+      UV_REQ_INIT(req, UV_ACCEPT);
+      req->accept_socket = INVALID_SOCKET;
+      req->data = handle;
+
+      req->wait_handle = INVALID_HANDLE_VALUE;
+      if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+        req->event_handle = CreateEvent(NULL, 0, 0, NULL);
+        if (!req->event_handle) {
+          uv_fatal_error(GetLastError(), "CreateEvent");
+        }
+      } else {
+        req->event_handle = NULL;
+      }
+
+      uv_tcp_queue_accept(handle, req);
+    }
+
+    /* Initialize other unused requests too, because uv_tcp_endgame doesn't
+     * know how many requests were initialized, so it will try to clean up
+     * {uv_simultaneous_server_accepts} requests. */
+    for (i = simultaneous_accepts; i < uv_simultaneous_server_accepts; i++) {
+      req = &handle->tcp.serv.accept_reqs[i];
+      UV_REQ_INIT(req, UV_ACCEPT);
+      req->accept_socket = INVALID_SOCKET;
+      req->data = handle;
+      req->wait_handle = INVALID_HANDLE_VALUE;
+      req->event_handle = NULL;
+    }
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_accept(uv_tcp_t* server, uv_tcp_t* client) {
+  uv_loop_t* loop = server->loop;
+  int err = 0;
+  int family;
+
+  uv_tcp_accept_t* req = server->tcp.serv.pending_accepts;
+
+  if (!req) {
+    /* No valid connections found, so we error out. */
+    return WSAEWOULDBLOCK;
+  }
+
+  if (req->accept_socket == INVALID_SOCKET) {
+    return WSAENOTCONN;
+  }
+
+  if (server->flags & UV_HANDLE_IPV6) {
+    family = AF_INET6;
+  } else {
+    family = AF_INET;
+  }
+
+  err = uv_tcp_set_socket(client->loop,
+                          client,
+                          req->accept_socket,
+                          family,
+                          0);
+  if (err) {
+    closesocket(req->accept_socket);
+  } else {
+    uv_connection_init((uv_stream_t*) client);
+    /* AcceptEx() implicitly binds the accepted socket. */
+    client->flags |= UV_HANDLE_BOUND | UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+  }
+
+  /* Prepare the req to pick up a new connection */
+  server->tcp.serv.pending_accepts = req->next_pending;
+  req->next_pending = NULL;
+  req->accept_socket = INVALID_SOCKET;
+
+  if (!(server->flags & UV__HANDLE_CLOSING)) {
+    /* Check if we're in a middle of changing the number of pending accepts. */
+    if (!(server->flags & UV_HANDLE_TCP_ACCEPT_STATE_CHANGING)) {
+      uv_tcp_queue_accept(server, req);
+    } else {
+      /* We better be switching to a single pending accept. */
+      assert(server->flags & UV_HANDLE_TCP_SINGLE_ACCEPT);
+
+      server->tcp.serv.processed_accepts++;
+
+      if (server->tcp.serv.processed_accepts >= uv_simultaneous_server_accepts) {
+        server->tcp.serv.processed_accepts = 0;
+        /*
+         * All previously queued accept requests are now processed.
+         * We now switch to queueing just a single accept.
+         */
+        uv_tcp_queue_accept(server, &server->tcp.serv.accept_reqs[0]);
+        server->flags &= ~UV_HANDLE_TCP_ACCEPT_STATE_CHANGING;
+        server->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
+      }
+    }
+  }
+
+  loop->active_tcp_streams++;
+
+  return err;
+}
+
+
+int uv_tcp_read_start(uv_tcp_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb) {
+  uv_loop_t* loop = handle->loop;
+
+  handle->flags |= UV_HANDLE_READING;
+  handle->read_cb = read_cb;
+  handle->alloc_cb = alloc_cb;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+
+  /* If reading was stopped and then started again, there could still be a read
+   * request pending. */
+  if (!(handle->flags & UV_HANDLE_READ_PENDING)) {
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        !handle->read_req.event_handle) {
+      handle->read_req.event_handle = CreateEvent(NULL, 0, 0, NULL);
+      if (!handle->read_req.event_handle) {
+        uv_fatal_error(GetLastError(), "CreateEvent");
+      }
+    }
+    uv_tcp_queue_read(loop, handle);
+  }
+
+  return 0;
+}
+
+
+static int uv_tcp_try_connect(uv_connect_t* req,
+                              uv_tcp_t* handle,
+                              const struct sockaddr* addr,
+                              unsigned int addrlen,
+                              uv_connect_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  const struct sockaddr* bind_addr;
+  struct sockaddr_storage converted;
+  BOOL success;
+  DWORD bytes;
+  int err;
+
+  err = uv__convert_to_localhost_if_unspecified(addr, &converted);
+  if (err)
+    return err;
+
+  if (handle->delayed_error) {
+    return handle->delayed_error;
+  }
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    if (addrlen == sizeof(uv_addr_ip4_any_)) {
+      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
+    } else if (addrlen == sizeof(uv_addr_ip6_any_)) {
+      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
+    } else {
+      abort();
+    }
+    err = uv_tcp_try_bind(handle, bind_addr, addrlen, 0);
+    if (err)
+      return err;
+    if (handle->delayed_error)
+      return handle->delayed_error;
+  }
+
+  if (!handle->tcp.conn.func_connectex) {
+    if (!uv_get_connectex_function(handle->socket, &handle->tcp.conn.func_connectex)) {
+      return WSAEAFNOSUPPORT;
+    }
+  }
+
+  UV_REQ_INIT(req, UV_CONNECT);
+  req->handle = (uv_stream_t*) handle;
+  req->cb = cb;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  success = handle->tcp.conn.func_connectex(handle->socket,
+                                            (const struct sockaddr*) &converted,
+                                            addrlen,
+                                            NULL,
+                                            0,
+                                            &bytes,
+                                            &req->u.io.overlapped);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(success)) {
+    /* Process the req without IOCP. */
+    handle->reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(success)) {
+    /* The req will be processed with IOCP. */
+    handle->reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+  } else {
+    return WSAGetLastError();
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_getsockname(const uv_tcp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+  int result;
+
+  if (handle->socket == INVALID_SOCKET) {
+    return UV_EINVAL;
+  }
+
+  if (handle->delayed_error) {
+    return uv_translate_sys_error(handle->delayed_error);
+  }
+
+  result = getsockname(handle->socket, name, namelen);
+  if (result != 0) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_getpeername(const uv_tcp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+  int result;
+
+  if (handle->socket == INVALID_SOCKET) {
+    return UV_EINVAL;
+  }
+
+  if (handle->delayed_error) {
+    return uv_translate_sys_error(handle->delayed_error);
+  }
+
+  result = getpeername(handle->socket, name, namelen);
+  if (result != 0) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_write(uv_loop_t* loop,
+                 uv_write_t* req,
+                 uv_tcp_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 uv_write_cb cb) {
+  int result;
+  DWORD bytes;
+
+  UV_REQ_INIT(req, UV_WRITE);
+  req->handle = (uv_stream_t*) handle;
+  req->cb = cb;
+
+  /* Prepare the overlapped structure. */
+  memset(&(req->u.io.overlapped), 0, sizeof(req->u.io.overlapped));
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    req->event_handle = CreateEvent(NULL, 0, 0, NULL);
+    if (!req->event_handle) {
+      uv_fatal_error(GetLastError(), "CreateEvent");
+    }
+    req->u.io.overlapped.hEvent = (HANDLE) ((ULONG_PTR) req->event_handle | 1);
+    req->wait_handle = INVALID_HANDLE_VALUE;
+  }
+
+  result = WSASend(handle->socket,
+                   (WSABUF*) bufs,
+                   nbufs,
+                   &bytes,
+                   0,
+                   &req->u.io.overlapped,
+                   NULL);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+    /* Request completed immediately. */
+    req->u.io.queued_bytes = 0;
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    uv_insert_pending_req(loop, (uv_req_t*) req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+    /* Request queued by the kernel. */
+    req->u.io.queued_bytes = uv__count_bufs(bufs, nbufs);
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    handle->write_queue_size += req->u.io.queued_bytes;
+    if (handle->flags & UV_HANDLE_EMULATE_IOCP &&
+        !RegisterWaitForSingleObject(&req->wait_handle,
+          req->event_handle, post_write_completion, (void*) req,
+          INFINITE, WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE)) {
+      SET_REQ_ERROR(req, GetLastError());
+      uv_insert_pending_req(loop, (uv_req_t*)req);
+    }
+  } else {
+    /* Send failed due to an error, report it later */
+    req->u.io.queued_bytes = 0;
+    handle->reqs_pending++;
+    handle->stream.conn.write_reqs_pending++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    SET_REQ_ERROR(req, WSAGetLastError());
+    uv_insert_pending_req(loop, (uv_req_t*) req);
+  }
+
+  return 0;
+}
+
+
+int uv__tcp_try_write(uv_tcp_t* handle,
+                     const uv_buf_t bufs[],
+                     unsigned int nbufs) {
+  int result;
+  DWORD bytes;
+
+  if (handle->stream.conn.write_reqs_pending > 0)
+    return UV_EAGAIN;
+
+  result = WSASend(handle->socket,
+                   (WSABUF*) bufs,
+                   nbufs,
+                   &bytes,
+                   0,
+                   NULL,
+                   NULL);
+
+  if (result == SOCKET_ERROR)
+    return uv_translate_sys_error(WSAGetLastError());
+  else
+    return bytes;
+}
+
+
+void uv_process_tcp_read_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_req_t* req) {
+  DWORD bytes, flags, err;
+  uv_buf_t buf;
+
+  assert(handle->type == UV_TCP);
+
+  handle->flags &= ~UV_HANDLE_READ_PENDING;
+
+  if (!REQ_SUCCESS(req)) {
+    /* An error occurred doing the read. */
+    if ((handle->flags & UV_HANDLE_READING) ||
+        !(handle->flags & UV_HANDLE_ZERO_READ)) {
+      handle->flags &= ~UV_HANDLE_READING;
+      DECREASE_ACTIVE_COUNT(loop, handle);
+      buf = (handle->flags & UV_HANDLE_ZERO_READ) ?
+            uv_buf_init(NULL, 0) : handle->tcp.conn.read_buffer;
+
+      err = GET_REQ_SOCK_ERROR(req);
+
+      if (err == WSAECONNABORTED) {
+        /* Turn WSAECONNABORTED into UV_ECONNRESET to be consistent with Unix.
+         */
+        err = WSAECONNRESET;
+      }
+
+      handle->read_cb((uv_stream_t*)handle,
+                      uv_translate_sys_error(err),
+                      &buf);
+    }
+  } else {
+    if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
+      /* The read was done with a non-zero buffer length. */
+      if (req->u.io.overlapped.InternalHigh > 0) {
+        /* Successful read */
+        handle->read_cb((uv_stream_t*)handle,
+                        req->u.io.overlapped.InternalHigh,
+                        &handle->tcp.conn.read_buffer);
+        /* Read again only if bytes == buf.len */
+        if (req->u.io.overlapped.InternalHigh < handle->tcp.conn.read_buffer.len) {
+          goto done;
+        }
+      } else {
+        /* Connection closed */
+        if (handle->flags & UV_HANDLE_READING) {
+          handle->flags &= ~UV_HANDLE_READING;
+          DECREASE_ACTIVE_COUNT(loop, handle);
+        }
+        handle->flags &= ~UV_HANDLE_READABLE;
+
+        buf.base = 0;
+        buf.len = 0;
+        handle->read_cb((uv_stream_t*)handle, UV_EOF, &handle->tcp.conn.read_buffer);
+        goto done;
+      }
+    }
+
+    /* Do nonblocking reads until the buffer is empty */
+    while (handle->flags & UV_HANDLE_READING) {
+      buf = uv_buf_init(NULL, 0);
+      handle->alloc_cb((uv_handle_t*) handle, 65536, &buf);
+      if (buf.base == NULL || buf.len == 0) {
+        handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
+        break;
+      }
+      assert(buf.base != NULL);
+
+      flags = 0;
+      if (WSARecv(handle->socket,
+                  (WSABUF*)&buf,
+                  1,
+                  &bytes,
+                  &flags,
+                  NULL,
+                  NULL) != SOCKET_ERROR) {
+        if (bytes > 0) {
+          /* Successful read */
+          handle->read_cb((uv_stream_t*)handle, bytes, &buf);
+          /* Read again only if bytes == buf.len */
+          if (bytes < buf.len) {
+            break;
+          }
+        } else {
+          /* Connection closed */
+          handle->flags &= ~(UV_HANDLE_READING | UV_HANDLE_READABLE);
+          DECREASE_ACTIVE_COUNT(loop, handle);
+
+          handle->read_cb((uv_stream_t*)handle, UV_EOF, &buf);
+          break;
+        }
+      } else {
+        err = WSAGetLastError();
+        if (err == WSAEWOULDBLOCK) {
+          /* Read buffer was completely empty, report a 0-byte read. */
+          handle->read_cb((uv_stream_t*)handle, 0, &buf);
+        } else {
+          /* Ouch! serious error. */
+          handle->flags &= ~UV_HANDLE_READING;
+          DECREASE_ACTIVE_COUNT(loop, handle);
+
+          if (err == WSAECONNABORTED) {
+            /* Turn WSAECONNABORTED into UV_ECONNRESET to be consistent with
+             * Unix. */
+            err = WSAECONNRESET;
+          }
+
+          handle->read_cb((uv_stream_t*)handle,
+                          uv_translate_sys_error(err),
+                          &buf);
+        }
+        break;
+      }
+    }
+
+done:
+    /* Post another read if still reading and not closing. */
+    if ((handle->flags & UV_HANDLE_READING) &&
+        !(handle->flags & UV_HANDLE_READ_PENDING)) {
+      uv_tcp_queue_read(loop, handle);
+    }
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_process_tcp_write_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_write_t* req) {
+  int err;
+
+  assert(handle->type == UV_TCP);
+
+  assert(handle->write_queue_size >= req->u.io.queued_bytes);
+  handle->write_queue_size -= req->u.io.queued_bytes;
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (handle->flags & UV_HANDLE_EMULATE_IOCP) {
+    if (req->wait_handle != INVALID_HANDLE_VALUE) {
+      UnregisterWait(req->wait_handle);
+      req->wait_handle = INVALID_HANDLE_VALUE;
+    }
+    if (req->event_handle) {
+      CloseHandle(req->event_handle);
+      req->event_handle = NULL;
+    }
+  }
+
+  if (req->cb) {
+    err = uv_translate_sys_error(GET_REQ_SOCK_ERROR(req));
+    if (err == UV_ECONNABORTED) {
+      /* use UV_ECANCELED for consistency with Unix */
+      err = UV_ECANCELED;
+    }
+    req->cb(req, err);
+  }
+
+  handle->stream.conn.write_reqs_pending--;
+  if (handle->stream.conn.shutdown_req != NULL &&
+      handle->stream.conn.write_reqs_pending == 0) {
+    uv_want_endgame(loop, (uv_handle_t*)handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_process_tcp_accept_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_req_t* raw_req) {
+  uv_tcp_accept_t* req = (uv_tcp_accept_t*) raw_req;
+  int err;
+
+  assert(handle->type == UV_TCP);
+
+  /* If handle->accepted_socket is not a valid socket, then uv_queue_accept
+   * must have failed. This is a serious error. We stop accepting connections
+   * and report this error to the connection callback. */
+  if (req->accept_socket == INVALID_SOCKET) {
+    if (handle->flags & UV_HANDLE_LISTENING) {
+      handle->flags &= ~UV_HANDLE_LISTENING;
+      DECREASE_ACTIVE_COUNT(loop, handle);
+      if (handle->stream.serv.connection_cb) {
+        err = GET_REQ_SOCK_ERROR(req);
+        handle->stream.serv.connection_cb((uv_stream_t*)handle,
+                                      uv_translate_sys_error(err));
+      }
+    }
+  } else if (REQ_SUCCESS(req) &&
+      setsockopt(req->accept_socket,
+                  SOL_SOCKET,
+                  SO_UPDATE_ACCEPT_CONTEXT,
+                  (char*)&handle->socket,
+                  sizeof(handle->socket)) == 0) {
+    req->next_pending = handle->tcp.serv.pending_accepts;
+    handle->tcp.serv.pending_accepts = req;
+
+    /* Accept and SO_UPDATE_ACCEPT_CONTEXT were successful. */
+    if (handle->stream.serv.connection_cb) {
+      handle->stream.serv.connection_cb((uv_stream_t*)handle, 0);
+    }
+  } else {
+    /* Error related to accepted socket is ignored because the server socket
+     * may still be healthy. If the server socket is broken uv_queue_accept
+     * will detect it. */
+    closesocket(req->accept_socket);
+    req->accept_socket = INVALID_SOCKET;
+    if (handle->flags & UV_HANDLE_LISTENING) {
+      uv_tcp_queue_accept(handle, req);
+    }
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_process_tcp_connect_req(uv_loop_t* loop, uv_tcp_t* handle,
+    uv_connect_t* req) {
+  int err;
+
+  assert(handle->type == UV_TCP);
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  err = 0;
+  if (REQ_SUCCESS(req)) {
+    if (handle->flags & UV__HANDLE_CLOSING) {
+      /* use UV_ECANCELED for consistency with Unix */
+      err = ERROR_OPERATION_ABORTED;
+    } else if (setsockopt(handle->socket,
+                          SOL_SOCKET,
+                          SO_UPDATE_CONNECT_CONTEXT,
+                          NULL,
+                          0) == 0) {
+      uv_connection_init((uv_stream_t*)handle);
+      handle->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+      loop->active_tcp_streams++;
+    } else {
+      err = WSAGetLastError();
+    }
+  } else {
+    err = GET_REQ_SOCK_ERROR(req);
+  }
+  req->cb(req, uv_translate_sys_error(err));
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+int uv__tcp_xfer_export(uv_tcp_t* handle,
+                        int target_pid,
+                        uv__ipc_socket_xfer_info_t* xfer_info) {
+  if (!(handle->flags & UV_HANDLE_CONNECTION)) {
+    /* We're about to share the socket with another process. Because this is a
+     * listening socket, we assume that the other process will be accepting
+     * connections on it. Thus, before sharing the socket with another process,
+     * we call listen here in the parent process. */
+    if (!(handle->flags & UV_HANDLE_LISTENING)) {
+      if (!(handle->flags & UV_HANDLE_BOUND)) {
+        return ERROR_NOT_SUPPORTED;
+      }
+      if (handle->delayed_error == 0 &&
+          listen(handle->socket, SOMAXCONN) == SOCKET_ERROR) {
+        handle->delayed_error = WSAGetLastError();
+      }
+    }
+  }
+
+  if (WSADuplicateSocketW(
+          handle->socket, target_pid, &xfer_info->socket_info)) {
+    return WSAGetLastError();
+  }
+  xfer_info->delayed_error = handle->delayed_error;
+  xfer_info->flags = handle->flags & UV_HANDLE_CONNECTION;
+
+  /* Mark the local copy of the handle as 'shared' so we behave in a way that's
+   * friendly to the process(es) that we share the socket with. */
+  handle->flags |= UV_HANDLE_SHARED_TCP_SOCKET;
+
+  return 0;
+}
+
+
+int uv__tcp_xfer_import(uv_tcp_t* tcp, uv__ipc_socket_xfer_info_t* xfer_info) {
+  int err;
+  SOCKET socket = WSASocketW(FROM_PROTOCOL_INFO,
+                             FROM_PROTOCOL_INFO,
+                             FROM_PROTOCOL_INFO,
+                             &xfer_info->socket_info,
+                             0,
+                             WSA_FLAG_OVERLAPPED);
+
+  if (socket == INVALID_SOCKET) {
+    return WSAGetLastError();
+  }
+
+  err = uv_tcp_set_socket(
+      tcp->loop, tcp, socket, xfer_info->socket_info.iAddressFamily, 1);
+  if (err) {
+    closesocket(socket);
+    return err;
+  }
+
+  tcp->delayed_error = xfer_info->delayed_error;
+  tcp->flags |= UV_HANDLE_BOUND | UV_HANDLE_SHARED_TCP_SOCKET;
+
+  if (xfer_info->flags & UV_HANDLE_CONNECTION) {
+    uv_connection_init((uv_stream_t*)tcp);
+    tcp->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+  }
+
+  tcp->loop->active_tcp_streams++;
+  return 0;
+}
+
+
+int uv_tcp_nodelay(uv_tcp_t* handle, int enable) {
+  int err;
+
+  if (handle->socket != INVALID_SOCKET) {
+    err = uv__tcp_nodelay(handle, handle->socket, enable);
+    if (err)
+      return err;
+  }
+
+  if (enable) {
+    handle->flags |= UV_HANDLE_TCP_NODELAY;
+  } else {
+    handle->flags &= ~UV_HANDLE_TCP_NODELAY;
+  }
+
+  return 0;
+}
+
+
+int uv_tcp_keepalive(uv_tcp_t* handle, int enable, unsigned int delay) {
+  int err;
+
+  if (handle->socket != INVALID_SOCKET) {
+    err = uv__tcp_keepalive(handle, handle->socket, enable, delay);
+    if (err)
+      return err;
+  }
+
+  if (enable) {
+    handle->flags |= UV_HANDLE_TCP_KEEPALIVE;
+  } else {
+    handle->flags &= ~UV_HANDLE_TCP_KEEPALIVE;
+  }
+
+  /* TODO: Store delay if handle->socket isn't created yet. */
+
+  return 0;
+}
+
+
+int uv_tcp_simultaneous_accepts(uv_tcp_t* handle, int enable) {
+  if (handle->flags & UV_HANDLE_CONNECTION) {
+    return UV_EINVAL;
+  }
+
+  /* Check if we're already in the desired mode. */
+  if ((enable && !(handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT)) ||
+      (!enable && handle->flags & UV_HANDLE_TCP_SINGLE_ACCEPT)) {
+    return 0;
+  }
+
+  /* Don't allow switching from single pending accept to many. */
+  if (enable) {
+    return UV_ENOTSUP;
+  }
+
+  /* Check if we're in a middle of changing the number of pending accepts. */
+  if (handle->flags & UV_HANDLE_TCP_ACCEPT_STATE_CHANGING) {
+    return 0;
+  }
+
+  handle->flags |= UV_HANDLE_TCP_SINGLE_ACCEPT;
+
+  /* Flip the changing flag if we have already queued multiple accepts. */
+  if (handle->flags & UV_HANDLE_LISTENING) {
+    handle->flags |= UV_HANDLE_TCP_ACCEPT_STATE_CHANGING;
+  }
+
+  return 0;
+}
+
+
+static int uv_tcp_try_cancel_io(uv_tcp_t* tcp) {
+  SOCKET socket = tcp->socket;
+  int non_ifs_lsp;
+
+  /* Check if we have any non-IFS LSPs stacked on top of TCP */
+  non_ifs_lsp = (tcp->flags & UV_HANDLE_IPV6) ? uv_tcp_non_ifs_lsp_ipv6 :
+                                                uv_tcp_non_ifs_lsp_ipv4;
+
+  /* If there are non-ifs LSPs then try to obtain a base handle for the socket.
+   * This will always fail on Windows XP/3k. */
+  if (non_ifs_lsp) {
+    DWORD bytes;
+    if (WSAIoctl(socket,
+                 SIO_BASE_HANDLE,
+                 NULL,
+                 0,
+                 &socket,
+                 sizeof socket,
+                 &bytes,
+                 NULL,
+                 NULL) != 0) {
+      /* Failed. We can't do CancelIo. */
+      return -1;
+    }
+  }
+
+  assert(socket != 0 && socket != INVALID_SOCKET);
+
+  if (!CancelIo((HANDLE) socket)) {
+    return GetLastError();
+  }
+
+  /* It worked. */
+  return 0;
+}
+
+
+void uv_tcp_close(uv_loop_t* loop, uv_tcp_t* tcp) {
+  int close_socket = 1;
+
+  if (tcp->flags & UV_HANDLE_READ_PENDING) {
+    /* In order for winsock to do a graceful close there must not be any any
+     * pending reads, or the socket must be shut down for writing */
+    if (!(tcp->flags & UV_HANDLE_SHARED_TCP_SOCKET)) {
+      /* Just do shutdown on non-shared sockets, which ensures graceful close. */
+      shutdown(tcp->socket, SD_SEND);
+
+    } else if (uv_tcp_try_cancel_io(tcp) == 0) {
+      /* In case of a shared socket, we try to cancel all outstanding I/O,. If
+       * that works, don't close the socket yet - wait for the read req to
+       * return and close the socket in uv_tcp_endgame. */
+      close_socket = 0;
+
+    } else {
+      /* When cancelling isn't possible - which could happen when an LSP is
+       * present on an old Windows version, we will have to close the socket
+       * with a read pending. That is not nice because trailing sent bytes may
+       * not make it to the other side. */
+    }
+
+  } else if ((tcp->flags & UV_HANDLE_SHARED_TCP_SOCKET) &&
+             tcp->tcp.serv.accept_reqs != NULL) {
+    /* Under normal circumstances closesocket() will ensure that all pending
+     * accept reqs are canceled. However, when the socket is shared the
+     * presence of another reference to the socket in another process will keep
+     * the accept reqs going, so we have to ensure that these are canceled. */
+    if (uv_tcp_try_cancel_io(tcp) != 0) {
+      /* When cancellation is not possible, there is another option: we can
+       * close the incoming sockets, which will also cancel the accept
+       * operations. However this is not cool because we might inadvertently
+       * close a socket that just accepted a new connection, which will cause
+       * the connection to be aborted. */
+      unsigned int i;
+      for (i = 0; i < uv_simultaneous_server_accepts; i++) {
+        uv_tcp_accept_t* req = &tcp->tcp.serv.accept_reqs[i];
+        if (req->accept_socket != INVALID_SOCKET &&
+            !HasOverlappedIoCompleted(&req->u.io.overlapped)) {
+          closesocket(req->accept_socket);
+          req->accept_socket = INVALID_SOCKET;
+        }
+      }
+    }
+  }
+
+  if (tcp->flags & UV_HANDLE_READING) {
+    tcp->flags &= ~UV_HANDLE_READING;
+    DECREASE_ACTIVE_COUNT(loop, tcp);
+  }
+
+  if (tcp->flags & UV_HANDLE_LISTENING) {
+    tcp->flags &= ~UV_HANDLE_LISTENING;
+    DECREASE_ACTIVE_COUNT(loop, tcp);
+  }
+
+  if (close_socket) {
+    closesocket(tcp->socket);
+    tcp->socket = INVALID_SOCKET;
+    tcp->flags |= UV_HANDLE_TCP_SOCKET_CLOSED;
+  }
+
+  tcp->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+  uv__handle_closing(tcp);
+
+  if (tcp->reqs_pending == 0) {
+    uv_want_endgame(tcp->loop, (uv_handle_t*)tcp);
+  }
+}
+
+
+int uv_tcp_open(uv_tcp_t* handle, uv_os_sock_t sock) {
+  WSAPROTOCOL_INFOW protocol_info;
+  int opt_len;
+  int err;
+  struct sockaddr_storage saddr;
+  int saddr_len;
+
+  /* Detect the address family of the socket. */
+  opt_len = (int) sizeof protocol_info;
+  if (getsockopt(sock,
+                 SOL_SOCKET,
+                 SO_PROTOCOL_INFOW,
+                 (char*) &protocol_info,
+                 &opt_len) == SOCKET_ERROR) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  err = uv_tcp_set_socket(handle->loop,
+                          handle,
+                          sock,
+                          protocol_info.iAddressFamily,
+                          1);
+  if (err) {
+    return uv_translate_sys_error(err);
+  }
+
+  /* Support already active socket. */
+  saddr_len = sizeof(saddr);
+  if (!uv_tcp_getsockname(handle, (struct sockaddr*) &saddr, &saddr_len)) {
+    /* Socket is already bound. */
+    handle->flags |= UV_HANDLE_BOUND;
+    saddr_len = sizeof(saddr);
+    if (!uv_tcp_getpeername(handle, (struct sockaddr*) &saddr, &saddr_len)) {
+      /* Socket is already connected. */
+      uv_connection_init((uv_stream_t*) handle);
+      handle->flags |= UV_HANDLE_READABLE | UV_HANDLE_WRITABLE;
+    }
+  }
+
+  return 0;
+}
+
+
+/* This function is an egress point, i.e. it returns libuv errors rather than
+ * system errors.
+ */
+int uv__tcp_bind(uv_tcp_t* handle,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags) {
+  int err;
+
+  err = uv_tcp_try_bind(handle, addr, addrlen, flags);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  return 0;
+}
+
+
+/* This function is an egress point, i.e. it returns libuv errors rather than
+ * system errors.
+ */
+int uv__tcp_connect(uv_connect_t* req,
+                    uv_tcp_t* handle,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen,
+                    uv_connect_cb cb) {
+  int err;
+
+  err = uv_tcp_try_connect(req, handle, addr, addrlen, cb);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/thread.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/thread.cpp
new file mode 100644
index 0000000..6ad8128
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/thread.cpp
@@ -0,0 +1,498 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <limits.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+
+static int uv_cond_condvar_init(uv_cond_t* cond);
+static void uv_cond_condvar_destroy(uv_cond_t* cond);
+static void uv_cond_condvar_signal(uv_cond_t* cond);
+static void uv_cond_condvar_broadcast(uv_cond_t* cond);
+static void uv_cond_condvar_wait(uv_cond_t* cond, uv_mutex_t* mutex);
+static int uv_cond_condvar_timedwait(uv_cond_t* cond,
+    uv_mutex_t* mutex, uint64_t timeout);
+
+
+static void uv__once_inner(uv_once_t* guard, void (*callback)(void)) {
+  DWORD result;
+  HANDLE existing_event, created_event;
+
+  created_event = CreateEvent(NULL, 1, 0, NULL);
+  if (created_event == 0) {
+    /* Could fail in a low-memory situation? */
+    uv_fatal_error(GetLastError(), "CreateEvent");
+  }
+
+  existing_event = InterlockedCompareExchangePointer(&guard->event,
+                                                     created_event,
+                                                     NULL);
+
+  if (existing_event == NULL) {
+    /* We won the race */
+    callback();
+
+    result = SetEvent(created_event);
+    assert(result);
+    guard->ran = 1;
+
+  } else {
+    /* We lost the race. Destroy the event we created and wait for the existing
+     * one to become signaled. */
+    CloseHandle(created_event);
+    result = WaitForSingleObject(existing_event, INFINITE);
+    assert(result == WAIT_OBJECT_0);
+  }
+}
+
+
+void uv_once(uv_once_t* guard, void (*callback)(void)) {
+  /* Fast case - avoid WaitForSingleObject. */
+  if (guard->ran) {
+    return;
+  }
+
+  uv__once_inner(guard, callback);
+}
+
+
+/* Verify that uv_thread_t can be stored in a TLS slot. */
+STATIC_ASSERT(sizeof(uv_thread_t) <= sizeof(void*));
+
+static uv_key_t uv__current_thread_key;
+static uv_once_t uv__current_thread_init_guard = UV_ONCE_INIT;
+
+
+static void uv__init_current_thread_key(void) {
+  if (uv_key_create(&uv__current_thread_key))
+    abort();
+}
+
+
+struct thread_ctx {
+  void (*entry)(void* arg);
+  void* arg;
+  uv_thread_t self;
+};
+
+
+static UINT __stdcall uv__thread_start(void* arg) {
+  struct thread_ctx *ctx_p;
+  struct thread_ctx ctx;
+
+  ctx_p = (struct thread_ctx*)arg;
+  ctx = *ctx_p;
+  uv__free(ctx_p);
+
+  uv_once(&uv__current_thread_init_guard, uv__init_current_thread_key);
+  uv_key_set(&uv__current_thread_key, (void*) ctx.self);
+
+  ctx.entry(ctx.arg);
+
+  return 0;
+}
+
+
+int uv_thread_create(uv_thread_t *tid, void (*entry)(void *arg), void *arg) {
+  struct thread_ctx* ctx;
+  int err;
+  HANDLE thread;
+
+  ctx = (struct thread_ctx*)uv__malloc(sizeof(*ctx));
+  if (ctx == NULL)
+    return UV_ENOMEM;
+
+  ctx->entry = entry;
+  ctx->arg = arg;
+
+  /* Create the thread in suspended state so we have a chance to pass
+   * its own creation handle to it */   
+  thread = (HANDLE) _beginthreadex(NULL,
+                                   0,
+                                   uv__thread_start,
+                                   ctx,
+                                   CREATE_SUSPENDED,
+                                   NULL);
+  if (thread == NULL) {
+    err = errno;
+    uv__free(ctx);
+  } else {
+    err = 0;
+    *tid = thread;
+    ctx->self = thread;
+    ResumeThread(thread);
+  }
+
+  switch (err) {
+    case 0:
+      return 0;
+    case EACCES:
+      return UV_EACCES;
+    case EAGAIN:
+      return UV_EAGAIN;
+    case EINVAL:
+      return UV_EINVAL;
+  }
+
+  return UV_EIO;
+}
+
+
+uv_thread_t uv_thread_self(void) {
+  uv_once(&uv__current_thread_init_guard, uv__init_current_thread_key);
+  return (uv_thread_t) uv_key_get(&uv__current_thread_key);
+}
+
+
+int uv_thread_join(uv_thread_t *tid) {
+  if (WaitForSingleObject(*tid, INFINITE))
+    return uv_translate_sys_error(GetLastError());
+  else {
+    CloseHandle(*tid);
+    *tid = 0;
+    MemoryBarrier();  /* For feature parity with pthread_join(). */
+    return 0;
+  }
+}
+
+
+int uv_thread_equal(const uv_thread_t* t1, const uv_thread_t* t2) {
+  return *t1 == *t2;
+}
+
+
+int uv_mutex_init(uv_mutex_t* mutex) {
+  InitializeCriticalSection(mutex);
+  return 0;
+}
+
+
+int uv_mutex_init_recursive(uv_mutex_t* mutex) {
+  return uv_mutex_init(mutex);
+}
+
+
+void uv_mutex_destroy(uv_mutex_t* mutex) {
+  DeleteCriticalSection(mutex);
+}
+
+
+void uv_mutex_lock(uv_mutex_t* mutex) {
+  EnterCriticalSection(mutex);
+}
+
+
+int uv_mutex_trylock(uv_mutex_t* mutex) {
+  if (TryEnterCriticalSection(mutex))
+    return 0;
+  else
+    return UV_EBUSY;
+}
+
+
+void uv_mutex_unlock(uv_mutex_t* mutex) {
+  LeaveCriticalSection(mutex);
+}
+
+
+int uv_rwlock_init(uv_rwlock_t* rwlock) {
+  /* Initialize the semaphore that acts as the write lock. */
+  HANDLE handle = CreateSemaphoreW(NULL, 1, 1, NULL);
+  if (handle == NULL)
+    return uv_translate_sys_error(GetLastError());
+  rwlock->state_.write_semaphore_ = handle;
+
+  /* Initialize the critical section protecting the reader count. */
+  InitializeCriticalSection(&rwlock->state_.num_readers_lock_);
+
+  /* Initialize the reader count. */
+  rwlock->state_.num_readers_ = 0;
+
+  return 0;
+}
+
+
+void uv_rwlock_destroy(uv_rwlock_t* rwlock) {
+  DeleteCriticalSection(&rwlock->state_.num_readers_lock_);
+  CloseHandle(rwlock->state_.write_semaphore_);
+}
+
+
+void uv_rwlock_rdlock(uv_rwlock_t* rwlock) {
+  /* Acquire the lock that protects the reader count. */
+  EnterCriticalSection(&rwlock->state_.num_readers_lock_);
+
+  /* Increase the reader count, and lock for write if this is the first
+   * reader.
+   */
+  if (++rwlock->state_.num_readers_ == 1) {
+    DWORD r = WaitForSingleObject(rwlock->state_.write_semaphore_, INFINITE);
+    if (r != WAIT_OBJECT_0)
+      uv_fatal_error(GetLastError(), "WaitForSingleObject");
+  }
+
+  /* Release the lock that protects the reader count. */
+  LeaveCriticalSection(&rwlock->state_.num_readers_lock_);
+}
+
+
+int uv_rwlock_tryrdlock(uv_rwlock_t* rwlock) {
+  int err;
+
+  if (!TryEnterCriticalSection(&rwlock->state_.num_readers_lock_))
+    return UV_EBUSY;
+
+  err = 0;
+
+  if (rwlock->state_.num_readers_ == 0) {
+    /* Currently there are no other readers, which means that the write lock
+     * needs to be acquired.
+     */
+    DWORD r = WaitForSingleObject(rwlock->state_.write_semaphore_, 0);
+    if (r == WAIT_OBJECT_0)
+      rwlock->state_.num_readers_++;
+    else if (r == WAIT_TIMEOUT)
+      err = UV_EBUSY;
+    else if (r == WAIT_FAILED)
+      uv_fatal_error(GetLastError(), "WaitForSingleObject");
+
+  } else {
+    /* The write lock has already been acquired because there are other
+     * active readers.
+     */
+    rwlock->state_.num_readers_++;
+  }
+
+  LeaveCriticalSection(&rwlock->state_.num_readers_lock_);
+  return err;
+}
+
+
+void uv_rwlock_rdunlock(uv_rwlock_t* rwlock) {
+  EnterCriticalSection(&rwlock->state_.num_readers_lock_);
+
+  if (--rwlock->state_.num_readers_ == 0) {
+    if (!ReleaseSemaphore(rwlock->state_.write_semaphore_, 1, NULL))
+      uv_fatal_error(GetLastError(), "ReleaseSemaphore");
+  }
+
+  LeaveCriticalSection(&rwlock->state_.num_readers_lock_);
+}
+
+
+void uv_rwlock_wrlock(uv_rwlock_t* rwlock) {
+  DWORD r = WaitForSingleObject(rwlock->state_.write_semaphore_, INFINITE);
+  if (r != WAIT_OBJECT_0)
+    uv_fatal_error(GetLastError(), "WaitForSingleObject");
+}
+
+
+int uv_rwlock_trywrlock(uv_rwlock_t* rwlock) {
+  DWORD r = WaitForSingleObject(rwlock->state_.write_semaphore_, 0);
+  if (r == WAIT_OBJECT_0)
+    return 0;
+  else if (r == WAIT_TIMEOUT)
+    return UV_EBUSY;
+  else
+    uv_fatal_error(GetLastError(), "WaitForSingleObject");
+}
+
+
+void uv_rwlock_wrunlock(uv_rwlock_t* rwlock) {
+  if (!ReleaseSemaphore(rwlock->state_.write_semaphore_, 1, NULL))
+    uv_fatal_error(GetLastError(), "ReleaseSemaphore");
+}
+
+
+int uv_sem_init(uv_sem_t* sem, unsigned int value) {
+  *sem = CreateSemaphore(NULL, value, INT_MAX, NULL);
+  if (*sem == NULL)
+    return uv_translate_sys_error(GetLastError());
+  else
+    return 0;
+}
+
+
+void uv_sem_destroy(uv_sem_t* sem) {
+  if (!CloseHandle(*sem))
+    abort();
+}
+
+
+void uv_sem_post(uv_sem_t* sem) {
+  if (!ReleaseSemaphore(*sem, 1, NULL))
+    abort();
+}
+
+
+void uv_sem_wait(uv_sem_t* sem) {
+  if (WaitForSingleObject(*sem, INFINITE) != WAIT_OBJECT_0)
+    abort();
+}
+
+
+int uv_sem_trywait(uv_sem_t* sem) {
+  DWORD r = WaitForSingleObject(*sem, 0);
+
+  if (r == WAIT_OBJECT_0)
+    return 0;
+
+  if (r == WAIT_TIMEOUT)
+    return UV_EAGAIN;
+
+  abort();
+  return -1; /* Satisfy the compiler. */
+}
+
+
+int uv_cond_init(uv_cond_t* cond) {
+  InitializeConditionVariable(&cond->cond_var);
+  return 0;
+}
+
+
+void uv_cond_destroy(uv_cond_t* cond) {
+  /* nothing to do */
+  UV__UNUSED(cond);
+}
+
+
+void uv_cond_signal(uv_cond_t* cond) {
+  WakeConditionVariable(&cond->cond_var);
+}
+
+
+void uv_cond_broadcast(uv_cond_t* cond) {
+  WakeAllConditionVariable(&cond->cond_var);
+}
+
+
+void uv_cond_wait(uv_cond_t* cond, uv_mutex_t* mutex) {
+  if (!SleepConditionVariableCS(&cond->cond_var, mutex, INFINITE))
+    abort();
+}
+
+int uv_cond_timedwait(uv_cond_t* cond, uv_mutex_t* mutex, uint64_t timeout) {
+  if (SleepConditionVariableCS(&cond->cond_var, mutex, (DWORD)(timeout / 1e6)))
+    return 0;
+  if (GetLastError() != ERROR_TIMEOUT)
+    abort();
+  return UV_ETIMEDOUT;
+}
+
+
+int uv_barrier_init(uv_barrier_t* barrier, unsigned int count) {
+  int err;
+
+  barrier->n = count;
+  barrier->count = 0;
+
+  err = uv_mutex_init(&barrier->mutex);
+  if (err)
+    return err;
+
+  err = uv_sem_init(&barrier->turnstile1, 0);
+  if (err)
+    goto error2;
+
+  err = uv_sem_init(&barrier->turnstile2, 1);
+  if (err)
+    goto error;
+
+  return 0;
+
+error:
+  uv_sem_destroy(&barrier->turnstile1);
+error2:
+  uv_mutex_destroy(&barrier->mutex);
+  return err;
+
+}
+
+
+void uv_barrier_destroy(uv_barrier_t* barrier) {
+  uv_sem_destroy(&barrier->turnstile2);
+  uv_sem_destroy(&barrier->turnstile1);
+  uv_mutex_destroy(&barrier->mutex);
+}
+
+
+int uv_barrier_wait(uv_barrier_t* barrier) {
+  int serial_thread;
+
+  uv_mutex_lock(&barrier->mutex);
+  if (++barrier->count == barrier->n) {
+    uv_sem_wait(&barrier->turnstile2);
+    uv_sem_post(&barrier->turnstile1);
+  }
+  uv_mutex_unlock(&barrier->mutex);
+
+  uv_sem_wait(&barrier->turnstile1);
+  uv_sem_post(&barrier->turnstile1);
+
+  uv_mutex_lock(&barrier->mutex);
+  serial_thread = (--barrier->count == 0);
+  if (serial_thread) {
+    uv_sem_wait(&barrier->turnstile1);
+    uv_sem_post(&barrier->turnstile2);
+  }
+  uv_mutex_unlock(&barrier->mutex);
+
+  uv_sem_wait(&barrier->turnstile2);
+  uv_sem_post(&barrier->turnstile2);
+  return serial_thread;
+}
+
+
+int uv_key_create(uv_key_t* key) {
+  key->tls_index = TlsAlloc();
+  if (key->tls_index == TLS_OUT_OF_INDEXES)
+    return UV_ENOMEM;
+  return 0;
+}
+
+
+void uv_key_delete(uv_key_t* key) {
+  if (TlsFree(key->tls_index) == FALSE)
+    abort();
+  key->tls_index = TLS_OUT_OF_INDEXES;
+}
+
+
+void* uv_key_get(uv_key_t* key) {
+  void* value;
+
+  value = TlsGetValue(key->tls_index);
+  if (value == NULL)
+    if (GetLastError() != ERROR_SUCCESS)
+      abort();
+
+  return value;
+}
+
+
+void uv_key_set(uv_key_t* key, void* value) {
+  if (TlsSetValue(key->tls_index, value) == FALSE)
+    abort();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/timer.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/timer.cpp
new file mode 100644
index 0000000..eda5c24
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/timer.cpp
@@ -0,0 +1,195 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <limits.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "uv/tree.h"
+#include "handle-inl.h"
+
+
+/* The number of milliseconds in one second. */
+#define UV__MILLISEC 1000
+
+
+void uv_update_time(uv_loop_t* loop) {
+  uint64_t new_time = uv__hrtime(UV__MILLISEC);
+  assert(new_time >= loop->time);
+  loop->time = new_time;
+}
+
+
+static int uv_timer_compare(uv_timer_t* a, uv_timer_t* b) {
+  if (a->due < b->due)
+    return -1;
+  if (a->due > b->due)
+    return 1;
+  /*
+   *  compare start_id when both has the same due. start_id is
+   *  allocated with loop->timer_counter in uv_timer_start().
+   */
+  if (a->start_id < b->start_id)
+    return -1;
+  if (a->start_id > b->start_id)
+    return 1;
+  return 0;
+}
+
+
+RB_GENERATE_STATIC(uv_timer_tree_s, uv_timer_s, tree_entry, uv_timer_compare)
+
+
+int uv_timer_init(uv_loop_t* loop, uv_timer_t* handle) {
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_TIMER);
+  handle->timer_cb = NULL;
+  handle->repeat = 0;
+
+  return 0;
+}
+
+
+void uv_timer_endgame(uv_loop_t* loop, uv_timer_t* handle) {
+  if (handle->flags & UV__HANDLE_CLOSING) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+    uv__handle_close(handle);
+  }
+}
+
+
+static uint64_t get_clamped_due_time(uint64_t loop_time, uint64_t timeout) {
+  uint64_t clamped_timeout;
+
+  clamped_timeout = loop_time + timeout;
+  if (clamped_timeout < timeout)
+    clamped_timeout = (uint64_t) -1;
+
+  return clamped_timeout;
+}
+
+
+int uv_timer_start(uv_timer_t* handle, uv_timer_cb timer_cb, uint64_t timeout,
+    uint64_t repeat) {
+  uv_loop_t* loop = handle->loop;
+  uv_timer_t* old;
+
+  if (timer_cb == NULL)
+    return UV_EINVAL;
+
+  if (uv__is_active(handle))
+    uv_timer_stop(handle);
+
+  handle->timer_cb = timer_cb;
+  handle->due = get_clamped_due_time(loop->time, timeout);
+  handle->repeat = repeat;
+  uv__handle_start(handle);
+
+  /* start_id is the second index to be compared in uv__timer_cmp() */
+  handle->start_id = handle->loop->timer_counter++;
+
+  old = RB_INSERT(uv_timer_tree_s, &loop->timers, handle);
+  assert(old == NULL);
+
+  return 0;
+}
+
+
+int uv_timer_stop(uv_timer_t* handle) {
+  uv_loop_t* loop = handle->loop;
+
+  if (!uv__is_active(handle))
+    return 0;
+
+  RB_REMOVE(uv_timer_tree_s, &loop->timers, handle);
+  uv__handle_stop(handle);
+
+  return 0;
+}
+
+
+int uv_timer_again(uv_timer_t* handle) {
+  /* If timer_cb is NULL that means that the timer was never started. */
+  if (!handle->timer_cb) {
+    return UV_EINVAL;
+  }
+
+  if (handle->repeat) {
+    uv_timer_stop(handle);
+    uv_timer_start(handle, handle->timer_cb, handle->repeat, handle->repeat);
+  }
+
+  return 0;
+}
+
+
+void uv_timer_set_repeat(uv_timer_t* handle, uint64_t repeat) {
+  assert(handle->type == UV_TIMER);
+  handle->repeat = repeat;
+}
+
+
+uint64_t uv_timer_get_repeat(const uv_timer_t* handle) {
+  assert(handle->type == UV_TIMER);
+  return handle->repeat;
+}
+
+
+DWORD uv__next_timeout(const uv_loop_t* loop) {
+  uv_timer_t* timer;
+  int64_t delta;
+
+  /* Check if there are any running timers
+   * Need to cast away const first, since RB_MIN doesn't know what we are
+   * going to do with this return value, it can't be marked const
+   */
+  timer = RB_MIN(uv_timer_tree_s, &((uv_loop_t*)loop)->timers);
+  if (timer) {
+    delta = timer->due - loop->time;
+    if (delta >= UINT_MAX - 1) {
+      /* A timeout value of UINT_MAX means infinite, so that's no good. */
+      return UINT_MAX - 1;
+    } else if (delta < 0) {
+      /* Negative timeout values are not allowed */
+      return 0;
+    } else {
+      return (DWORD)delta;
+    }
+  } else {
+    /* No timers */
+    return INFINITE;
+  }
+}
+
+
+void uv_process_timers(uv_loop_t* loop) {
+  uv_timer_t* timer;
+
+  /* Call timer callbacks */
+  for (timer = RB_MIN(uv_timer_tree_s, &loop->timers);
+       timer != NULL && timer->due <= loop->time;
+       timer = RB_MIN(uv_timer_tree_s, &loop->timers)) {
+
+    uv_timer_stop(timer);
+    uv_timer_again(timer);
+    timer->timer_cb((uv_timer_t*) timer);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/tty.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/tty.cpp
new file mode 100644
index 0000000..4ac21b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/tty.cpp
@@ -0,0 +1,2335 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <io.h>
+#include <string.h>
+#include <stdlib.h>
+
+#if defined(_MSC_VER) && _MSC_VER < 1600
+# include "uv/stdint-msvc2008.h"
+#else
+# include <stdint.h>
+#endif
+
+#ifndef COMMON_LVB_REVERSE_VIDEO
+# define COMMON_LVB_REVERSE_VIDEO 0x4000
+#endif
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "stream-inl.h"
+#include "req-inl.h"
+
+#pragma comment(lib, "User32.lib")
+
+#ifndef InterlockedOr
+# define InterlockedOr _InterlockedOr
+#endif
+
+#define UNICODE_REPLACEMENT_CHARACTER (0xfffd)
+
+#define ANSI_NORMAL           0x00
+#define ANSI_ESCAPE_SEEN      0x02
+#define ANSI_CSI              0x04
+#define ANSI_ST_CONTROL       0x08
+#define ANSI_IGNORE           0x10
+#define ANSI_IN_ARG           0x20
+#define ANSI_IN_STRING        0x40
+#define ANSI_BACKSLASH_SEEN   0x80
+
+#define MAX_INPUT_BUFFER_LENGTH 8192
+#define MAX_CONSOLE_CHAR 8192
+
+#ifndef ENABLE_VIRTUAL_TERMINAL_PROCESSING
+#define ENABLE_VIRTUAL_TERMINAL_PROCESSING 0x0004
+#endif
+
+static void uv_tty_capture_initial_style(CONSOLE_SCREEN_BUFFER_INFO* info);
+static void uv_tty_update_virtual_window(CONSOLE_SCREEN_BUFFER_INFO* info);
+static int uv__cancel_read_console(uv_tty_t* handle);
+
+
+/* Null uv_buf_t */
+static const uv_buf_t uv_null_buf_ = { 0, NULL };
+
+enum uv__read_console_status_e {
+  NOT_STARTED,
+  IN_PROGRESS,
+  TRAP_REQUESTED,
+  COMPLETED
+};
+
+static volatile LONG uv__read_console_status = NOT_STARTED;
+static volatile LONG uv__restore_screen_state;
+static CONSOLE_SCREEN_BUFFER_INFO uv__saved_screen_state;
+
+
+/*
+ * The console virtual window.
+ *
+ * Normally cursor movement in windows is relative to the console screen buffer,
+ * e.g. the application is allowed to overwrite the 'history'. This is very
+ * inconvenient, it makes absolute cursor movement pretty useless. There is
+ * also the concept of 'client rect' which is defined by the actual size of
+ * the console window and the scroll position of the screen buffer, but it's
+ * very volatile because it changes when the user scrolls.
+ *
+ * To make cursor movement behave sensibly we define a virtual window to which
+ * cursor movement is confined. The virtual window is always as wide as the
+ * console screen buffer, but it's height is defined by the size of the
+ * console window. The top of the virtual window aligns with the position
+ * of the caret when the first stdout/err handle is created, unless that would
+ * mean that it would extend beyond the bottom of the screen buffer -  in that
+ * that case it's located as far down as possible.
+ *
+ * When the user writes a long text or many newlines, such that the output
+ * reaches beyond the bottom of the virtual window, the virtual window is
+ * shifted downwards, but not resized.
+ *
+ * Since all tty i/o happens on the same console, this window is shared
+ * between all stdout/stderr handles.
+ */
+
+static int uv_tty_virtual_offset = -1;
+static int uv_tty_virtual_height = -1;
+static int uv_tty_virtual_width = -1;
+
+/* The console window size
+ * We keep this separate from uv_tty_virtual_*. We use those values to only
+ * handle signalling SIGWINCH
+ */
+
+static HANDLE uv__tty_console_handle = INVALID_HANDLE_VALUE;
+static int uv__tty_console_height = -1;
+static int uv__tty_console_width = -1;
+
+static DWORD WINAPI uv__tty_console_resize_message_loop_thread(void* param);
+static void CALLBACK uv__tty_console_resize_event(HWINEVENTHOOK hWinEventHook,
+                                                  DWORD event,
+                                                  HWND hwnd,
+                                                  LONG idObject,
+                                                  LONG idChild,
+                                                  DWORD dwEventThread,
+                                                  DWORD dwmsEventTime);
+
+/* We use a semaphore rather than a mutex or critical section because in some
+   cases (uv__cancel_read_console) we need take the lock in the main thread and
+   release it in another thread. Using a semaphore ensures that in such
+   scenario the main thread will still block when trying to acquire the lock. */
+static uv_sem_t uv_tty_output_lock;
+
+static WORD uv_tty_default_text_attributes =
+    FOREGROUND_RED | FOREGROUND_GREEN | FOREGROUND_BLUE;
+
+static char uv_tty_default_fg_color = 7;
+static char uv_tty_default_bg_color = 0;
+static char uv_tty_default_fg_bright = 0;
+static char uv_tty_default_bg_bright = 0;
+static char uv_tty_default_inverse = 0;
+
+typedef enum {
+  UV_SUPPORTED,
+  UV_UNCHECKED,
+  UV_UNSUPPORTED
+} uv_vtermstate_t;
+/* Determine whether or not ANSI support is enabled. */
+static uv_vtermstate_t uv__vterm_state = UV_UNCHECKED;
+static void uv__determine_vterm_state(HANDLE handle);
+
+void uv_console_init(void) {
+  if (uv_sem_init(&uv_tty_output_lock, 1))
+    abort();
+  uv__tty_console_handle = CreateFileW(L"CONOUT$",
+                                       GENERIC_READ | GENERIC_WRITE,
+                                       FILE_SHARE_WRITE,
+                                       0,
+                                       OPEN_EXISTING,
+                                       0,
+                                       0);
+  if (uv__tty_console_handle != NULL) {
+    QueueUserWorkItem(uv__tty_console_resize_message_loop_thread,
+                      NULL,
+                      WT_EXECUTELONGFUNCTION);
+  }
+}
+
+
+int uv_tty_init(uv_loop_t* loop, uv_tty_t* tty, uv_file fd, int readable) {
+  HANDLE handle;
+  CONSOLE_SCREEN_BUFFER_INFO screen_buffer_info;
+
+  uv__once_init();
+  handle = (HANDLE) uv__get_osfhandle(fd);
+  if (handle == INVALID_HANDLE_VALUE)
+    return UV_EBADF;
+
+  if (fd <= 2) {
+    /* In order to avoid closing a stdio file descriptor 0-2, duplicate the
+     * underlying OS handle and forget about the original fd.
+     * We could also opt to use the original OS handle and just never close it,
+     * but then there would be no reliable way to cancel pending read operations
+     * upon close.
+     */
+    if (!DuplicateHandle(INVALID_HANDLE_VALUE,
+                         handle,
+                         INVALID_HANDLE_VALUE,
+                         &handle,
+                         0,
+                         FALSE,
+                         DUPLICATE_SAME_ACCESS))
+      return uv_translate_sys_error(GetLastError());
+    fd = -1;
+  }
+
+  if (!readable) {
+    /* Obtain the screen buffer info with the output handle. */
+    if (!GetConsoleScreenBufferInfo(handle, &screen_buffer_info)) {
+      return uv_translate_sys_error(GetLastError());
+    }
+
+    /* Obtain the tty_output_lock because the virtual window state is shared
+     * between all uv_tty_t handles. */
+    uv_sem_wait(&uv_tty_output_lock);
+
+    if (uv__vterm_state == UV_UNCHECKED)
+      uv__determine_vterm_state(handle);
+
+    /* Remember the original console text attributes. */
+    uv_tty_capture_initial_style(&screen_buffer_info);
+
+    uv_tty_update_virtual_window(&screen_buffer_info);
+
+    uv_sem_post(&uv_tty_output_lock);
+  }
+
+
+  uv_stream_init(loop, (uv_stream_t*) tty, UV_TTY);
+  uv_connection_init((uv_stream_t*) tty);
+
+  tty->handle = handle;
+  tty->u.fd = fd;
+  tty->reqs_pending = 0;
+  tty->flags |= UV_HANDLE_BOUND;
+
+  if (readable) {
+    /* Initialize TTY input specific fields. */
+    tty->flags |= UV_HANDLE_TTY_READABLE | UV_HANDLE_READABLE;
+    /* TODO: remove me in v2.x. */
+    tty->tty.rd.unused_ = NULL;
+    tty->tty.rd.read_line_buffer = uv_null_buf_;
+    tty->tty.rd.read_raw_wait = NULL;
+
+    /* Init keycode-to-vt100 mapper state. */
+    tty->tty.rd.last_key_len = 0;
+    tty->tty.rd.last_key_offset = 0;
+    tty->tty.rd.last_utf16_high_surrogate = 0;
+    memset(&tty->tty.rd.last_input_record, 0, sizeof tty->tty.rd.last_input_record);
+  } else {
+    /* TTY output specific fields. */
+    tty->flags |= UV_HANDLE_WRITABLE;
+
+    /* Init utf8-to-utf16 conversion state. */
+    tty->tty.wr.utf8_bytes_left = 0;
+    tty->tty.wr.utf8_codepoint = 0;
+
+    /* Initialize eol conversion state */
+    tty->tty.wr.previous_eol = 0;
+
+    /* Init ANSI parser state. */
+    tty->tty.wr.ansi_parser_state = ANSI_NORMAL;
+  }
+
+  return 0;
+}
+
+
+/* Set the default console text attributes based on how the console was
+ * configured when libuv started.
+ */
+static void uv_tty_capture_initial_style(CONSOLE_SCREEN_BUFFER_INFO* info) {
+  static int style_captured = 0;
+
+  /* Only do this once.
+     Assumption: Caller has acquired uv_tty_output_lock. */
+  if (style_captured)
+    return;
+
+  /* Save raw win32 attributes. */
+  uv_tty_default_text_attributes = info->wAttributes;
+
+  /* Convert black text on black background to use white text. */
+  if (uv_tty_default_text_attributes == 0)
+    uv_tty_default_text_attributes = 7;
+
+  /* Convert Win32 attributes to ANSI colors. */
+  uv_tty_default_fg_color = 0;
+  uv_tty_default_bg_color = 0;
+  uv_tty_default_fg_bright = 0;
+  uv_tty_default_bg_bright = 0;
+  uv_tty_default_inverse = 0;
+
+  if (uv_tty_default_text_attributes & FOREGROUND_RED)
+    uv_tty_default_fg_color |= 1;
+
+  if (uv_tty_default_text_attributes & FOREGROUND_GREEN)
+    uv_tty_default_fg_color |= 2;
+
+  if (uv_tty_default_text_attributes & FOREGROUND_BLUE)
+    uv_tty_default_fg_color |= 4;
+
+  if (uv_tty_default_text_attributes & BACKGROUND_RED)
+    uv_tty_default_bg_color |= 1;
+
+  if (uv_tty_default_text_attributes & BACKGROUND_GREEN)
+    uv_tty_default_bg_color |= 2;
+
+  if (uv_tty_default_text_attributes & BACKGROUND_BLUE)
+    uv_tty_default_bg_color |= 4;
+
+  if (uv_tty_default_text_attributes & FOREGROUND_INTENSITY)
+    uv_tty_default_fg_bright = 1;
+
+  if (uv_tty_default_text_attributes & BACKGROUND_INTENSITY)
+    uv_tty_default_bg_bright = 1;
+
+  if (uv_tty_default_text_attributes & COMMON_LVB_REVERSE_VIDEO)
+    uv_tty_default_inverse = 1;
+
+  style_captured = 1;
+}
+
+
+int uv_tty_set_mode(uv_tty_t* tty, uv_tty_mode_t mode) {
+  DWORD flags;
+  unsigned char was_reading;
+  uv_alloc_cb alloc_cb;
+  uv_read_cb read_cb;
+  int err;
+
+  if (!(tty->flags & UV_HANDLE_TTY_READABLE)) {
+    return UV_EINVAL;
+  }
+
+  if (!!mode == !!(tty->flags & UV_HANDLE_TTY_RAW)) {
+    return 0;
+  }
+
+  switch (mode) {
+    case UV_TTY_MODE_NORMAL:
+      flags = ENABLE_ECHO_INPUT | ENABLE_LINE_INPUT | ENABLE_PROCESSED_INPUT;
+      break;
+    case UV_TTY_MODE_RAW:
+      flags = ENABLE_WINDOW_INPUT;
+      break;
+    case UV_TTY_MODE_IO:
+      return UV_ENOTSUP;
+    default:
+      return UV_EINVAL;
+  }
+
+  /* If currently reading, stop, and restart reading. */
+  if (tty->flags & UV_HANDLE_READING) {
+    was_reading = 1;
+    alloc_cb = tty->alloc_cb;
+    read_cb = tty->read_cb;
+    err = uv_tty_read_stop(tty);
+    if (err) {
+      return uv_translate_sys_error(err);
+    }
+  } else {
+    was_reading = 0;
+  }
+
+  uv_sem_wait(&uv_tty_output_lock);
+  if (!SetConsoleMode(tty->handle, flags)) {
+    err = uv_translate_sys_error(GetLastError());
+    uv_sem_post(&uv_tty_output_lock);
+    return err;
+  }
+  uv_sem_post(&uv_tty_output_lock);
+
+  /* Update flag. */
+  tty->flags &= ~UV_HANDLE_TTY_RAW;
+  tty->flags |= mode ? UV_HANDLE_TTY_RAW : 0;
+
+  /* If we just stopped reading, restart. */
+  if (was_reading) {
+    err = uv_tty_read_start(tty, alloc_cb, read_cb);
+    if (err) {
+      return uv_translate_sys_error(err);
+    }
+  }
+
+  return 0;
+}
+
+
+int uv_is_tty(uv_file file) {
+  DWORD result;
+  return GetConsoleMode((HANDLE) _get_osfhandle(file), &result) != 0;
+}
+
+
+int uv_tty_get_winsize(uv_tty_t* tty, int* width, int* height) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+
+  if (!GetConsoleScreenBufferInfo(tty->handle, &info)) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  uv_sem_wait(&uv_tty_output_lock);
+  uv_tty_update_virtual_window(&info);
+  uv_sem_post(&uv_tty_output_lock);
+
+  *width = uv_tty_virtual_width;
+  *height = uv_tty_virtual_height;
+
+  return 0;
+}
+
+
+static void CALLBACK uv_tty_post_raw_read(void* data, BOOLEAN didTimeout) {
+  uv_loop_t* loop;
+  uv_tty_t* handle;
+  uv_req_t* req;
+
+  assert(data);
+  assert(!didTimeout);
+
+  req = (uv_req_t*) data;
+  handle = (uv_tty_t*) req->data;
+  loop = handle->loop;
+
+  UnregisterWait(handle->tty.rd.read_raw_wait);
+  handle->tty.rd.read_raw_wait = NULL;
+
+  SET_REQ_SUCCESS(req);
+  POST_COMPLETION_FOR_REQ(loop, req);
+}
+
+
+static void uv_tty_queue_read_raw(uv_loop_t* loop, uv_tty_t* handle) {
+  uv_read_t* req;
+  BOOL r;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+
+  assert(handle->handle && handle->handle != INVALID_HANDLE_VALUE);
+
+  handle->tty.rd.read_line_buffer = uv_null_buf_;
+
+  req = &handle->read_req;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  r = RegisterWaitForSingleObject(&handle->tty.rd.read_raw_wait,
+                                  handle->handle,
+                                  uv_tty_post_raw_read,
+                                  (void*) req,
+                                  INFINITE,
+                                  WT_EXECUTEINWAITTHREAD | WT_EXECUTEONLYONCE);
+  if (!r) {
+    handle->tty.rd.read_raw_wait = NULL;
+    SET_REQ_ERROR(req, GetLastError());
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+  }
+
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+}
+
+
+static DWORD CALLBACK uv_tty_line_read_thread(void* data) {
+  uv_loop_t* loop;
+  uv_tty_t* handle;
+  uv_req_t* req;
+  DWORD bytes, read_bytes;
+  WCHAR utf16[MAX_INPUT_BUFFER_LENGTH / 3];
+  DWORD chars, read_chars;
+  LONG status;
+  COORD pos;
+  BOOL read_console_success;
+
+  assert(data);
+
+  req = (uv_req_t*) data;
+  handle = (uv_tty_t*) req->data;
+  loop = handle->loop;
+
+  assert(handle->tty.rd.read_line_buffer.base != NULL);
+  assert(handle->tty.rd.read_line_buffer.len > 0);
+
+  /* ReadConsole can't handle big buffers. */
+  if (handle->tty.rd.read_line_buffer.len < MAX_INPUT_BUFFER_LENGTH) {
+    bytes = handle->tty.rd.read_line_buffer.len;
+  } else {
+    bytes = MAX_INPUT_BUFFER_LENGTH;
+  }
+
+  /* At last, unicode! One utf-16 codeunit never takes more than 3 utf-8
+   * codeunits to encode. */
+  chars = bytes / 3;
+
+  status = InterlockedExchange(&uv__read_console_status, IN_PROGRESS);
+  if (status == TRAP_REQUESTED) {
+    SET_REQ_SUCCESS(req);
+    req->u.io.overlapped.InternalHigh = 0;
+    POST_COMPLETION_FOR_REQ(loop, req);
+    return 0;
+  }
+
+  read_console_success = ReadConsoleW(handle->handle,
+                                      (void*) utf16,
+                                      chars,
+                                      &read_chars,
+                                      NULL);
+
+  if (read_console_success) {
+    read_bytes = WideCharToMultiByte(CP_UTF8,
+                                     0,
+                                     utf16,
+                                     read_chars,
+                                     handle->tty.rd.read_line_buffer.base,
+                                     bytes,
+                                     NULL,
+                                     NULL);
+    SET_REQ_SUCCESS(req);
+    req->u.io.overlapped.InternalHigh = read_bytes;
+  } else {
+    SET_REQ_ERROR(req, GetLastError());
+  }
+
+  status = InterlockedExchange(&uv__read_console_status, COMPLETED);
+
+  if (status ==  TRAP_REQUESTED) {
+    /* If we canceled the read by sending a VK_RETURN event, restore the
+       screen state to undo the visual effect of the VK_RETURN */
+    if (read_console_success && InterlockedOr(&uv__restore_screen_state, 0)) {
+      HANDLE active_screen_buffer;
+      active_screen_buffer = CreateFileA("conout$",
+                                         GENERIC_READ | GENERIC_WRITE,
+                                         FILE_SHARE_READ | FILE_SHARE_WRITE,
+                                         NULL,
+                                         OPEN_EXISTING,
+                                         FILE_ATTRIBUTE_NORMAL,
+                                         NULL);
+      if (active_screen_buffer != INVALID_HANDLE_VALUE) {
+        pos = uv__saved_screen_state.dwCursorPosition;
+
+        /* If the cursor was at the bottom line of the screen buffer, the
+           VK_RETURN would have caused the buffer contents to scroll up by one
+           line. The right position to reset the cursor to is therefore one line
+           higher */
+        if (pos.Y == uv__saved_screen_state.dwSize.Y - 1)
+          pos.Y--;
+
+        SetConsoleCursorPosition(active_screen_buffer, pos);
+        CloseHandle(active_screen_buffer);
+      }
+    }
+    uv_sem_post(&uv_tty_output_lock);
+  }
+  POST_COMPLETION_FOR_REQ(loop, req);
+  return 0;
+}
+
+
+static void uv_tty_queue_read_line(uv_loop_t* loop, uv_tty_t* handle) {
+  uv_read_t* req;
+  BOOL r;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+  assert(handle->handle && handle->handle != INVALID_HANDLE_VALUE);
+
+  req = &handle->read_req;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  handle->tty.rd.read_line_buffer = uv_buf_init(NULL, 0);
+  handle->alloc_cb((uv_handle_t*) handle, 8192, &handle->tty.rd.read_line_buffer);
+  if (handle->tty.rd.read_line_buffer.base == NULL ||
+      handle->tty.rd.read_line_buffer.len == 0) {
+    handle->read_cb((uv_stream_t*) handle,
+                    UV_ENOBUFS,
+                    &handle->tty.rd.read_line_buffer);
+    return;
+  }
+  assert(handle->tty.rd.read_line_buffer.base != NULL);
+
+  /* Reset flags  No locking is required since there cannot be a line read
+     in progress. We are also relying on the memory barrier provided by
+     QueueUserWorkItem*/
+  uv__restore_screen_state = FALSE;
+  uv__read_console_status = NOT_STARTED;
+  r = QueueUserWorkItem(uv_tty_line_read_thread,
+                        (void*) req,
+                        WT_EXECUTELONGFUNCTION);
+  if (!r) {
+    SET_REQ_ERROR(req, GetLastError());
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+  }
+
+  handle->flags |= UV_HANDLE_READ_PENDING;
+  handle->reqs_pending++;
+}
+
+
+static void uv_tty_queue_read(uv_loop_t* loop, uv_tty_t* handle) {
+  if (handle->flags & UV_HANDLE_TTY_RAW) {
+    uv_tty_queue_read_raw(loop, handle);
+  } else {
+    uv_tty_queue_read_line(loop, handle);
+  }
+}
+
+
+static const char* get_vt100_fn_key(DWORD code, char shift, char ctrl,
+    size_t* len) {
+#define VK_CASE(vk, normal_str, shift_str, ctrl_str, shift_ctrl_str)          \
+    case (vk):                                                                \
+      if (shift && ctrl) {                                                    \
+        *len = sizeof shift_ctrl_str;                                         \
+        return "\033" shift_ctrl_str;                                         \
+      } else if (shift) {                                                     \
+        *len = sizeof shift_str ;                                             \
+        return "\033" shift_str;                                              \
+      } else if (ctrl) {                                                      \
+        *len = sizeof ctrl_str;                                               \
+        return "\033" ctrl_str;                                               \
+      } else {                                                                \
+        *len = sizeof normal_str;                                             \
+        return "\033" normal_str;                                             \
+      }
+
+  switch (code) {
+    /* These mappings are the same as Cygwin's. Unmodified and alt-modified
+     * keypad keys comply with linux console, modifiers comply with xterm
+     * modifier usage. F1. f12 and shift-f1. f10 comply with linux console, f6.
+     * f12 with and without modifiers comply with rxvt. */
+    VK_CASE(VK_INSERT,  "[2~",  "[2;2~", "[2;5~", "[2;6~")
+    VK_CASE(VK_END,     "[4~",  "[4;2~", "[4;5~", "[4;6~")
+    VK_CASE(VK_DOWN,    "[B",   "[1;2B", "[1;5B", "[1;6B")
+    VK_CASE(VK_NEXT,    "[6~",  "[6;2~", "[6;5~", "[6;6~")
+    VK_CASE(VK_LEFT,    "[D",   "[1;2D", "[1;5D", "[1;6D")
+    VK_CASE(VK_CLEAR,   "[G",   "[1;2G", "[1;5G", "[1;6G")
+    VK_CASE(VK_RIGHT,   "[C",   "[1;2C", "[1;5C", "[1;6C")
+    VK_CASE(VK_UP,      "[A",   "[1;2A", "[1;5A", "[1;6A")
+    VK_CASE(VK_HOME,    "[1~",  "[1;2~", "[1;5~", "[1;6~")
+    VK_CASE(VK_PRIOR,   "[5~",  "[5;2~", "[5;5~", "[5;6~")
+    VK_CASE(VK_DELETE,  "[3~",  "[3;2~", "[3;5~", "[3;6~")
+    VK_CASE(VK_NUMPAD0, "[2~",  "[2;2~", "[2;5~", "[2;6~")
+    VK_CASE(VK_NUMPAD1, "[4~",  "[4;2~", "[4;5~", "[4;6~")
+    VK_CASE(VK_NUMPAD2, "[B",   "[1;2B", "[1;5B", "[1;6B")
+    VK_CASE(VK_NUMPAD3, "[6~",  "[6;2~", "[6;5~", "[6;6~")
+    VK_CASE(VK_NUMPAD4, "[D",   "[1;2D", "[1;5D", "[1;6D")
+    VK_CASE(VK_NUMPAD5, "[G",   "[1;2G", "[1;5G", "[1;6G")
+    VK_CASE(VK_NUMPAD6, "[C",   "[1;2C", "[1;5C", "[1;6C")
+    VK_CASE(VK_NUMPAD7, "[A",   "[1;2A", "[1;5A", "[1;6A")
+    VK_CASE(VK_NUMPAD8, "[1~",  "[1;2~", "[1;5~", "[1;6~")
+    VK_CASE(VK_NUMPAD9, "[5~",  "[5;2~", "[5;5~", "[5;6~")
+    VK_CASE(VK_DECIMAL, "[3~",  "[3;2~", "[3;5~", "[3;6~")
+    VK_CASE(VK_F1,      "[[A",  "[23~",  "[11^",  "[23^" )
+    VK_CASE(VK_F2,      "[[B",  "[24~",  "[12^",  "[24^" )
+    VK_CASE(VK_F3,      "[[C",  "[25~",  "[13^",  "[25^" )
+    VK_CASE(VK_F4,      "[[D",  "[26~",  "[14^",  "[26^" )
+    VK_CASE(VK_F5,      "[[E",  "[28~",  "[15^",  "[28^" )
+    VK_CASE(VK_F6,      "[17~", "[29~",  "[17^",  "[29^" )
+    VK_CASE(VK_F7,      "[18~", "[31~",  "[18^",  "[31^" )
+    VK_CASE(VK_F8,      "[19~", "[32~",  "[19^",  "[32^" )
+    VK_CASE(VK_F9,      "[20~", "[33~",  "[20^",  "[33^" )
+    VK_CASE(VK_F10,     "[21~", "[34~",  "[21^",  "[34^" )
+    VK_CASE(VK_F11,     "[23~", "[23$",  "[23^",  "[23@" )
+    VK_CASE(VK_F12,     "[24~", "[24$",  "[24^",  "[24@" )
+
+    default:
+      *len = 0;
+      return NULL;
+  }
+#undef VK_CASE
+}
+
+
+void uv_process_tty_read_raw_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* req) {
+  /* Shortcut for handle->tty.rd.last_input_record.Event.KeyEvent. */
+#define KEV handle->tty.rd.last_input_record.Event.KeyEvent
+
+  DWORD records_left, records_read;
+  uv_buf_t buf;
+  off_t buf_used;
+
+  assert(handle->type == UV_TTY);
+  assert(handle->flags & UV_HANDLE_TTY_READABLE);
+  handle->flags &= ~UV_HANDLE_READ_PENDING;
+
+  if (!(handle->flags & UV_HANDLE_READING) ||
+      !(handle->flags & UV_HANDLE_TTY_RAW)) {
+    goto out;
+  }
+
+  if (!REQ_SUCCESS(req)) {
+    /* An error occurred while waiting for the event. */
+    if ((handle->flags & UV_HANDLE_READING)) {
+      handle->flags &= ~UV_HANDLE_READING;
+      handle->read_cb((uv_stream_t*)handle,
+                      uv_translate_sys_error(GET_REQ_ERROR(req)),
+                      &uv_null_buf_);
+    }
+    goto out;
+  }
+
+  /* Fetch the number of events  */
+  if (!GetNumberOfConsoleInputEvents(handle->handle, &records_left)) {
+    handle->flags &= ~UV_HANDLE_READING;
+    DECREASE_ACTIVE_COUNT(loop, handle);
+    handle->read_cb((uv_stream_t*)handle,
+                    uv_translate_sys_error(GetLastError()),
+                    &uv_null_buf_);
+    goto out;
+  }
+
+  /* Windows sends a lot of events that we're not interested in, so buf will be
+   * allocated on demand, when there's actually something to emit. */
+  buf = uv_null_buf_;
+  buf_used = 0;
+
+  while ((records_left > 0 || handle->tty.rd.last_key_len > 0) &&
+         (handle->flags & UV_HANDLE_READING)) {
+    if (handle->tty.rd.last_key_len == 0) {
+      /* Read the next input record */
+      if (!ReadConsoleInputW(handle->handle,
+                             &handle->tty.rd.last_input_record,
+                             1,
+                             &records_read)) {
+        handle->flags &= ~UV_HANDLE_READING;
+        DECREASE_ACTIVE_COUNT(loop, handle);
+        handle->read_cb((uv_stream_t*) handle,
+                        uv_translate_sys_error(GetLastError()),
+                        &buf);
+        goto out;
+      }
+      records_left--;
+
+      /* Ignore other events that are not key events. */
+      if (handle->tty.rd.last_input_record.EventType != KEY_EVENT) {
+        continue;
+      }
+
+      /* Ignore keyup events, unless the left alt key was held and a valid
+       * unicode character was emitted. */
+      if (!KEV.bKeyDown && !(((KEV.dwControlKeyState & LEFT_ALT_PRESSED) ||
+          KEV.wVirtualKeyCode==VK_MENU) && KEV.uChar.UnicodeChar != 0)) {
+        continue;
+      }
+
+      /* Ignore keypresses to numpad number keys if the left alt is held
+       * because the user is composing a character, or windows simulating this.
+       */
+      if ((KEV.dwControlKeyState & LEFT_ALT_PRESSED) &&
+          !(KEV.dwControlKeyState & ENHANCED_KEY) &&
+          (KEV.wVirtualKeyCode == VK_INSERT ||
+          KEV.wVirtualKeyCode == VK_END ||
+          KEV.wVirtualKeyCode == VK_DOWN ||
+          KEV.wVirtualKeyCode == VK_NEXT ||
+          KEV.wVirtualKeyCode == VK_LEFT ||
+          KEV.wVirtualKeyCode == VK_CLEAR ||
+          KEV.wVirtualKeyCode == VK_RIGHT ||
+          KEV.wVirtualKeyCode == VK_HOME ||
+          KEV.wVirtualKeyCode == VK_UP ||
+          KEV.wVirtualKeyCode == VK_PRIOR ||
+          KEV.wVirtualKeyCode == VK_NUMPAD0 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD1 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD2 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD3 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD4 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD5 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD6 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD7 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD8 ||
+          KEV.wVirtualKeyCode == VK_NUMPAD9)) {
+        continue;
+      }
+
+      if (KEV.uChar.UnicodeChar != 0) {
+        int prefix_len, char_len;
+
+        /* Character key pressed */
+        if (KEV.uChar.UnicodeChar >= 0xD800 &&
+            KEV.uChar.UnicodeChar < 0xDC00) {
+          /* UTF-16 high surrogate */
+          handle->tty.rd.last_utf16_high_surrogate = KEV.uChar.UnicodeChar;
+          continue;
+        }
+
+        /* Prefix with \u033 if alt was held, but alt was not used as part a
+         * compose sequence. */
+        if ((KEV.dwControlKeyState & (LEFT_ALT_PRESSED | RIGHT_ALT_PRESSED))
+            && !(KEV.dwControlKeyState & (LEFT_CTRL_PRESSED |
+            RIGHT_CTRL_PRESSED)) && KEV.bKeyDown) {
+          handle->tty.rd.last_key[0] = '\033';
+          prefix_len = 1;
+        } else {
+          prefix_len = 0;
+        }
+
+        if (KEV.uChar.UnicodeChar >= 0xDC00 &&
+            KEV.uChar.UnicodeChar < 0xE000) {
+          /* UTF-16 surrogate pair */
+          WCHAR utf16_buffer[2] = { handle->tty.rd.last_utf16_high_surrogate,
+                                    KEV.uChar.UnicodeChar};
+          char_len = WideCharToMultiByte(CP_UTF8,
+                                         0,
+                                         utf16_buffer,
+                                         2,
+                                         &handle->tty.rd.last_key[prefix_len],
+                                         sizeof handle->tty.rd.last_key,
+                                         NULL,
+                                         NULL);
+        } else {
+          /* Single UTF-16 character */
+          char_len = WideCharToMultiByte(CP_UTF8,
+                                         0,
+                                         &KEV.uChar.UnicodeChar,
+                                         1,
+                                         &handle->tty.rd.last_key[prefix_len],
+                                         sizeof handle->tty.rd.last_key,
+                                         NULL,
+                                         NULL);
+        }
+
+        /* Whatever happened, the last character wasn't a high surrogate. */
+        handle->tty.rd.last_utf16_high_surrogate = 0;
+
+        /* If the utf16 character(s) couldn't be converted something must be
+         * wrong. */
+        if (!char_len) {
+          handle->flags &= ~UV_HANDLE_READING;
+          DECREASE_ACTIVE_COUNT(loop, handle);
+          handle->read_cb((uv_stream_t*) handle,
+                          uv_translate_sys_error(GetLastError()),
+                          &buf);
+          goto out;
+        }
+
+        handle->tty.rd.last_key_len = (unsigned char) (prefix_len + char_len);
+        handle->tty.rd.last_key_offset = 0;
+        continue;
+
+      } else {
+        /* Function key pressed */
+        const char* vt100;
+        size_t prefix_len, vt100_len;
+
+        vt100 = get_vt100_fn_key(KEV.wVirtualKeyCode,
+                                  !!(KEV.dwControlKeyState & SHIFT_PRESSED),
+                                  !!(KEV.dwControlKeyState & (
+                                    LEFT_CTRL_PRESSED |
+                                    RIGHT_CTRL_PRESSED)),
+                                  &vt100_len);
+
+        /* If we were unable to map to a vt100 sequence, just ignore. */
+        if (!vt100) {
+          continue;
+        }
+
+        /* Prefix with \x033 when the alt key was held. */
+        if (KEV.dwControlKeyState & (LEFT_ALT_PRESSED | RIGHT_ALT_PRESSED)) {
+          handle->tty.rd.last_key[0] = '\033';
+          prefix_len = 1;
+        } else {
+          prefix_len = 0;
+        }
+
+        /* Copy the vt100 sequence to the handle buffer. */
+        assert(prefix_len + vt100_len < sizeof handle->tty.rd.last_key);
+        memcpy(&handle->tty.rd.last_key[prefix_len], vt100, vt100_len);
+
+        handle->tty.rd.last_key_len = (unsigned char) (prefix_len + vt100_len);
+        handle->tty.rd.last_key_offset = 0;
+        continue;
+      }
+    } else {
+      /* Copy any bytes left from the last keypress to the user buffer. */
+      if (handle->tty.rd.last_key_offset < handle->tty.rd.last_key_len) {
+        /* Allocate a buffer if needed */
+        if (buf_used == 0) {
+          buf = uv_buf_init(NULL, 0);
+          handle->alloc_cb((uv_handle_t*) handle, 1024, &buf);
+          if (buf.base == NULL || buf.len == 0) {
+            handle->read_cb((uv_stream_t*) handle, UV_ENOBUFS, &buf);
+            goto out;
+          }
+          assert(buf.base != NULL);
+        }
+
+        buf.base[buf_used++] = handle->tty.rd.last_key[handle->tty.rd.last_key_offset++];
+
+        /* If the buffer is full, emit it */
+        if ((size_t) buf_used == buf.len) {
+          handle->read_cb((uv_stream_t*) handle, buf_used, &buf);
+          buf = uv_null_buf_;
+          buf_used = 0;
+        }
+
+        continue;
+      }
+
+      /* Apply dwRepeat from the last input record. */
+      if (--KEV.wRepeatCount > 0) {
+        handle->tty.rd.last_key_offset = 0;
+        continue;
+      }
+
+      handle->tty.rd.last_key_len = 0;
+      continue;
+    }
+  }
+
+  /* Send the buffer back to the user */
+  if (buf_used > 0) {
+    handle->read_cb((uv_stream_t*) handle, buf_used, &buf);
+  }
+
+ out:
+  /* Wait for more input events. */
+  if ((handle->flags & UV_HANDLE_READING) &&
+      !(handle->flags & UV_HANDLE_READ_PENDING)) {
+    uv_tty_queue_read(loop, handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+
+#undef KEV
+}
+
+
+
+void uv_process_tty_read_line_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* req) {
+  uv_buf_t buf;
+
+  assert(handle->type == UV_TTY);
+  assert(handle->flags & UV_HANDLE_TTY_READABLE);
+
+  buf = handle->tty.rd.read_line_buffer;
+
+  handle->flags &= ~UV_HANDLE_READ_PENDING;
+  handle->tty.rd.read_line_buffer = uv_null_buf_;
+
+  if (!REQ_SUCCESS(req)) {
+    /* Read was not successful */
+    if (handle->flags & UV_HANDLE_READING) {
+      /* Real error */
+      handle->flags &= ~UV_HANDLE_READING;
+      DECREASE_ACTIVE_COUNT(loop, handle);
+      handle->read_cb((uv_stream_t*) handle,
+                      uv_translate_sys_error(GET_REQ_ERROR(req)),
+                      &buf);
+    } else {
+      /* The read was cancelled, or whatever we don't care */
+      handle->read_cb((uv_stream_t*) handle, 0, &buf);
+    }
+
+  } else {
+    if (!(handle->flags & UV_HANDLE_CANCELLATION_PENDING)) {
+      /* Read successful. TODO: read unicode, convert to utf-8 */
+      DWORD bytes = req->u.io.overlapped.InternalHigh;
+      handle->read_cb((uv_stream_t*) handle, bytes, &buf);
+    } else {
+      handle->flags &= ~UV_HANDLE_CANCELLATION_PENDING;
+      handle->read_cb((uv_stream_t*) handle, 0, &buf);
+    }
+  }
+
+  /* Wait for more input events. */
+  if ((handle->flags & UV_HANDLE_READING) &&
+      !(handle->flags & UV_HANDLE_READ_PENDING)) {
+    uv_tty_queue_read(loop, handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_process_tty_read_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* req) {
+  assert(handle->type == UV_TTY);
+  assert(handle->flags & UV_HANDLE_TTY_READABLE);
+
+  /* If the read_line_buffer member is zero, it must have been an raw read.
+   * Otherwise it was a line-buffered read. FIXME: This is quite obscure. Use a
+   * flag or something. */
+  if (handle->tty.rd.read_line_buffer.len == 0) {
+    uv_process_tty_read_raw_req(loop, handle, req);
+  } else {
+    uv_process_tty_read_line_req(loop, handle, req);
+  }
+}
+
+
+int uv_tty_read_start(uv_tty_t* handle, uv_alloc_cb alloc_cb,
+    uv_read_cb read_cb) {
+  uv_loop_t* loop = handle->loop;
+
+  if (!(handle->flags & UV_HANDLE_TTY_READABLE)) {
+    return ERROR_INVALID_PARAMETER;
+  }
+
+  handle->flags |= UV_HANDLE_READING;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+  handle->read_cb = read_cb;
+  handle->alloc_cb = alloc_cb;
+
+  /* If reading was stopped and then started again, there could still be a read
+   * request pending. */
+  if (handle->flags & UV_HANDLE_READ_PENDING) {
+    return 0;
+  }
+
+  /* Maybe the user stopped reading half-way while processing key events.
+   * Short-circuit if this could be the case. */
+  if (handle->tty.rd.last_key_len > 0) {
+    SET_REQ_SUCCESS(&handle->read_req);
+    uv_insert_pending_req(handle->loop, (uv_req_t*) &handle->read_req);
+    /* Make sure no attempt is made to insert it again until it's handled. */
+    handle->flags |= UV_HANDLE_READ_PENDING;
+    handle->reqs_pending++;
+    return 0;
+  }
+
+  uv_tty_queue_read(loop, handle);
+
+  return 0;
+}
+
+
+int uv_tty_read_stop(uv_tty_t* handle) {
+  INPUT_RECORD record;
+  DWORD written, err;
+
+  handle->flags &= ~UV_HANDLE_READING;
+  DECREASE_ACTIVE_COUNT(handle->loop, handle);
+
+  if (!(handle->flags & UV_HANDLE_READ_PENDING))
+    return 0;
+
+  if (handle->flags & UV_HANDLE_TTY_RAW) {
+    /* Cancel raw read. Write some bullshit event to force the console wait to
+     * return. */
+    memset(&record, 0, sizeof record);
+    if (!WriteConsoleInputW(handle->handle, &record, 1, &written)) {
+      return GetLastError();
+    }
+  } else if (!(handle->flags & UV_HANDLE_CANCELLATION_PENDING)) {
+    /* Cancel line-buffered read if not already pending */
+    err = uv__cancel_read_console(handle);
+    if (err)
+      return err;
+
+    handle->flags |= UV_HANDLE_CANCELLATION_PENDING;
+  }
+
+  return 0;
+}
+
+static int uv__cancel_read_console(uv_tty_t* handle) {
+  HANDLE active_screen_buffer = INVALID_HANDLE_VALUE;
+  INPUT_RECORD record;
+  DWORD written;
+  DWORD err = 0;
+  LONG status;
+
+  assert(!(handle->flags & UV_HANDLE_CANCELLATION_PENDING));
+
+  /* Hold the output lock during the cancellation, to ensure that further
+     writes don't interfere with the screen state. It will be the ReadConsole
+     thread's responsibility to release the lock. */
+  uv_sem_wait(&uv_tty_output_lock);
+  status = InterlockedExchange(&uv__read_console_status, TRAP_REQUESTED);
+  if (status != IN_PROGRESS) {
+    /* Either we have managed to set a trap for the other thread before
+       ReadConsole is called, or ReadConsole has returned because the user
+       has pressed ENTER. In either case, there is nothing else to do. */
+    uv_sem_post(&uv_tty_output_lock);
+    return 0;
+  }
+
+  /* Save screen state before sending the VK_RETURN event */
+  active_screen_buffer = CreateFileA("conout$",
+                                     GENERIC_READ | GENERIC_WRITE,
+                                     FILE_SHARE_READ | FILE_SHARE_WRITE,
+                                     NULL,
+                                     OPEN_EXISTING,
+                                     FILE_ATTRIBUTE_NORMAL,
+                                     NULL);
+
+  if (active_screen_buffer != INVALID_HANDLE_VALUE &&
+      GetConsoleScreenBufferInfo(active_screen_buffer,
+                                 &uv__saved_screen_state)) {
+    InterlockedOr(&uv__restore_screen_state, 1);
+  }
+
+  /* Write enter key event to force the console wait to return. */
+  record.EventType = KEY_EVENT;
+  record.Event.KeyEvent.bKeyDown = TRUE;
+  record.Event.KeyEvent.wRepeatCount = 1;
+  record.Event.KeyEvent.wVirtualKeyCode = VK_RETURN;
+  record.Event.KeyEvent.wVirtualScanCode =
+    MapVirtualKeyW(VK_RETURN, MAPVK_VK_TO_VSC);
+  record.Event.KeyEvent.uChar.UnicodeChar = L'\r';
+  record.Event.KeyEvent.dwControlKeyState = 0;
+  if (!WriteConsoleInputW(handle->handle, &record, 1, &written))
+    err = GetLastError();
+
+  if (active_screen_buffer != INVALID_HANDLE_VALUE)
+    CloseHandle(active_screen_buffer);
+
+  return err;
+}
+
+
+static void uv_tty_update_virtual_window(CONSOLE_SCREEN_BUFFER_INFO* info) {
+  uv_tty_virtual_width = info->dwSize.X;
+  uv_tty_virtual_height = info->srWindow.Bottom - info->srWindow.Top + 1;
+
+  /* Recompute virtual window offset row. */
+  if (uv_tty_virtual_offset == -1) {
+    uv_tty_virtual_offset = info->dwCursorPosition.Y;
+  } else if (uv_tty_virtual_offset < info->dwCursorPosition.Y -
+             uv_tty_virtual_height + 1) {
+    /* If suddenly find the cursor outside of the virtual window, it must have
+     * somehow scrolled. Update the virtual window offset. */
+    uv_tty_virtual_offset = info->dwCursorPosition.Y -
+                            uv_tty_virtual_height + 1;
+  }
+  if (uv_tty_virtual_offset + uv_tty_virtual_height > info->dwSize.Y) {
+    uv_tty_virtual_offset = info->dwSize.Y - uv_tty_virtual_height;
+  }
+  if (uv_tty_virtual_offset < 0) {
+    uv_tty_virtual_offset = 0;
+  }
+}
+
+
+static COORD uv_tty_make_real_coord(uv_tty_t* handle,
+    CONSOLE_SCREEN_BUFFER_INFO* info, int x, unsigned char x_relative, int y,
+    unsigned char y_relative) {
+  COORD result;
+
+  uv_tty_update_virtual_window(info);
+
+  /* Adjust y position */
+  if (y_relative) {
+    y = info->dwCursorPosition.Y + y;
+  } else {
+    y = uv_tty_virtual_offset + y;
+  }
+  /* Clip y to virtual client rectangle */
+  if (y < uv_tty_virtual_offset) {
+    y = uv_tty_virtual_offset;
+  } else if (y >= uv_tty_virtual_offset + uv_tty_virtual_height) {
+    y = uv_tty_virtual_offset + uv_tty_virtual_height - 1;
+  }
+
+  /* Adjust x */
+  if (x_relative) {
+    x = info->dwCursorPosition.X + x;
+  }
+  /* Clip x */
+  if (x < 0) {
+    x = 0;
+  } else if (x >= uv_tty_virtual_width) {
+    x = uv_tty_virtual_width - 1;
+  }
+
+  result.X = (unsigned short) x;
+  result.Y = (unsigned short) y;
+  return result;
+}
+
+
+static int uv_tty_emit_text(uv_tty_t* handle, WCHAR buffer[], DWORD length,
+    DWORD* error) {
+  DWORD written;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  if (!WriteConsoleW(handle->handle,
+                     (void*) buffer,
+                     length,
+                     &written,
+                     NULL)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  return 0;
+}
+
+
+static int uv_tty_move_caret(uv_tty_t* handle, int x, unsigned char x_relative,
+    int y, unsigned char y_relative, DWORD* error) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+  COORD pos;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+ retry:
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+  }
+
+  pos = uv_tty_make_real_coord(handle, &info, x, x_relative, y, y_relative);
+
+  if (!SetConsoleCursorPosition(handle->handle, pos)) {
+    if (GetLastError() == ERROR_INVALID_PARAMETER) {
+      /* The console may be resized - retry */
+      goto retry;
+    } else {
+      *error = GetLastError();
+      return -1;
+    }
+  }
+
+  return 0;
+}
+
+
+static int uv_tty_reset(uv_tty_t* handle, DWORD* error) {
+  const COORD origin = {0, 0};
+  const WORD char_attrs = uv_tty_default_text_attributes;
+  CONSOLE_SCREEN_BUFFER_INFO info;
+  DWORD count, written;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  /* Reset original text attributes. */
+  if (!SetConsoleTextAttribute(handle->handle, char_attrs)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  /* Move the cursor position to (0, 0). */
+  if (!SetConsoleCursorPosition(handle->handle, origin)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  /* Clear the screen buffer. */
+ retry:
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  count = info.dwSize.X * info.dwSize.Y;
+
+  if (!(FillConsoleOutputCharacterW(handle->handle,
+                                    L'\x20',
+                                    count,
+                                    origin,
+                                    &written) &&
+        FillConsoleOutputAttribute(handle->handle,
+                                   char_attrs,
+                                   written,
+                                   origin,
+                                   &written))) {
+    if (GetLastError() == ERROR_INVALID_PARAMETER) {
+      /* The console may be resized - retry */
+      goto retry;
+    } else {
+      *error = GetLastError();
+      return -1;
+    }
+  }
+
+  /* Move the virtual window up to the top. */
+  uv_tty_virtual_offset = 0;
+  uv_tty_update_virtual_window(&info);
+
+  return 0;
+}
+
+
+static int uv_tty_clear(uv_tty_t* handle, int dir, char entire_screen,
+    DWORD* error) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+  COORD start, end;
+  DWORD count, written;
+
+  int x1, x2, y1, y2;
+  int x1r, x2r, y1r, y2r;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  if (dir == 0) {
+    /* Clear from current position */
+    x1 = 0;
+    x1r = 1;
+  } else {
+    /* Clear from column 0 */
+    x1 = 0;
+    x1r = 0;
+  }
+
+  if (dir == 1) {
+    /* Clear to current position */
+    x2 = 0;
+    x2r = 1;
+  } else {
+    /* Clear to end of row. We pretend the console is 65536 characters wide,
+     * uv_tty_make_real_coord will clip it to the actual console width. */
+    x2 = 0xffff;
+    x2r = 0;
+  }
+
+  if (!entire_screen) {
+    /* Stay on our own row */
+    y1 = y2 = 0;
+    y1r = y2r = 1;
+  } else {
+    /* Apply columns direction to row */
+    y1 = x1;
+    y1r = x1r;
+    y2 = x2;
+    y2r = x2r;
+  }
+
+ retry:
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  start = uv_tty_make_real_coord(handle, &info, x1, x1r, y1, y1r);
+  end = uv_tty_make_real_coord(handle, &info, x2, x2r, y2, y2r);
+  count = (end.Y * info.dwSize.X + end.X) -
+          (start.Y * info.dwSize.X + start.X) + 1;
+
+  if (!(FillConsoleOutputCharacterW(handle->handle,
+                              L'\x20',
+                              count,
+                              start,
+                              &written) &&
+        FillConsoleOutputAttribute(handle->handle,
+                                   info.wAttributes,
+                                   written,
+                                   start,
+                                   &written))) {
+    if (GetLastError() == ERROR_INVALID_PARAMETER) {
+      /* The console may be resized - retry */
+      goto retry;
+    } else {
+      *error = GetLastError();
+      return -1;
+    }
+  }
+
+  return 0;
+}
+
+#define FLIP_FGBG                                                             \
+    do {                                                                      \
+      WORD fg = info.wAttributes & 0xF;                                       \
+      WORD bg = info.wAttributes & 0xF0;                                      \
+      info.wAttributes &= 0xFF00;                                             \
+      info.wAttributes |= fg << 4;                                            \
+      info.wAttributes |= bg >> 4;                                            \
+    } while (0)
+
+static int uv_tty_set_style(uv_tty_t* handle, DWORD* error) {
+  unsigned short argc = handle->tty.wr.ansi_csi_argc;
+  unsigned short* argv = handle->tty.wr.ansi_csi_argv;
+  int i;
+  CONSOLE_SCREEN_BUFFER_INFO info;
+
+  char fg_color = -1, bg_color = -1;
+  char fg_bright = -1, bg_bright = -1;
+  char inverse = -1;
+
+  if (argc == 0) {
+    /* Reset mode */
+    fg_color = uv_tty_default_fg_color;
+    bg_color = uv_tty_default_bg_color;
+    fg_bright = uv_tty_default_fg_bright;
+    bg_bright = uv_tty_default_bg_bright;
+    inverse = uv_tty_default_inverse;
+  }
+
+  for (i = 0; i < argc; i++) {
+    short arg = argv[i];
+
+    if (arg == 0) {
+      /* Reset mode */
+      fg_color = uv_tty_default_fg_color;
+      bg_color = uv_tty_default_bg_color;
+      fg_bright = uv_tty_default_fg_bright;
+      bg_bright = uv_tty_default_bg_bright;
+      inverse = uv_tty_default_inverse;
+
+    } else if (arg == 1) {
+      /* Foreground bright on */
+      fg_bright = 1;
+
+    } else if (arg == 2) {
+      /* Both bright off */
+      fg_bright = 0;
+      bg_bright = 0;
+
+    } else if (arg == 5) {
+      /* Background bright on */
+      bg_bright = 1;
+
+    } else if (arg == 7) {
+      /* Inverse: on */
+      inverse = 1;
+
+    } else if (arg == 21 || arg == 22) {
+      /* Foreground bright off */
+      fg_bright = 0;
+
+    } else if (arg == 25) {
+      /* Background bright off */
+      bg_bright = 0;
+
+    } else if (arg == 27) {
+      /* Inverse: off */
+      inverse = 0;
+
+    } else if (arg >= 30 && arg <= 37) {
+      /* Set foreground color */
+      fg_color = arg - 30;
+
+    } else if (arg == 39) {
+      /* Default text color */
+      fg_color = uv_tty_default_fg_color;
+      fg_bright = uv_tty_default_fg_bright;
+
+    } else if (arg >= 40 && arg <= 47) {
+      /* Set background color */
+      bg_color = arg - 40;
+
+    } else if (arg ==  49) {
+      /* Default background color */
+      bg_color = uv_tty_default_bg_color;
+      bg_bright = uv_tty_default_bg_bright;
+
+    } else if (arg >= 90 && arg <= 97) {
+      /* Set bold foreground color */
+      fg_bright = 1;
+      fg_color = arg - 90;
+
+    } else if (arg >= 100 && arg <= 107) {
+      /* Set bold background color */
+      bg_bright = 1;
+      bg_color = arg - 100;
+
+    }
+  }
+
+  if (fg_color == -1 && bg_color == -1 && fg_bright == -1 &&
+      bg_bright == -1 && inverse == -1) {
+    /* Nothing changed */
+    return 0;
+  }
+
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  if ((info.wAttributes & COMMON_LVB_REVERSE_VIDEO) > 0) {
+    FLIP_FGBG;
+  }
+
+  if (fg_color != -1) {
+    info.wAttributes &= ~(FOREGROUND_RED | FOREGROUND_GREEN | FOREGROUND_BLUE);
+    if (fg_color & 1) info.wAttributes |= FOREGROUND_RED;
+    if (fg_color & 2) info.wAttributes |= FOREGROUND_GREEN;
+    if (fg_color & 4) info.wAttributes |= FOREGROUND_BLUE;
+  }
+
+  if (fg_bright != -1) {
+    if (fg_bright) {
+      info.wAttributes |= FOREGROUND_INTENSITY;
+    } else {
+      info.wAttributes &= ~FOREGROUND_INTENSITY;
+    }
+  }
+
+  if (bg_color != -1) {
+    info.wAttributes &= ~(BACKGROUND_RED | BACKGROUND_GREEN | BACKGROUND_BLUE);
+    if (bg_color & 1) info.wAttributes |= BACKGROUND_RED;
+    if (bg_color & 2) info.wAttributes |= BACKGROUND_GREEN;
+    if (bg_color & 4) info.wAttributes |= BACKGROUND_BLUE;
+  }
+
+  if (bg_bright != -1) {
+    if (bg_bright) {
+      info.wAttributes |= BACKGROUND_INTENSITY;
+    } else {
+      info.wAttributes &= ~BACKGROUND_INTENSITY;
+    }
+  }
+
+  if (inverse != -1) {
+    if (inverse) {
+      info.wAttributes |= COMMON_LVB_REVERSE_VIDEO;
+    } else {
+      info.wAttributes &= ~COMMON_LVB_REVERSE_VIDEO;
+    }
+  }
+
+  if ((info.wAttributes & COMMON_LVB_REVERSE_VIDEO) > 0) {
+    FLIP_FGBG;
+  }
+
+  if (!SetConsoleTextAttribute(handle->handle, info.wAttributes)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  return 0;
+}
+
+
+static int uv_tty_save_state(uv_tty_t* handle, unsigned char save_attributes,
+    DWORD* error) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  uv_tty_update_virtual_window(&info);
+
+  handle->tty.wr.saved_position.X = info.dwCursorPosition.X;
+  handle->tty.wr.saved_position.Y = info.dwCursorPosition.Y - uv_tty_virtual_offset;
+  handle->flags |= UV_HANDLE_TTY_SAVED_POSITION;
+
+  if (save_attributes) {
+    handle->tty.wr.saved_attributes = info.wAttributes &
+        (FOREGROUND_INTENSITY | BACKGROUND_INTENSITY);
+    handle->flags |= UV_HANDLE_TTY_SAVED_ATTRIBUTES;
+  }
+
+  return 0;
+}
+
+
+static int uv_tty_restore_state(uv_tty_t* handle,
+    unsigned char restore_attributes, DWORD* error) {
+  CONSOLE_SCREEN_BUFFER_INFO info;
+  WORD new_attributes;
+
+  if (*error != ERROR_SUCCESS) {
+    return -1;
+  }
+
+  if (handle->flags & UV_HANDLE_TTY_SAVED_POSITION) {
+    if (uv_tty_move_caret(handle,
+                          handle->tty.wr.saved_position.X,
+                          0,
+                          handle->tty.wr.saved_position.Y,
+                          0,
+                          error) != 0) {
+      return -1;
+    }
+  }
+
+  if (restore_attributes &&
+      (handle->flags & UV_HANDLE_TTY_SAVED_ATTRIBUTES)) {
+    if (!GetConsoleScreenBufferInfo(handle->handle, &info)) {
+      *error = GetLastError();
+      return -1;
+    }
+
+    new_attributes = info.wAttributes;
+    new_attributes &= ~(FOREGROUND_INTENSITY | BACKGROUND_INTENSITY);
+    new_attributes |= handle->tty.wr.saved_attributes;
+
+    if (!SetConsoleTextAttribute(handle->handle, new_attributes)) {
+      *error = GetLastError();
+      return -1;
+    }
+  }
+
+  return 0;
+}
+
+static int uv_tty_set_cursor_visibility(uv_tty_t* handle,
+                                        BOOL visible,
+                                        DWORD* error) {
+  CONSOLE_CURSOR_INFO cursor_info;
+
+  if (!GetConsoleCursorInfo(handle->handle, &cursor_info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  cursor_info.bVisible = visible;
+
+  if (!SetConsoleCursorInfo(handle->handle, &cursor_info)) {
+    *error = GetLastError();
+    return -1;
+  }
+
+  return 0;
+}
+
+static int uv_tty_write_bufs(uv_tty_t* handle,
+                             const uv_buf_t bufs[],
+                             unsigned int nbufs,
+                             DWORD* error) {
+  /* We can only write 8k characters at a time. Windows can't handle much more
+   * characters in a single console write anyway. */
+  WCHAR utf16_buf[MAX_CONSOLE_CHAR];
+  WCHAR* utf16_buffer;
+  DWORD utf16_buf_used = 0;
+  unsigned int i, len, max_len, pos;
+  int allocate = 0;
+
+#define FLUSH_TEXT()                                                 \
+  do {                                                               \
+    pos = 0;                                                         \
+    do {                                                             \
+      len = utf16_buf_used - pos;                                    \
+      if (len > MAX_CONSOLE_CHAR)                                    \
+        len = MAX_CONSOLE_CHAR;                                      \
+      uv_tty_emit_text(handle, &utf16_buffer[pos], len, error);      \
+      pos += len;                                                    \
+    } while (pos < utf16_buf_used);                                  \
+    if (allocate) {                                                  \
+      uv__free(utf16_buffer);                                        \
+      allocate = 0;                                                  \
+      utf16_buffer = utf16_buf;                                      \
+    }                                                                \
+    utf16_buf_used = 0;                                              \
+ } while (0)
+
+#define ENSURE_BUFFER_SPACE(wchars_needed)                          \
+  if (wchars_needed > ARRAY_SIZE(utf16_buf) - utf16_buf_used) {     \
+    FLUSH_TEXT();                                                   \
+  }
+
+  /* Cache for fast access */
+  unsigned char utf8_bytes_left = handle->tty.wr.utf8_bytes_left;
+  unsigned int utf8_codepoint = handle->tty.wr.utf8_codepoint;
+  unsigned char previous_eol = handle->tty.wr.previous_eol;
+  unsigned char ansi_parser_state = handle->tty.wr.ansi_parser_state;
+
+  /* Store the error here. If we encounter an error, stop trying to do i/o but
+   * keep parsing the buffer so we leave the parser in a consistent state. */
+  *error = ERROR_SUCCESS;
+
+  utf16_buffer = utf16_buf;
+
+  uv_sem_wait(&uv_tty_output_lock);
+
+  for (i = 0; i < nbufs; i++) {
+    uv_buf_t buf = bufs[i];
+    unsigned int j;
+
+    if (uv__vterm_state == UV_SUPPORTED && buf.len > 0) {
+      utf16_buf_used = MultiByteToWideChar(CP_UTF8,
+                                           0,
+                                           buf.base,
+                                           buf.len,
+                                           NULL,
+                                           0);
+
+      if (utf16_buf_used == 0) {
+        *error = GetLastError();
+        break;
+      }
+
+      max_len = (utf16_buf_used + 1) * sizeof(WCHAR);
+      allocate = max_len > MAX_CONSOLE_CHAR;
+      if (allocate)
+        utf16_buffer = (WCHAR*)uv__malloc(max_len);
+      if (!MultiByteToWideChar(CP_UTF8,
+                               0,
+                               buf.base,
+                               buf.len,
+                               utf16_buffer,
+                               utf16_buf_used)) {
+        if (allocate)
+          uv__free(utf16_buffer);
+        *error = GetLastError();
+        break;
+      }
+
+      FLUSH_TEXT();
+
+      continue;
+    }
+
+    for (j = 0; j < buf.len; j++) {
+      unsigned char c = buf.base[j];
+
+      /* Run the character through the utf8 decoder We happily accept non
+       * shortest form encodings and invalid code points - there's no real harm
+       * that can be done. */
+      if (utf8_bytes_left == 0) {
+        /* Read utf-8 start byte */
+        DWORD first_zero_bit;
+        unsigned char not_c = ~c;
+#ifdef _MSC_VER /* msvc */
+        if (_BitScanReverse(&first_zero_bit, not_c)) {
+#else /* assume gcc */
+        if (c != 0) {
+          first_zero_bit = (sizeof(int) * 8) - 1 - __builtin_clz(not_c);
+#endif
+          if (first_zero_bit == 7) {
+            /* Ascii - pass right through */
+            utf8_codepoint = (unsigned int) c;
+
+          } else if (first_zero_bit <= 5) {
+            /* Multibyte sequence */
+            utf8_codepoint = (0xff >> (8 - first_zero_bit)) & c;
+            utf8_bytes_left = (char) (6 - first_zero_bit);
+
+          } else {
+            /* Invalid continuation */
+            utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
+          }
+
+        } else {
+          /* 0xff -- invalid */
+          utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
+        }
+
+      } else if ((c & 0xc0) == 0x80) {
+        /* Valid continuation of utf-8 multibyte sequence */
+        utf8_bytes_left--;
+        utf8_codepoint <<= 6;
+        utf8_codepoint |= ((unsigned int) c & 0x3f);
+
+      } else {
+        /* Start byte where continuation was expected. */
+        utf8_bytes_left = 0;
+        utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
+        /* Patch buf offset so this character will be parsed again as a start
+         * byte. */
+        j--;
+      }
+
+      /* Maybe we need to parse more bytes to find a character. */
+      if (utf8_bytes_left != 0) {
+        continue;
+      }
+
+      /* Parse vt100/ansi escape codes */
+      if (ansi_parser_state == ANSI_NORMAL) {
+        switch (utf8_codepoint) {
+          case '\033':
+            ansi_parser_state = ANSI_ESCAPE_SEEN;
+            continue;
+
+          case 0233:
+            ansi_parser_state = ANSI_CSI;
+            handle->tty.wr.ansi_csi_argc = 0;
+            continue;
+        }
+
+      } else if (ansi_parser_state == ANSI_ESCAPE_SEEN) {
+        switch (utf8_codepoint) {
+          case '[':
+            ansi_parser_state = ANSI_CSI;
+            handle->tty.wr.ansi_csi_argc = 0;
+            continue;
+
+          case '^':
+          case '_':
+          case 'P':
+          case ']':
+            /* Not supported, but we'll have to parse until we see a stop code,
+             * e. g. ESC \ or BEL. */
+            ansi_parser_state = ANSI_ST_CONTROL;
+            continue;
+
+          case '\033':
+            /* Ignore double escape. */
+            continue;
+
+          case 'c':
+            /* Full console reset. */
+            FLUSH_TEXT();
+            uv_tty_reset(handle, error);
+            ansi_parser_state = ANSI_NORMAL;
+            continue;
+
+          case '7':
+            /* Save the cursor position and text attributes. */
+            FLUSH_TEXT();
+            uv_tty_save_state(handle, 1, error);
+            ansi_parser_state = ANSI_NORMAL;
+            continue;
+
+           case '8':
+            /* Restore the cursor position and text attributes */
+            FLUSH_TEXT();
+            uv_tty_restore_state(handle, 1, error);
+            ansi_parser_state = ANSI_NORMAL;
+            continue;
+
+          default:
+            if (utf8_codepoint >= '@' && utf8_codepoint <= '_') {
+              /* Single-char control. */
+              ansi_parser_state = ANSI_NORMAL;
+              continue;
+            } else {
+              /* Invalid - proceed as normal, */
+              ansi_parser_state = ANSI_NORMAL;
+            }
+        }
+
+      } else if (ansi_parser_state & ANSI_CSI) {
+        if (!(ansi_parser_state & ANSI_IGNORE)) {
+          if (utf8_codepoint >= '0' && utf8_codepoint <= '9') {
+            /* Parsing a numerical argument */
+
+            if (!(ansi_parser_state & ANSI_IN_ARG)) {
+              /* We were not currently parsing a number */
+
+              /* Check for too many arguments */
+              if (handle->tty.wr.ansi_csi_argc >= ARRAY_SIZE(handle->tty.wr.ansi_csi_argv)) {
+                ansi_parser_state |= ANSI_IGNORE;
+                continue;
+              }
+
+              ansi_parser_state |= ANSI_IN_ARG;
+              handle->tty.wr.ansi_csi_argc++;
+              handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] =
+                  (unsigned short) utf8_codepoint - '0';
+              continue;
+            } else {
+              /* We were already parsing a number. Parse next digit. */
+              uint32_t value = 10 *
+                  handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1];
+
+              /* Check for overflow. */
+              if (value > UINT16_MAX) {
+                ansi_parser_state |= ANSI_IGNORE;
+                continue;
+              }
+
+               handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] =
+                   (unsigned short) value + (utf8_codepoint - '0');
+               continue;
+            }
+
+          } else if (utf8_codepoint == ';') {
+            /* Denotes the end of an argument. */
+            if (ansi_parser_state & ANSI_IN_ARG) {
+              ansi_parser_state &= ~ANSI_IN_ARG;
+              continue;
+
+            } else {
+              /* If ANSI_IN_ARG is not set, add another argument and default it
+               * to 0. */
+
+              /* Check for too many arguments */
+              if (handle->tty.wr.ansi_csi_argc >= ARRAY_SIZE(handle->tty.wr.ansi_csi_argv)) {
+                ansi_parser_state |= ANSI_IGNORE;
+                continue;
+              }
+
+              handle->tty.wr.ansi_csi_argc++;
+              handle->tty.wr.ansi_csi_argv[handle->tty.wr.ansi_csi_argc - 1] = 0;
+              continue;
+            }
+
+          } else if (utf8_codepoint == '?' && !(ansi_parser_state & ANSI_IN_ARG) &&
+                     handle->tty.wr.ansi_csi_argc == 0) {
+            /* Ignores '?' if it is the first character after CSI[. This is an
+             * extension character from the VT100 codeset that is supported and
+             * used by most ANSI terminals today. */
+            continue;
+
+          } else if (utf8_codepoint >= '@' && utf8_codepoint <= '~' &&
+                     (handle->tty.wr.ansi_csi_argc > 0 || utf8_codepoint != '[')) {
+            int x, y, d;
+
+            /* Command byte */
+            switch (utf8_codepoint) {
+              case 'A':
+                /* cursor up */
+                FLUSH_TEXT();
+                y = -(handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1);
+                uv_tty_move_caret(handle, 0, 1, y, 1, error);
+                break;
+
+              case 'B':
+                /* cursor down */
+                FLUSH_TEXT();
+                y = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1;
+                uv_tty_move_caret(handle, 0, 1, y, 1, error);
+                break;
+
+              case 'C':
+                /* cursor forward */
+                FLUSH_TEXT();
+                x = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1;
+                uv_tty_move_caret(handle, x, 1, 0, 1, error);
+                break;
+
+              case 'D':
+                /* cursor back */
+                FLUSH_TEXT();
+                x = -(handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1);
+                uv_tty_move_caret(handle, x, 1, 0, 1, error);
+                break;
+
+              case 'E':
+                /* cursor next line */
+                FLUSH_TEXT();
+                y = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1;
+                uv_tty_move_caret(handle, 0, 0, y, 1, error);
+                break;
+
+              case 'F':
+                /* cursor previous line */
+                FLUSH_TEXT();
+                y = -(handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 1);
+                uv_tty_move_caret(handle, 0, 0, y, 1, error);
+                break;
+
+              case 'G':
+                /* cursor horizontal move absolute */
+                FLUSH_TEXT();
+                x = (handle->tty.wr.ansi_csi_argc >= 1 && handle->tty.wr.ansi_csi_argv[0])
+                  ? handle->tty.wr.ansi_csi_argv[0] - 1 : 0;
+                uv_tty_move_caret(handle, x, 0, 0, 1, error);
+                break;
+
+              case 'H':
+              case 'f':
+                /* cursor move absolute */
+                FLUSH_TEXT();
+                y = (handle->tty.wr.ansi_csi_argc >= 1 && handle->tty.wr.ansi_csi_argv[0])
+                  ? handle->tty.wr.ansi_csi_argv[0] - 1 : 0;
+                x = (handle->tty.wr.ansi_csi_argc >= 2 && handle->tty.wr.ansi_csi_argv[1])
+                  ? handle->tty.wr.ansi_csi_argv[1] - 1 : 0;
+                uv_tty_move_caret(handle, x, 0, y, 0, error);
+                break;
+
+              case 'J':
+                /* Erase screen */
+                FLUSH_TEXT();
+                d = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 0;
+                if (d >= 0 && d <= 2) {
+                  uv_tty_clear(handle, d, 1, error);
+                }
+                break;
+
+              case 'K':
+                /* Erase line */
+                FLUSH_TEXT();
+                d = handle->tty.wr.ansi_csi_argc ? handle->tty.wr.ansi_csi_argv[0] : 0;
+                if (d >= 0 && d <= 2) {
+                  uv_tty_clear(handle, d, 0, error);
+                }
+                break;
+
+              case 'm':
+                /* Set style */
+                FLUSH_TEXT();
+                uv_tty_set_style(handle, error);
+                break;
+
+              case 's':
+                /* Save the cursor position. */
+                FLUSH_TEXT();
+                uv_tty_save_state(handle, 0, error);
+                break;
+
+              case 'u':
+                /* Restore the cursor position */
+                FLUSH_TEXT();
+                uv_tty_restore_state(handle, 0, error);
+                break;
+
+              case 'l':
+                /* Hide the cursor */
+                if (handle->tty.wr.ansi_csi_argc == 1 &&
+                    handle->tty.wr.ansi_csi_argv[0] == 25) {
+                  FLUSH_TEXT();
+                  uv_tty_set_cursor_visibility(handle, 0, error);
+                }
+                break;
+
+              case 'h':
+                /* Show the cursor */
+                if (handle->tty.wr.ansi_csi_argc == 1 &&
+                    handle->tty.wr.ansi_csi_argv[0] == 25) {
+                  FLUSH_TEXT();
+                  uv_tty_set_cursor_visibility(handle, 1, error);
+                }
+                break;
+            }
+
+            /* Sequence ended - go back to normal state. */
+            ansi_parser_state = ANSI_NORMAL;
+            continue;
+
+          } else {
+            /* We don't support commands that use private mode characters or
+             * intermediaries. Ignore the rest of the sequence. */
+            ansi_parser_state |= ANSI_IGNORE;
+            continue;
+          }
+        } else {
+          /* We're ignoring this command. Stop only on command character. */
+          if (utf8_codepoint >= '@' && utf8_codepoint <= '~') {
+            ansi_parser_state = ANSI_NORMAL;
+          }
+          continue;
+        }
+
+      } else if (ansi_parser_state & ANSI_ST_CONTROL) {
+        /* Unsupported control code.
+         * Ignore everything until we see `BEL` or `ESC \`. */
+        if (ansi_parser_state & ANSI_IN_STRING) {
+          if (!(ansi_parser_state & ANSI_BACKSLASH_SEEN)) {
+            if (utf8_codepoint == '"') {
+              ansi_parser_state &= ~ANSI_IN_STRING;
+            } else if (utf8_codepoint == '\\') {
+              ansi_parser_state |= ANSI_BACKSLASH_SEEN;
+            }
+          } else {
+            ansi_parser_state &= ~ANSI_BACKSLASH_SEEN;
+          }
+        } else {
+          if (utf8_codepoint == '\007' || (utf8_codepoint == '\\' &&
+              (ansi_parser_state & ANSI_ESCAPE_SEEN))) {
+            /* End of sequence */
+            ansi_parser_state = ANSI_NORMAL;
+          } else if (utf8_codepoint == '\033') {
+            /* Escape character */
+            ansi_parser_state |= ANSI_ESCAPE_SEEN;
+          } else if (utf8_codepoint == '"') {
+             /* String starting */
+            ansi_parser_state |= ANSI_IN_STRING;
+            ansi_parser_state &= ~ANSI_ESCAPE_SEEN;
+            ansi_parser_state &= ~ANSI_BACKSLASH_SEEN;
+          } else {
+            ansi_parser_state &= ~ANSI_ESCAPE_SEEN;
+          }
+        }
+        continue;
+      } else {
+        /* Inconsistent state */
+        abort();
+      }
+
+      /* We wouldn't mind emitting utf-16 surrogate pairs. Too bad, the windows
+       * console doesn't really support UTF-16, so just emit the replacement
+       * character. */
+      if (utf8_codepoint > 0xffff) {
+        utf8_codepoint = UNICODE_REPLACEMENT_CHARACTER;
+      }
+
+      if (utf8_codepoint == 0x0a || utf8_codepoint == 0x0d) {
+        /* EOL conversion - emit \r\n when we see \n. */
+
+        if (utf8_codepoint == 0x0a && previous_eol != 0x0d) {
+          /* \n was not preceded by \r; print \r\n. */
+          ENSURE_BUFFER_SPACE(2);
+          utf16_buf[utf16_buf_used++] = L'\r';
+          utf16_buf[utf16_buf_used++] = L'\n';
+        } else if (utf8_codepoint == 0x0d && previous_eol == 0x0a) {
+          /* \n was followed by \r; do not print the \r, since the source was
+           * either \r\n\r (so the second \r is redundant) or was \n\r (so the
+           * \n was processed by the last case and an \r automatically
+           * inserted). */
+        } else {
+          /* \r without \n; print \r as-is. */
+          ENSURE_BUFFER_SPACE(1);
+          utf16_buf[utf16_buf_used++] = (WCHAR) utf8_codepoint;
+        }
+
+        previous_eol = (char) utf8_codepoint;
+
+      } else if (utf8_codepoint <= 0xffff) {
+        /* Encode character into utf-16 buffer. */
+        ENSURE_BUFFER_SPACE(1);
+        utf16_buf[utf16_buf_used++] = (WCHAR) utf8_codepoint;
+        previous_eol = 0;
+      }
+    }
+  }
+
+  /* Flush remaining characters */
+  FLUSH_TEXT();
+
+  /* Copy cached values back to struct. */
+  handle->tty.wr.utf8_bytes_left = utf8_bytes_left;
+  handle->tty.wr.utf8_codepoint = utf8_codepoint;
+  handle->tty.wr.previous_eol = previous_eol;
+  handle->tty.wr.ansi_parser_state = ansi_parser_state;
+
+  uv_sem_post(&uv_tty_output_lock);
+
+  if (*error == STATUS_SUCCESS) {
+    return 0;
+  } else {
+    return -1;
+  }
+
+#undef FLUSH_TEXT
+}
+
+
+int uv_tty_write(uv_loop_t* loop,
+                 uv_write_t* req,
+                 uv_tty_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 uv_write_cb cb) {
+  DWORD error;
+
+  UV_REQ_INIT(req, UV_WRITE);
+  req->handle = (uv_stream_t*) handle;
+  req->cb = cb;
+
+  handle->reqs_pending++;
+  handle->stream.conn.write_reqs_pending++;
+  REGISTER_HANDLE_REQ(loop, handle, req);
+
+  req->u.io.queued_bytes = 0;
+
+  if (!uv_tty_write_bufs(handle, bufs, nbufs, &error)) {
+    SET_REQ_SUCCESS(req);
+  } else {
+    SET_REQ_ERROR(req, error);
+  }
+
+  uv_insert_pending_req(loop, (uv_req_t*) req);
+
+  return 0;
+}
+
+
+int uv__tty_try_write(uv_tty_t* handle,
+                      const uv_buf_t bufs[],
+                      unsigned int nbufs) {
+  DWORD error;
+
+  if (handle->stream.conn.write_reqs_pending > 0)
+    return UV_EAGAIN;
+
+  if (uv_tty_write_bufs(handle, bufs, nbufs, &error))
+    return uv_translate_sys_error(error);
+
+  return uv__count_bufs(bufs, nbufs);
+}
+
+
+void uv_process_tty_write_req(uv_loop_t* loop, uv_tty_t* handle,
+  uv_write_t* req) {
+  int err;
+
+  handle->write_queue_size -= req->u.io.queued_bytes;
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (req->cb) {
+    err = GET_REQ_ERROR(req);
+    req->cb(req, uv_translate_sys_error(err));
+  }
+
+  handle->stream.conn.write_reqs_pending--;
+  if (handle->stream.conn.shutdown_req != NULL &&
+      handle->stream.conn.write_reqs_pending == 0) {
+    uv_want_endgame(loop, (uv_handle_t*)handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_tty_close(uv_tty_t* handle) {
+  assert(handle->u.fd == -1 || handle->u.fd > 2);
+  if (handle->u.fd == -1)
+    CloseHandle(handle->handle);
+  else
+    close(handle->u.fd);
+
+  if (handle->flags & UV_HANDLE_READING)
+    uv_tty_read_stop(handle);
+
+  handle->u.fd = -1;
+  handle->handle = INVALID_HANDLE_VALUE;
+  handle->flags &= ~(UV_HANDLE_READABLE | UV_HANDLE_WRITABLE);
+  uv__handle_closing(handle);
+
+  if (handle->reqs_pending == 0) {
+    uv_want_endgame(handle->loop, (uv_handle_t*) handle);
+  }
+}
+
+
+void uv_tty_endgame(uv_loop_t* loop, uv_tty_t* handle) {
+  if (!(handle->flags & UV_HANDLE_TTY_READABLE) &&
+      handle->stream.conn.shutdown_req != NULL &&
+      handle->stream.conn.write_reqs_pending == 0) {
+    UNREGISTER_HANDLE_REQ(loop, handle, handle->stream.conn.shutdown_req);
+
+    /* TTY shutdown is really just a no-op */
+    if (handle->stream.conn.shutdown_req->cb) {
+      if (handle->flags & UV__HANDLE_CLOSING) {
+        handle->stream.conn.shutdown_req->cb(handle->stream.conn.shutdown_req, UV_ECANCELED);
+      } else {
+        handle->stream.conn.shutdown_req->cb(handle->stream.conn.shutdown_req, 0);
+      }
+    }
+
+    handle->stream.conn.shutdown_req = NULL;
+
+    DECREASE_PENDING_REQ_COUNT(handle);
+    return;
+  }
+
+  if (handle->flags & UV__HANDLE_CLOSING &&
+      handle->reqs_pending == 0) {
+    /* The wait handle used for raw reading should be unregistered when the
+     * wait callback runs. */
+    assert(!(handle->flags & UV_HANDLE_TTY_READABLE) ||
+           handle->tty.rd.read_raw_wait == NULL);
+
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+    uv__handle_close(handle);
+  }
+}
+
+
+/*
+ * uv_process_tty_accept_req() is a stub to keep DELEGATE_STREAM_REQ working
+ * TODO: find a way to remove it
+ */
+void uv_process_tty_accept_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_req_t* raw_req) {
+  abort();
+}
+
+
+/*
+ * uv_process_tty_connect_req() is a stub to keep DELEGATE_STREAM_REQ working
+ * TODO: find a way to remove it
+ */
+void uv_process_tty_connect_req(uv_loop_t* loop, uv_tty_t* handle,
+    uv_connect_t* req) {
+  abort();
+}
+
+
+int uv_tty_reset_mode(void) {
+  /* Not necessary to do anything. */
+  return 0;
+}
+
+/* Determine whether or not this version of windows supports
+ * proper ANSI color codes. Should be supported as of windows
+ * 10 version 1511, build number 10.0.10586.
+ */
+static void uv__determine_vterm_state(HANDLE handle) {
+  DWORD dwMode = 0;
+
+  if (!GetConsoleMode(handle, &dwMode)) {
+    uv__vterm_state = UV_UNSUPPORTED;
+    return;
+  }
+
+  dwMode |= ENABLE_VIRTUAL_TERMINAL_PROCESSING;
+  if (!SetConsoleMode(handle, dwMode)) {
+    uv__vterm_state = UV_UNSUPPORTED;
+    return;
+  }
+
+  uv__vterm_state = UV_SUPPORTED;
+}
+
+static DWORD WINAPI uv__tty_console_resize_message_loop_thread(void* param) {
+  CONSOLE_SCREEN_BUFFER_INFO sb_info;
+  MSG msg;
+
+  if (!GetConsoleScreenBufferInfo(uv__tty_console_handle, &sb_info))
+    return 0;
+
+  uv__tty_console_width = sb_info.dwSize.X;
+  uv__tty_console_height = sb_info.srWindow.Bottom - sb_info.srWindow.Top + 1;
+
+  if (pSetWinEventHook == NULL)
+    return 0;
+
+  if (!pSetWinEventHook(EVENT_CONSOLE_LAYOUT,
+                        EVENT_CONSOLE_LAYOUT,
+                        NULL,
+                        uv__tty_console_resize_event,
+                        0,
+                        0,
+                        WINEVENT_OUTOFCONTEXT))
+    return 0;
+
+  while (GetMessage(&msg, NULL, 0, 0)) {
+    TranslateMessage(&msg);
+    DispatchMessage(&msg);
+  }
+  return 0;
+}
+
+static void CALLBACK uv__tty_console_resize_event(HWINEVENTHOOK hWinEventHook,
+                                                  DWORD event,
+                                                  HWND hwnd,
+                                                  LONG idObject,
+                                                  LONG idChild,
+                                                  DWORD dwEventThread,
+                                                  DWORD dwmsEventTime) {
+  CONSOLE_SCREEN_BUFFER_INFO sb_info;
+  int width, height;
+
+  if (!GetConsoleScreenBufferInfo(uv__tty_console_handle, &sb_info))
+    return;
+
+  width = sb_info.dwSize.X;
+  height = sb_info.srWindow.Bottom - sb_info.srWindow.Top + 1;
+
+  if (width != uv__tty_console_width || height != uv__tty_console_height) {
+    uv__tty_console_width = width;
+    uv__tty_console_height = height;
+    uv__signal_dispatch(SIGWINCH);
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/udp.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/udp.cpp
new file mode 100644
index 0000000..e56282a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/udp.cpp
@@ -0,0 +1,962 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+#include "handle-inl.h"
+#include "stream-inl.h"
+#include "req-inl.h"
+
+
+/*
+ * Threshold of active udp streams for which to preallocate udp read buffers.
+ */
+const unsigned int uv_active_udp_streams_threshold = 0;
+
+/* A zero-size buffer for use by uv_udp_read */
+static char uv_zero_[] = "";
+
+int uv_udp_getsockname(const uv_udp_t* handle,
+                       struct sockaddr* name,
+                       int* namelen) {
+  int result;
+
+  if (handle->socket == INVALID_SOCKET) {
+    return UV_EINVAL;
+  }
+
+  result = getsockname(handle->socket, name, namelen);
+  if (result != 0) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+static int uv_udp_set_socket(uv_loop_t* loop, uv_udp_t* handle, SOCKET socket,
+    int family) {
+  DWORD yes = 1;
+  WSAPROTOCOL_INFOW info;
+  int opt_len;
+
+  if (handle->socket != INVALID_SOCKET)
+    return UV_EBUSY;
+
+  /* Set the socket to nonblocking mode */
+  if (ioctlsocket(socket, FIONBIO, &yes) == SOCKET_ERROR) {
+    return WSAGetLastError();
+  }
+
+  /* Make the socket non-inheritable */
+  if (!SetHandleInformation((HANDLE)socket, HANDLE_FLAG_INHERIT, 0)) {
+    return GetLastError();
+  }
+
+  /* Associate it with the I/O completion port. Use uv_handle_t pointer as
+   * completion key. */
+  if (CreateIoCompletionPort((HANDLE)socket,
+                             loop->iocp,
+                             (ULONG_PTR)socket,
+                             0) == NULL) {
+    return GetLastError();
+  }
+
+  /* All known Windows that support SetFileCompletionNotificationModes have a
+   * bug that makes it impossible to use this function in conjunction with
+   * datagram sockets. We can work around that but only if the user is using
+   * the default UDP driver (AFD) and has no other. LSPs stacked on top. Here
+   * we check whether that is the case. */
+  opt_len = (int) sizeof info;
+  if (getsockopt(
+          socket, SOL_SOCKET, SO_PROTOCOL_INFOW, (char*) &info, &opt_len) ==
+      SOCKET_ERROR) {
+    return GetLastError();
+  }
+
+  if (info.ProtocolChain.ChainLen == 1) {
+    if (SetFileCompletionNotificationModes(
+            (HANDLE) socket,
+            FILE_SKIP_SET_EVENT_ON_HANDLE |
+                FILE_SKIP_COMPLETION_PORT_ON_SUCCESS)) {
+      handle->flags |= UV_HANDLE_SYNC_BYPASS_IOCP;
+      handle->func_wsarecv = uv_wsarecv_workaround;
+      handle->func_wsarecvfrom = uv_wsarecvfrom_workaround;
+    } else if (GetLastError() != ERROR_INVALID_FUNCTION) {
+      return GetLastError();
+    }
+  }
+
+  handle->socket = socket;
+
+  if (family == AF_INET6) {
+    handle->flags |= UV_HANDLE_IPV6;
+  } else {
+    assert(!(handle->flags & UV_HANDLE_IPV6));
+  }
+
+  return 0;
+}
+
+
+int uv_udp_init_ex(uv_loop_t* loop, uv_udp_t* handle, unsigned int flags) {
+  int domain;
+
+  /* Use the lower 8 bits for the domain */
+  domain = flags & 0xFF;
+  if (domain != AF_INET && domain != AF_INET6 && domain != AF_UNSPEC)
+    return UV_EINVAL;
+
+  if (flags & ~0xFF)
+    return UV_EINVAL;
+
+  uv__handle_init(loop, (uv_handle_t*) handle, UV_UDP);
+  handle->socket = INVALID_SOCKET;
+  handle->reqs_pending = 0;
+  handle->activecnt = 0;
+  handle->func_wsarecv = WSARecv;
+  handle->func_wsarecvfrom = WSARecvFrom;
+  handle->send_queue_size = 0;
+  handle->send_queue_count = 0;
+  UV_REQ_INIT(&handle->recv_req, UV_UDP_RECV);
+  handle->recv_req.data = handle;
+
+  /* If anything fails beyond this point we need to remove the handle from
+   * the handle queue, since it was added by uv__handle_init.
+   */
+
+  if (domain != AF_UNSPEC) {
+    SOCKET sock;
+    DWORD err;
+
+    sock = socket(domain, SOCK_DGRAM, 0);
+    if (sock == INVALID_SOCKET) {
+      err = WSAGetLastError();
+      QUEUE_REMOVE(&handle->handle_queue);
+      return uv_translate_sys_error(err);
+    }
+
+    err = uv_udp_set_socket(handle->loop, handle, sock, domain);
+    if (err) {
+      closesocket(sock);
+      QUEUE_REMOVE(&handle->handle_queue);
+      return uv_translate_sys_error(err);
+    }
+  }
+
+  return 0;
+}
+
+
+int uv_udp_init(uv_loop_t* loop, uv_udp_t* handle) {
+  return uv_udp_init_ex(loop, handle, AF_UNSPEC);
+}
+
+
+void uv_udp_close(uv_loop_t* loop, uv_udp_t* handle) {
+  uv_udp_recv_stop(handle);
+  closesocket(handle->socket);
+  handle->socket = INVALID_SOCKET;
+
+  uv__handle_closing(handle);
+
+  if (handle->reqs_pending == 0) {
+    uv_want_endgame(loop, (uv_handle_t*) handle);
+  }
+}
+
+
+void uv_udp_endgame(uv_loop_t* loop, uv_udp_t* handle) {
+  if (handle->flags & UV__HANDLE_CLOSING &&
+      handle->reqs_pending == 0) {
+    assert(!(handle->flags & UV_HANDLE_CLOSED));
+    uv__handle_close(handle);
+  }
+}
+
+
+static int uv_udp_maybe_bind(uv_udp_t* handle,
+                             const struct sockaddr* addr,
+                             unsigned int addrlen,
+                             unsigned int flags) {
+  int r;
+  int err;
+  DWORD no = 0;
+
+  if (handle->flags & UV_HANDLE_BOUND)
+    return 0;
+
+  if ((flags & UV_UDP_IPV6ONLY) && addr->sa_family != AF_INET6) {
+    /* UV_UDP_IPV6ONLY is supported only for IPV6 sockets */
+    return ERROR_INVALID_PARAMETER;
+  }
+
+  if (handle->socket == INVALID_SOCKET) {
+    SOCKET sock = socket(addr->sa_family, SOCK_DGRAM, 0);
+    if (sock == INVALID_SOCKET) {
+      return WSAGetLastError();
+    }
+
+    err = uv_udp_set_socket(handle->loop, handle, sock, addr->sa_family);
+    if (err) {
+      closesocket(sock);
+      return err;
+    }
+  }
+
+  if (flags & UV_UDP_REUSEADDR) {
+    DWORD yes = 1;
+    /* Set SO_REUSEADDR on the socket. */
+    if (setsockopt(handle->socket,
+                   SOL_SOCKET,
+                   SO_REUSEADDR,
+                   (char*) &yes,
+                   sizeof yes) == SOCKET_ERROR) {
+      err = WSAGetLastError();
+      return err;
+    }
+  }
+
+  if (addr->sa_family == AF_INET6)
+    handle->flags |= UV_HANDLE_IPV6;
+
+  if (addr->sa_family == AF_INET6 && !(flags & UV_UDP_IPV6ONLY)) {
+    /* On windows IPV6ONLY is on by default. If the user doesn't specify it
+     * libuv turns it off. */
+
+    /* TODO: how to handle errors? This may fail if there is no ipv4 stack
+     * available, or when run on XP/2003 which have no support for dualstack
+     * sockets. For now we're silently ignoring the error. */
+    setsockopt(handle->socket,
+               IPPROTO_IPV6,
+               IPV6_V6ONLY,
+               (char*) &no,
+               sizeof no);
+  }
+
+  r = bind(handle->socket, addr, addrlen);
+  if (r == SOCKET_ERROR) {
+    return WSAGetLastError();
+  }
+
+  handle->flags |= UV_HANDLE_BOUND;
+
+  return 0;
+}
+
+
+static void uv_udp_queue_recv(uv_loop_t* loop, uv_udp_t* handle) {
+  uv_req_t* req;
+  uv_buf_t buf;
+  DWORD bytes, flags;
+  int result;
+
+  assert(handle->flags & UV_HANDLE_READING);
+  assert(!(handle->flags & UV_HANDLE_READ_PENDING));
+
+  req = &handle->recv_req;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  /*
+   * Preallocate a read buffer if the number of active streams is below
+   * the threshold.
+  */
+  if (loop->active_udp_streams < uv_active_udp_streams_threshold) {
+    handle->flags &= ~UV_HANDLE_ZERO_READ;
+
+    handle->recv_buffer = uv_buf_init(NULL, 0);
+    handle->alloc_cb((uv_handle_t*) handle, 65536, &handle->recv_buffer);
+    if (handle->recv_buffer.base == NULL || handle->recv_buffer.len == 0) {
+      handle->recv_cb(handle, UV_ENOBUFS, &handle->recv_buffer, NULL, 0);
+      return;
+    }
+    assert(handle->recv_buffer.base != NULL);
+
+    buf = handle->recv_buffer;
+    memset(&handle->recv_from, 0, sizeof handle->recv_from);
+    handle->recv_from_len = sizeof handle->recv_from;
+    flags = 0;
+
+    result = handle->func_wsarecvfrom(handle->socket,
+                                      (WSABUF*) &buf,
+                                      1,
+                                      &bytes,
+                                      &flags,
+                                      (struct sockaddr*) &handle->recv_from,
+                                      &handle->recv_from_len,
+                                      &req->u.io.overlapped,
+                                      NULL);
+
+    if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+      /* Process the req without IOCP. */
+      handle->flags |= UV_HANDLE_READ_PENDING;
+      req->u.io.overlapped.InternalHigh = bytes;
+      handle->reqs_pending++;
+      uv_insert_pending_req(loop, req);
+    } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+      /* The req will be processed with IOCP. */
+      handle->flags |= UV_HANDLE_READ_PENDING;
+      handle->reqs_pending++;
+    } else {
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, WSAGetLastError());
+      uv_insert_pending_req(loop, req);
+      handle->reqs_pending++;
+    }
+
+  } else {
+    handle->flags |= UV_HANDLE_ZERO_READ;
+
+    buf.base = (char*) uv_zero_;
+    buf.len = 0;
+    flags = MSG_PEEK;
+
+    result = handle->func_wsarecv(handle->socket,
+                                  (WSABUF*) &buf,
+                                  1,
+                                  &bytes,
+                                  &flags,
+                                  &req->u.io.overlapped,
+                                  NULL);
+
+    if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+      /* Process the req without IOCP. */
+      handle->flags |= UV_HANDLE_READ_PENDING;
+      req->u.io.overlapped.InternalHigh = bytes;
+      handle->reqs_pending++;
+      uv_insert_pending_req(loop, req);
+    } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+      /* The req will be processed with IOCP. */
+      handle->flags |= UV_HANDLE_READ_PENDING;
+      handle->reqs_pending++;
+    } else {
+      /* Make this req pending reporting an error. */
+      SET_REQ_ERROR(req, WSAGetLastError());
+      uv_insert_pending_req(loop, req);
+      handle->reqs_pending++;
+    }
+  }
+}
+
+
+int uv__udp_recv_start(uv_udp_t* handle, uv_alloc_cb alloc_cb,
+    uv_udp_recv_cb recv_cb) {
+  uv_loop_t* loop = handle->loop;
+  int err;
+
+  if (handle->flags & UV_HANDLE_READING) {
+    return WSAEALREADY;
+  }
+
+  err = uv_udp_maybe_bind(handle,
+                          (const struct sockaddr*) &uv_addr_ip4_any_,
+                          sizeof(uv_addr_ip4_any_),
+                          0);
+  if (err)
+    return err;
+
+  handle->flags |= UV_HANDLE_READING;
+  INCREASE_ACTIVE_COUNT(loop, handle);
+  loop->active_udp_streams++;
+
+  handle->recv_cb = recv_cb;
+  handle->alloc_cb = alloc_cb;
+
+  /* If reading was stopped and then started again, there could still be a recv
+   * request pending. */
+  if (!(handle->flags & UV_HANDLE_READ_PENDING))
+    uv_udp_queue_recv(loop, handle);
+
+  return 0;
+}
+
+
+int uv__udp_recv_stop(uv_udp_t* handle) {
+  if (handle->flags & UV_HANDLE_READING) {
+    handle->flags &= ~UV_HANDLE_READING;
+    handle->loop->active_udp_streams--;
+    DECREASE_ACTIVE_COUNT(loop, handle);
+  }
+
+  return 0;
+}
+
+
+static int uv__send(uv_udp_send_t* req,
+                    uv_udp_t* handle,
+                    const uv_buf_t bufs[],
+                    unsigned int nbufs,
+                    const struct sockaddr* addr,
+                    unsigned int addrlen,
+                    uv_udp_send_cb cb) {
+  uv_loop_t* loop = handle->loop;
+  DWORD result, bytes;
+
+  UV_REQ_INIT(req, UV_UDP_SEND);
+  req->handle = handle;
+  req->cb = cb;
+  memset(&req->u.io.overlapped, 0, sizeof(req->u.io.overlapped));
+
+  result = WSASendTo(handle->socket,
+                     (WSABUF*)bufs,
+                     nbufs,
+                     &bytes,
+                     0,
+                     addr,
+                     addrlen,
+                     &req->u.io.overlapped,
+                     NULL);
+
+  if (UV_SUCCEEDED_WITHOUT_IOCP(result == 0)) {
+    /* Request completed immediately. */
+    req->u.io.queued_bytes = 0;
+    handle->reqs_pending++;
+    handle->send_queue_size += req->u.io.queued_bytes;
+    handle->send_queue_count++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+    uv_insert_pending_req(loop, (uv_req_t*)req);
+  } else if (UV_SUCCEEDED_WITH_IOCP(result == 0)) {
+    /* Request queued by the kernel. */
+    req->u.io.queued_bytes = uv__count_bufs(bufs, nbufs);
+    handle->reqs_pending++;
+    handle->send_queue_size += req->u.io.queued_bytes;
+    handle->send_queue_count++;
+    REGISTER_HANDLE_REQ(loop, handle, req);
+  } else {
+    /* Send failed due to an error. */
+    return WSAGetLastError();
+  }
+
+  return 0;
+}
+
+
+void uv_process_udp_recv_req(uv_loop_t* loop, uv_udp_t* handle,
+    uv_req_t* req) {
+  uv_buf_t buf;
+  int partial;
+
+  assert(handle->type == UV_UDP);
+
+  handle->flags &= ~UV_HANDLE_READ_PENDING;
+
+  if (!REQ_SUCCESS(req)) {
+    DWORD err = GET_REQ_SOCK_ERROR(req);
+    if (err == WSAEMSGSIZE) {
+      /* Not a real error, it just indicates that the received packet was
+       * bigger than the receive buffer. */
+    } else if (err == WSAECONNRESET || err == WSAENETRESET) {
+      /* A previous sendto operation failed; ignore this error. If zero-reading
+       * we need to call WSARecv/WSARecvFrom _without_ the. MSG_PEEK flag to
+       * clear out the error queue. For nonzero reads, immediately queue a new
+       * receive. */
+      if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
+        goto done;
+      }
+    } else {
+      /* A real error occurred. Report the error to the user only if we're
+       * currently reading. */
+      if (handle->flags & UV_HANDLE_READING) {
+        uv_udp_recv_stop(handle);
+        buf = (handle->flags & UV_HANDLE_ZERO_READ) ?
+              uv_buf_init(NULL, 0) : handle->recv_buffer;
+        handle->recv_cb(handle, uv_translate_sys_error(err), &buf, NULL, 0);
+      }
+      goto done;
+    }
+  }
+
+  if (!(handle->flags & UV_HANDLE_ZERO_READ)) {
+    /* Successful read */
+    partial = !REQ_SUCCESS(req);
+    handle->recv_cb(handle,
+                    req->u.io.overlapped.InternalHigh,
+                    &handle->recv_buffer,
+                    (const struct sockaddr*) &handle->recv_from,
+                    partial ? UV_UDP_PARTIAL : 0);
+  } else if (handle->flags & UV_HANDLE_READING) {
+    DWORD bytes, err, flags;
+    struct sockaddr_storage from;
+    int from_len;
+
+    /* Do a nonblocking receive.
+     * TODO: try to read multiple datagrams at once. FIONREAD maybe? */
+    buf = uv_buf_init(NULL, 0);
+    handle->alloc_cb((uv_handle_t*) handle, 65536, &buf);
+    if (buf.base == NULL || buf.len == 0) {
+      handle->recv_cb(handle, UV_ENOBUFS, &buf, NULL, 0);
+      goto done;
+    }
+    assert(buf.base != NULL);
+
+    memset(&from, 0, sizeof from);
+    from_len = sizeof from;
+
+    flags = 0;
+
+    if (WSARecvFrom(handle->socket,
+                    (WSABUF*)&buf,
+                    1,
+                    &bytes,
+                    &flags,
+                    (struct sockaddr*) &from,
+                    &from_len,
+                    NULL,
+                    NULL) != SOCKET_ERROR) {
+
+      /* Message received */
+      handle->recv_cb(handle, bytes, &buf, (const struct sockaddr*) &from, 0);
+    } else {
+      err = WSAGetLastError();
+      if (err == WSAEMSGSIZE) {
+        /* Message truncated */
+        handle->recv_cb(handle,
+                        bytes,
+                        &buf,
+                        (const struct sockaddr*) &from,
+                        UV_UDP_PARTIAL);
+      } else if (err == WSAEWOULDBLOCK) {
+        /* Kernel buffer empty */
+        handle->recv_cb(handle, 0, &buf, NULL, 0);
+      } else if (err == WSAECONNRESET || err == WSAENETRESET) {
+        /* WSAECONNRESET/WSANETRESET is ignored because this just indicates
+         * that a previous sendto operation failed.
+         */
+        handle->recv_cb(handle, 0, &buf, NULL, 0);
+      } else {
+        /* Any other error that we want to report back to the user. */
+        uv_udp_recv_stop(handle);
+        handle->recv_cb(handle, uv_translate_sys_error(err), &buf, NULL, 0);
+      }
+    }
+  }
+
+done:
+  /* Post another read if still reading and not closing. */
+  if ((handle->flags & UV_HANDLE_READING) &&
+      !(handle->flags & UV_HANDLE_READ_PENDING)) {
+    uv_udp_queue_recv(loop, handle);
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+void uv_process_udp_send_req(uv_loop_t* loop, uv_udp_t* handle,
+    uv_udp_send_t* req) {
+  int err;
+
+  assert(handle->type == UV_UDP);
+
+  assert(handle->send_queue_size >= req->u.io.queued_bytes);
+  assert(handle->send_queue_count >= 1);
+  handle->send_queue_size -= req->u.io.queued_bytes;
+  handle->send_queue_count--;
+
+  UNREGISTER_HANDLE_REQ(loop, handle, req);
+
+  if (req->cb) {
+    err = 0;
+    if (!REQ_SUCCESS(req)) {
+      err = GET_REQ_SOCK_ERROR(req);
+    }
+    req->cb(req, uv_translate_sys_error(err));
+  }
+
+  DECREASE_PENDING_REQ_COUNT(handle);
+}
+
+
+static int uv__udp_set_membership4(uv_udp_t* handle,
+                                   const struct sockaddr_in* multicast_addr,
+                                   const char* interface_addr,
+                                   uv_membership membership) {
+  int err;
+  int optname;
+  struct ip_mreq mreq;
+
+  if (handle->flags & UV_HANDLE_IPV6)
+    return UV_EINVAL;
+
+  /* If the socket is unbound, bind to inaddr_any. */
+  err = uv_udp_maybe_bind(handle,
+                          (const struct sockaddr*) &uv_addr_ip4_any_,
+                          sizeof(uv_addr_ip4_any_),
+                          UV_UDP_REUSEADDR);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  memset(&mreq, 0, sizeof mreq);
+
+  if (interface_addr) {
+    err = uv_inet_pton(AF_INET, interface_addr, &mreq.imr_interface.s_addr);
+    if (err)
+      return err;
+  } else {
+    mreq.imr_interface.s_addr = htonl(INADDR_ANY);
+  }
+
+  mreq.imr_multiaddr.s_addr = multicast_addr->sin_addr.s_addr;
+
+  switch (membership) {
+    case UV_JOIN_GROUP:
+      optname = IP_ADD_MEMBERSHIP;
+      break;
+    case UV_LEAVE_GROUP:
+      optname = IP_DROP_MEMBERSHIP;
+      break;
+    default:
+      return UV_EINVAL;
+  }
+
+  if (setsockopt(handle->socket,
+                 IPPROTO_IP,
+                 optname,
+                 (char*) &mreq,
+                 sizeof mreq) == SOCKET_ERROR) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv__udp_set_membership6(uv_udp_t* handle,
+                            const struct sockaddr_in6* multicast_addr,
+                            const char* interface_addr,
+                            uv_membership membership) {
+  int optname;
+  int err;
+  struct ipv6_mreq mreq;
+  struct sockaddr_in6 addr6;
+
+  if ((handle->flags & UV_HANDLE_BOUND) && !(handle->flags & UV_HANDLE_IPV6))
+    return UV_EINVAL;
+
+  err = uv_udp_maybe_bind(handle,
+                          (const struct sockaddr*) &uv_addr_ip6_any_,
+                          sizeof(uv_addr_ip6_any_),
+                          UV_UDP_REUSEADDR);
+
+  if (err)
+    return uv_translate_sys_error(err);
+
+  memset(&mreq, 0, sizeof(mreq));
+
+  if (interface_addr) {
+    if (uv_ip6_addr(interface_addr, 0, &addr6))
+      return UV_EINVAL;
+    mreq.ipv6mr_interface = addr6.sin6_scope_id;
+  } else {
+    mreq.ipv6mr_interface = 0;
+  }
+
+  mreq.ipv6mr_multiaddr = multicast_addr->sin6_addr;
+
+  switch (membership) {
+  case UV_JOIN_GROUP:
+    optname = IPV6_ADD_MEMBERSHIP;
+    break;
+  case UV_LEAVE_GROUP:
+    optname = IPV6_DROP_MEMBERSHIP;
+    break;
+  default:
+    return UV_EINVAL;
+  }
+
+  if (setsockopt(handle->socket,
+                 IPPROTO_IPV6,
+                 optname,
+                 (char*) &mreq,
+                 sizeof mreq) == SOCKET_ERROR) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv_udp_set_membership(uv_udp_t* handle,
+                          const char* multicast_addr,
+                          const char* interface_addr,
+                          uv_membership membership) {
+  struct sockaddr_in addr4;
+  struct sockaddr_in6 addr6;
+
+  if (uv_ip4_addr(multicast_addr, 0, &addr4) == 0)
+    return uv__udp_set_membership4(handle, &addr4, interface_addr, membership);
+  else if (uv_ip6_addr(multicast_addr, 0, &addr6) == 0)
+    return uv__udp_set_membership6(handle, &addr6, interface_addr, membership);
+  else
+    return UV_EINVAL;
+}
+
+
+int uv_udp_set_multicast_interface(uv_udp_t* handle, const char* interface_addr) {
+  struct sockaddr_storage addr_st;
+  struct sockaddr_in* addr4;
+  struct sockaddr_in6* addr6;
+
+  addr4 = (struct sockaddr_in*) &addr_st;
+  addr6 = (struct sockaddr_in6*) &addr_st;
+
+  if (!interface_addr) {
+    memset(&addr_st, 0, sizeof addr_st);
+    if (handle->flags & UV_HANDLE_IPV6) {
+      addr_st.ss_family = AF_INET6;
+      addr6->sin6_scope_id = 0;
+    } else {
+      addr_st.ss_family = AF_INET;
+      addr4->sin_addr.s_addr = htonl(INADDR_ANY);
+    }
+  } else if (uv_ip4_addr(interface_addr, 0, addr4) == 0) {
+    /* nothing, address was parsed */
+  } else if (uv_ip6_addr(interface_addr, 0, addr6) == 0) {
+    /* nothing, address was parsed */
+  } else {
+    return UV_EINVAL;
+  }
+
+  if (handle->socket == INVALID_SOCKET)
+    return UV_EBADF;
+
+  if (addr_st.ss_family == AF_INET) {
+    if (setsockopt(handle->socket,
+                   IPPROTO_IP,
+                   IP_MULTICAST_IF,
+                   (char*) &addr4->sin_addr,
+                   sizeof(addr4->sin_addr)) == SOCKET_ERROR) {
+      return uv_translate_sys_error(WSAGetLastError());
+    }
+  } else if (addr_st.ss_family == AF_INET6) {
+    if (setsockopt(handle->socket,
+                   IPPROTO_IPV6,
+                   IPV6_MULTICAST_IF,
+                   (char*) &addr6->sin6_scope_id,
+                   sizeof(addr6->sin6_scope_id)) == SOCKET_ERROR) {
+      return uv_translate_sys_error(WSAGetLastError());
+    }
+  } else {
+    assert(0 && "unexpected address family");
+    abort();
+  }
+
+  return 0;
+}
+
+
+int uv_udp_set_broadcast(uv_udp_t* handle, int value) {
+  BOOL optval = (BOOL) value;
+
+  if (handle->socket == INVALID_SOCKET)
+    return UV_EBADF;
+
+  if (setsockopt(handle->socket,
+                 SOL_SOCKET,
+                 SO_BROADCAST,
+                 (char*) &optval,
+                 sizeof optval)) {
+    return uv_translate_sys_error(WSAGetLastError());
+  }
+
+  return 0;
+}
+
+
+int uv_udp_open(uv_udp_t* handle, uv_os_sock_t sock) {
+  WSAPROTOCOL_INFOW protocol_info;
+  int opt_len;
+  int err;
+
+  /* Detect the address family of the socket. */
+  opt_len = (int) sizeof protocol_info;
+  if (getsockopt(sock,
+                 SOL_SOCKET,
+                 SO_PROTOCOL_INFOW,
+                 (char*) &protocol_info,
+                 &opt_len) == SOCKET_ERROR) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  err = uv_udp_set_socket(handle->loop,
+                          handle,
+                          sock,
+                          protocol_info.iAddressFamily);
+  return uv_translate_sys_error(err);
+}
+
+
+#define SOCKOPT_SETTER(name, option4, option6, validate)                      \
+  int uv_udp_set_##name(uv_udp_t* handle, int value) {                        \
+    DWORD optval = (DWORD) value;                                             \
+                                                                              \
+    if (!(validate(value))) {                                                 \
+      return UV_EINVAL;                                                       \
+    }                                                                         \
+                                                                              \
+    if (handle->socket == INVALID_SOCKET)                                     \
+      return UV_EBADF;                                                        \
+                                                                              \
+    if (!(handle->flags & UV_HANDLE_IPV6)) {                                  \
+      /* Set IPv4 socket option */                                            \
+      if (setsockopt(handle->socket,                                          \
+                     IPPROTO_IP,                                              \
+                     option4,                                                 \
+                     (char*) &optval,                                         \
+                     sizeof optval)) {                                        \
+        return uv_translate_sys_error(WSAGetLastError());                     \
+      }                                                                       \
+    } else {                                                                  \
+      /* Set IPv6 socket option */                                            \
+      if (setsockopt(handle->socket,                                          \
+                     IPPROTO_IPV6,                                            \
+                     option6,                                                 \
+                     (char*) &optval,                                         \
+                     sizeof optval)) {                                        \
+        return uv_translate_sys_error(WSAGetLastError());                     \
+      }                                                                       \
+    }                                                                         \
+    return 0;                                                                 \
+  }
+
+#define VALIDATE_TTL(value) ((value) >= 1 && (value) <= 255)
+#define VALIDATE_MULTICAST_TTL(value) ((value) >= -1 && (value) <= 255)
+#define VALIDATE_MULTICAST_LOOP(value) (1)
+
+SOCKOPT_SETTER(ttl,
+               IP_TTL,
+               IPV6_HOPLIMIT,
+               VALIDATE_TTL)
+SOCKOPT_SETTER(multicast_ttl,
+               IP_MULTICAST_TTL,
+               IPV6_MULTICAST_HOPS,
+               VALIDATE_MULTICAST_TTL)
+SOCKOPT_SETTER(multicast_loop,
+               IP_MULTICAST_LOOP,
+               IPV6_MULTICAST_LOOP,
+               VALIDATE_MULTICAST_LOOP)
+
+#undef SOCKOPT_SETTER
+#undef VALIDATE_TTL
+#undef VALIDATE_MULTICAST_TTL
+#undef VALIDATE_MULTICAST_LOOP
+
+
+/* This function is an egress point, i.e. it returns libuv errors rather than
+ * system errors.
+ */
+int uv__udp_bind(uv_udp_t* handle,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 unsigned int flags) {
+  int err;
+
+  err = uv_udp_maybe_bind(handle, addr, addrlen, flags);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  return 0;
+}
+
+
+/* This function is an egress point, i.e. it returns libuv errors rather than
+ * system errors.
+ */
+int uv__udp_send(uv_udp_send_t* req,
+                 uv_udp_t* handle,
+                 const uv_buf_t bufs[],
+                 unsigned int nbufs,
+                 const struct sockaddr* addr,
+                 unsigned int addrlen,
+                 uv_udp_send_cb send_cb) {
+  const struct sockaddr* bind_addr;
+  int err;
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    if (addrlen == sizeof(uv_addr_ip4_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
+    else if (addrlen == sizeof(uv_addr_ip6_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
+    else
+      return UV_EINVAL;
+    err = uv_udp_maybe_bind(handle, bind_addr, addrlen, 0);
+    if (err)
+      return uv_translate_sys_error(err);
+  }
+
+  err = uv__send(req, handle, bufs, nbufs, addr, addrlen, send_cb);
+  if (err)
+    return uv_translate_sys_error(err);
+
+  return 0;
+}
+
+
+int uv__udp_try_send(uv_udp_t* handle,
+                     const uv_buf_t bufs[],
+                     unsigned int nbufs,
+                     const struct sockaddr* addr,
+                     unsigned int addrlen) {
+  DWORD bytes;
+  const struct sockaddr* bind_addr;
+  struct sockaddr_storage converted;
+  int err;
+
+  assert(nbufs > 0);
+
+  err = uv__convert_to_localhost_if_unspecified(addr, &converted);
+  if (err)
+    return err;
+
+  /* Already sending a message.*/
+  if (handle->send_queue_count != 0)
+    return UV_EAGAIN;
+
+  if (!(handle->flags & UV_HANDLE_BOUND)) {
+    if (addrlen == sizeof(uv_addr_ip4_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip4_any_;
+    else if (addrlen == sizeof(uv_addr_ip6_any_))
+      bind_addr = (const struct sockaddr*) &uv_addr_ip6_any_;
+    else
+      return UV_EINVAL;
+    err = uv_udp_maybe_bind(handle, bind_addr, addrlen, 0);
+    if (err)
+      return uv_translate_sys_error(err);
+  }
+
+  err = WSASendTo(handle->socket,
+                  (WSABUF*)bufs,
+                  nbufs,
+                  &bytes,
+                  0,
+                  (const struct sockaddr*) &converted,
+                  addrlen,
+                  NULL,
+                  NULL);
+
+  if (err)
+    return uv_translate_sys_error(WSAGetLastError());
+
+  return bytes;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/util.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/util.cpp
new file mode 100644
index 0000000..1917c02
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/util.cpp
@@ -0,0 +1,1539 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <direct.h>
+#include <limits.h>
+#include <stdio.h>
+#include <string.h>
+#include <time.h>
+#include <wchar.h>
+
+#include "uv.h"
+#include "internal.h"
+
+#include <winsock2.h>
+#include <winperf.h>
+#include <iphlpapi.h>
+#include <psapi.h>
+#include <tlhelp32.h>
+#include <windows.h>
+#include <userenv.h>
+#include <math.h>
+
+/*
+ * Max title length; the only thing MSDN tells us about the maximum length
+ * of the console title is that it is smaller than 64K. However in practice
+ * it is much smaller, and there is no way to figure out what the exact length
+ * of the title is or can be, at least not on XP. To make it even more
+ * annoying, GetConsoleTitle fails when the buffer to be read into is bigger
+ * than the actual maximum length. So we make a conservative guess here;
+ * just don't put the novel you're writing in the title, unless the plot
+ * survives truncation.
+ */
+#define MAX_TITLE_LENGTH 8192
+
+/* The number of nanoseconds in one second. */
+#define UV__NANOSEC 1000000000
+
+/* Max user name length, from iphlpapi.h */
+#ifndef UNLEN
+# define UNLEN 256
+#endif
+
+/*
+  Max hostname length. The Windows gethostname() documentation states that 256
+  bytes will always be large enough to hold the null-terminated hostname.
+*/
+#ifndef MAXHOSTNAMELEN
+# define MAXHOSTNAMELEN 256
+#endif
+
+/* Maximum environment variable size, including the terminating null */
+#define MAX_ENV_VAR_LENGTH 32767
+
+/* Cached copy of the process title, plus a mutex guarding it. */
+static char *process_title;
+static CRITICAL_SECTION process_title_lock;
+
+#pragma comment(lib, "Advapi32.lib")
+#pragma comment(lib, "IPHLPAPI.lib")
+#pragma comment(lib, "Psapi.lib")
+#pragma comment(lib, "Userenv.lib")
+#pragma comment(lib, "kernel32.lib")
+
+/* Interval (in seconds) of the high-resolution clock. */
+static double hrtime_interval_ = 0;
+
+
+/*
+ * One-time initialization code for functionality defined in util.c.
+ */
+void uv__util_init(void) {
+  LARGE_INTEGER perf_frequency;
+
+  /* Initialize process title access mutex. */
+  InitializeCriticalSection(&process_title_lock);
+
+  /* Retrieve high-resolution timer frequency
+   * and precompute its reciprocal.
+   */
+  if (QueryPerformanceFrequency(&perf_frequency)) {
+    hrtime_interval_ = 1.0 / perf_frequency.QuadPart;
+  } else {
+    hrtime_interval_= 0;
+  }
+}
+
+
+int uv_exepath(char* buffer, size_t* size_ptr) {
+  int utf8_len, utf16_buffer_len, utf16_len;
+  WCHAR* utf16_buffer;
+  int err;
+
+  if (buffer == NULL || size_ptr == NULL || *size_ptr == 0) {
+    return UV_EINVAL;
+  }
+
+  if (*size_ptr > 32768) {
+    /* Windows paths can never be longer than this. */
+    utf16_buffer_len = 32768;
+  } else {
+    utf16_buffer_len = (int) *size_ptr;
+  }
+
+  utf16_buffer = (WCHAR*) uv__malloc(sizeof(WCHAR) * utf16_buffer_len);
+  if (!utf16_buffer) {
+    return UV_ENOMEM;
+  }
+
+  /* Get the path as UTF-16. */
+  utf16_len = GetModuleFileNameW(NULL, utf16_buffer, utf16_buffer_len);
+  if (utf16_len <= 0) {
+    err = GetLastError();
+    goto error;
+  }
+
+  /* utf16_len contains the length, *not* including the terminating null. */
+  utf16_buffer[utf16_len] = L'\0';
+
+  /* Convert to UTF-8 */
+  utf8_len = WideCharToMultiByte(CP_UTF8,
+                                 0,
+                                 utf16_buffer,
+                                 -1,
+                                 buffer,
+                                 (int) *size_ptr,
+                                 NULL,
+                                 NULL);
+  if (utf8_len == 0) {
+    err = GetLastError();
+    goto error;
+  }
+
+  uv__free(utf16_buffer);
+
+  /* utf8_len *does* include the terminating null at this point, but the
+   * returned size shouldn't. */
+  *size_ptr = utf8_len - 1;
+  return 0;
+
+ error:
+  uv__free(utf16_buffer);
+  return uv_translate_sys_error(err);
+}
+
+
+int uv_cwd(char* buffer, size_t* size) {
+  DWORD utf16_len;
+  WCHAR utf16_buffer[MAX_PATH];
+  int r;
+
+  if (buffer == NULL || size == NULL) {
+    return UV_EINVAL;
+  }
+
+  utf16_len = GetCurrentDirectoryW(MAX_PATH, utf16_buffer);
+  if (utf16_len == 0) {
+    return uv_translate_sys_error(GetLastError());
+  } else if (utf16_len > MAX_PATH) {
+    /* This should be impossible; however the CRT has a code path to deal with
+     * this scenario, so I added a check anyway. */
+    return UV_EIO;
+  }
+
+  /* utf16_len contains the length, *not* including the terminating null. */
+  utf16_buffer[utf16_len] = L'\0';
+
+  /* The returned directory should not have a trailing slash, unless it points
+   * at a drive root, like c:\. Remove it if needed. */
+  if (utf16_buffer[utf16_len - 1] == L'\\' &&
+      !(utf16_len == 3 && utf16_buffer[1] == L':')) {
+    utf16_len--;
+    utf16_buffer[utf16_len] = L'\0';
+  }
+
+  /* Check how much space we need */
+  r = WideCharToMultiByte(CP_UTF8,
+                          0,
+                          utf16_buffer,
+                          -1,
+                          NULL,
+                          0,
+                          NULL,
+                          NULL);
+  if (r == 0) {
+    return uv_translate_sys_error(GetLastError());
+  } else if (r > (int) *size) {
+    *size = r;
+    return UV_ENOBUFS;
+  }
+
+  /* Convert to UTF-8 */
+  r = WideCharToMultiByte(CP_UTF8,
+                          0,
+                          utf16_buffer,
+                          -1,
+                          buffer,
+                          *size > INT_MAX ? INT_MAX : (int) *size,
+                          NULL,
+                          NULL);
+  if (r == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  *size = r - 1;
+  return 0;
+}
+
+
+int uv_chdir(const char* dir) {
+  WCHAR utf16_buffer[MAX_PATH];
+  size_t utf16_len;
+  WCHAR drive_letter, env_var[4];
+
+  if (dir == NULL) {
+    return UV_EINVAL;
+  }
+
+  if (MultiByteToWideChar(CP_UTF8,
+                          0,
+                          dir,
+                          -1,
+                          utf16_buffer,
+                          MAX_PATH) == 0) {
+    DWORD error = GetLastError();
+    /* The maximum length of the current working directory is 260 chars,
+     * including terminating null. If it doesn't fit, the path name must be too
+     * long. */
+    if (error == ERROR_INSUFFICIENT_BUFFER) {
+      return UV_ENAMETOOLONG;
+    } else {
+      return uv_translate_sys_error(error);
+    }
+  }
+
+  if (!SetCurrentDirectoryW(utf16_buffer)) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  /* Windows stores the drive-local path in an "hidden" environment variable,
+   * which has the form "=C:=C:\Windows". SetCurrentDirectory does not update
+   * this, so we'll have to do it. */
+  utf16_len = GetCurrentDirectoryW(MAX_PATH, utf16_buffer);
+  if (utf16_len == 0) {
+    return uv_translate_sys_error(GetLastError());
+  } else if (utf16_len > MAX_PATH) {
+    return UV_EIO;
+  }
+
+  /* The returned directory should not have a trailing slash, unless it points
+   * at a drive root, like c:\. Remove it if needed. */
+  if (utf16_buffer[utf16_len - 1] == L'\\' &&
+      !(utf16_len == 3 && utf16_buffer[1] == L':')) {
+    utf16_len--;
+    utf16_buffer[utf16_len] = L'\0';
+  }
+
+  if (utf16_len < 2 || utf16_buffer[1] != L':') {
+    /* Doesn't look like a drive letter could be there - probably an UNC path.
+     * TODO: Need to handle win32 namespaces like \\?\C:\ ? */
+    drive_letter = 0;
+  } else if (utf16_buffer[0] >= L'A' && utf16_buffer[0] <= L'Z') {
+    drive_letter = utf16_buffer[0];
+  } else if (utf16_buffer[0] >= L'a' && utf16_buffer[0] <= L'z') {
+    /* Convert to uppercase. */
+    drive_letter = utf16_buffer[0] - L'a' + L'A';
+  } else {
+    /* Not valid. */
+    drive_letter = 0;
+  }
+
+  if (drive_letter != 0) {
+    /* Construct the environment variable name and set it. */
+    env_var[0] = L'=';
+    env_var[1] = drive_letter;
+    env_var[2] = L':';
+    env_var[3] = L'\0';
+
+    if (!SetEnvironmentVariableW(env_var, utf16_buffer)) {
+      return uv_translate_sys_error(GetLastError());
+    }
+  }
+
+  return 0;
+}
+
+
+void uv_loadavg(double avg[3]) {
+  /* Can't be implemented */
+  avg[0] = avg[1] = avg[2] = 0;
+}
+
+
+uint64_t uv_get_free_memory(void) {
+  MEMORYSTATUSEX memory_status;
+  memory_status.dwLength = sizeof(memory_status);
+
+  if (!GlobalMemoryStatusEx(&memory_status)) {
+     return -1;
+  }
+
+  return (uint64_t)memory_status.ullAvailPhys;
+}
+
+
+uint64_t uv_get_total_memory(void) {
+  MEMORYSTATUSEX memory_status;
+  memory_status.dwLength = sizeof(memory_status);
+
+  if (!GlobalMemoryStatusEx(&memory_status)) {
+    return -1;
+  }
+
+  return (uint64_t)memory_status.ullTotalPhys;
+}
+
+
+uv_pid_t uv_os_getpid(void) {
+  return GetCurrentProcessId();
+}
+
+
+uv_pid_t uv_os_getppid(void) {
+  int parent_pid = -1;
+  HANDLE handle;
+  PROCESSENTRY32 pe;
+  DWORD current_pid = GetCurrentProcessId();
+
+  pe.dwSize = sizeof(PROCESSENTRY32);
+  handle = CreateToolhelp32Snapshot(TH32CS_SNAPPROCESS, 0);
+
+  if (Process32First(handle, &pe)) {
+    do {
+      if (pe.th32ProcessID == current_pid) {
+        parent_pid = pe.th32ParentProcessID;
+        break;
+      }
+    } while( Process32Next(handle, &pe));
+  }
+
+  CloseHandle(handle);
+  return parent_pid;
+}
+
+
+char** uv_setup_args(int argc, char** argv) {
+  return argv;
+}
+
+
+int uv_set_process_title(const char* title) {
+  int err;
+  int length;
+  WCHAR* title_w = NULL;
+
+  uv__once_init();
+
+  /* Find out how big the buffer for the wide-char title must be */
+  length = MultiByteToWideChar(CP_UTF8, 0, title, -1, NULL, 0);
+  if (!length) {
+    err = GetLastError();
+    goto done;
+  }
+
+  /* Convert to wide-char string */
+  title_w = (WCHAR*)uv__malloc(sizeof(WCHAR) * length);
+  if (!title_w) {
+    uv_fatal_error(ERROR_OUTOFMEMORY, "uv__malloc");
+  }
+
+  length = MultiByteToWideChar(CP_UTF8, 0, title, -1, title_w, length);
+  if (!length) {
+    err = GetLastError();
+    goto done;
+  }
+
+  /* If the title must be truncated insert a \0 terminator there */
+  if (length > MAX_TITLE_LENGTH) {
+    title_w[MAX_TITLE_LENGTH - 1] = L'\0';
+  }
+
+  if (!SetConsoleTitleW(title_w)) {
+    err = GetLastError();
+    goto done;
+  }
+
+  EnterCriticalSection(&process_title_lock);
+  uv__free(process_title);
+  process_title = uv__strdup(title);
+  LeaveCriticalSection(&process_title_lock);
+
+  err = 0;
+
+done:
+  uv__free(title_w);
+  return uv_translate_sys_error(err);
+}
+
+
+static int uv__get_process_title(void) {
+  WCHAR title_w[MAX_TITLE_LENGTH];
+
+  if (!GetConsoleTitleW(title_w, sizeof(title_w) / sizeof(WCHAR))) {
+    return -1;
+  }
+
+  if (uv__convert_utf16_to_utf8(title_w, -1, &process_title) != 0)
+    return -1;
+
+  return 0;
+}
+
+
+int uv_get_process_title(char* buffer, size_t size) {
+  size_t len;
+
+  if (buffer == NULL || size == 0)
+    return UV_EINVAL;
+
+  uv__once_init();
+
+  EnterCriticalSection(&process_title_lock);
+  /*
+   * If the process_title was never read before nor explicitly set,
+   * we must query it with getConsoleTitleW
+   */
+  if (!process_title && uv__get_process_title() == -1) {
+    LeaveCriticalSection(&process_title_lock);
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  assert(process_title);
+  len = strlen(process_title) + 1;
+
+  if (size < len) {
+    LeaveCriticalSection(&process_title_lock);
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, process_title, len);
+  LeaveCriticalSection(&process_title_lock);
+
+  return 0;
+}
+
+
+uint64_t uv_hrtime(void) {
+  uv__once_init();
+  return uv__hrtime(UV__NANOSEC);
+}
+
+uint64_t uv__hrtime(double scale) {
+  LARGE_INTEGER counter;
+
+  /* If the performance interval is zero, there's no support. */
+  if (hrtime_interval_ == 0) {
+    return 0;
+  }
+
+  if (!QueryPerformanceCounter(&counter)) {
+    return 0;
+  }
+
+  /* Because we have no guarantee about the order of magnitude of the
+   * performance counter interval, integer math could cause this computation
+   * to overflow. Therefore we resort to floating point math.
+   */
+  return (uint64_t) ((double) counter.QuadPart * hrtime_interval_ * scale);
+}
+
+
+int uv_resident_set_memory(size_t* rss) {
+  HANDLE current_process;
+  PROCESS_MEMORY_COUNTERS pmc;
+
+  current_process = GetCurrentProcess();
+
+  if (!GetProcessMemoryInfo(current_process, &pmc, sizeof(pmc))) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  *rss = pmc.WorkingSetSize;
+
+  return 0;
+}
+
+
+int uv_uptime(double* uptime) {
+  BYTE stack_buffer[4096];
+  BYTE* malloced_buffer = NULL;
+  BYTE* buffer = (BYTE*) stack_buffer;
+  size_t buffer_size = sizeof(stack_buffer);
+  DWORD data_size;
+
+  PERF_DATA_BLOCK* data_block;
+  PERF_OBJECT_TYPE* object_type;
+  PERF_COUNTER_DEFINITION* counter_definition;
+
+  DWORD i;
+
+  for (;;) {
+    LONG result;
+
+    data_size = (DWORD) buffer_size;
+    result = RegQueryValueExW(HKEY_PERFORMANCE_DATA,
+                              L"2",
+                              NULL,
+                              NULL,
+                              buffer,
+                              &data_size);
+    if (result == ERROR_SUCCESS) {
+      break;
+    } else if (result != ERROR_MORE_DATA) {
+      *uptime = 0;
+      return uv_translate_sys_error(result);
+    }
+
+    buffer_size *= 2;
+    /* Don't let the buffer grow infinitely. */
+    if (buffer_size > 1 << 20) {
+      goto internalError;
+    }
+
+    uv__free(malloced_buffer);
+
+    buffer = malloced_buffer = (BYTE*) uv__malloc(buffer_size);
+    if (malloced_buffer == NULL) {
+      *uptime = 0;
+      return UV_ENOMEM;
+    }
+  }
+
+  if (data_size < sizeof(*data_block))
+    goto internalError;
+
+  data_block = (PERF_DATA_BLOCK*) buffer;
+
+  if (wmemcmp(data_block->Signature, L"PERF", 4) != 0)
+    goto internalError;
+
+  if (data_size < data_block->HeaderLength + sizeof(*object_type))
+    goto internalError;
+
+  object_type = (PERF_OBJECT_TYPE*) (buffer + data_block->HeaderLength);
+
+  if (object_type->NumInstances != PERF_NO_INSTANCES)
+    goto internalError;
+
+  counter_definition = (PERF_COUNTER_DEFINITION*) (buffer +
+      data_block->HeaderLength + object_type->HeaderLength);
+  for (i = 0; i < object_type->NumCounters; i++) {
+    if ((BYTE*) counter_definition + sizeof(*counter_definition) >
+        buffer + data_size) {
+      break;
+    }
+
+    if (counter_definition->CounterNameTitleIndex == 674 &&
+        counter_definition->CounterSize == sizeof(uint64_t)) {
+      if (counter_definition->CounterOffset + sizeof(uint64_t) > data_size ||
+          !(counter_definition->CounterType & PERF_OBJECT_TIMER)) {
+        goto internalError;
+      } else {
+        BYTE* address = (BYTE*) object_type + object_type->DefinitionLength +
+                        counter_definition->CounterOffset;
+        uint64_t value = *((uint64_t*) address);
+        *uptime = floor((double) (object_type->PerfTime.QuadPart - value) /
+                        (double) object_type->PerfFreq.QuadPart);
+        uv__free(malloced_buffer);
+        return 0;
+      }
+    }
+
+    counter_definition = (PERF_COUNTER_DEFINITION*)
+        ((BYTE*) counter_definition + counter_definition->ByteLength);
+  }
+
+  /* If we get here, the uptime value was not found. */
+  uv__free(malloced_buffer);
+  *uptime = 0;
+  return UV_ENOSYS;
+
+ internalError:
+  uv__free(malloced_buffer);
+  *uptime = 0;
+  return UV_EIO;
+}
+
+
+int uv_cpu_info(uv_cpu_info_t** cpu_infos_ptr, int* cpu_count_ptr) {
+  uv_cpu_info_t* cpu_infos;
+  SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION* sppi;
+  DWORD sppi_size;
+  SYSTEM_INFO system_info;
+  DWORD cpu_count, i;
+  NTSTATUS status;
+  ULONG result_size;
+  int err;
+  uv_cpu_info_t* cpu_info;
+
+  cpu_infos = NULL;
+  cpu_count = 0;
+  sppi = NULL;
+
+  uv__once_init();
+
+  GetSystemInfo(&system_info);
+  cpu_count = system_info.dwNumberOfProcessors;
+
+  cpu_infos = (uv_cpu_info_t*)uv__calloc(cpu_count, sizeof *cpu_infos);
+  if (cpu_infos == NULL) {
+    err = ERROR_OUTOFMEMORY;
+    goto error;
+  }
+
+  sppi_size = cpu_count * sizeof(*sppi);
+  sppi = (SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION*)uv__malloc(sppi_size);
+  if (sppi == NULL) {
+    err = ERROR_OUTOFMEMORY;
+    goto error;
+  }
+
+  status = pNtQuerySystemInformation(SystemProcessorPerformanceInformation,
+                                     sppi,
+                                     sppi_size,
+                                     &result_size);
+  if (!NT_SUCCESS(status)) {
+    err = pRtlNtStatusToDosError(status);
+    goto error;
+  }
+
+  assert(result_size == sppi_size);
+
+  for (i = 0; i < cpu_count; i++) {
+    WCHAR key_name[128];
+    HKEY processor_key;
+    DWORD cpu_speed;
+    DWORD cpu_speed_size = sizeof(cpu_speed);
+    WCHAR cpu_brand[256];
+    DWORD cpu_brand_size = sizeof(cpu_brand);
+    size_t len;
+
+    len = _snwprintf(key_name,
+                     ARRAY_SIZE(key_name),
+                     L"HARDWARE\\DESCRIPTION\\System\\CentralProcessor\\%d",
+                     i);
+
+    assert(len > 0 && len < ARRAY_SIZE(key_name));
+
+    err = RegOpenKeyExW(HKEY_LOCAL_MACHINE,
+                        key_name,
+                        0,
+                        KEY_QUERY_VALUE,
+                        &processor_key);
+    if (err != ERROR_SUCCESS) {
+      goto error;
+    }
+
+    err = RegQueryValueExW(processor_key,
+                           L"~MHz",
+                           NULL,
+                           NULL,
+                           (BYTE*)&cpu_speed,
+                           &cpu_speed_size);
+    if (err != ERROR_SUCCESS) {
+      RegCloseKey(processor_key);
+      goto error;
+    }
+
+    err = RegQueryValueExW(processor_key,
+                           L"ProcessorNameString",
+                           NULL,
+                           NULL,
+                           (BYTE*)&cpu_brand,
+                           &cpu_brand_size);
+    if (err != ERROR_SUCCESS) {
+      RegCloseKey(processor_key);
+      goto error;
+    }
+
+    RegCloseKey(processor_key);
+
+    cpu_info = &cpu_infos[i];
+    cpu_info->speed = cpu_speed;
+    cpu_info->cpu_times.user = sppi[i].UserTime.QuadPart / 10000;
+    cpu_info->cpu_times.sys = (sppi[i].KernelTime.QuadPart -
+        sppi[i].IdleTime.QuadPart) / 10000;
+    cpu_info->cpu_times.idle = sppi[i].IdleTime.QuadPart / 10000;
+    cpu_info->cpu_times.irq = sppi[i].InterruptTime.QuadPart / 10000;
+    cpu_info->cpu_times.nice = 0;
+
+    uv__convert_utf16_to_utf8(cpu_brand,
+                              cpu_brand_size / sizeof(WCHAR),
+                              &(cpu_info->model));
+  }
+
+  uv__free(sppi);
+
+  *cpu_count_ptr = cpu_count;
+  *cpu_infos_ptr = cpu_infos;
+
+  return 0;
+
+ error:
+  /* This is safe because the cpu_infos array is zeroed on allocation. */
+  for (i = 0; i < cpu_count; i++)
+    uv__free(cpu_infos[i].model);
+
+  uv__free(cpu_infos);
+  uv__free(sppi);
+
+  return uv_translate_sys_error(err);
+}
+
+
+void uv_free_cpu_info(uv_cpu_info_t* cpu_infos, int count) {
+  int i;
+
+  for (i = 0; i < count; i++) {
+    uv__free(cpu_infos[i].model);
+  }
+
+  uv__free(cpu_infos);
+}
+
+
+static int is_windows_version_or_greater(DWORD os_major,
+                                         DWORD os_minor,
+                                         WORD service_pack_major,
+                                         WORD service_pack_minor) {
+  OSVERSIONINFOEX osvi;
+  DWORDLONG condition_mask = 0;
+  int op = VER_GREATER_EQUAL;
+
+  /* Initialize the OSVERSIONINFOEX structure. */
+  ZeroMemory(&osvi, sizeof(OSVERSIONINFOEX));
+  osvi.dwOSVersionInfoSize = sizeof(OSVERSIONINFOEX);
+  osvi.dwMajorVersion = os_major;
+  osvi.dwMinorVersion = os_minor;
+  osvi.wServicePackMajor = service_pack_major;
+  osvi.wServicePackMinor = service_pack_minor;
+
+  /* Initialize the condition mask. */
+  VER_SET_CONDITION(condition_mask, VER_MAJORVERSION, op);
+  VER_SET_CONDITION(condition_mask, VER_MINORVERSION, op);
+  VER_SET_CONDITION(condition_mask, VER_SERVICEPACKMAJOR, op);
+  VER_SET_CONDITION(condition_mask, VER_SERVICEPACKMINOR, op);
+
+  /* Perform the test. */
+  return (int) VerifyVersionInfo(
+    &osvi,
+    VER_MAJORVERSION | VER_MINORVERSION |
+    VER_SERVICEPACKMAJOR | VER_SERVICEPACKMINOR,
+    condition_mask);
+}
+
+
+static int address_prefix_match(int family,
+                                struct sockaddr* address,
+                                struct sockaddr* prefix_address,
+                                int prefix_len) {
+  uint8_t* address_data;
+  uint8_t* prefix_address_data;
+  int i;
+
+  assert(address->sa_family == family);
+  assert(prefix_address->sa_family == family);
+
+  if (family == AF_INET6) {
+    address_data = (uint8_t*) &(((struct sockaddr_in6 *) address)->sin6_addr);
+    prefix_address_data =
+      (uint8_t*) &(((struct sockaddr_in6 *) prefix_address)->sin6_addr);
+  } else {
+    address_data = (uint8_t*) &(((struct sockaddr_in *) address)->sin_addr);
+    prefix_address_data =
+      (uint8_t*) &(((struct sockaddr_in *) prefix_address)->sin_addr);
+  }
+
+  for (i = 0; i < prefix_len >> 3; i++) {
+    if (address_data[i] != prefix_address_data[i])
+      return 0;
+  }
+
+  if (prefix_len % 8)
+    return prefix_address_data[i] ==
+      (address_data[i] & (0xff << (8 - prefix_len % 8)));
+
+  return 1;
+}
+
+
+int uv_interface_addresses(uv_interface_address_t** addresses_ptr,
+    int* count_ptr) {
+  IP_ADAPTER_ADDRESSES* win_address_buf;
+  ULONG win_address_buf_size;
+  IP_ADAPTER_ADDRESSES* adapter;
+
+  uv_interface_address_t* uv_address_buf;
+  char* name_buf;
+  size_t uv_address_buf_size;
+  uv_interface_address_t* uv_address;
+
+  int count;
+
+  int is_vista_or_greater;
+  ULONG flags;
+
+  is_vista_or_greater = is_windows_version_or_greater(6, 0, 0, 0);
+  if (is_vista_or_greater) {
+    flags = GAA_FLAG_SKIP_ANYCAST | GAA_FLAG_SKIP_MULTICAST |
+      GAA_FLAG_SKIP_DNS_SERVER;
+  } else {
+    /* We need at least XP SP1. */
+    if (!is_windows_version_or_greater(5, 1, 1, 0))
+      return UV_ENOTSUP;
+
+    flags = GAA_FLAG_SKIP_ANYCAST | GAA_FLAG_SKIP_MULTICAST |
+      GAA_FLAG_SKIP_DNS_SERVER | GAA_FLAG_INCLUDE_PREFIX;
+  }
+
+
+  /* Fetch the size of the adapters reported by windows, and then get the list
+   * itself. */
+  win_address_buf_size = 0;
+  win_address_buf = NULL;
+
+  for (;;) {
+    ULONG r;
+
+    /* If win_address_buf is 0, then GetAdaptersAddresses will fail with.
+     * ERROR_BUFFER_OVERFLOW, and the required buffer size will be stored in
+     * win_address_buf_size. */
+    r = GetAdaptersAddresses(AF_UNSPEC,
+                             flags,
+                             NULL,
+                             win_address_buf,
+                             &win_address_buf_size);
+
+    if (r == ERROR_SUCCESS)
+      break;
+
+    uv__free(win_address_buf);
+
+    switch (r) {
+      case ERROR_BUFFER_OVERFLOW:
+        /* This happens when win_address_buf is NULL or too small to hold all
+         * adapters. */
+        win_address_buf =
+            (IP_ADAPTER_ADDRESSES*)uv__malloc(win_address_buf_size);
+        if (win_address_buf == NULL)
+          return UV_ENOMEM;
+
+        continue;
+
+      case ERROR_NO_DATA: {
+        /* No adapters were found. */
+        uv_address_buf = (uv_interface_address_t*)uv__malloc(1);
+        if (uv_address_buf == NULL)
+          return UV_ENOMEM;
+
+        *count_ptr = 0;
+        *addresses_ptr = uv_address_buf;
+
+        return 0;
+      }
+
+      case ERROR_ADDRESS_NOT_ASSOCIATED:
+        return UV_EAGAIN;
+
+      case ERROR_INVALID_PARAMETER:
+        /* MSDN says:
+         *   "This error is returned for any of the following conditions: the
+         *   SizePointer parameter is NULL, the Address parameter is not
+         *   AF_INET, AF_INET6, or AF_UNSPEC, or the address information for
+         *   the parameters requested is greater than ULONG_MAX."
+         * Since the first two conditions are not met, it must be that the
+         * adapter data is too big.
+         */
+        return UV_ENOBUFS;
+
+      default:
+        /* Other (unspecified) errors can happen, but we don't have any special
+         * meaning for them. */
+        assert(r != ERROR_SUCCESS);
+        return uv_translate_sys_error(r);
+    }
+  }
+
+  /* Count the number of enabled interfaces and compute how much space is
+   * needed to store their info. */
+  count = 0;
+  uv_address_buf_size = 0;
+
+  for (adapter = win_address_buf;
+       adapter != NULL;
+       adapter = adapter->Next) {
+    IP_ADAPTER_UNICAST_ADDRESS* unicast_address;
+    int name_size;
+
+    /* Interfaces that are not 'up' should not be reported. Also skip
+     * interfaces that have no associated unicast address, as to avoid
+     * allocating space for the name for this interface. */
+    if (adapter->OperStatus != IfOperStatusUp ||
+        adapter->FirstUnicastAddress == NULL)
+      continue;
+
+    /* Compute the size of the interface name. */
+    name_size = WideCharToMultiByte(CP_UTF8,
+                                    0,
+                                    adapter->FriendlyName,
+                                    -1,
+                                    NULL,
+                                    0,
+                                    NULL,
+                                    FALSE);
+    if (name_size <= 0) {
+      uv__free(win_address_buf);
+      return uv_translate_sys_error(GetLastError());
+    }
+    uv_address_buf_size += name_size;
+
+    /* Count the number of addresses associated with this interface, and
+     * compute the size. */
+    for (unicast_address = (IP_ADAPTER_UNICAST_ADDRESS*)
+                           adapter->FirstUnicastAddress;
+         unicast_address != NULL;
+         unicast_address = unicast_address->Next) {
+      count++;
+      uv_address_buf_size += sizeof(uv_interface_address_t);
+    }
+  }
+
+  /* Allocate space to store interface data plus adapter names. */
+  uv_address_buf = (uv_interface_address_t*)uv__malloc(uv_address_buf_size);
+  if (uv_address_buf == NULL) {
+    uv__free(win_address_buf);
+    return UV_ENOMEM;
+  }
+
+  /* Compute the start of the uv_interface_address_t array, and the place in
+   * the buffer where the interface names will be stored. */
+  uv_address = uv_address_buf;
+  name_buf = (char*) (uv_address_buf + count);
+
+  /* Fill out the output buffer. */
+  for (adapter = win_address_buf;
+       adapter != NULL;
+       adapter = adapter->Next) {
+    IP_ADAPTER_UNICAST_ADDRESS* unicast_address;
+    int name_size;
+    size_t max_name_size;
+
+    if (adapter->OperStatus != IfOperStatusUp ||
+        adapter->FirstUnicastAddress == NULL)
+      continue;
+
+    /* Convert the interface name to UTF8. */
+    max_name_size = (char*) uv_address_buf + uv_address_buf_size - name_buf;
+    if (max_name_size > (size_t) INT_MAX)
+      max_name_size = INT_MAX;
+    name_size = WideCharToMultiByte(CP_UTF8,
+                                    0,
+                                    adapter->FriendlyName,
+                                    -1,
+                                    name_buf,
+                                    (int) max_name_size,
+                                    NULL,
+                                    FALSE);
+    if (name_size <= 0) {
+      uv__free(win_address_buf);
+      uv__free(uv_address_buf);
+      return uv_translate_sys_error(GetLastError());
+    }
+
+    /* Add an uv_interface_address_t element for every unicast address. */
+    for (unicast_address = (IP_ADAPTER_UNICAST_ADDRESS*)
+                           adapter->FirstUnicastAddress;
+         unicast_address != NULL;
+         unicast_address = unicast_address->Next) {
+      struct sockaddr* sa;
+      ULONG prefix_len;
+
+      sa = unicast_address->Address.lpSockaddr;
+
+      /* XP has no OnLinkPrefixLength field. */
+      if (is_vista_or_greater) {
+        prefix_len =
+          ((IP_ADAPTER_UNICAST_ADDRESS_LH*) unicast_address)->OnLinkPrefixLength;
+      } else {
+        /* Prior to Windows Vista the FirstPrefix pointed to the list with
+         * single prefix for each IP address assigned to the adapter.
+         * Order of FirstPrefix does not match order of FirstUnicastAddress,
+         * so we need to find corresponding prefix.
+         */
+        IP_ADAPTER_PREFIX* prefix;
+        prefix_len = 0;
+
+        for (prefix = adapter->FirstPrefix; prefix; prefix = prefix->Next) {
+          /* We want the longest matching prefix. */
+          if (prefix->Address.lpSockaddr->sa_family != sa->sa_family ||
+              prefix->PrefixLength <= prefix_len)
+            continue;
+
+          if (address_prefix_match(sa->sa_family, sa,
+              prefix->Address.lpSockaddr, prefix->PrefixLength)) {
+            prefix_len = prefix->PrefixLength;
+          }
+        }
+
+        /* If there is no matching prefix information, return a single-host
+         * subnet mask (e.g. 255.255.255.255 for IPv4).
+         */
+        if (!prefix_len)
+          prefix_len = (sa->sa_family == AF_INET6) ? 128 : 32;
+      }
+
+      memset(uv_address, 0, sizeof *uv_address);
+
+      uv_address->name = name_buf;
+
+      if (adapter->PhysicalAddressLength == sizeof(uv_address->phys_addr)) {
+        memcpy(uv_address->phys_addr,
+               adapter->PhysicalAddress,
+               sizeof(uv_address->phys_addr));
+      }
+
+      uv_address->is_internal =
+          (adapter->IfType == IF_TYPE_SOFTWARE_LOOPBACK);
+
+      if (sa->sa_family == AF_INET6) {
+        uv_address->address.address6 = *((struct sockaddr_in6 *) sa);
+
+        uv_address->netmask.netmask6.sin6_family = AF_INET6;
+        memset(uv_address->netmask.netmask6.sin6_addr.s6_addr, 0xff, prefix_len >> 3);
+        /* This check ensures that we don't write past the size of the data. */
+        if (prefix_len % 8) {
+          uv_address->netmask.netmask6.sin6_addr.s6_addr[prefix_len >> 3] =
+              0xff << (8 - prefix_len % 8);
+        }
+
+      } else {
+        uv_address->address.address4 = *((struct sockaddr_in *) sa);
+
+        uv_address->netmask.netmask4.sin_family = AF_INET;
+        uv_address->netmask.netmask4.sin_addr.s_addr = (prefix_len > 0) ?
+            htonl(0xffffffff << (32 - prefix_len)) : 0;
+      }
+
+      uv_address++;
+    }
+
+    name_buf += name_size;
+  }
+
+  uv__free(win_address_buf);
+
+  *addresses_ptr = uv_address_buf;
+  *count_ptr = count;
+
+  return 0;
+}
+
+
+void uv_free_interface_addresses(uv_interface_address_t* addresses,
+    int count) {
+  uv__free(addresses);
+}
+
+
+int uv_getrusage(uv_rusage_t *uv_rusage) {
+  FILETIME createTime, exitTime, kernelTime, userTime;
+  SYSTEMTIME kernelSystemTime, userSystemTime;
+  PROCESS_MEMORY_COUNTERS memCounters;
+  IO_COUNTERS ioCounters;
+  int ret;
+
+  ret = GetProcessTimes(GetCurrentProcess(), &createTime, &exitTime, &kernelTime, &userTime);
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  ret = FileTimeToSystemTime(&kernelTime, &kernelSystemTime);
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  ret = FileTimeToSystemTime(&userTime, &userSystemTime);
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  ret = GetProcessMemoryInfo(GetCurrentProcess(),
+                             &memCounters,
+                             sizeof(memCounters));
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  ret = GetProcessIoCounters(GetCurrentProcess(), &ioCounters);
+  if (ret == 0) {
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  memset(uv_rusage, 0, sizeof(*uv_rusage));
+
+  uv_rusage->ru_utime.tv_sec = userSystemTime.wHour * 3600 +
+                               userSystemTime.wMinute * 60 +
+                               userSystemTime.wSecond;
+  uv_rusage->ru_utime.tv_usec = userSystemTime.wMilliseconds * 1000;
+
+  uv_rusage->ru_stime.tv_sec = kernelSystemTime.wHour * 3600 +
+                               kernelSystemTime.wMinute * 60 +
+                               kernelSystemTime.wSecond;
+  uv_rusage->ru_stime.tv_usec = kernelSystemTime.wMilliseconds * 1000;
+
+  uv_rusage->ru_majflt = (uint64_t) memCounters.PageFaultCount;
+  uv_rusage->ru_maxrss = (uint64_t) memCounters.PeakWorkingSetSize / 1024;
+
+  uv_rusage->ru_oublock = (uint64_t) ioCounters.WriteOperationCount;
+  uv_rusage->ru_inblock = (uint64_t) ioCounters.ReadOperationCount;
+
+  return 0;
+}
+
+
+int uv_os_homedir(char* buffer, size_t* size) {
+  uv_passwd_t pwd;
+  size_t len;
+  int r;
+
+  /* Check if the USERPROFILE environment variable is set first. The task of
+     performing input validation on buffer and size is taken care of by
+     uv_os_getenv(). */
+  r = uv_os_getenv("USERPROFILE", buffer, size);
+
+  /* Don't return an error if USERPROFILE was not found. */
+  if (r != UV_ENOENT)
+    return r;
+
+  /* USERPROFILE is not set, so call uv__getpwuid_r() */
+  r = uv__getpwuid_r(&pwd);
+
+  if (r != 0) {
+    return r;
+  }
+
+  len = strlen(pwd.homedir);
+
+  if (len >= *size) {
+    *size = len + 1;
+    uv_os_free_passwd(&pwd);
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, pwd.homedir, len + 1);
+  *size = len;
+  uv_os_free_passwd(&pwd);
+
+  return 0;
+}
+
+
+int uv_os_tmpdir(char* buffer, size_t* size) {
+  wchar_t path[MAX_PATH + 1];
+  DWORD bufsize;
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  len = GetTempPathW(MAX_PATH + 1, path);
+
+  if (len == 0) {
+    return uv_translate_sys_error(GetLastError());
+  } else if (len > MAX_PATH + 1) {
+    /* This should not be possible */
+    return UV_EIO;
+  }
+
+  /* The returned directory should not have a trailing slash, unless it points
+   * at a drive root, like c:\. Remove it if needed. */
+  if (path[len - 1] == L'\\' &&
+      !(len == 3 && path[1] == L':')) {
+    len--;
+    path[len] = L'\0';
+  }
+
+  /* Check how much space we need */
+  bufsize = WideCharToMultiByte(CP_UTF8, 0, path, -1, NULL, 0, NULL, NULL);
+
+  if (bufsize == 0) {
+    return uv_translate_sys_error(GetLastError());
+  } else if (bufsize > *size) {
+    *size = bufsize;
+    return UV_ENOBUFS;
+  }
+
+  /* Convert to UTF-8 */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                path,
+                                -1,
+                                buffer,
+                                *size,
+                                NULL,
+                                NULL);
+
+  if (bufsize == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  *size = bufsize - 1;
+  return 0;
+}
+
+
+void uv_os_free_passwd(uv_passwd_t* pwd) {
+  if (pwd == NULL)
+    return;
+
+  uv__free(pwd->username);
+  uv__free(pwd->homedir);
+  pwd->username = NULL;
+  pwd->homedir = NULL;
+}
+
+
+/*
+ * Converts a UTF-16 string into a UTF-8 one. The resulting string is
+ * null-terminated.
+ *
+ * If utf16 is null terminated, utf16len can be set to -1, otherwise it must
+ * be specified.
+ */
+int uv__convert_utf16_to_utf8(const WCHAR* utf16, int utf16len, char** utf8) {
+  DWORD bufsize;
+
+  if (utf16 == NULL)
+    return UV_EINVAL;
+
+  /* Check how much space we need */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                utf16,
+                                utf16len,
+                                NULL,
+                                0,
+                                NULL,
+                                NULL);
+
+  if (bufsize == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  /* Allocate the destination buffer adding an extra byte for the terminating
+   * NULL. If utf16len is not -1 WideCharToMultiByte will not add it, so
+   * we do it ourselves always, just in case. */
+  *utf8 = (char*)uv__malloc(bufsize + 1);
+
+  if (*utf8 == NULL)
+    return UV_ENOMEM;
+
+  /* Convert to UTF-8 */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                utf16,
+                                utf16len,
+                                *utf8,
+                                bufsize,
+                                NULL,
+                                NULL);
+
+  if (bufsize == 0) {
+    uv__free(*utf8);
+    *utf8 = NULL;
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  (*utf8)[bufsize] = '\0';
+  return 0;
+}
+
+
+/*
+ * Converts a UTF-8 string into a UTF-16 one. The resulting string is
+ * null-terminated.
+ *
+ * If utf8 is null terminated, utf8len can be set to -1, otherwise it must
+ * be specified.
+ */
+int uv__convert_utf8_to_utf16(const char* utf8, int utf8len, WCHAR** utf16) {
+  int bufsize;
+
+  if (utf8 == NULL)
+    return UV_EINVAL;
+
+  /* Check how much space we need */
+  bufsize = MultiByteToWideChar(CP_UTF8, 0, utf8, utf8len, NULL, 0);
+
+  if (bufsize == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  /* Allocate the destination buffer adding an extra byte for the terminating
+   * NULL. If utf8len is not -1 MultiByteToWideChar will not add it, so
+   * we do it ourselves always, just in case. */
+  *utf16 = (WCHAR*)uv__malloc(sizeof(WCHAR) * (bufsize + 1));
+
+  if (*utf16 == NULL)
+    return UV_ENOMEM;
+
+  /* Convert to UTF-16 */
+  bufsize = MultiByteToWideChar(CP_UTF8, 0, utf8, utf8len, *utf16, bufsize);
+
+  if (bufsize == 0) {
+    uv__free(*utf16);
+    *utf16 = NULL;
+    return uv_translate_sys_error(GetLastError());
+  }
+
+  (*utf16)[bufsize] = '\0';
+  return 0;
+}
+
+
+int uv__getpwuid_r(uv_passwd_t* pwd) {
+  HANDLE token;
+  wchar_t username[UNLEN + 1];
+  wchar_t path[MAX_PATH];
+  DWORD bufsize;
+  int r;
+
+  if (pwd == NULL)
+    return UV_EINVAL;
+
+  /* Get the home directory using GetUserProfileDirectoryW() */
+  if (OpenProcessToken(GetCurrentProcess(), TOKEN_READ, &token) == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  bufsize = ARRAY_SIZE(path);
+  if (!GetUserProfileDirectoryW(token, path, &bufsize)) {
+    r = GetLastError();
+    CloseHandle(token);
+
+    /* This should not be possible */
+    if (r == ERROR_INSUFFICIENT_BUFFER)
+      return UV_ENOMEM;
+
+    return uv_translate_sys_error(r);
+  }
+
+  CloseHandle(token);
+
+  /* Get the username using GetUserNameW() */
+  bufsize = ARRAY_SIZE(username);
+  if (!GetUserNameW(username, &bufsize)) {
+    r = GetLastError();
+
+    /* This should not be possible */
+    if (r == ERROR_INSUFFICIENT_BUFFER)
+      return UV_ENOMEM;
+
+    return uv_translate_sys_error(r);
+  }
+
+  pwd->homedir = NULL;
+  r = uv__convert_utf16_to_utf8(path, -1, &pwd->homedir);
+
+  if (r != 0)
+    return r;
+
+  pwd->username = NULL;
+  r = uv__convert_utf16_to_utf8(username, -1, &pwd->username);
+
+  if (r != 0) {
+    uv__free(pwd->homedir);
+    return r;
+  }
+
+  pwd->shell = NULL;
+  pwd->uid = -1;
+  pwd->gid = -1;
+
+  return 0;
+}
+
+
+int uv_os_get_passwd(uv_passwd_t* pwd) {
+  return uv__getpwuid_r(pwd);
+}
+
+
+int uv_os_getenv(const char* name, char* buffer, size_t* size) {
+  wchar_t var[MAX_ENV_VAR_LENGTH];
+  wchar_t* name_w;
+  DWORD bufsize;
+  size_t len;
+  int r;
+
+  if (name == NULL || buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
+
+  if (r != 0)
+    return r;
+
+  len = GetEnvironmentVariableW(name_w, var, MAX_ENV_VAR_LENGTH);
+  uv__free(name_w);
+  assert(len < MAX_ENV_VAR_LENGTH); /* len does not include the null */
+
+  if (len == 0) {
+    r = GetLastError();
+
+    if (r == ERROR_ENVVAR_NOT_FOUND)
+      return UV_ENOENT;
+
+    return uv_translate_sys_error(r);
+  }
+
+  /* Check how much space we need */
+  bufsize = WideCharToMultiByte(CP_UTF8, 0, var, -1, NULL, 0, NULL, NULL);
+
+  if (bufsize == 0) {
+    return uv_translate_sys_error(GetLastError());
+  } else if (bufsize > *size) {
+    *size = bufsize;
+    return UV_ENOBUFS;
+  }
+
+  /* Convert to UTF-8 */
+  bufsize = WideCharToMultiByte(CP_UTF8,
+                                0,
+                                var,
+                                -1,
+                                buffer,
+                                *size,
+                                NULL,
+                                NULL);
+
+  if (bufsize == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  *size = bufsize - 1;
+  return 0;
+}
+
+
+int uv_os_setenv(const char* name, const char* value) {
+  wchar_t* name_w;
+  wchar_t* value_w;
+  int r;
+
+  if (name == NULL || value == NULL)
+    return UV_EINVAL;
+
+  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
+
+  if (r != 0)
+    return r;
+
+  r = uv__convert_utf8_to_utf16(value, -1, &value_w);
+
+  if (r != 0) {
+    uv__free(name_w);
+    return r;
+  }
+
+  r = SetEnvironmentVariableW(name_w, value_w);
+  uv__free(name_w);
+  uv__free(value_w);
+
+  if (r == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  return 0;
+}
+
+
+int uv_os_unsetenv(const char* name) {
+  wchar_t* name_w;
+  int r;
+
+  if (name == NULL)
+    return UV_EINVAL;
+
+  r = uv__convert_utf8_to_utf16(name, -1, &name_w);
+
+  if (r != 0)
+    return r;
+
+  r = SetEnvironmentVariableW(name_w, NULL);
+  uv__free(name_w);
+
+  if (r == 0)
+    return uv_translate_sys_error(GetLastError());
+
+  return 0;
+}
+
+
+int uv_os_gethostname(char* buffer, size_t* size) {
+  char buf[MAXHOSTNAMELEN + 1];
+  size_t len;
+
+  if (buffer == NULL || size == NULL || *size == 0)
+    return UV_EINVAL;
+
+  uv__once_init(); /* Initialize winsock */
+
+  if (gethostname(buf, sizeof(buf)) != 0)
+    return uv_translate_sys_error(WSAGetLastError());
+
+  buf[sizeof(buf) - 1] = '\0'; /* Null terminate, just to be safe. */
+  len = strlen(buf);
+
+  if (len >= *size) {
+    *size = len + 1;
+    return UV_ENOBUFS;
+  }
+
+  memcpy(buffer, buf, len + 1);
+  *size = len;
+  return 0;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winapi.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winapi.cpp
new file mode 100644
index 0000000..0fd598e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winapi.cpp
@@ -0,0 +1,113 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+/* Ntdll function pointers */
+sRtlNtStatusToDosError pRtlNtStatusToDosError;
+sNtDeviceIoControlFile pNtDeviceIoControlFile;
+sNtQueryInformationFile pNtQueryInformationFile;
+sNtSetInformationFile pNtSetInformationFile;
+sNtQueryVolumeInformationFile pNtQueryVolumeInformationFile;
+sNtQueryDirectoryFile pNtQueryDirectoryFile;
+sNtQuerySystemInformation pNtQuerySystemInformation;
+
+/* Powrprof.dll function pointer */
+sPowerRegisterSuspendResumeNotification pPowerRegisterSuspendResumeNotification;
+
+/* User32.dll function pointer */
+sSetWinEventHook pSetWinEventHook;
+
+
+void uv_winapi_init(void) {
+  HMODULE ntdll_module;
+  HMODULE powrprof_module;
+  HMODULE user32_module;
+
+  ntdll_module = GetModuleHandleA("ntdll.dll");
+  if (ntdll_module == NULL) {
+    uv_fatal_error(GetLastError(), "GetModuleHandleA");
+  }
+
+  pRtlNtStatusToDosError = (sRtlNtStatusToDosError) GetProcAddress(
+      ntdll_module,
+      "RtlNtStatusToDosError");
+  if (pRtlNtStatusToDosError == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtDeviceIoControlFile = (sNtDeviceIoControlFile) GetProcAddress(
+      ntdll_module,
+      "NtDeviceIoControlFile");
+  if (pNtDeviceIoControlFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQueryInformationFile = (sNtQueryInformationFile) GetProcAddress(
+      ntdll_module,
+      "NtQueryInformationFile");
+  if (pNtQueryInformationFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtSetInformationFile = (sNtSetInformationFile) GetProcAddress(
+      ntdll_module,
+      "NtSetInformationFile");
+  if (pNtSetInformationFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQueryVolumeInformationFile = (sNtQueryVolumeInformationFile)
+      GetProcAddress(ntdll_module, "NtQueryVolumeInformationFile");
+  if (pNtQueryVolumeInformationFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQueryDirectoryFile = (sNtQueryDirectoryFile)
+      GetProcAddress(ntdll_module, "NtQueryDirectoryFile");
+  if (pNtQueryVolumeInformationFile == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  pNtQuerySystemInformation = (sNtQuerySystemInformation) GetProcAddress(
+      ntdll_module,
+      "NtQuerySystemInformation");
+  if (pNtQuerySystemInformation == NULL) {
+    uv_fatal_error(GetLastError(), "GetProcAddress");
+  }
+
+  powrprof_module = LoadLibraryA("powrprof.dll");
+  if (powrprof_module != NULL) {
+    pPowerRegisterSuspendResumeNotification = (sPowerRegisterSuspendResumeNotification)
+      GetProcAddress(powrprof_module, "PowerRegisterSuspendResumeNotification");
+  }
+
+  user32_module = LoadLibraryA("user32.dll");
+  if (user32_module != NULL) {
+    pSetWinEventHook = (sSetWinEventHook)
+      GetProcAddress(user32_module, "SetWinEventHook");
+  }
+
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winapi.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winapi.h
new file mode 100644
index 0000000..d0fcfd8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winapi.h
@@ -0,0 +1,4713 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_WINAPI_H_
+#define UV_WIN_WINAPI_H_
+
+#include <windows.h>
+
+
+/*
+ * Ntdll headers
+ */
+#ifndef STATUS_SEVERITY_SUCCESS
+# define STATUS_SEVERITY_SUCCESS 0x0
+#endif
+
+#ifndef STATUS_SEVERITY_INFORMATIONAL
+# define STATUS_SEVERITY_INFORMATIONAL 0x1
+#endif
+
+#ifndef STATUS_SEVERITY_WARNING
+# define STATUS_SEVERITY_WARNING 0x2
+#endif
+
+#ifndef STATUS_SEVERITY_ERROR
+# define STATUS_SEVERITY_ERROR 0x3
+#endif
+
+#ifndef FACILITY_NTWIN32
+# define FACILITY_NTWIN32 0x7
+#endif
+
+#ifndef NT_SUCCESS
+# define NT_SUCCESS(status) (((NTSTATUS) (status)) >= 0)
+#endif
+
+#ifndef NT_INFORMATION
+# define NT_INFORMATION(status) ((((ULONG) (status)) >> 30) == 1)
+#endif
+
+#ifndef NT_WARNING
+# define NT_WARNING(status) ((((ULONG) (status)) >> 30) == 2)
+#endif
+
+#ifndef NT_ERROR
+# define NT_ERROR(status) ((((ULONG) (status)) >> 30) == 3)
+#endif
+
+#ifndef STATUS_SUCCESS
+# define STATUS_SUCCESS ((NTSTATUS) 0x00000000L)
+#endif
+
+#ifndef STATUS_WAIT_0
+# define STATUS_WAIT_0 ((NTSTATUS) 0x00000000L)
+#endif
+
+#ifndef STATUS_WAIT_1
+# define STATUS_WAIT_1 ((NTSTATUS) 0x00000001L)
+#endif
+
+#ifndef STATUS_WAIT_2
+# define STATUS_WAIT_2 ((NTSTATUS) 0x00000002L)
+#endif
+
+#ifndef STATUS_WAIT_3
+# define STATUS_WAIT_3 ((NTSTATUS) 0x00000003L)
+#endif
+
+#ifndef STATUS_WAIT_63
+# define STATUS_WAIT_63 ((NTSTATUS) 0x0000003FL)
+#endif
+
+#ifndef STATUS_ABANDONED
+# define STATUS_ABANDONED ((NTSTATUS) 0x00000080L)
+#endif
+
+#ifndef STATUS_ABANDONED_WAIT_0
+# define STATUS_ABANDONED_WAIT_0 ((NTSTATUS) 0x00000080L)
+#endif
+
+#ifndef STATUS_ABANDONED_WAIT_63
+# define STATUS_ABANDONED_WAIT_63 ((NTSTATUS) 0x000000BFL)
+#endif
+
+#ifndef STATUS_USER_APC
+# define STATUS_USER_APC ((NTSTATUS) 0x000000C0L)
+#endif
+
+#ifndef STATUS_KERNEL_APC
+# define STATUS_KERNEL_APC ((NTSTATUS) 0x00000100L)
+#endif
+
+#ifndef STATUS_ALERTED
+# define STATUS_ALERTED ((NTSTATUS) 0x00000101L)
+#endif
+
+#ifndef STATUS_TIMEOUT
+# define STATUS_TIMEOUT ((NTSTATUS) 0x00000102L)
+#endif
+
+#ifndef STATUS_PENDING
+# define STATUS_PENDING ((NTSTATUS) 0x00000103L)
+#endif
+
+#ifndef STATUS_REPARSE
+# define STATUS_REPARSE ((NTSTATUS) 0x00000104L)
+#endif
+
+#ifndef STATUS_MORE_ENTRIES
+# define STATUS_MORE_ENTRIES ((NTSTATUS) 0x00000105L)
+#endif
+
+#ifndef STATUS_NOT_ALL_ASSIGNED
+# define STATUS_NOT_ALL_ASSIGNED ((NTSTATUS) 0x00000106L)
+#endif
+
+#ifndef STATUS_SOME_NOT_MAPPED
+# define STATUS_SOME_NOT_MAPPED ((NTSTATUS) 0x00000107L)
+#endif
+
+#ifndef STATUS_OPLOCK_BREAK_IN_PROGRESS
+# define STATUS_OPLOCK_BREAK_IN_PROGRESS ((NTSTATUS) 0x00000108L)
+#endif
+
+#ifndef STATUS_VOLUME_MOUNTED
+# define STATUS_VOLUME_MOUNTED ((NTSTATUS) 0x00000109L)
+#endif
+
+#ifndef STATUS_RXACT_COMMITTED
+# define STATUS_RXACT_COMMITTED ((NTSTATUS) 0x0000010AL)
+#endif
+
+#ifndef STATUS_NOTIFY_CLEANUP
+# define STATUS_NOTIFY_CLEANUP ((NTSTATUS) 0x0000010BL)
+#endif
+
+#ifndef STATUS_NOTIFY_ENUM_DIR
+# define STATUS_NOTIFY_ENUM_DIR ((NTSTATUS) 0x0000010CL)
+#endif
+
+#ifndef STATUS_NO_QUOTAS_FOR_ACCOUNT
+# define STATUS_NO_QUOTAS_FOR_ACCOUNT ((NTSTATUS) 0x0000010DL)
+#endif
+
+#ifndef STATUS_PRIMARY_TRANSPORT_CONNECT_FAILED
+# define STATUS_PRIMARY_TRANSPORT_CONNECT_FAILED ((NTSTATUS) 0x0000010EL)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_TRANSITION
+# define STATUS_PAGE_FAULT_TRANSITION ((NTSTATUS) 0x00000110L)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_DEMAND_ZERO
+# define STATUS_PAGE_FAULT_DEMAND_ZERO ((NTSTATUS) 0x00000111L)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_COPY_ON_WRITE
+# define STATUS_PAGE_FAULT_COPY_ON_WRITE ((NTSTATUS) 0x00000112L)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_GUARD_PAGE
+# define STATUS_PAGE_FAULT_GUARD_PAGE ((NTSTATUS) 0x00000113L)
+#endif
+
+#ifndef STATUS_PAGE_FAULT_PAGING_FILE
+# define STATUS_PAGE_FAULT_PAGING_FILE ((NTSTATUS) 0x00000114L)
+#endif
+
+#ifndef STATUS_CACHE_PAGE_LOCKED
+# define STATUS_CACHE_PAGE_LOCKED ((NTSTATUS) 0x00000115L)
+#endif
+
+#ifndef STATUS_CRASH_DUMP
+# define STATUS_CRASH_DUMP ((NTSTATUS) 0x00000116L)
+#endif
+
+#ifndef STATUS_BUFFER_ALL_ZEROS
+# define STATUS_BUFFER_ALL_ZEROS ((NTSTATUS) 0x00000117L)
+#endif
+
+#ifndef STATUS_REPARSE_OBJECT
+# define STATUS_REPARSE_OBJECT ((NTSTATUS) 0x00000118L)
+#endif
+
+#ifndef STATUS_RESOURCE_REQUIREMENTS_CHANGED
+# define STATUS_RESOURCE_REQUIREMENTS_CHANGED ((NTSTATUS) 0x00000119L)
+#endif
+
+#ifndef STATUS_TRANSLATION_COMPLETE
+# define STATUS_TRANSLATION_COMPLETE ((NTSTATUS) 0x00000120L)
+#endif
+
+#ifndef STATUS_DS_MEMBERSHIP_EVALUATED_LOCALLY
+# define STATUS_DS_MEMBERSHIP_EVALUATED_LOCALLY ((NTSTATUS) 0x00000121L)
+#endif
+
+#ifndef STATUS_NOTHING_TO_TERMINATE
+# define STATUS_NOTHING_TO_TERMINATE ((NTSTATUS) 0x00000122L)
+#endif
+
+#ifndef STATUS_PROCESS_NOT_IN_JOB
+# define STATUS_PROCESS_NOT_IN_JOB ((NTSTATUS) 0x00000123L)
+#endif
+
+#ifndef STATUS_PROCESS_IN_JOB
+# define STATUS_PROCESS_IN_JOB ((NTSTATUS) 0x00000124L)
+#endif
+
+#ifndef STATUS_VOLSNAP_HIBERNATE_READY
+# define STATUS_VOLSNAP_HIBERNATE_READY ((NTSTATUS) 0x00000125L)
+#endif
+
+#ifndef STATUS_FSFILTER_OP_COMPLETED_SUCCESSFULLY
+# define STATUS_FSFILTER_OP_COMPLETED_SUCCESSFULLY ((NTSTATUS) 0x00000126L)
+#endif
+
+#ifndef STATUS_INTERRUPT_VECTOR_ALREADY_CONNECTED
+# define STATUS_INTERRUPT_VECTOR_ALREADY_CONNECTED ((NTSTATUS) 0x00000127L)
+#endif
+
+#ifndef STATUS_INTERRUPT_STILL_CONNECTED
+# define STATUS_INTERRUPT_STILL_CONNECTED ((NTSTATUS) 0x00000128L)
+#endif
+
+#ifndef STATUS_PROCESS_CLONED
+# define STATUS_PROCESS_CLONED ((NTSTATUS) 0x00000129L)
+#endif
+
+#ifndef STATUS_FILE_LOCKED_WITH_ONLY_READERS
+# define STATUS_FILE_LOCKED_WITH_ONLY_READERS ((NTSTATUS) 0x0000012AL)
+#endif
+
+#ifndef STATUS_FILE_LOCKED_WITH_WRITERS
+# define STATUS_FILE_LOCKED_WITH_WRITERS ((NTSTATUS) 0x0000012BL)
+#endif
+
+#ifndef STATUS_RESOURCEMANAGER_READ_ONLY
+# define STATUS_RESOURCEMANAGER_READ_ONLY ((NTSTATUS) 0x00000202L)
+#endif
+
+#ifndef STATUS_RING_PREVIOUSLY_EMPTY
+# define STATUS_RING_PREVIOUSLY_EMPTY ((NTSTATUS) 0x00000210L)
+#endif
+
+#ifndef STATUS_RING_PREVIOUSLY_FULL
+# define STATUS_RING_PREVIOUSLY_FULL ((NTSTATUS) 0x00000211L)
+#endif
+
+#ifndef STATUS_RING_PREVIOUSLY_ABOVE_QUOTA
+# define STATUS_RING_PREVIOUSLY_ABOVE_QUOTA ((NTSTATUS) 0x00000212L)
+#endif
+
+#ifndef STATUS_RING_NEWLY_EMPTY
+# define STATUS_RING_NEWLY_EMPTY ((NTSTATUS) 0x00000213L)
+#endif
+
+#ifndef STATUS_RING_SIGNAL_OPPOSITE_ENDPOINT
+# define STATUS_RING_SIGNAL_OPPOSITE_ENDPOINT ((NTSTATUS) 0x00000214L)
+#endif
+
+#ifndef STATUS_OPLOCK_SWITCHED_TO_NEW_HANDLE
+# define STATUS_OPLOCK_SWITCHED_TO_NEW_HANDLE ((NTSTATUS) 0x00000215L)
+#endif
+
+#ifndef STATUS_OPLOCK_HANDLE_CLOSED
+# define STATUS_OPLOCK_HANDLE_CLOSED ((NTSTATUS) 0x00000216L)
+#endif
+
+#ifndef STATUS_WAIT_FOR_OPLOCK
+# define STATUS_WAIT_FOR_OPLOCK ((NTSTATUS) 0x00000367L)
+#endif
+
+#ifndef STATUS_OBJECT_NAME_EXISTS
+# define STATUS_OBJECT_NAME_EXISTS ((NTSTATUS) 0x40000000L)
+#endif
+
+#ifndef STATUS_THREAD_WAS_SUSPENDED
+# define STATUS_THREAD_WAS_SUSPENDED ((NTSTATUS) 0x40000001L)
+#endif
+
+#ifndef STATUS_WORKING_SET_LIMIT_RANGE
+# define STATUS_WORKING_SET_LIMIT_RANGE ((NTSTATUS) 0x40000002L)
+#endif
+
+#ifndef STATUS_IMAGE_NOT_AT_BASE
+# define STATUS_IMAGE_NOT_AT_BASE ((NTSTATUS) 0x40000003L)
+#endif
+
+#ifndef STATUS_RXACT_STATE_CREATED
+# define STATUS_RXACT_STATE_CREATED ((NTSTATUS) 0x40000004L)
+#endif
+
+#ifndef STATUS_SEGMENT_NOTIFICATION
+# define STATUS_SEGMENT_NOTIFICATION ((NTSTATUS) 0x40000005L)
+#endif
+
+#ifndef STATUS_LOCAL_USER_SESSION_KEY
+# define STATUS_LOCAL_USER_SESSION_KEY ((NTSTATUS) 0x40000006L)
+#endif
+
+#ifndef STATUS_BAD_CURRENT_DIRECTORY
+# define STATUS_BAD_CURRENT_DIRECTORY ((NTSTATUS) 0x40000007L)
+#endif
+
+#ifndef STATUS_SERIAL_MORE_WRITES
+# define STATUS_SERIAL_MORE_WRITES ((NTSTATUS) 0x40000008L)
+#endif
+
+#ifndef STATUS_REGISTRY_RECOVERED
+# define STATUS_REGISTRY_RECOVERED ((NTSTATUS) 0x40000009L)
+#endif
+
+#ifndef STATUS_FT_READ_RECOVERY_FROM_BACKUP
+# define STATUS_FT_READ_RECOVERY_FROM_BACKUP ((NTSTATUS) 0x4000000AL)
+#endif
+
+#ifndef STATUS_FT_WRITE_RECOVERY
+# define STATUS_FT_WRITE_RECOVERY ((NTSTATUS) 0x4000000BL)
+#endif
+
+#ifndef STATUS_SERIAL_COUNTER_TIMEOUT
+# define STATUS_SERIAL_COUNTER_TIMEOUT ((NTSTATUS) 0x4000000CL)
+#endif
+
+#ifndef STATUS_NULL_LM_PASSWORD
+# define STATUS_NULL_LM_PASSWORD ((NTSTATUS) 0x4000000DL)
+#endif
+
+#ifndef STATUS_IMAGE_MACHINE_TYPE_MISMATCH
+# define STATUS_IMAGE_MACHINE_TYPE_MISMATCH ((NTSTATUS) 0x4000000EL)
+#endif
+
+#ifndef STATUS_RECEIVE_PARTIAL
+# define STATUS_RECEIVE_PARTIAL ((NTSTATUS) 0x4000000FL)
+#endif
+
+#ifndef STATUS_RECEIVE_EXPEDITED
+# define STATUS_RECEIVE_EXPEDITED ((NTSTATUS) 0x40000010L)
+#endif
+
+#ifndef STATUS_RECEIVE_PARTIAL_EXPEDITED
+# define STATUS_RECEIVE_PARTIAL_EXPEDITED ((NTSTATUS) 0x40000011L)
+#endif
+
+#ifndef STATUS_EVENT_DONE
+# define STATUS_EVENT_DONE ((NTSTATUS) 0x40000012L)
+#endif
+
+#ifndef STATUS_EVENT_PENDING
+# define STATUS_EVENT_PENDING ((NTSTATUS) 0x40000013L)
+#endif
+
+#ifndef STATUS_CHECKING_FILE_SYSTEM
+# define STATUS_CHECKING_FILE_SYSTEM ((NTSTATUS) 0x40000014L)
+#endif
+
+#ifndef STATUS_FATAL_APP_EXIT
+# define STATUS_FATAL_APP_EXIT ((NTSTATUS) 0x40000015L)
+#endif
+
+#ifndef STATUS_PREDEFINED_HANDLE
+# define STATUS_PREDEFINED_HANDLE ((NTSTATUS) 0x40000016L)
+#endif
+
+#ifndef STATUS_WAS_UNLOCKED
+# define STATUS_WAS_UNLOCKED ((NTSTATUS) 0x40000017L)
+#endif
+
+#ifndef STATUS_SERVICE_NOTIFICATION
+# define STATUS_SERVICE_NOTIFICATION ((NTSTATUS) 0x40000018L)
+#endif
+
+#ifndef STATUS_WAS_LOCKED
+# define STATUS_WAS_LOCKED ((NTSTATUS) 0x40000019L)
+#endif
+
+#ifndef STATUS_LOG_HARD_ERROR
+# define STATUS_LOG_HARD_ERROR ((NTSTATUS) 0x4000001AL)
+#endif
+
+#ifndef STATUS_ALREADY_WIN32
+# define STATUS_ALREADY_WIN32 ((NTSTATUS) 0x4000001BL)
+#endif
+
+#ifndef STATUS_WX86_UNSIMULATE
+# define STATUS_WX86_UNSIMULATE ((NTSTATUS) 0x4000001CL)
+#endif
+
+#ifndef STATUS_WX86_CONTINUE
+# define STATUS_WX86_CONTINUE ((NTSTATUS) 0x4000001DL)
+#endif
+
+#ifndef STATUS_WX86_SINGLE_STEP
+# define STATUS_WX86_SINGLE_STEP ((NTSTATUS) 0x4000001EL)
+#endif
+
+#ifndef STATUS_WX86_BREAKPOINT
+# define STATUS_WX86_BREAKPOINT ((NTSTATUS) 0x4000001FL)
+#endif
+
+#ifndef STATUS_WX86_EXCEPTION_CONTINUE
+# define STATUS_WX86_EXCEPTION_CONTINUE ((NTSTATUS) 0x40000020L)
+#endif
+
+#ifndef STATUS_WX86_EXCEPTION_LASTCHANCE
+# define STATUS_WX86_EXCEPTION_LASTCHANCE ((NTSTATUS) 0x40000021L)
+#endif
+
+#ifndef STATUS_WX86_EXCEPTION_CHAIN
+# define STATUS_WX86_EXCEPTION_CHAIN ((NTSTATUS) 0x40000022L)
+#endif
+
+#ifndef STATUS_IMAGE_MACHINE_TYPE_MISMATCH_EXE
+# define STATUS_IMAGE_MACHINE_TYPE_MISMATCH_EXE ((NTSTATUS) 0x40000023L)
+#endif
+
+#ifndef STATUS_NO_YIELD_PERFORMED
+# define STATUS_NO_YIELD_PERFORMED ((NTSTATUS) 0x40000024L)
+#endif
+
+#ifndef STATUS_TIMER_RESUME_IGNORED
+# define STATUS_TIMER_RESUME_IGNORED ((NTSTATUS) 0x40000025L)
+#endif
+
+#ifndef STATUS_ARBITRATION_UNHANDLED
+# define STATUS_ARBITRATION_UNHANDLED ((NTSTATUS) 0x40000026L)
+#endif
+
+#ifndef STATUS_CARDBUS_NOT_SUPPORTED
+# define STATUS_CARDBUS_NOT_SUPPORTED ((NTSTATUS) 0x40000027L)
+#endif
+
+#ifndef STATUS_WX86_CREATEWX86TIB
+# define STATUS_WX86_CREATEWX86TIB ((NTSTATUS) 0x40000028L)
+#endif
+
+#ifndef STATUS_MP_PROCESSOR_MISMATCH
+# define STATUS_MP_PROCESSOR_MISMATCH ((NTSTATUS) 0x40000029L)
+#endif
+
+#ifndef STATUS_HIBERNATED
+# define STATUS_HIBERNATED ((NTSTATUS) 0x4000002AL)
+#endif
+
+#ifndef STATUS_RESUME_HIBERNATION
+# define STATUS_RESUME_HIBERNATION ((NTSTATUS) 0x4000002BL)
+#endif
+
+#ifndef STATUS_FIRMWARE_UPDATED
+# define STATUS_FIRMWARE_UPDATED ((NTSTATUS) 0x4000002CL)
+#endif
+
+#ifndef STATUS_DRIVERS_LEAKING_LOCKED_PAGES
+# define STATUS_DRIVERS_LEAKING_LOCKED_PAGES ((NTSTATUS) 0x4000002DL)
+#endif
+
+#ifndef STATUS_MESSAGE_RETRIEVED
+# define STATUS_MESSAGE_RETRIEVED ((NTSTATUS) 0x4000002EL)
+#endif
+
+#ifndef STATUS_SYSTEM_POWERSTATE_TRANSITION
+# define STATUS_SYSTEM_POWERSTATE_TRANSITION ((NTSTATUS) 0x4000002FL)
+#endif
+
+#ifndef STATUS_ALPC_CHECK_COMPLETION_LIST
+# define STATUS_ALPC_CHECK_COMPLETION_LIST ((NTSTATUS) 0x40000030L)
+#endif
+
+#ifndef STATUS_SYSTEM_POWERSTATE_COMPLEX_TRANSITION
+# define STATUS_SYSTEM_POWERSTATE_COMPLEX_TRANSITION ((NTSTATUS) 0x40000031L)
+#endif
+
+#ifndef STATUS_ACCESS_AUDIT_BY_POLICY
+# define STATUS_ACCESS_AUDIT_BY_POLICY ((NTSTATUS) 0x40000032L)
+#endif
+
+#ifndef STATUS_ABANDON_HIBERFILE
+# define STATUS_ABANDON_HIBERFILE ((NTSTATUS) 0x40000033L)
+#endif
+
+#ifndef STATUS_BIZRULES_NOT_ENABLED
+# define STATUS_BIZRULES_NOT_ENABLED ((NTSTATUS) 0x40000034L)
+#endif
+
+#ifndef STATUS_GUARD_PAGE_VIOLATION
+# define STATUS_GUARD_PAGE_VIOLATION ((NTSTATUS) 0x80000001L)
+#endif
+
+#ifndef STATUS_DATATYPE_MISALIGNMENT
+# define STATUS_DATATYPE_MISALIGNMENT ((NTSTATUS) 0x80000002L)
+#endif
+
+#ifndef STATUS_BREAKPOINT
+# define STATUS_BREAKPOINT ((NTSTATUS) 0x80000003L)
+#endif
+
+#ifndef STATUS_SINGLE_STEP
+# define STATUS_SINGLE_STEP ((NTSTATUS) 0x80000004L)
+#endif
+
+#ifndef STATUS_BUFFER_OVERFLOW
+# define STATUS_BUFFER_OVERFLOW ((NTSTATUS) 0x80000005L)
+#endif
+
+#ifndef STATUS_NO_MORE_FILES
+# define STATUS_NO_MORE_FILES ((NTSTATUS) 0x80000006L)
+#endif
+
+#ifndef STATUS_WAKE_SYSTEM_DEBUGGER
+# define STATUS_WAKE_SYSTEM_DEBUGGER ((NTSTATUS) 0x80000007L)
+#endif
+
+#ifndef STATUS_HANDLES_CLOSED
+# define STATUS_HANDLES_CLOSED ((NTSTATUS) 0x8000000AL)
+#endif
+
+#ifndef STATUS_NO_INHERITANCE
+# define STATUS_NO_INHERITANCE ((NTSTATUS) 0x8000000BL)
+#endif
+
+#ifndef STATUS_GUID_SUBSTITUTION_MADE
+# define STATUS_GUID_SUBSTITUTION_MADE ((NTSTATUS) 0x8000000CL)
+#endif
+
+#ifndef STATUS_PARTIAL_COPY
+# define STATUS_PARTIAL_COPY ((NTSTATUS) 0x8000000DL)
+#endif
+
+#ifndef STATUS_DEVICE_PAPER_EMPTY
+# define STATUS_DEVICE_PAPER_EMPTY ((NTSTATUS) 0x8000000EL)
+#endif
+
+#ifndef STATUS_DEVICE_POWERED_OFF
+# define STATUS_DEVICE_POWERED_OFF ((NTSTATUS) 0x8000000FL)
+#endif
+
+#ifndef STATUS_DEVICE_OFF_LINE
+# define STATUS_DEVICE_OFF_LINE ((NTSTATUS) 0x80000010L)
+#endif
+
+#ifndef STATUS_DEVICE_BUSY
+# define STATUS_DEVICE_BUSY ((NTSTATUS) 0x80000011L)
+#endif
+
+#ifndef STATUS_NO_MORE_EAS
+# define STATUS_NO_MORE_EAS ((NTSTATUS) 0x80000012L)
+#endif
+
+#ifndef STATUS_INVALID_EA_NAME
+# define STATUS_INVALID_EA_NAME ((NTSTATUS) 0x80000013L)
+#endif
+
+#ifndef STATUS_EA_LIST_INCONSISTENT
+# define STATUS_EA_LIST_INCONSISTENT ((NTSTATUS) 0x80000014L)
+#endif
+
+#ifndef STATUS_INVALID_EA_FLAG
+# define STATUS_INVALID_EA_FLAG ((NTSTATUS) 0x80000015L)
+#endif
+
+#ifndef STATUS_VERIFY_REQUIRED
+# define STATUS_VERIFY_REQUIRED ((NTSTATUS) 0x80000016L)
+#endif
+
+#ifndef STATUS_EXTRANEOUS_INFORMATION
+# define STATUS_EXTRANEOUS_INFORMATION ((NTSTATUS) 0x80000017L)
+#endif
+
+#ifndef STATUS_RXACT_COMMIT_NECESSARY
+# define STATUS_RXACT_COMMIT_NECESSARY ((NTSTATUS) 0x80000018L)
+#endif
+
+#ifndef STATUS_NO_MORE_ENTRIES
+# define STATUS_NO_MORE_ENTRIES ((NTSTATUS) 0x8000001AL)
+#endif
+
+#ifndef STATUS_FILEMARK_DETECTED
+# define STATUS_FILEMARK_DETECTED ((NTSTATUS) 0x8000001BL)
+#endif
+
+#ifndef STATUS_MEDIA_CHANGED
+# define STATUS_MEDIA_CHANGED ((NTSTATUS) 0x8000001CL)
+#endif
+
+#ifndef STATUS_BUS_RESET
+# define STATUS_BUS_RESET ((NTSTATUS) 0x8000001DL)
+#endif
+
+#ifndef STATUS_END_OF_MEDIA
+# define STATUS_END_OF_MEDIA ((NTSTATUS) 0x8000001EL)
+#endif
+
+#ifndef STATUS_BEGINNING_OF_MEDIA
+# define STATUS_BEGINNING_OF_MEDIA ((NTSTATUS) 0x8000001FL)
+#endif
+
+#ifndef STATUS_MEDIA_CHECK
+# define STATUS_MEDIA_CHECK ((NTSTATUS) 0x80000020L)
+#endif
+
+#ifndef STATUS_SETMARK_DETECTED
+# define STATUS_SETMARK_DETECTED ((NTSTATUS) 0x80000021L)
+#endif
+
+#ifndef STATUS_NO_DATA_DETECTED
+# define STATUS_NO_DATA_DETECTED ((NTSTATUS) 0x80000022L)
+#endif
+
+#ifndef STATUS_REDIRECTOR_HAS_OPEN_HANDLES
+# define STATUS_REDIRECTOR_HAS_OPEN_HANDLES ((NTSTATUS) 0x80000023L)
+#endif
+
+#ifndef STATUS_SERVER_HAS_OPEN_HANDLES
+# define STATUS_SERVER_HAS_OPEN_HANDLES ((NTSTATUS) 0x80000024L)
+#endif
+
+#ifndef STATUS_ALREADY_DISCONNECTED
+# define STATUS_ALREADY_DISCONNECTED ((NTSTATUS) 0x80000025L)
+#endif
+
+#ifndef STATUS_LONGJUMP
+# define STATUS_LONGJUMP ((NTSTATUS) 0x80000026L)
+#endif
+
+#ifndef STATUS_CLEANER_CARTRIDGE_INSTALLED
+# define STATUS_CLEANER_CARTRIDGE_INSTALLED ((NTSTATUS) 0x80000027L)
+#endif
+
+#ifndef STATUS_PLUGPLAY_QUERY_VETOED
+# define STATUS_PLUGPLAY_QUERY_VETOED ((NTSTATUS) 0x80000028L)
+#endif
+
+#ifndef STATUS_UNWIND_CONSOLIDATE
+# define STATUS_UNWIND_CONSOLIDATE ((NTSTATUS) 0x80000029L)
+#endif
+
+#ifndef STATUS_REGISTRY_HIVE_RECOVERED
+# define STATUS_REGISTRY_HIVE_RECOVERED ((NTSTATUS) 0x8000002AL)
+#endif
+
+#ifndef STATUS_DLL_MIGHT_BE_INSECURE
+# define STATUS_DLL_MIGHT_BE_INSECURE ((NTSTATUS) 0x8000002BL)
+#endif
+
+#ifndef STATUS_DLL_MIGHT_BE_INCOMPATIBLE
+# define STATUS_DLL_MIGHT_BE_INCOMPATIBLE ((NTSTATUS) 0x8000002CL)
+#endif
+
+#ifndef STATUS_STOPPED_ON_SYMLINK
+# define STATUS_STOPPED_ON_SYMLINK ((NTSTATUS) 0x8000002DL)
+#endif
+
+#ifndef STATUS_CANNOT_GRANT_REQUESTED_OPLOCK
+# define STATUS_CANNOT_GRANT_REQUESTED_OPLOCK ((NTSTATUS) 0x8000002EL)
+#endif
+
+#ifndef STATUS_NO_ACE_CONDITION
+# define STATUS_NO_ACE_CONDITION ((NTSTATUS) 0x8000002FL)
+#endif
+
+#ifndef STATUS_UNSUCCESSFUL
+# define STATUS_UNSUCCESSFUL ((NTSTATUS) 0xC0000001L)
+#endif
+
+#ifndef STATUS_NOT_IMPLEMENTED
+# define STATUS_NOT_IMPLEMENTED ((NTSTATUS) 0xC0000002L)
+#endif
+
+#ifndef STATUS_INVALID_INFO_CLASS
+# define STATUS_INVALID_INFO_CLASS ((NTSTATUS) 0xC0000003L)
+#endif
+
+#ifndef STATUS_INFO_LENGTH_MISMATCH
+# define STATUS_INFO_LENGTH_MISMATCH ((NTSTATUS) 0xC0000004L)
+#endif
+
+#ifndef STATUS_ACCESS_VIOLATION
+# define STATUS_ACCESS_VIOLATION ((NTSTATUS) 0xC0000005L)
+#endif
+
+#ifndef STATUS_IN_PAGE_ERROR
+# define STATUS_IN_PAGE_ERROR ((NTSTATUS) 0xC0000006L)
+#endif
+
+#ifndef STATUS_PAGEFILE_QUOTA
+# define STATUS_PAGEFILE_QUOTA ((NTSTATUS) 0xC0000007L)
+#endif
+
+#ifndef STATUS_INVALID_HANDLE
+# define STATUS_INVALID_HANDLE ((NTSTATUS) 0xC0000008L)
+#endif
+
+#ifndef STATUS_BAD_INITIAL_STACK
+# define STATUS_BAD_INITIAL_STACK ((NTSTATUS) 0xC0000009L)
+#endif
+
+#ifndef STATUS_BAD_INITIAL_PC
+# define STATUS_BAD_INITIAL_PC ((NTSTATUS) 0xC000000AL)
+#endif
+
+#ifndef STATUS_INVALID_CID
+# define STATUS_INVALID_CID ((NTSTATUS) 0xC000000BL)
+#endif
+
+#ifndef STATUS_TIMER_NOT_CANCELED
+# define STATUS_TIMER_NOT_CANCELED ((NTSTATUS) 0xC000000CL)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER
+# define STATUS_INVALID_PARAMETER ((NTSTATUS) 0xC000000DL)
+#endif
+
+#ifndef STATUS_NO_SUCH_DEVICE
+# define STATUS_NO_SUCH_DEVICE ((NTSTATUS) 0xC000000EL)
+#endif
+
+#ifndef STATUS_NO_SUCH_FILE
+# define STATUS_NO_SUCH_FILE ((NTSTATUS) 0xC000000FL)
+#endif
+
+#ifndef STATUS_INVALID_DEVICE_REQUEST
+# define STATUS_INVALID_DEVICE_REQUEST ((NTSTATUS) 0xC0000010L)
+#endif
+
+#ifndef STATUS_END_OF_FILE
+# define STATUS_END_OF_FILE ((NTSTATUS) 0xC0000011L)
+#endif
+
+#ifndef STATUS_WRONG_VOLUME
+# define STATUS_WRONG_VOLUME ((NTSTATUS) 0xC0000012L)
+#endif
+
+#ifndef STATUS_NO_MEDIA_IN_DEVICE
+# define STATUS_NO_MEDIA_IN_DEVICE ((NTSTATUS) 0xC0000013L)
+#endif
+
+#ifndef STATUS_UNRECOGNIZED_MEDIA
+# define STATUS_UNRECOGNIZED_MEDIA ((NTSTATUS) 0xC0000014L)
+#endif
+
+#ifndef STATUS_NONEXISTENT_SECTOR
+# define STATUS_NONEXISTENT_SECTOR ((NTSTATUS) 0xC0000015L)
+#endif
+
+#ifndef STATUS_MORE_PROCESSING_REQUIRED
+# define STATUS_MORE_PROCESSING_REQUIRED ((NTSTATUS) 0xC0000016L)
+#endif
+
+#ifndef STATUS_NO_MEMORY
+# define STATUS_NO_MEMORY ((NTSTATUS) 0xC0000017L)
+#endif
+
+#ifndef STATUS_CONFLICTING_ADDRESSES
+# define STATUS_CONFLICTING_ADDRESSES ((NTSTATUS) 0xC0000018L)
+#endif
+
+#ifndef STATUS_NOT_MAPPED_VIEW
+# define STATUS_NOT_MAPPED_VIEW ((NTSTATUS) 0xC0000019L)
+#endif
+
+#ifndef STATUS_UNABLE_TO_FREE_VM
+# define STATUS_UNABLE_TO_FREE_VM ((NTSTATUS) 0xC000001AL)
+#endif
+
+#ifndef STATUS_UNABLE_TO_DELETE_SECTION
+# define STATUS_UNABLE_TO_DELETE_SECTION ((NTSTATUS) 0xC000001BL)
+#endif
+
+#ifndef STATUS_INVALID_SYSTEM_SERVICE
+# define STATUS_INVALID_SYSTEM_SERVICE ((NTSTATUS) 0xC000001CL)
+#endif
+
+#ifndef STATUS_ILLEGAL_INSTRUCTION
+# define STATUS_ILLEGAL_INSTRUCTION ((NTSTATUS) 0xC000001DL)
+#endif
+
+#ifndef STATUS_INVALID_LOCK_SEQUENCE
+# define STATUS_INVALID_LOCK_SEQUENCE ((NTSTATUS) 0xC000001EL)
+#endif
+
+#ifndef STATUS_INVALID_VIEW_SIZE
+# define STATUS_INVALID_VIEW_SIZE ((NTSTATUS) 0xC000001FL)
+#endif
+
+#ifndef STATUS_INVALID_FILE_FOR_SECTION
+# define STATUS_INVALID_FILE_FOR_SECTION ((NTSTATUS) 0xC0000020L)
+#endif
+
+#ifndef STATUS_ALREADY_COMMITTED
+# define STATUS_ALREADY_COMMITTED ((NTSTATUS) 0xC0000021L)
+#endif
+
+#ifndef STATUS_ACCESS_DENIED
+# define STATUS_ACCESS_DENIED ((NTSTATUS) 0xC0000022L)
+#endif
+
+#ifndef STATUS_BUFFER_TOO_SMALL
+# define STATUS_BUFFER_TOO_SMALL ((NTSTATUS) 0xC0000023L)
+#endif
+
+#ifndef STATUS_OBJECT_TYPE_MISMATCH
+# define STATUS_OBJECT_TYPE_MISMATCH ((NTSTATUS) 0xC0000024L)
+#endif
+
+#ifndef STATUS_NONCONTINUABLE_EXCEPTION
+# define STATUS_NONCONTINUABLE_EXCEPTION ((NTSTATUS) 0xC0000025L)
+#endif
+
+#ifndef STATUS_INVALID_DISPOSITION
+# define STATUS_INVALID_DISPOSITION ((NTSTATUS) 0xC0000026L)
+#endif
+
+#ifndef STATUS_UNWIND
+# define STATUS_UNWIND ((NTSTATUS) 0xC0000027L)
+#endif
+
+#ifndef STATUS_BAD_STACK
+# define STATUS_BAD_STACK ((NTSTATUS) 0xC0000028L)
+#endif
+
+#ifndef STATUS_INVALID_UNWIND_TARGET
+# define STATUS_INVALID_UNWIND_TARGET ((NTSTATUS) 0xC0000029L)
+#endif
+
+#ifndef STATUS_NOT_LOCKED
+# define STATUS_NOT_LOCKED ((NTSTATUS) 0xC000002AL)
+#endif
+
+#ifndef STATUS_PARITY_ERROR
+# define STATUS_PARITY_ERROR ((NTSTATUS) 0xC000002BL)
+#endif
+
+#ifndef STATUS_UNABLE_TO_DECOMMIT_VM
+# define STATUS_UNABLE_TO_DECOMMIT_VM ((NTSTATUS) 0xC000002CL)
+#endif
+
+#ifndef STATUS_NOT_COMMITTED
+# define STATUS_NOT_COMMITTED ((NTSTATUS) 0xC000002DL)
+#endif
+
+#ifndef STATUS_INVALID_PORT_ATTRIBUTES
+# define STATUS_INVALID_PORT_ATTRIBUTES ((NTSTATUS) 0xC000002EL)
+#endif
+
+#ifndef STATUS_PORT_MESSAGE_TOO_LONG
+# define STATUS_PORT_MESSAGE_TOO_LONG ((NTSTATUS) 0xC000002FL)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_MIX
+# define STATUS_INVALID_PARAMETER_MIX ((NTSTATUS) 0xC0000030L)
+#endif
+
+#ifndef STATUS_INVALID_QUOTA_LOWER
+# define STATUS_INVALID_QUOTA_LOWER ((NTSTATUS) 0xC0000031L)
+#endif
+
+#ifndef STATUS_DISK_CORRUPT_ERROR
+# define STATUS_DISK_CORRUPT_ERROR ((NTSTATUS) 0xC0000032L)
+#endif
+
+#ifndef STATUS_OBJECT_NAME_INVALID
+# define STATUS_OBJECT_NAME_INVALID ((NTSTATUS) 0xC0000033L)
+#endif
+
+#ifndef STATUS_OBJECT_NAME_NOT_FOUND
+# define STATUS_OBJECT_NAME_NOT_FOUND ((NTSTATUS) 0xC0000034L)
+#endif
+
+#ifndef STATUS_OBJECT_NAME_COLLISION
+# define STATUS_OBJECT_NAME_COLLISION ((NTSTATUS) 0xC0000035L)
+#endif
+
+#ifndef STATUS_PORT_DISCONNECTED
+# define STATUS_PORT_DISCONNECTED ((NTSTATUS) 0xC0000037L)
+#endif
+
+#ifndef STATUS_DEVICE_ALREADY_ATTACHED
+# define STATUS_DEVICE_ALREADY_ATTACHED ((NTSTATUS) 0xC0000038L)
+#endif
+
+#ifndef STATUS_OBJECT_PATH_INVALID
+# define STATUS_OBJECT_PATH_INVALID ((NTSTATUS) 0xC0000039L)
+#endif
+
+#ifndef STATUS_OBJECT_PATH_NOT_FOUND
+# define STATUS_OBJECT_PATH_NOT_FOUND ((NTSTATUS) 0xC000003AL)
+#endif
+
+#ifndef STATUS_OBJECT_PATH_SYNTAX_BAD
+# define STATUS_OBJECT_PATH_SYNTAX_BAD ((NTSTATUS) 0xC000003BL)
+#endif
+
+#ifndef STATUS_DATA_OVERRUN
+# define STATUS_DATA_OVERRUN ((NTSTATUS) 0xC000003CL)
+#endif
+
+#ifndef STATUS_DATA_LATE_ERROR
+# define STATUS_DATA_LATE_ERROR ((NTSTATUS) 0xC000003DL)
+#endif
+
+#ifndef STATUS_DATA_ERROR
+# define STATUS_DATA_ERROR ((NTSTATUS) 0xC000003EL)
+#endif
+
+#ifndef STATUS_CRC_ERROR
+# define STATUS_CRC_ERROR ((NTSTATUS) 0xC000003FL)
+#endif
+
+#ifndef STATUS_SECTION_TOO_BIG
+# define STATUS_SECTION_TOO_BIG ((NTSTATUS) 0xC0000040L)
+#endif
+
+#ifndef STATUS_PORT_CONNECTION_REFUSED
+# define STATUS_PORT_CONNECTION_REFUSED ((NTSTATUS) 0xC0000041L)
+#endif
+
+#ifndef STATUS_INVALID_PORT_HANDLE
+# define STATUS_INVALID_PORT_HANDLE ((NTSTATUS) 0xC0000042L)
+#endif
+
+#ifndef STATUS_SHARING_VIOLATION
+# define STATUS_SHARING_VIOLATION ((NTSTATUS) 0xC0000043L)
+#endif
+
+#ifndef STATUS_QUOTA_EXCEEDED
+# define STATUS_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000044L)
+#endif
+
+#ifndef STATUS_INVALID_PAGE_PROTECTION
+# define STATUS_INVALID_PAGE_PROTECTION ((NTSTATUS) 0xC0000045L)
+#endif
+
+#ifndef STATUS_MUTANT_NOT_OWNED
+# define STATUS_MUTANT_NOT_OWNED ((NTSTATUS) 0xC0000046L)
+#endif
+
+#ifndef STATUS_SEMAPHORE_LIMIT_EXCEEDED
+# define STATUS_SEMAPHORE_LIMIT_EXCEEDED ((NTSTATUS) 0xC0000047L)
+#endif
+
+#ifndef STATUS_PORT_ALREADY_SET
+# define STATUS_PORT_ALREADY_SET ((NTSTATUS) 0xC0000048L)
+#endif
+
+#ifndef STATUS_SECTION_NOT_IMAGE
+# define STATUS_SECTION_NOT_IMAGE ((NTSTATUS) 0xC0000049L)
+#endif
+
+#ifndef STATUS_SUSPEND_COUNT_EXCEEDED
+# define STATUS_SUSPEND_COUNT_EXCEEDED ((NTSTATUS) 0xC000004AL)
+#endif
+
+#ifndef STATUS_THREAD_IS_TERMINATING
+# define STATUS_THREAD_IS_TERMINATING ((NTSTATUS) 0xC000004BL)
+#endif
+
+#ifndef STATUS_BAD_WORKING_SET_LIMIT
+# define STATUS_BAD_WORKING_SET_LIMIT ((NTSTATUS) 0xC000004CL)
+#endif
+
+#ifndef STATUS_INCOMPATIBLE_FILE_MAP
+# define STATUS_INCOMPATIBLE_FILE_MAP ((NTSTATUS) 0xC000004DL)
+#endif
+
+#ifndef STATUS_SECTION_PROTECTION
+# define STATUS_SECTION_PROTECTION ((NTSTATUS) 0xC000004EL)
+#endif
+
+#ifndef STATUS_EAS_NOT_SUPPORTED
+# define STATUS_EAS_NOT_SUPPORTED ((NTSTATUS) 0xC000004FL)
+#endif
+
+#ifndef STATUS_EA_TOO_LARGE
+# define STATUS_EA_TOO_LARGE ((NTSTATUS) 0xC0000050L)
+#endif
+
+#ifndef STATUS_NONEXISTENT_EA_ENTRY
+# define STATUS_NONEXISTENT_EA_ENTRY ((NTSTATUS) 0xC0000051L)
+#endif
+
+#ifndef STATUS_NO_EAS_ON_FILE
+# define STATUS_NO_EAS_ON_FILE ((NTSTATUS) 0xC0000052L)
+#endif
+
+#ifndef STATUS_EA_CORRUPT_ERROR
+# define STATUS_EA_CORRUPT_ERROR ((NTSTATUS) 0xC0000053L)
+#endif
+
+#ifndef STATUS_FILE_LOCK_CONFLICT
+# define STATUS_FILE_LOCK_CONFLICT ((NTSTATUS) 0xC0000054L)
+#endif
+
+#ifndef STATUS_LOCK_NOT_GRANTED
+# define STATUS_LOCK_NOT_GRANTED ((NTSTATUS) 0xC0000055L)
+#endif
+
+#ifndef STATUS_DELETE_PENDING
+# define STATUS_DELETE_PENDING ((NTSTATUS) 0xC0000056L)
+#endif
+
+#ifndef STATUS_CTL_FILE_NOT_SUPPORTED
+# define STATUS_CTL_FILE_NOT_SUPPORTED ((NTSTATUS) 0xC0000057L)
+#endif
+
+#ifndef STATUS_UNKNOWN_REVISION
+# define STATUS_UNKNOWN_REVISION ((NTSTATUS) 0xC0000058L)
+#endif
+
+#ifndef STATUS_REVISION_MISMATCH
+# define STATUS_REVISION_MISMATCH ((NTSTATUS) 0xC0000059L)
+#endif
+
+#ifndef STATUS_INVALID_OWNER
+# define STATUS_INVALID_OWNER ((NTSTATUS) 0xC000005AL)
+#endif
+
+#ifndef STATUS_INVALID_PRIMARY_GROUP
+# define STATUS_INVALID_PRIMARY_GROUP ((NTSTATUS) 0xC000005BL)
+#endif
+
+#ifndef STATUS_NO_IMPERSONATION_TOKEN
+# define STATUS_NO_IMPERSONATION_TOKEN ((NTSTATUS) 0xC000005CL)
+#endif
+
+#ifndef STATUS_CANT_DISABLE_MANDATORY
+# define STATUS_CANT_DISABLE_MANDATORY ((NTSTATUS) 0xC000005DL)
+#endif
+
+#ifndef STATUS_NO_LOGON_SERVERS
+# define STATUS_NO_LOGON_SERVERS ((NTSTATUS) 0xC000005EL)
+#endif
+
+#ifndef STATUS_NO_SUCH_LOGON_SESSION
+# define STATUS_NO_SUCH_LOGON_SESSION ((NTSTATUS) 0xC000005FL)
+#endif
+
+#ifndef STATUS_NO_SUCH_PRIVILEGE
+# define STATUS_NO_SUCH_PRIVILEGE ((NTSTATUS) 0xC0000060L)
+#endif
+
+#ifndef STATUS_PRIVILEGE_NOT_HELD
+# define STATUS_PRIVILEGE_NOT_HELD ((NTSTATUS) 0xC0000061L)
+#endif
+
+#ifndef STATUS_INVALID_ACCOUNT_NAME
+# define STATUS_INVALID_ACCOUNT_NAME ((NTSTATUS) 0xC0000062L)
+#endif
+
+#ifndef STATUS_USER_EXISTS
+# define STATUS_USER_EXISTS ((NTSTATUS) 0xC0000063L)
+#endif
+
+#ifndef STATUS_NO_SUCH_USER
+# define STATUS_NO_SUCH_USER ((NTSTATUS) 0xC0000064L)
+#endif
+
+#ifndef STATUS_GROUP_EXISTS
+# define STATUS_GROUP_EXISTS ((NTSTATUS) 0xC0000065L)
+#endif
+
+#ifndef STATUS_NO_SUCH_GROUP
+# define STATUS_NO_SUCH_GROUP ((NTSTATUS) 0xC0000066L)
+#endif
+
+#ifndef STATUS_MEMBER_IN_GROUP
+# define STATUS_MEMBER_IN_GROUP ((NTSTATUS) 0xC0000067L)
+#endif
+
+#ifndef STATUS_MEMBER_NOT_IN_GROUP
+# define STATUS_MEMBER_NOT_IN_GROUP ((NTSTATUS) 0xC0000068L)
+#endif
+
+#ifndef STATUS_LAST_ADMIN
+# define STATUS_LAST_ADMIN ((NTSTATUS) 0xC0000069L)
+#endif
+
+#ifndef STATUS_WRONG_PASSWORD
+# define STATUS_WRONG_PASSWORD ((NTSTATUS) 0xC000006AL)
+#endif
+
+#ifndef STATUS_ILL_FORMED_PASSWORD
+# define STATUS_ILL_FORMED_PASSWORD ((NTSTATUS) 0xC000006BL)
+#endif
+
+#ifndef STATUS_PASSWORD_RESTRICTION
+# define STATUS_PASSWORD_RESTRICTION ((NTSTATUS) 0xC000006CL)
+#endif
+
+#ifndef STATUS_LOGON_FAILURE
+# define STATUS_LOGON_FAILURE ((NTSTATUS) 0xC000006DL)
+#endif
+
+#ifndef STATUS_ACCOUNT_RESTRICTION
+# define STATUS_ACCOUNT_RESTRICTION ((NTSTATUS) 0xC000006EL)
+#endif
+
+#ifndef STATUS_INVALID_LOGON_HOURS
+# define STATUS_INVALID_LOGON_HOURS ((NTSTATUS) 0xC000006FL)
+#endif
+
+#ifndef STATUS_INVALID_WORKSTATION
+# define STATUS_INVALID_WORKSTATION ((NTSTATUS) 0xC0000070L)
+#endif
+
+#ifndef STATUS_PASSWORD_EXPIRED
+# define STATUS_PASSWORD_EXPIRED ((NTSTATUS) 0xC0000071L)
+#endif
+
+#ifndef STATUS_ACCOUNT_DISABLED
+# define STATUS_ACCOUNT_DISABLED ((NTSTATUS) 0xC0000072L)
+#endif
+
+#ifndef STATUS_NONE_MAPPED
+# define STATUS_NONE_MAPPED ((NTSTATUS) 0xC0000073L)
+#endif
+
+#ifndef STATUS_TOO_MANY_LUIDS_REQUESTED
+# define STATUS_TOO_MANY_LUIDS_REQUESTED ((NTSTATUS) 0xC0000074L)
+#endif
+
+#ifndef STATUS_LUIDS_EXHAUSTED
+# define STATUS_LUIDS_EXHAUSTED ((NTSTATUS) 0xC0000075L)
+#endif
+
+#ifndef STATUS_INVALID_SUB_AUTHORITY
+# define STATUS_INVALID_SUB_AUTHORITY ((NTSTATUS) 0xC0000076L)
+#endif
+
+#ifndef STATUS_INVALID_ACL
+# define STATUS_INVALID_ACL ((NTSTATUS) 0xC0000077L)
+#endif
+
+#ifndef STATUS_INVALID_SID
+# define STATUS_INVALID_SID ((NTSTATUS) 0xC0000078L)
+#endif
+
+#ifndef STATUS_INVALID_SECURITY_DESCR
+# define STATUS_INVALID_SECURITY_DESCR ((NTSTATUS) 0xC0000079L)
+#endif
+
+#ifndef STATUS_PROCEDURE_NOT_FOUND
+# define STATUS_PROCEDURE_NOT_FOUND ((NTSTATUS) 0xC000007AL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_FORMAT
+# define STATUS_INVALID_IMAGE_FORMAT ((NTSTATUS) 0xC000007BL)
+#endif
+
+#ifndef STATUS_NO_TOKEN
+# define STATUS_NO_TOKEN ((NTSTATUS) 0xC000007CL)
+#endif
+
+#ifndef STATUS_BAD_INHERITANCE_ACL
+# define STATUS_BAD_INHERITANCE_ACL ((NTSTATUS) 0xC000007DL)
+#endif
+
+#ifndef STATUS_RANGE_NOT_LOCKED
+# define STATUS_RANGE_NOT_LOCKED ((NTSTATUS) 0xC000007EL)
+#endif
+
+#ifndef STATUS_DISK_FULL
+# define STATUS_DISK_FULL ((NTSTATUS) 0xC000007FL)
+#endif
+
+#ifndef STATUS_SERVER_DISABLED
+# define STATUS_SERVER_DISABLED ((NTSTATUS) 0xC0000080L)
+#endif
+
+#ifndef STATUS_SERVER_NOT_DISABLED
+# define STATUS_SERVER_NOT_DISABLED ((NTSTATUS) 0xC0000081L)
+#endif
+
+#ifndef STATUS_TOO_MANY_GUIDS_REQUESTED
+# define STATUS_TOO_MANY_GUIDS_REQUESTED ((NTSTATUS) 0xC0000082L)
+#endif
+
+#ifndef STATUS_GUIDS_EXHAUSTED
+# define STATUS_GUIDS_EXHAUSTED ((NTSTATUS) 0xC0000083L)
+#endif
+
+#ifndef STATUS_INVALID_ID_AUTHORITY
+# define STATUS_INVALID_ID_AUTHORITY ((NTSTATUS) 0xC0000084L)
+#endif
+
+#ifndef STATUS_AGENTS_EXHAUSTED
+# define STATUS_AGENTS_EXHAUSTED ((NTSTATUS) 0xC0000085L)
+#endif
+
+#ifndef STATUS_INVALID_VOLUME_LABEL
+# define STATUS_INVALID_VOLUME_LABEL ((NTSTATUS) 0xC0000086L)
+#endif
+
+#ifndef STATUS_SECTION_NOT_EXTENDED
+# define STATUS_SECTION_NOT_EXTENDED ((NTSTATUS) 0xC0000087L)
+#endif
+
+#ifndef STATUS_NOT_MAPPED_DATA
+# define STATUS_NOT_MAPPED_DATA ((NTSTATUS) 0xC0000088L)
+#endif
+
+#ifndef STATUS_RESOURCE_DATA_NOT_FOUND
+# define STATUS_RESOURCE_DATA_NOT_FOUND ((NTSTATUS) 0xC0000089L)
+#endif
+
+#ifndef STATUS_RESOURCE_TYPE_NOT_FOUND
+# define STATUS_RESOURCE_TYPE_NOT_FOUND ((NTSTATUS) 0xC000008AL)
+#endif
+
+#ifndef STATUS_RESOURCE_NAME_NOT_FOUND
+# define STATUS_RESOURCE_NAME_NOT_FOUND ((NTSTATUS) 0xC000008BL)
+#endif
+
+#ifndef STATUS_ARRAY_BOUNDS_EXCEEDED
+# define STATUS_ARRAY_BOUNDS_EXCEEDED ((NTSTATUS) 0xC000008CL)
+#endif
+
+#ifndef STATUS_FLOAT_DENORMAL_OPERAND
+# define STATUS_FLOAT_DENORMAL_OPERAND ((NTSTATUS) 0xC000008DL)
+#endif
+
+#ifndef STATUS_FLOAT_DIVIDE_BY_ZERO
+# define STATUS_FLOAT_DIVIDE_BY_ZERO ((NTSTATUS) 0xC000008EL)
+#endif
+
+#ifndef STATUS_FLOAT_INEXACT_RESULT
+# define STATUS_FLOAT_INEXACT_RESULT ((NTSTATUS) 0xC000008FL)
+#endif
+
+#ifndef STATUS_FLOAT_INVALID_OPERATION
+# define STATUS_FLOAT_INVALID_OPERATION ((NTSTATUS) 0xC0000090L)
+#endif
+
+#ifndef STATUS_FLOAT_OVERFLOW
+# define STATUS_FLOAT_OVERFLOW ((NTSTATUS) 0xC0000091L)
+#endif
+
+#ifndef STATUS_FLOAT_STACK_CHECK
+# define STATUS_FLOAT_STACK_CHECK ((NTSTATUS) 0xC0000092L)
+#endif
+
+#ifndef STATUS_FLOAT_UNDERFLOW
+# define STATUS_FLOAT_UNDERFLOW ((NTSTATUS) 0xC0000093L)
+#endif
+
+#ifndef STATUS_INTEGER_DIVIDE_BY_ZERO
+# define STATUS_INTEGER_DIVIDE_BY_ZERO ((NTSTATUS) 0xC0000094L)
+#endif
+
+#ifndef STATUS_INTEGER_OVERFLOW
+# define STATUS_INTEGER_OVERFLOW ((NTSTATUS) 0xC0000095L)
+#endif
+
+#ifndef STATUS_PRIVILEGED_INSTRUCTION
+# define STATUS_PRIVILEGED_INSTRUCTION ((NTSTATUS) 0xC0000096L)
+#endif
+
+#ifndef STATUS_TOO_MANY_PAGING_FILES
+# define STATUS_TOO_MANY_PAGING_FILES ((NTSTATUS) 0xC0000097L)
+#endif
+
+#ifndef STATUS_FILE_INVALID
+# define STATUS_FILE_INVALID ((NTSTATUS) 0xC0000098L)
+#endif
+
+#ifndef STATUS_ALLOTTED_SPACE_EXCEEDED
+# define STATUS_ALLOTTED_SPACE_EXCEEDED ((NTSTATUS) 0xC0000099L)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_RESOURCES
+# define STATUS_INSUFFICIENT_RESOURCES ((NTSTATUS) 0xC000009AL)
+#endif
+
+#ifndef STATUS_DFS_EXIT_PATH_FOUND
+# define STATUS_DFS_EXIT_PATH_FOUND ((NTSTATUS) 0xC000009BL)
+#endif
+
+#ifndef STATUS_DEVICE_DATA_ERROR
+# define STATUS_DEVICE_DATA_ERROR ((NTSTATUS) 0xC000009CL)
+#endif
+
+#ifndef STATUS_DEVICE_NOT_CONNECTED
+# define STATUS_DEVICE_NOT_CONNECTED ((NTSTATUS) 0xC000009DL)
+#endif
+
+#ifndef STATUS_DEVICE_POWER_FAILURE
+# define STATUS_DEVICE_POWER_FAILURE ((NTSTATUS) 0xC000009EL)
+#endif
+
+#ifndef STATUS_FREE_VM_NOT_AT_BASE
+# define STATUS_FREE_VM_NOT_AT_BASE ((NTSTATUS) 0xC000009FL)
+#endif
+
+#ifndef STATUS_MEMORY_NOT_ALLOCATED
+# define STATUS_MEMORY_NOT_ALLOCATED ((NTSTATUS) 0xC00000A0L)
+#endif
+
+#ifndef STATUS_WORKING_SET_QUOTA
+# define STATUS_WORKING_SET_QUOTA ((NTSTATUS) 0xC00000A1L)
+#endif
+
+#ifndef STATUS_MEDIA_WRITE_PROTECTED
+# define STATUS_MEDIA_WRITE_PROTECTED ((NTSTATUS) 0xC00000A2L)
+#endif
+
+#ifndef STATUS_DEVICE_NOT_READY
+# define STATUS_DEVICE_NOT_READY ((NTSTATUS) 0xC00000A3L)
+#endif
+
+#ifndef STATUS_INVALID_GROUP_ATTRIBUTES
+# define STATUS_INVALID_GROUP_ATTRIBUTES ((NTSTATUS) 0xC00000A4L)
+#endif
+
+#ifndef STATUS_BAD_IMPERSONATION_LEVEL
+# define STATUS_BAD_IMPERSONATION_LEVEL ((NTSTATUS) 0xC00000A5L)
+#endif
+
+#ifndef STATUS_CANT_OPEN_ANONYMOUS
+# define STATUS_CANT_OPEN_ANONYMOUS ((NTSTATUS) 0xC00000A6L)
+#endif
+
+#ifndef STATUS_BAD_VALIDATION_CLASS
+# define STATUS_BAD_VALIDATION_CLASS ((NTSTATUS) 0xC00000A7L)
+#endif
+
+#ifndef STATUS_BAD_TOKEN_TYPE
+# define STATUS_BAD_TOKEN_TYPE ((NTSTATUS) 0xC00000A8L)
+#endif
+
+#ifndef STATUS_BAD_MASTER_BOOT_RECORD
+# define STATUS_BAD_MASTER_BOOT_RECORD ((NTSTATUS) 0xC00000A9L)
+#endif
+
+#ifndef STATUS_INSTRUCTION_MISALIGNMENT
+# define STATUS_INSTRUCTION_MISALIGNMENT ((NTSTATUS) 0xC00000AAL)
+#endif
+
+#ifndef STATUS_INSTANCE_NOT_AVAILABLE
+# define STATUS_INSTANCE_NOT_AVAILABLE ((NTSTATUS) 0xC00000ABL)
+#endif
+
+#ifndef STATUS_PIPE_NOT_AVAILABLE
+# define STATUS_PIPE_NOT_AVAILABLE ((NTSTATUS) 0xC00000ACL)
+#endif
+
+#ifndef STATUS_INVALID_PIPE_STATE
+# define STATUS_INVALID_PIPE_STATE ((NTSTATUS) 0xC00000ADL)
+#endif
+
+#ifndef STATUS_PIPE_BUSY
+# define STATUS_PIPE_BUSY ((NTSTATUS) 0xC00000AEL)
+#endif
+
+#ifndef STATUS_ILLEGAL_FUNCTION
+# define STATUS_ILLEGAL_FUNCTION ((NTSTATUS) 0xC00000AFL)
+#endif
+
+#ifndef STATUS_PIPE_DISCONNECTED
+# define STATUS_PIPE_DISCONNECTED ((NTSTATUS) 0xC00000B0L)
+#endif
+
+#ifndef STATUS_PIPE_CLOSING
+# define STATUS_PIPE_CLOSING ((NTSTATUS) 0xC00000B1L)
+#endif
+
+#ifndef STATUS_PIPE_CONNECTED
+# define STATUS_PIPE_CONNECTED ((NTSTATUS) 0xC00000B2L)
+#endif
+
+#ifndef STATUS_PIPE_LISTENING
+# define STATUS_PIPE_LISTENING ((NTSTATUS) 0xC00000B3L)
+#endif
+
+#ifndef STATUS_INVALID_READ_MODE
+# define STATUS_INVALID_READ_MODE ((NTSTATUS) 0xC00000B4L)
+#endif
+
+#ifndef STATUS_IO_TIMEOUT
+# define STATUS_IO_TIMEOUT ((NTSTATUS) 0xC00000B5L)
+#endif
+
+#ifndef STATUS_FILE_FORCED_CLOSED
+# define STATUS_FILE_FORCED_CLOSED ((NTSTATUS) 0xC00000B6L)
+#endif
+
+#ifndef STATUS_PROFILING_NOT_STARTED
+# define STATUS_PROFILING_NOT_STARTED ((NTSTATUS) 0xC00000B7L)
+#endif
+
+#ifndef STATUS_PROFILING_NOT_STOPPED
+# define STATUS_PROFILING_NOT_STOPPED ((NTSTATUS) 0xC00000B8L)
+#endif
+
+#ifndef STATUS_COULD_NOT_INTERPRET
+# define STATUS_COULD_NOT_INTERPRET ((NTSTATUS) 0xC00000B9L)
+#endif
+
+#ifndef STATUS_FILE_IS_A_DIRECTORY
+# define STATUS_FILE_IS_A_DIRECTORY ((NTSTATUS) 0xC00000BAL)
+#endif
+
+#ifndef STATUS_NOT_SUPPORTED
+# define STATUS_NOT_SUPPORTED ((NTSTATUS) 0xC00000BBL)
+#endif
+
+#ifndef STATUS_REMOTE_NOT_LISTENING
+# define STATUS_REMOTE_NOT_LISTENING ((NTSTATUS) 0xC00000BCL)
+#endif
+
+#ifndef STATUS_DUPLICATE_NAME
+# define STATUS_DUPLICATE_NAME ((NTSTATUS) 0xC00000BDL)
+#endif
+
+#ifndef STATUS_BAD_NETWORK_PATH
+# define STATUS_BAD_NETWORK_PATH ((NTSTATUS) 0xC00000BEL)
+#endif
+
+#ifndef STATUS_NETWORK_BUSY
+# define STATUS_NETWORK_BUSY ((NTSTATUS) 0xC00000BFL)
+#endif
+
+#ifndef STATUS_DEVICE_DOES_NOT_EXIST
+# define STATUS_DEVICE_DOES_NOT_EXIST ((NTSTATUS) 0xC00000C0L)
+#endif
+
+#ifndef STATUS_TOO_MANY_COMMANDS
+# define STATUS_TOO_MANY_COMMANDS ((NTSTATUS) 0xC00000C1L)
+#endif
+
+#ifndef STATUS_ADAPTER_HARDWARE_ERROR
+# define STATUS_ADAPTER_HARDWARE_ERROR ((NTSTATUS) 0xC00000C2L)
+#endif
+
+#ifndef STATUS_INVALID_NETWORK_RESPONSE
+# define STATUS_INVALID_NETWORK_RESPONSE ((NTSTATUS) 0xC00000C3L)
+#endif
+
+#ifndef STATUS_UNEXPECTED_NETWORK_ERROR
+# define STATUS_UNEXPECTED_NETWORK_ERROR ((NTSTATUS) 0xC00000C4L)
+#endif
+
+#ifndef STATUS_BAD_REMOTE_ADAPTER
+# define STATUS_BAD_REMOTE_ADAPTER ((NTSTATUS) 0xC00000C5L)
+#endif
+
+#ifndef STATUS_PRINT_QUEUE_FULL
+# define STATUS_PRINT_QUEUE_FULL ((NTSTATUS) 0xC00000C6L)
+#endif
+
+#ifndef STATUS_NO_SPOOL_SPACE
+# define STATUS_NO_SPOOL_SPACE ((NTSTATUS) 0xC00000C7L)
+#endif
+
+#ifndef STATUS_PRINT_CANCELLED
+# define STATUS_PRINT_CANCELLED ((NTSTATUS) 0xC00000C8L)
+#endif
+
+#ifndef STATUS_NETWORK_NAME_DELETED
+# define STATUS_NETWORK_NAME_DELETED ((NTSTATUS) 0xC00000C9L)
+#endif
+
+#ifndef STATUS_NETWORK_ACCESS_DENIED
+# define STATUS_NETWORK_ACCESS_DENIED ((NTSTATUS) 0xC00000CAL)
+#endif
+
+#ifndef STATUS_BAD_DEVICE_TYPE
+# define STATUS_BAD_DEVICE_TYPE ((NTSTATUS) 0xC00000CBL)
+#endif
+
+#ifndef STATUS_BAD_NETWORK_NAME
+# define STATUS_BAD_NETWORK_NAME ((NTSTATUS) 0xC00000CCL)
+#endif
+
+#ifndef STATUS_TOO_MANY_NAMES
+# define STATUS_TOO_MANY_NAMES ((NTSTATUS) 0xC00000CDL)
+#endif
+
+#ifndef STATUS_TOO_MANY_SESSIONS
+# define STATUS_TOO_MANY_SESSIONS ((NTSTATUS) 0xC00000CEL)
+#endif
+
+#ifndef STATUS_SHARING_PAUSED
+# define STATUS_SHARING_PAUSED ((NTSTATUS) 0xC00000CFL)
+#endif
+
+#ifndef STATUS_REQUEST_NOT_ACCEPTED
+# define STATUS_REQUEST_NOT_ACCEPTED ((NTSTATUS) 0xC00000D0L)
+#endif
+
+#ifndef STATUS_REDIRECTOR_PAUSED
+# define STATUS_REDIRECTOR_PAUSED ((NTSTATUS) 0xC00000D1L)
+#endif
+
+#ifndef STATUS_NET_WRITE_FAULT
+# define STATUS_NET_WRITE_FAULT ((NTSTATUS) 0xC00000D2L)
+#endif
+
+#ifndef STATUS_PROFILING_AT_LIMIT
+# define STATUS_PROFILING_AT_LIMIT ((NTSTATUS) 0xC00000D3L)
+#endif
+
+#ifndef STATUS_NOT_SAME_DEVICE
+# define STATUS_NOT_SAME_DEVICE ((NTSTATUS) 0xC00000D4L)
+#endif
+
+#ifndef STATUS_FILE_RENAMED
+# define STATUS_FILE_RENAMED ((NTSTATUS) 0xC00000D5L)
+#endif
+
+#ifndef STATUS_VIRTUAL_CIRCUIT_CLOSED
+# define STATUS_VIRTUAL_CIRCUIT_CLOSED ((NTSTATUS) 0xC00000D6L)
+#endif
+
+#ifndef STATUS_NO_SECURITY_ON_OBJECT
+# define STATUS_NO_SECURITY_ON_OBJECT ((NTSTATUS) 0xC00000D7L)
+#endif
+
+#ifndef STATUS_CANT_WAIT
+# define STATUS_CANT_WAIT ((NTSTATUS) 0xC00000D8L)
+#endif
+
+#ifndef STATUS_PIPE_EMPTY
+# define STATUS_PIPE_EMPTY ((NTSTATUS) 0xC00000D9L)
+#endif
+
+#ifndef STATUS_CANT_ACCESS_DOMAIN_INFO
+# define STATUS_CANT_ACCESS_DOMAIN_INFO ((NTSTATUS) 0xC00000DAL)
+#endif
+
+#ifndef STATUS_CANT_TERMINATE_SELF
+# define STATUS_CANT_TERMINATE_SELF ((NTSTATUS) 0xC00000DBL)
+#endif
+
+#ifndef STATUS_INVALID_SERVER_STATE
+# define STATUS_INVALID_SERVER_STATE ((NTSTATUS) 0xC00000DCL)
+#endif
+
+#ifndef STATUS_INVALID_DOMAIN_STATE
+# define STATUS_INVALID_DOMAIN_STATE ((NTSTATUS) 0xC00000DDL)
+#endif
+
+#ifndef STATUS_INVALID_DOMAIN_ROLE
+# define STATUS_INVALID_DOMAIN_ROLE ((NTSTATUS) 0xC00000DEL)
+#endif
+
+#ifndef STATUS_NO_SUCH_DOMAIN
+# define STATUS_NO_SUCH_DOMAIN ((NTSTATUS) 0xC00000DFL)
+#endif
+
+#ifndef STATUS_DOMAIN_EXISTS
+# define STATUS_DOMAIN_EXISTS ((NTSTATUS) 0xC00000E0L)
+#endif
+
+#ifndef STATUS_DOMAIN_LIMIT_EXCEEDED
+# define STATUS_DOMAIN_LIMIT_EXCEEDED ((NTSTATUS) 0xC00000E1L)
+#endif
+
+#ifndef STATUS_OPLOCK_NOT_GRANTED
+# define STATUS_OPLOCK_NOT_GRANTED ((NTSTATUS) 0xC00000E2L)
+#endif
+
+#ifndef STATUS_INVALID_OPLOCK_PROTOCOL
+# define STATUS_INVALID_OPLOCK_PROTOCOL ((NTSTATUS) 0xC00000E3L)
+#endif
+
+#ifndef STATUS_INTERNAL_DB_CORRUPTION
+# define STATUS_INTERNAL_DB_CORRUPTION ((NTSTATUS) 0xC00000E4L)
+#endif
+
+#ifndef STATUS_INTERNAL_ERROR
+# define STATUS_INTERNAL_ERROR ((NTSTATUS) 0xC00000E5L)
+#endif
+
+#ifndef STATUS_GENERIC_NOT_MAPPED
+# define STATUS_GENERIC_NOT_MAPPED ((NTSTATUS) 0xC00000E6L)
+#endif
+
+#ifndef STATUS_BAD_DESCRIPTOR_FORMAT
+# define STATUS_BAD_DESCRIPTOR_FORMAT ((NTSTATUS) 0xC00000E7L)
+#endif
+
+#ifndef STATUS_INVALID_USER_BUFFER
+# define STATUS_INVALID_USER_BUFFER ((NTSTATUS) 0xC00000E8L)
+#endif
+
+#ifndef STATUS_UNEXPECTED_IO_ERROR
+# define STATUS_UNEXPECTED_IO_ERROR ((NTSTATUS) 0xC00000E9L)
+#endif
+
+#ifndef STATUS_UNEXPECTED_MM_CREATE_ERR
+# define STATUS_UNEXPECTED_MM_CREATE_ERR ((NTSTATUS) 0xC00000EAL)
+#endif
+
+#ifndef STATUS_UNEXPECTED_MM_MAP_ERROR
+# define STATUS_UNEXPECTED_MM_MAP_ERROR ((NTSTATUS) 0xC00000EBL)
+#endif
+
+#ifndef STATUS_UNEXPECTED_MM_EXTEND_ERR
+# define STATUS_UNEXPECTED_MM_EXTEND_ERR ((NTSTATUS) 0xC00000ECL)
+#endif
+
+#ifndef STATUS_NOT_LOGON_PROCESS
+# define STATUS_NOT_LOGON_PROCESS ((NTSTATUS) 0xC00000EDL)
+#endif
+
+#ifndef STATUS_LOGON_SESSION_EXISTS
+# define STATUS_LOGON_SESSION_EXISTS ((NTSTATUS) 0xC00000EEL)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_1
+# define STATUS_INVALID_PARAMETER_1 ((NTSTATUS) 0xC00000EFL)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_2
+# define STATUS_INVALID_PARAMETER_2 ((NTSTATUS) 0xC00000F0L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_3
+# define STATUS_INVALID_PARAMETER_3 ((NTSTATUS) 0xC00000F1L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_4
+# define STATUS_INVALID_PARAMETER_4 ((NTSTATUS) 0xC00000F2L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_5
+# define STATUS_INVALID_PARAMETER_5 ((NTSTATUS) 0xC00000F3L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_6
+# define STATUS_INVALID_PARAMETER_6 ((NTSTATUS) 0xC00000F4L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_7
+# define STATUS_INVALID_PARAMETER_7 ((NTSTATUS) 0xC00000F5L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_8
+# define STATUS_INVALID_PARAMETER_8 ((NTSTATUS) 0xC00000F6L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_9
+# define STATUS_INVALID_PARAMETER_9 ((NTSTATUS) 0xC00000F7L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_10
+# define STATUS_INVALID_PARAMETER_10 ((NTSTATUS) 0xC00000F8L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_11
+# define STATUS_INVALID_PARAMETER_11 ((NTSTATUS) 0xC00000F9L)
+#endif
+
+#ifndef STATUS_INVALID_PARAMETER_12
+# define STATUS_INVALID_PARAMETER_12 ((NTSTATUS) 0xC00000FAL)
+#endif
+
+#ifndef STATUS_REDIRECTOR_NOT_STARTED
+# define STATUS_REDIRECTOR_NOT_STARTED ((NTSTATUS) 0xC00000FBL)
+#endif
+
+#ifndef STATUS_REDIRECTOR_STARTED
+# define STATUS_REDIRECTOR_STARTED ((NTSTATUS) 0xC00000FCL)
+#endif
+
+#ifndef STATUS_STACK_OVERFLOW
+# define STATUS_STACK_OVERFLOW ((NTSTATUS) 0xC00000FDL)
+#endif
+
+#ifndef STATUS_NO_SUCH_PACKAGE
+# define STATUS_NO_SUCH_PACKAGE ((NTSTATUS) 0xC00000FEL)
+#endif
+
+#ifndef STATUS_BAD_FUNCTION_TABLE
+# define STATUS_BAD_FUNCTION_TABLE ((NTSTATUS) 0xC00000FFL)
+#endif
+
+#ifndef STATUS_VARIABLE_NOT_FOUND
+# define STATUS_VARIABLE_NOT_FOUND ((NTSTATUS) 0xC0000100L)
+#endif
+
+#ifndef STATUS_DIRECTORY_NOT_EMPTY
+# define STATUS_DIRECTORY_NOT_EMPTY ((NTSTATUS) 0xC0000101L)
+#endif
+
+#ifndef STATUS_FILE_CORRUPT_ERROR
+# define STATUS_FILE_CORRUPT_ERROR ((NTSTATUS) 0xC0000102L)
+#endif
+
+#ifndef STATUS_NOT_A_DIRECTORY
+# define STATUS_NOT_A_DIRECTORY ((NTSTATUS) 0xC0000103L)
+#endif
+
+#ifndef STATUS_BAD_LOGON_SESSION_STATE
+# define STATUS_BAD_LOGON_SESSION_STATE ((NTSTATUS) 0xC0000104L)
+#endif
+
+#ifndef STATUS_LOGON_SESSION_COLLISION
+# define STATUS_LOGON_SESSION_COLLISION ((NTSTATUS) 0xC0000105L)
+#endif
+
+#ifndef STATUS_NAME_TOO_LONG
+# define STATUS_NAME_TOO_LONG ((NTSTATUS) 0xC0000106L)
+#endif
+
+#ifndef STATUS_FILES_OPEN
+# define STATUS_FILES_OPEN ((NTSTATUS) 0xC0000107L)
+#endif
+
+#ifndef STATUS_CONNECTION_IN_USE
+# define STATUS_CONNECTION_IN_USE ((NTSTATUS) 0xC0000108L)
+#endif
+
+#ifndef STATUS_MESSAGE_NOT_FOUND
+# define STATUS_MESSAGE_NOT_FOUND ((NTSTATUS) 0xC0000109L)
+#endif
+
+#ifndef STATUS_PROCESS_IS_TERMINATING
+# define STATUS_PROCESS_IS_TERMINATING ((NTSTATUS) 0xC000010AL)
+#endif
+
+#ifndef STATUS_INVALID_LOGON_TYPE
+# define STATUS_INVALID_LOGON_TYPE ((NTSTATUS) 0xC000010BL)
+#endif
+
+#ifndef STATUS_NO_GUID_TRANSLATION
+# define STATUS_NO_GUID_TRANSLATION ((NTSTATUS) 0xC000010CL)
+#endif
+
+#ifndef STATUS_CANNOT_IMPERSONATE
+# define STATUS_CANNOT_IMPERSONATE ((NTSTATUS) 0xC000010DL)
+#endif
+
+#ifndef STATUS_IMAGE_ALREADY_LOADED
+# define STATUS_IMAGE_ALREADY_LOADED ((NTSTATUS) 0xC000010EL)
+#endif
+
+#ifndef STATUS_ABIOS_NOT_PRESENT
+# define STATUS_ABIOS_NOT_PRESENT ((NTSTATUS) 0xC000010FL)
+#endif
+
+#ifndef STATUS_ABIOS_LID_NOT_EXIST
+# define STATUS_ABIOS_LID_NOT_EXIST ((NTSTATUS) 0xC0000110L)
+#endif
+
+#ifndef STATUS_ABIOS_LID_ALREADY_OWNED
+# define STATUS_ABIOS_LID_ALREADY_OWNED ((NTSTATUS) 0xC0000111L)
+#endif
+
+#ifndef STATUS_ABIOS_NOT_LID_OWNER
+# define STATUS_ABIOS_NOT_LID_OWNER ((NTSTATUS) 0xC0000112L)
+#endif
+
+#ifndef STATUS_ABIOS_INVALID_COMMAND
+# define STATUS_ABIOS_INVALID_COMMAND ((NTSTATUS) 0xC0000113L)
+#endif
+
+#ifndef STATUS_ABIOS_INVALID_LID
+# define STATUS_ABIOS_INVALID_LID ((NTSTATUS) 0xC0000114L)
+#endif
+
+#ifndef STATUS_ABIOS_SELECTOR_NOT_AVAILABLE
+# define STATUS_ABIOS_SELECTOR_NOT_AVAILABLE ((NTSTATUS) 0xC0000115L)
+#endif
+
+#ifndef STATUS_ABIOS_INVALID_SELECTOR
+# define STATUS_ABIOS_INVALID_SELECTOR ((NTSTATUS) 0xC0000116L)
+#endif
+
+#ifndef STATUS_NO_LDT
+# define STATUS_NO_LDT ((NTSTATUS) 0xC0000117L)
+#endif
+
+#ifndef STATUS_INVALID_LDT_SIZE
+# define STATUS_INVALID_LDT_SIZE ((NTSTATUS) 0xC0000118L)
+#endif
+
+#ifndef STATUS_INVALID_LDT_OFFSET
+# define STATUS_INVALID_LDT_OFFSET ((NTSTATUS) 0xC0000119L)
+#endif
+
+#ifndef STATUS_INVALID_LDT_DESCRIPTOR
+# define STATUS_INVALID_LDT_DESCRIPTOR ((NTSTATUS) 0xC000011AL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_NE_FORMAT
+# define STATUS_INVALID_IMAGE_NE_FORMAT ((NTSTATUS) 0xC000011BL)
+#endif
+
+#ifndef STATUS_RXACT_INVALID_STATE
+# define STATUS_RXACT_INVALID_STATE ((NTSTATUS) 0xC000011CL)
+#endif
+
+#ifndef STATUS_RXACT_COMMIT_FAILURE
+# define STATUS_RXACT_COMMIT_FAILURE ((NTSTATUS) 0xC000011DL)
+#endif
+
+#ifndef STATUS_MAPPED_FILE_SIZE_ZERO
+# define STATUS_MAPPED_FILE_SIZE_ZERO ((NTSTATUS) 0xC000011EL)
+#endif
+
+#ifndef STATUS_TOO_MANY_OPENED_FILES
+# define STATUS_TOO_MANY_OPENED_FILES ((NTSTATUS) 0xC000011FL)
+#endif
+
+#ifndef STATUS_CANCELLED
+# define STATUS_CANCELLED ((NTSTATUS) 0xC0000120L)
+#endif
+
+#ifndef STATUS_CANNOT_DELETE
+# define STATUS_CANNOT_DELETE ((NTSTATUS) 0xC0000121L)
+#endif
+
+#ifndef STATUS_INVALID_COMPUTER_NAME
+# define STATUS_INVALID_COMPUTER_NAME ((NTSTATUS) 0xC0000122L)
+#endif
+
+#ifndef STATUS_FILE_DELETED
+# define STATUS_FILE_DELETED ((NTSTATUS) 0xC0000123L)
+#endif
+
+#ifndef STATUS_SPECIAL_ACCOUNT
+# define STATUS_SPECIAL_ACCOUNT ((NTSTATUS) 0xC0000124L)
+#endif
+
+#ifndef STATUS_SPECIAL_GROUP
+# define STATUS_SPECIAL_GROUP ((NTSTATUS) 0xC0000125L)
+#endif
+
+#ifndef STATUS_SPECIAL_USER
+# define STATUS_SPECIAL_USER ((NTSTATUS) 0xC0000126L)
+#endif
+
+#ifndef STATUS_MEMBERS_PRIMARY_GROUP
+# define STATUS_MEMBERS_PRIMARY_GROUP ((NTSTATUS) 0xC0000127L)
+#endif
+
+#ifndef STATUS_FILE_CLOSED
+# define STATUS_FILE_CLOSED ((NTSTATUS) 0xC0000128L)
+#endif
+
+#ifndef STATUS_TOO_MANY_THREADS
+# define STATUS_TOO_MANY_THREADS ((NTSTATUS) 0xC0000129L)
+#endif
+
+#ifndef STATUS_THREAD_NOT_IN_PROCESS
+# define STATUS_THREAD_NOT_IN_PROCESS ((NTSTATUS) 0xC000012AL)
+#endif
+
+#ifndef STATUS_TOKEN_ALREADY_IN_USE
+# define STATUS_TOKEN_ALREADY_IN_USE ((NTSTATUS) 0xC000012BL)
+#endif
+
+#ifndef STATUS_PAGEFILE_QUOTA_EXCEEDED
+# define STATUS_PAGEFILE_QUOTA_EXCEEDED ((NTSTATUS) 0xC000012CL)
+#endif
+
+#ifndef STATUS_COMMITMENT_LIMIT
+# define STATUS_COMMITMENT_LIMIT ((NTSTATUS) 0xC000012DL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_LE_FORMAT
+# define STATUS_INVALID_IMAGE_LE_FORMAT ((NTSTATUS) 0xC000012EL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_NOT_MZ
+# define STATUS_INVALID_IMAGE_NOT_MZ ((NTSTATUS) 0xC000012FL)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_PROTECT
+# define STATUS_INVALID_IMAGE_PROTECT ((NTSTATUS) 0xC0000130L)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_WIN_16
+# define STATUS_INVALID_IMAGE_WIN_16 ((NTSTATUS) 0xC0000131L)
+#endif
+
+#ifndef STATUS_LOGON_SERVER_CONFLICT
+# define STATUS_LOGON_SERVER_CONFLICT ((NTSTATUS) 0xC0000132L)
+#endif
+
+#ifndef STATUS_TIME_DIFFERENCE_AT_DC
+# define STATUS_TIME_DIFFERENCE_AT_DC ((NTSTATUS) 0xC0000133L)
+#endif
+
+#ifndef STATUS_SYNCHRONIZATION_REQUIRED
+# define STATUS_SYNCHRONIZATION_REQUIRED ((NTSTATUS) 0xC0000134L)
+#endif
+
+#ifndef STATUS_DLL_NOT_FOUND
+# define STATUS_DLL_NOT_FOUND ((NTSTATUS) 0xC0000135L)
+#endif
+
+#ifndef STATUS_OPEN_FAILED
+# define STATUS_OPEN_FAILED ((NTSTATUS) 0xC0000136L)
+#endif
+
+#ifndef STATUS_IO_PRIVILEGE_FAILED
+# define STATUS_IO_PRIVILEGE_FAILED ((NTSTATUS) 0xC0000137L)
+#endif
+
+#ifndef STATUS_ORDINAL_NOT_FOUND
+# define STATUS_ORDINAL_NOT_FOUND ((NTSTATUS) 0xC0000138L)
+#endif
+
+#ifndef STATUS_ENTRYPOINT_NOT_FOUND
+# define STATUS_ENTRYPOINT_NOT_FOUND ((NTSTATUS) 0xC0000139L)
+#endif
+
+#ifndef STATUS_CONTROL_C_EXIT
+# define STATUS_CONTROL_C_EXIT ((NTSTATUS) 0xC000013AL)
+#endif
+
+#ifndef STATUS_LOCAL_DISCONNECT
+# define STATUS_LOCAL_DISCONNECT ((NTSTATUS) 0xC000013BL)
+#endif
+
+#ifndef STATUS_REMOTE_DISCONNECT
+# define STATUS_REMOTE_DISCONNECT ((NTSTATUS) 0xC000013CL)
+#endif
+
+#ifndef STATUS_REMOTE_RESOURCES
+# define STATUS_REMOTE_RESOURCES ((NTSTATUS) 0xC000013DL)
+#endif
+
+#ifndef STATUS_LINK_FAILED
+# define STATUS_LINK_FAILED ((NTSTATUS) 0xC000013EL)
+#endif
+
+#ifndef STATUS_LINK_TIMEOUT
+# define STATUS_LINK_TIMEOUT ((NTSTATUS) 0xC000013FL)
+#endif
+
+#ifndef STATUS_INVALID_CONNECTION
+# define STATUS_INVALID_CONNECTION ((NTSTATUS) 0xC0000140L)
+#endif
+
+#ifndef STATUS_INVALID_ADDRESS
+# define STATUS_INVALID_ADDRESS ((NTSTATUS) 0xC0000141L)
+#endif
+
+#ifndef STATUS_DLL_INIT_FAILED
+# define STATUS_DLL_INIT_FAILED ((NTSTATUS) 0xC0000142L)
+#endif
+
+#ifndef STATUS_MISSING_SYSTEMFILE
+# define STATUS_MISSING_SYSTEMFILE ((NTSTATUS) 0xC0000143L)
+#endif
+
+#ifndef STATUS_UNHANDLED_EXCEPTION
+# define STATUS_UNHANDLED_EXCEPTION ((NTSTATUS) 0xC0000144L)
+#endif
+
+#ifndef STATUS_APP_INIT_FAILURE
+# define STATUS_APP_INIT_FAILURE ((NTSTATUS) 0xC0000145L)
+#endif
+
+#ifndef STATUS_PAGEFILE_CREATE_FAILED
+# define STATUS_PAGEFILE_CREATE_FAILED ((NTSTATUS) 0xC0000146L)
+#endif
+
+#ifndef STATUS_NO_PAGEFILE
+# define STATUS_NO_PAGEFILE ((NTSTATUS) 0xC0000147L)
+#endif
+
+#ifndef STATUS_INVALID_LEVEL
+# define STATUS_INVALID_LEVEL ((NTSTATUS) 0xC0000148L)
+#endif
+
+#ifndef STATUS_WRONG_PASSWORD_CORE
+# define STATUS_WRONG_PASSWORD_CORE ((NTSTATUS) 0xC0000149L)
+#endif
+
+#ifndef STATUS_ILLEGAL_FLOAT_CONTEXT
+# define STATUS_ILLEGAL_FLOAT_CONTEXT ((NTSTATUS) 0xC000014AL)
+#endif
+
+#ifndef STATUS_PIPE_BROKEN
+# define STATUS_PIPE_BROKEN ((NTSTATUS) 0xC000014BL)
+#endif
+
+#ifndef STATUS_REGISTRY_CORRUPT
+# define STATUS_REGISTRY_CORRUPT ((NTSTATUS) 0xC000014CL)
+#endif
+
+#ifndef STATUS_REGISTRY_IO_FAILED
+# define STATUS_REGISTRY_IO_FAILED ((NTSTATUS) 0xC000014DL)
+#endif
+
+#ifndef STATUS_NO_EVENT_PAIR
+# define STATUS_NO_EVENT_PAIR ((NTSTATUS) 0xC000014EL)
+#endif
+
+#ifndef STATUS_UNRECOGNIZED_VOLUME
+# define STATUS_UNRECOGNIZED_VOLUME ((NTSTATUS) 0xC000014FL)
+#endif
+
+#ifndef STATUS_SERIAL_NO_DEVICE_INITED
+# define STATUS_SERIAL_NO_DEVICE_INITED ((NTSTATUS) 0xC0000150L)
+#endif
+
+#ifndef STATUS_NO_SUCH_ALIAS
+# define STATUS_NO_SUCH_ALIAS ((NTSTATUS) 0xC0000151L)
+#endif
+
+#ifndef STATUS_MEMBER_NOT_IN_ALIAS
+# define STATUS_MEMBER_NOT_IN_ALIAS ((NTSTATUS) 0xC0000152L)
+#endif
+
+#ifndef STATUS_MEMBER_IN_ALIAS
+# define STATUS_MEMBER_IN_ALIAS ((NTSTATUS) 0xC0000153L)
+#endif
+
+#ifndef STATUS_ALIAS_EXISTS
+# define STATUS_ALIAS_EXISTS ((NTSTATUS) 0xC0000154L)
+#endif
+
+#ifndef STATUS_LOGON_NOT_GRANTED
+# define STATUS_LOGON_NOT_GRANTED ((NTSTATUS) 0xC0000155L)
+#endif
+
+#ifndef STATUS_TOO_MANY_SECRETS
+# define STATUS_TOO_MANY_SECRETS ((NTSTATUS) 0xC0000156L)
+#endif
+
+#ifndef STATUS_SECRET_TOO_LONG
+# define STATUS_SECRET_TOO_LONG ((NTSTATUS) 0xC0000157L)
+#endif
+
+#ifndef STATUS_INTERNAL_DB_ERROR
+# define STATUS_INTERNAL_DB_ERROR ((NTSTATUS) 0xC0000158L)
+#endif
+
+#ifndef STATUS_FULLSCREEN_MODE
+# define STATUS_FULLSCREEN_MODE ((NTSTATUS) 0xC0000159L)
+#endif
+
+#ifndef STATUS_TOO_MANY_CONTEXT_IDS
+# define STATUS_TOO_MANY_CONTEXT_IDS ((NTSTATUS) 0xC000015AL)
+#endif
+
+#ifndef STATUS_LOGON_TYPE_NOT_GRANTED
+# define STATUS_LOGON_TYPE_NOT_GRANTED ((NTSTATUS) 0xC000015BL)
+#endif
+
+#ifndef STATUS_NOT_REGISTRY_FILE
+# define STATUS_NOT_REGISTRY_FILE ((NTSTATUS) 0xC000015CL)
+#endif
+
+#ifndef STATUS_NT_CROSS_ENCRYPTION_REQUIRED
+# define STATUS_NT_CROSS_ENCRYPTION_REQUIRED ((NTSTATUS) 0xC000015DL)
+#endif
+
+#ifndef STATUS_DOMAIN_CTRLR_CONFIG_ERROR
+# define STATUS_DOMAIN_CTRLR_CONFIG_ERROR ((NTSTATUS) 0xC000015EL)
+#endif
+
+#ifndef STATUS_FT_MISSING_MEMBER
+# define STATUS_FT_MISSING_MEMBER ((NTSTATUS) 0xC000015FL)
+#endif
+
+#ifndef STATUS_ILL_FORMED_SERVICE_ENTRY
+# define STATUS_ILL_FORMED_SERVICE_ENTRY ((NTSTATUS) 0xC0000160L)
+#endif
+
+#ifndef STATUS_ILLEGAL_CHARACTER
+# define STATUS_ILLEGAL_CHARACTER ((NTSTATUS) 0xC0000161L)
+#endif
+
+#ifndef STATUS_UNMAPPABLE_CHARACTER
+# define STATUS_UNMAPPABLE_CHARACTER ((NTSTATUS) 0xC0000162L)
+#endif
+
+#ifndef STATUS_UNDEFINED_CHARACTER
+# define STATUS_UNDEFINED_CHARACTER ((NTSTATUS) 0xC0000163L)
+#endif
+
+#ifndef STATUS_FLOPPY_VOLUME
+# define STATUS_FLOPPY_VOLUME ((NTSTATUS) 0xC0000164L)
+#endif
+
+#ifndef STATUS_FLOPPY_ID_MARK_NOT_FOUND
+# define STATUS_FLOPPY_ID_MARK_NOT_FOUND ((NTSTATUS) 0xC0000165L)
+#endif
+
+#ifndef STATUS_FLOPPY_WRONG_CYLINDER
+# define STATUS_FLOPPY_WRONG_CYLINDER ((NTSTATUS) 0xC0000166L)
+#endif
+
+#ifndef STATUS_FLOPPY_UNKNOWN_ERROR
+# define STATUS_FLOPPY_UNKNOWN_ERROR ((NTSTATUS) 0xC0000167L)
+#endif
+
+#ifndef STATUS_FLOPPY_BAD_REGISTERS
+# define STATUS_FLOPPY_BAD_REGISTERS ((NTSTATUS) 0xC0000168L)
+#endif
+
+#ifndef STATUS_DISK_RECALIBRATE_FAILED
+# define STATUS_DISK_RECALIBRATE_FAILED ((NTSTATUS) 0xC0000169L)
+#endif
+
+#ifndef STATUS_DISK_OPERATION_FAILED
+# define STATUS_DISK_OPERATION_FAILED ((NTSTATUS) 0xC000016AL)
+#endif
+
+#ifndef STATUS_DISK_RESET_FAILED
+# define STATUS_DISK_RESET_FAILED ((NTSTATUS) 0xC000016BL)
+#endif
+
+#ifndef STATUS_SHARED_IRQ_BUSY
+# define STATUS_SHARED_IRQ_BUSY ((NTSTATUS) 0xC000016CL)
+#endif
+
+#ifndef STATUS_FT_ORPHANING
+# define STATUS_FT_ORPHANING ((NTSTATUS) 0xC000016DL)
+#endif
+
+#ifndef STATUS_BIOS_FAILED_TO_CONNECT_INTERRUPT
+# define STATUS_BIOS_FAILED_TO_CONNECT_INTERRUPT ((NTSTATUS) 0xC000016EL)
+#endif
+
+#ifndef STATUS_PARTITION_FAILURE
+# define STATUS_PARTITION_FAILURE ((NTSTATUS) 0xC0000172L)
+#endif
+
+#ifndef STATUS_INVALID_BLOCK_LENGTH
+# define STATUS_INVALID_BLOCK_LENGTH ((NTSTATUS) 0xC0000173L)
+#endif
+
+#ifndef STATUS_DEVICE_NOT_PARTITIONED
+# define STATUS_DEVICE_NOT_PARTITIONED ((NTSTATUS) 0xC0000174L)
+#endif
+
+#ifndef STATUS_UNABLE_TO_LOCK_MEDIA
+# define STATUS_UNABLE_TO_LOCK_MEDIA ((NTSTATUS) 0xC0000175L)
+#endif
+
+#ifndef STATUS_UNABLE_TO_UNLOAD_MEDIA
+# define STATUS_UNABLE_TO_UNLOAD_MEDIA ((NTSTATUS) 0xC0000176L)
+#endif
+
+#ifndef STATUS_EOM_OVERFLOW
+# define STATUS_EOM_OVERFLOW ((NTSTATUS) 0xC0000177L)
+#endif
+
+#ifndef STATUS_NO_MEDIA
+# define STATUS_NO_MEDIA ((NTSTATUS) 0xC0000178L)
+#endif
+
+#ifndef STATUS_NO_SUCH_MEMBER
+# define STATUS_NO_SUCH_MEMBER ((NTSTATUS) 0xC000017AL)
+#endif
+
+#ifndef STATUS_INVALID_MEMBER
+# define STATUS_INVALID_MEMBER ((NTSTATUS) 0xC000017BL)
+#endif
+
+#ifndef STATUS_KEY_DELETED
+# define STATUS_KEY_DELETED ((NTSTATUS) 0xC000017CL)
+#endif
+
+#ifndef STATUS_NO_LOG_SPACE
+# define STATUS_NO_LOG_SPACE ((NTSTATUS) 0xC000017DL)
+#endif
+
+#ifndef STATUS_TOO_MANY_SIDS
+# define STATUS_TOO_MANY_SIDS ((NTSTATUS) 0xC000017EL)
+#endif
+
+#ifndef STATUS_LM_CROSS_ENCRYPTION_REQUIRED
+# define STATUS_LM_CROSS_ENCRYPTION_REQUIRED ((NTSTATUS) 0xC000017FL)
+#endif
+
+#ifndef STATUS_KEY_HAS_CHILDREN
+# define STATUS_KEY_HAS_CHILDREN ((NTSTATUS) 0xC0000180L)
+#endif
+
+#ifndef STATUS_CHILD_MUST_BE_VOLATILE
+# define STATUS_CHILD_MUST_BE_VOLATILE ((NTSTATUS) 0xC0000181L)
+#endif
+
+#ifndef STATUS_DEVICE_CONFIGURATION_ERROR
+# define STATUS_DEVICE_CONFIGURATION_ERROR ((NTSTATUS) 0xC0000182L)
+#endif
+
+#ifndef STATUS_DRIVER_INTERNAL_ERROR
+# define STATUS_DRIVER_INTERNAL_ERROR ((NTSTATUS) 0xC0000183L)
+#endif
+
+#ifndef STATUS_INVALID_DEVICE_STATE
+# define STATUS_INVALID_DEVICE_STATE ((NTSTATUS) 0xC0000184L)
+#endif
+
+#ifndef STATUS_IO_DEVICE_ERROR
+# define STATUS_IO_DEVICE_ERROR ((NTSTATUS) 0xC0000185L)
+#endif
+
+#ifndef STATUS_DEVICE_PROTOCOL_ERROR
+# define STATUS_DEVICE_PROTOCOL_ERROR ((NTSTATUS) 0xC0000186L)
+#endif
+
+#ifndef STATUS_BACKUP_CONTROLLER
+# define STATUS_BACKUP_CONTROLLER ((NTSTATUS) 0xC0000187L)
+#endif
+
+#ifndef STATUS_LOG_FILE_FULL
+# define STATUS_LOG_FILE_FULL ((NTSTATUS) 0xC0000188L)
+#endif
+
+#ifndef STATUS_TOO_LATE
+# define STATUS_TOO_LATE ((NTSTATUS) 0xC0000189L)
+#endif
+
+#ifndef STATUS_NO_TRUST_LSA_SECRET
+# define STATUS_NO_TRUST_LSA_SECRET ((NTSTATUS) 0xC000018AL)
+#endif
+
+#ifndef STATUS_NO_TRUST_SAM_ACCOUNT
+# define STATUS_NO_TRUST_SAM_ACCOUNT ((NTSTATUS) 0xC000018BL)
+#endif
+
+#ifndef STATUS_TRUSTED_DOMAIN_FAILURE
+# define STATUS_TRUSTED_DOMAIN_FAILURE ((NTSTATUS) 0xC000018CL)
+#endif
+
+#ifndef STATUS_TRUSTED_RELATIONSHIP_FAILURE
+# define STATUS_TRUSTED_RELATIONSHIP_FAILURE ((NTSTATUS) 0xC000018DL)
+#endif
+
+#ifndef STATUS_EVENTLOG_FILE_CORRUPT
+# define STATUS_EVENTLOG_FILE_CORRUPT ((NTSTATUS) 0xC000018EL)
+#endif
+
+#ifndef STATUS_EVENTLOG_CANT_START
+# define STATUS_EVENTLOG_CANT_START ((NTSTATUS) 0xC000018FL)
+#endif
+
+#ifndef STATUS_TRUST_FAILURE
+# define STATUS_TRUST_FAILURE ((NTSTATUS) 0xC0000190L)
+#endif
+
+#ifndef STATUS_MUTANT_LIMIT_EXCEEDED
+# define STATUS_MUTANT_LIMIT_EXCEEDED ((NTSTATUS) 0xC0000191L)
+#endif
+
+#ifndef STATUS_NETLOGON_NOT_STARTED
+# define STATUS_NETLOGON_NOT_STARTED ((NTSTATUS) 0xC0000192L)
+#endif
+
+#ifndef STATUS_ACCOUNT_EXPIRED
+# define STATUS_ACCOUNT_EXPIRED ((NTSTATUS) 0xC0000193L)
+#endif
+
+#ifndef STATUS_POSSIBLE_DEADLOCK
+# define STATUS_POSSIBLE_DEADLOCK ((NTSTATUS) 0xC0000194L)
+#endif
+
+#ifndef STATUS_NETWORK_CREDENTIAL_CONFLICT
+# define STATUS_NETWORK_CREDENTIAL_CONFLICT ((NTSTATUS) 0xC0000195L)
+#endif
+
+#ifndef STATUS_REMOTE_SESSION_LIMIT
+# define STATUS_REMOTE_SESSION_LIMIT ((NTSTATUS) 0xC0000196L)
+#endif
+
+#ifndef STATUS_EVENTLOG_FILE_CHANGED
+# define STATUS_EVENTLOG_FILE_CHANGED ((NTSTATUS) 0xC0000197L)
+#endif
+
+#ifndef STATUS_NOLOGON_INTERDOMAIN_TRUST_ACCOUNT
+# define STATUS_NOLOGON_INTERDOMAIN_TRUST_ACCOUNT ((NTSTATUS) 0xC0000198L)
+#endif
+
+#ifndef STATUS_NOLOGON_WORKSTATION_TRUST_ACCOUNT
+# define STATUS_NOLOGON_WORKSTATION_TRUST_ACCOUNT ((NTSTATUS) 0xC0000199L)
+#endif
+
+#ifndef STATUS_NOLOGON_SERVER_TRUST_ACCOUNT
+# define STATUS_NOLOGON_SERVER_TRUST_ACCOUNT ((NTSTATUS) 0xC000019AL)
+#endif
+
+#ifndef STATUS_DOMAIN_TRUST_INCONSISTENT
+# define STATUS_DOMAIN_TRUST_INCONSISTENT ((NTSTATUS) 0xC000019BL)
+#endif
+
+#ifndef STATUS_FS_DRIVER_REQUIRED
+# define STATUS_FS_DRIVER_REQUIRED ((NTSTATUS) 0xC000019CL)
+#endif
+
+#ifndef STATUS_IMAGE_ALREADY_LOADED_AS_DLL
+# define STATUS_IMAGE_ALREADY_LOADED_AS_DLL ((NTSTATUS) 0xC000019DL)
+#endif
+
+#ifndef STATUS_INCOMPATIBLE_WITH_GLOBAL_SHORT_NAME_REGISTRY_SETTING
+# define STATUS_INCOMPATIBLE_WITH_GLOBAL_SHORT_NAME_REGISTRY_SETTING ((NTSTATUS) 0xC000019EL)
+#endif
+
+#ifndef STATUS_SHORT_NAMES_NOT_ENABLED_ON_VOLUME
+# define STATUS_SHORT_NAMES_NOT_ENABLED_ON_VOLUME ((NTSTATUS) 0xC000019FL)
+#endif
+
+#ifndef STATUS_SECURITY_STREAM_IS_INCONSISTENT
+# define STATUS_SECURITY_STREAM_IS_INCONSISTENT ((NTSTATUS) 0xC00001A0L)
+#endif
+
+#ifndef STATUS_INVALID_LOCK_RANGE
+# define STATUS_INVALID_LOCK_RANGE ((NTSTATUS) 0xC00001A1L)
+#endif
+
+#ifndef STATUS_INVALID_ACE_CONDITION
+# define STATUS_INVALID_ACE_CONDITION ((NTSTATUS) 0xC00001A2L)
+#endif
+
+#ifndef STATUS_IMAGE_SUBSYSTEM_NOT_PRESENT
+# define STATUS_IMAGE_SUBSYSTEM_NOT_PRESENT ((NTSTATUS) 0xC00001A3L)
+#endif
+
+#ifndef STATUS_NOTIFICATION_GUID_ALREADY_DEFINED
+# define STATUS_NOTIFICATION_GUID_ALREADY_DEFINED ((NTSTATUS) 0xC00001A4L)
+#endif
+
+#ifndef STATUS_NETWORK_OPEN_RESTRICTION
+# define STATUS_NETWORK_OPEN_RESTRICTION ((NTSTATUS) 0xC0000201L)
+#endif
+
+#ifndef STATUS_NO_USER_SESSION_KEY
+# define STATUS_NO_USER_SESSION_KEY ((NTSTATUS) 0xC0000202L)
+#endif
+
+#ifndef STATUS_USER_SESSION_DELETED
+# define STATUS_USER_SESSION_DELETED ((NTSTATUS) 0xC0000203L)
+#endif
+
+#ifndef STATUS_RESOURCE_LANG_NOT_FOUND
+# define STATUS_RESOURCE_LANG_NOT_FOUND ((NTSTATUS) 0xC0000204L)
+#endif
+
+#ifndef STATUS_INSUFF_SERVER_RESOURCES
+# define STATUS_INSUFF_SERVER_RESOURCES ((NTSTATUS) 0xC0000205L)
+#endif
+
+#ifndef STATUS_INVALID_BUFFER_SIZE
+# define STATUS_INVALID_BUFFER_SIZE ((NTSTATUS) 0xC0000206L)
+#endif
+
+#ifndef STATUS_INVALID_ADDRESS_COMPONENT
+# define STATUS_INVALID_ADDRESS_COMPONENT ((NTSTATUS) 0xC0000207L)
+#endif
+
+#ifndef STATUS_INVALID_ADDRESS_WILDCARD
+# define STATUS_INVALID_ADDRESS_WILDCARD ((NTSTATUS) 0xC0000208L)
+#endif
+
+#ifndef STATUS_TOO_MANY_ADDRESSES
+# define STATUS_TOO_MANY_ADDRESSES ((NTSTATUS) 0xC0000209L)
+#endif
+
+#ifndef STATUS_ADDRESS_ALREADY_EXISTS
+# define STATUS_ADDRESS_ALREADY_EXISTS ((NTSTATUS) 0xC000020AL)
+#endif
+
+#ifndef STATUS_ADDRESS_CLOSED
+# define STATUS_ADDRESS_CLOSED ((NTSTATUS) 0xC000020BL)
+#endif
+
+#ifndef STATUS_CONNECTION_DISCONNECTED
+# define STATUS_CONNECTION_DISCONNECTED ((NTSTATUS) 0xC000020CL)
+#endif
+
+#ifndef STATUS_CONNECTION_RESET
+# define STATUS_CONNECTION_RESET ((NTSTATUS) 0xC000020DL)
+#endif
+
+#ifndef STATUS_TOO_MANY_NODES
+# define STATUS_TOO_MANY_NODES ((NTSTATUS) 0xC000020EL)
+#endif
+
+#ifndef STATUS_TRANSACTION_ABORTED
+# define STATUS_TRANSACTION_ABORTED ((NTSTATUS) 0xC000020FL)
+#endif
+
+#ifndef STATUS_TRANSACTION_TIMED_OUT
+# define STATUS_TRANSACTION_TIMED_OUT ((NTSTATUS) 0xC0000210L)
+#endif
+
+#ifndef STATUS_TRANSACTION_NO_RELEASE
+# define STATUS_TRANSACTION_NO_RELEASE ((NTSTATUS) 0xC0000211L)
+#endif
+
+#ifndef STATUS_TRANSACTION_NO_MATCH
+# define STATUS_TRANSACTION_NO_MATCH ((NTSTATUS) 0xC0000212L)
+#endif
+
+#ifndef STATUS_TRANSACTION_RESPONDED
+# define STATUS_TRANSACTION_RESPONDED ((NTSTATUS) 0xC0000213L)
+#endif
+
+#ifndef STATUS_TRANSACTION_INVALID_ID
+# define STATUS_TRANSACTION_INVALID_ID ((NTSTATUS) 0xC0000214L)
+#endif
+
+#ifndef STATUS_TRANSACTION_INVALID_TYPE
+# define STATUS_TRANSACTION_INVALID_TYPE ((NTSTATUS) 0xC0000215L)
+#endif
+
+#ifndef STATUS_NOT_SERVER_SESSION
+# define STATUS_NOT_SERVER_SESSION ((NTSTATUS) 0xC0000216L)
+#endif
+
+#ifndef STATUS_NOT_CLIENT_SESSION
+# define STATUS_NOT_CLIENT_SESSION ((NTSTATUS) 0xC0000217L)
+#endif
+
+#ifndef STATUS_CANNOT_LOAD_REGISTRY_FILE
+# define STATUS_CANNOT_LOAD_REGISTRY_FILE ((NTSTATUS) 0xC0000218L)
+#endif
+
+#ifndef STATUS_DEBUG_ATTACH_FAILED
+# define STATUS_DEBUG_ATTACH_FAILED ((NTSTATUS) 0xC0000219L)
+#endif
+
+#ifndef STATUS_SYSTEM_PROCESS_TERMINATED
+# define STATUS_SYSTEM_PROCESS_TERMINATED ((NTSTATUS) 0xC000021AL)
+#endif
+
+#ifndef STATUS_DATA_NOT_ACCEPTED
+# define STATUS_DATA_NOT_ACCEPTED ((NTSTATUS) 0xC000021BL)
+#endif
+
+#ifndef STATUS_NO_BROWSER_SERVERS_FOUND
+# define STATUS_NO_BROWSER_SERVERS_FOUND ((NTSTATUS) 0xC000021CL)
+#endif
+
+#ifndef STATUS_VDM_HARD_ERROR
+# define STATUS_VDM_HARD_ERROR ((NTSTATUS) 0xC000021DL)
+#endif
+
+#ifndef STATUS_DRIVER_CANCEL_TIMEOUT
+# define STATUS_DRIVER_CANCEL_TIMEOUT ((NTSTATUS) 0xC000021EL)
+#endif
+
+#ifndef STATUS_REPLY_MESSAGE_MISMATCH
+# define STATUS_REPLY_MESSAGE_MISMATCH ((NTSTATUS) 0xC000021FL)
+#endif
+
+#ifndef STATUS_MAPPED_ALIGNMENT
+# define STATUS_MAPPED_ALIGNMENT ((NTSTATUS) 0xC0000220L)
+#endif
+
+#ifndef STATUS_IMAGE_CHECKSUM_MISMATCH
+# define STATUS_IMAGE_CHECKSUM_MISMATCH ((NTSTATUS) 0xC0000221L)
+#endif
+
+#ifndef STATUS_LOST_WRITEBEHIND_DATA
+# define STATUS_LOST_WRITEBEHIND_DATA ((NTSTATUS) 0xC0000222L)
+#endif
+
+#ifndef STATUS_CLIENT_SERVER_PARAMETERS_INVALID
+# define STATUS_CLIENT_SERVER_PARAMETERS_INVALID ((NTSTATUS) 0xC0000223L)
+#endif
+
+#ifndef STATUS_PASSWORD_MUST_CHANGE
+# define STATUS_PASSWORD_MUST_CHANGE ((NTSTATUS) 0xC0000224L)
+#endif
+
+#ifndef STATUS_NOT_FOUND
+# define STATUS_NOT_FOUND ((NTSTATUS) 0xC0000225L)
+#endif
+
+#ifndef STATUS_NOT_TINY_STREAM
+# define STATUS_NOT_TINY_STREAM ((NTSTATUS) 0xC0000226L)
+#endif
+
+#ifndef STATUS_RECOVERY_FAILURE
+# define STATUS_RECOVERY_FAILURE ((NTSTATUS) 0xC0000227L)
+#endif
+
+#ifndef STATUS_STACK_OVERFLOW_READ
+# define STATUS_STACK_OVERFLOW_READ ((NTSTATUS) 0xC0000228L)
+#endif
+
+#ifndef STATUS_FAIL_CHECK
+# define STATUS_FAIL_CHECK ((NTSTATUS) 0xC0000229L)
+#endif
+
+#ifndef STATUS_DUPLICATE_OBJECTID
+# define STATUS_DUPLICATE_OBJECTID ((NTSTATUS) 0xC000022AL)
+#endif
+
+#ifndef STATUS_OBJECTID_EXISTS
+# define STATUS_OBJECTID_EXISTS ((NTSTATUS) 0xC000022BL)
+#endif
+
+#ifndef STATUS_CONVERT_TO_LARGE
+# define STATUS_CONVERT_TO_LARGE ((NTSTATUS) 0xC000022CL)
+#endif
+
+#ifndef STATUS_RETRY
+# define STATUS_RETRY ((NTSTATUS) 0xC000022DL)
+#endif
+
+#ifndef STATUS_FOUND_OUT_OF_SCOPE
+# define STATUS_FOUND_OUT_OF_SCOPE ((NTSTATUS) 0xC000022EL)
+#endif
+
+#ifndef STATUS_ALLOCATE_BUCKET
+# define STATUS_ALLOCATE_BUCKET ((NTSTATUS) 0xC000022FL)
+#endif
+
+#ifndef STATUS_PROPSET_NOT_FOUND
+# define STATUS_PROPSET_NOT_FOUND ((NTSTATUS) 0xC0000230L)
+#endif
+
+#ifndef STATUS_MARSHALL_OVERFLOW
+# define STATUS_MARSHALL_OVERFLOW ((NTSTATUS) 0xC0000231L)
+#endif
+
+#ifndef STATUS_INVALID_VARIANT
+# define STATUS_INVALID_VARIANT ((NTSTATUS) 0xC0000232L)
+#endif
+
+#ifndef STATUS_DOMAIN_CONTROLLER_NOT_FOUND
+# define STATUS_DOMAIN_CONTROLLER_NOT_FOUND ((NTSTATUS) 0xC0000233L)
+#endif
+
+#ifndef STATUS_ACCOUNT_LOCKED_OUT
+# define STATUS_ACCOUNT_LOCKED_OUT ((NTSTATUS) 0xC0000234L)
+#endif
+
+#ifndef STATUS_HANDLE_NOT_CLOSABLE
+# define STATUS_HANDLE_NOT_CLOSABLE ((NTSTATUS) 0xC0000235L)
+#endif
+
+#ifndef STATUS_CONNECTION_REFUSED
+# define STATUS_CONNECTION_REFUSED ((NTSTATUS) 0xC0000236L)
+#endif
+
+#ifndef STATUS_GRACEFUL_DISCONNECT
+# define STATUS_GRACEFUL_DISCONNECT ((NTSTATUS) 0xC0000237L)
+#endif
+
+#ifndef STATUS_ADDRESS_ALREADY_ASSOCIATED
+# define STATUS_ADDRESS_ALREADY_ASSOCIATED ((NTSTATUS) 0xC0000238L)
+#endif
+
+#ifndef STATUS_ADDRESS_NOT_ASSOCIATED
+# define STATUS_ADDRESS_NOT_ASSOCIATED ((NTSTATUS) 0xC0000239L)
+#endif
+
+#ifndef STATUS_CONNECTION_INVALID
+# define STATUS_CONNECTION_INVALID ((NTSTATUS) 0xC000023AL)
+#endif
+
+#ifndef STATUS_CONNECTION_ACTIVE
+# define STATUS_CONNECTION_ACTIVE ((NTSTATUS) 0xC000023BL)
+#endif
+
+#ifndef STATUS_NETWORK_UNREACHABLE
+# define STATUS_NETWORK_UNREACHABLE ((NTSTATUS) 0xC000023CL)
+#endif
+
+#ifndef STATUS_HOST_UNREACHABLE
+# define STATUS_HOST_UNREACHABLE ((NTSTATUS) 0xC000023DL)
+#endif
+
+#ifndef STATUS_PROTOCOL_UNREACHABLE
+# define STATUS_PROTOCOL_UNREACHABLE ((NTSTATUS) 0xC000023EL)
+#endif
+
+#ifndef STATUS_PORT_UNREACHABLE
+# define STATUS_PORT_UNREACHABLE ((NTSTATUS) 0xC000023FL)
+#endif
+
+#ifndef STATUS_REQUEST_ABORTED
+# define STATUS_REQUEST_ABORTED ((NTSTATUS) 0xC0000240L)
+#endif
+
+#ifndef STATUS_CONNECTION_ABORTED
+# define STATUS_CONNECTION_ABORTED ((NTSTATUS) 0xC0000241L)
+#endif
+
+#ifndef STATUS_BAD_COMPRESSION_BUFFER
+# define STATUS_BAD_COMPRESSION_BUFFER ((NTSTATUS) 0xC0000242L)
+#endif
+
+#ifndef STATUS_USER_MAPPED_FILE
+# define STATUS_USER_MAPPED_FILE ((NTSTATUS) 0xC0000243L)
+#endif
+
+#ifndef STATUS_AUDIT_FAILED
+# define STATUS_AUDIT_FAILED ((NTSTATUS) 0xC0000244L)
+#endif
+
+#ifndef STATUS_TIMER_RESOLUTION_NOT_SET
+# define STATUS_TIMER_RESOLUTION_NOT_SET ((NTSTATUS) 0xC0000245L)
+#endif
+
+#ifndef STATUS_CONNECTION_COUNT_LIMIT
+# define STATUS_CONNECTION_COUNT_LIMIT ((NTSTATUS) 0xC0000246L)
+#endif
+
+#ifndef STATUS_LOGIN_TIME_RESTRICTION
+# define STATUS_LOGIN_TIME_RESTRICTION ((NTSTATUS) 0xC0000247L)
+#endif
+
+#ifndef STATUS_LOGIN_WKSTA_RESTRICTION
+# define STATUS_LOGIN_WKSTA_RESTRICTION ((NTSTATUS) 0xC0000248L)
+#endif
+
+#ifndef STATUS_IMAGE_MP_UP_MISMATCH
+# define STATUS_IMAGE_MP_UP_MISMATCH ((NTSTATUS) 0xC0000249L)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_LOGON_INFO
+# define STATUS_INSUFFICIENT_LOGON_INFO ((NTSTATUS) 0xC0000250L)
+#endif
+
+#ifndef STATUS_BAD_DLL_ENTRYPOINT
+# define STATUS_BAD_DLL_ENTRYPOINT ((NTSTATUS) 0xC0000251L)
+#endif
+
+#ifndef STATUS_BAD_SERVICE_ENTRYPOINT
+# define STATUS_BAD_SERVICE_ENTRYPOINT ((NTSTATUS) 0xC0000252L)
+#endif
+
+#ifndef STATUS_LPC_REPLY_LOST
+# define STATUS_LPC_REPLY_LOST ((NTSTATUS) 0xC0000253L)
+#endif
+
+#ifndef STATUS_IP_ADDRESS_CONFLICT1
+# define STATUS_IP_ADDRESS_CONFLICT1 ((NTSTATUS) 0xC0000254L)
+#endif
+
+#ifndef STATUS_IP_ADDRESS_CONFLICT2
+# define STATUS_IP_ADDRESS_CONFLICT2 ((NTSTATUS) 0xC0000255L)
+#endif
+
+#ifndef STATUS_REGISTRY_QUOTA_LIMIT
+# define STATUS_REGISTRY_QUOTA_LIMIT ((NTSTATUS) 0xC0000256L)
+#endif
+
+#ifndef STATUS_PATH_NOT_COVERED
+# define STATUS_PATH_NOT_COVERED ((NTSTATUS) 0xC0000257L)
+#endif
+
+#ifndef STATUS_NO_CALLBACK_ACTIVE
+# define STATUS_NO_CALLBACK_ACTIVE ((NTSTATUS) 0xC0000258L)
+#endif
+
+#ifndef STATUS_LICENSE_QUOTA_EXCEEDED
+# define STATUS_LICENSE_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000259L)
+#endif
+
+#ifndef STATUS_PWD_TOO_SHORT
+# define STATUS_PWD_TOO_SHORT ((NTSTATUS) 0xC000025AL)
+#endif
+
+#ifndef STATUS_PWD_TOO_RECENT
+# define STATUS_PWD_TOO_RECENT ((NTSTATUS) 0xC000025BL)
+#endif
+
+#ifndef STATUS_PWD_HISTORY_CONFLICT
+# define STATUS_PWD_HISTORY_CONFLICT ((NTSTATUS) 0xC000025CL)
+#endif
+
+#ifndef STATUS_PLUGPLAY_NO_DEVICE
+# define STATUS_PLUGPLAY_NO_DEVICE ((NTSTATUS) 0xC000025EL)
+#endif
+
+#ifndef STATUS_UNSUPPORTED_COMPRESSION
+# define STATUS_UNSUPPORTED_COMPRESSION ((NTSTATUS) 0xC000025FL)
+#endif
+
+#ifndef STATUS_INVALID_HW_PROFILE
+# define STATUS_INVALID_HW_PROFILE ((NTSTATUS) 0xC0000260L)
+#endif
+
+#ifndef STATUS_INVALID_PLUGPLAY_DEVICE_PATH
+# define STATUS_INVALID_PLUGPLAY_DEVICE_PATH ((NTSTATUS) 0xC0000261L)
+#endif
+
+#ifndef STATUS_DRIVER_ORDINAL_NOT_FOUND
+# define STATUS_DRIVER_ORDINAL_NOT_FOUND ((NTSTATUS) 0xC0000262L)
+#endif
+
+#ifndef STATUS_DRIVER_ENTRYPOINT_NOT_FOUND
+# define STATUS_DRIVER_ENTRYPOINT_NOT_FOUND ((NTSTATUS) 0xC0000263L)
+#endif
+
+#ifndef STATUS_RESOURCE_NOT_OWNED
+# define STATUS_RESOURCE_NOT_OWNED ((NTSTATUS) 0xC0000264L)
+#endif
+
+#ifndef STATUS_TOO_MANY_LINKS
+# define STATUS_TOO_MANY_LINKS ((NTSTATUS) 0xC0000265L)
+#endif
+
+#ifndef STATUS_QUOTA_LIST_INCONSISTENT
+# define STATUS_QUOTA_LIST_INCONSISTENT ((NTSTATUS) 0xC0000266L)
+#endif
+
+#ifndef STATUS_FILE_IS_OFFLINE
+# define STATUS_FILE_IS_OFFLINE ((NTSTATUS) 0xC0000267L)
+#endif
+
+#ifndef STATUS_EVALUATION_EXPIRATION
+# define STATUS_EVALUATION_EXPIRATION ((NTSTATUS) 0xC0000268L)
+#endif
+
+#ifndef STATUS_ILLEGAL_DLL_RELOCATION
+# define STATUS_ILLEGAL_DLL_RELOCATION ((NTSTATUS) 0xC0000269L)
+#endif
+
+#ifndef STATUS_LICENSE_VIOLATION
+# define STATUS_LICENSE_VIOLATION ((NTSTATUS) 0xC000026AL)
+#endif
+
+#ifndef STATUS_DLL_INIT_FAILED_LOGOFF
+# define STATUS_DLL_INIT_FAILED_LOGOFF ((NTSTATUS) 0xC000026BL)
+#endif
+
+#ifndef STATUS_DRIVER_UNABLE_TO_LOAD
+# define STATUS_DRIVER_UNABLE_TO_LOAD ((NTSTATUS) 0xC000026CL)
+#endif
+
+#ifndef STATUS_DFS_UNAVAILABLE
+# define STATUS_DFS_UNAVAILABLE ((NTSTATUS) 0xC000026DL)
+#endif
+
+#ifndef STATUS_VOLUME_DISMOUNTED
+# define STATUS_VOLUME_DISMOUNTED ((NTSTATUS) 0xC000026EL)
+#endif
+
+#ifndef STATUS_WX86_INTERNAL_ERROR
+# define STATUS_WX86_INTERNAL_ERROR ((NTSTATUS) 0xC000026FL)
+#endif
+
+#ifndef STATUS_WX86_FLOAT_STACK_CHECK
+# define STATUS_WX86_FLOAT_STACK_CHECK ((NTSTATUS) 0xC0000270L)
+#endif
+
+#ifndef STATUS_VALIDATE_CONTINUE
+# define STATUS_VALIDATE_CONTINUE ((NTSTATUS) 0xC0000271L)
+#endif
+
+#ifndef STATUS_NO_MATCH
+# define STATUS_NO_MATCH ((NTSTATUS) 0xC0000272L)
+#endif
+
+#ifndef STATUS_NO_MORE_MATCHES
+# define STATUS_NO_MORE_MATCHES ((NTSTATUS) 0xC0000273L)
+#endif
+
+#ifndef STATUS_NOT_A_REPARSE_POINT
+# define STATUS_NOT_A_REPARSE_POINT ((NTSTATUS) 0xC0000275L)
+#endif
+
+#ifndef STATUS_IO_REPARSE_TAG_INVALID
+# define STATUS_IO_REPARSE_TAG_INVALID ((NTSTATUS) 0xC0000276L)
+#endif
+
+#ifndef STATUS_IO_REPARSE_TAG_MISMATCH
+# define STATUS_IO_REPARSE_TAG_MISMATCH ((NTSTATUS) 0xC0000277L)
+#endif
+
+#ifndef STATUS_IO_REPARSE_DATA_INVALID
+# define STATUS_IO_REPARSE_DATA_INVALID ((NTSTATUS) 0xC0000278L)
+#endif
+
+#ifndef STATUS_IO_REPARSE_TAG_NOT_HANDLED
+# define STATUS_IO_REPARSE_TAG_NOT_HANDLED ((NTSTATUS) 0xC0000279L)
+#endif
+
+#ifndef STATUS_REPARSE_POINT_NOT_RESOLVED
+# define STATUS_REPARSE_POINT_NOT_RESOLVED ((NTSTATUS) 0xC0000280L)
+#endif
+
+#ifndef STATUS_DIRECTORY_IS_A_REPARSE_POINT
+# define STATUS_DIRECTORY_IS_A_REPARSE_POINT ((NTSTATUS) 0xC0000281L)
+#endif
+
+#ifndef STATUS_RANGE_LIST_CONFLICT
+# define STATUS_RANGE_LIST_CONFLICT ((NTSTATUS) 0xC0000282L)
+#endif
+
+#ifndef STATUS_SOURCE_ELEMENT_EMPTY
+# define STATUS_SOURCE_ELEMENT_EMPTY ((NTSTATUS) 0xC0000283L)
+#endif
+
+#ifndef STATUS_DESTINATION_ELEMENT_FULL
+# define STATUS_DESTINATION_ELEMENT_FULL ((NTSTATUS) 0xC0000284L)
+#endif
+
+#ifndef STATUS_ILLEGAL_ELEMENT_ADDRESS
+# define STATUS_ILLEGAL_ELEMENT_ADDRESS ((NTSTATUS) 0xC0000285L)
+#endif
+
+#ifndef STATUS_MAGAZINE_NOT_PRESENT
+# define STATUS_MAGAZINE_NOT_PRESENT ((NTSTATUS) 0xC0000286L)
+#endif
+
+#ifndef STATUS_REINITIALIZATION_NEEDED
+# define STATUS_REINITIALIZATION_NEEDED ((NTSTATUS) 0xC0000287L)
+#endif
+
+#ifndef STATUS_DEVICE_REQUIRES_CLEANING
+# define STATUS_DEVICE_REQUIRES_CLEANING ((NTSTATUS) 0x80000288L)
+#endif
+
+#ifndef STATUS_DEVICE_DOOR_OPEN
+# define STATUS_DEVICE_DOOR_OPEN ((NTSTATUS) 0x80000289L)
+#endif
+
+#ifndef STATUS_ENCRYPTION_FAILED
+# define STATUS_ENCRYPTION_FAILED ((NTSTATUS) 0xC000028AL)
+#endif
+
+#ifndef STATUS_DECRYPTION_FAILED
+# define STATUS_DECRYPTION_FAILED ((NTSTATUS) 0xC000028BL)
+#endif
+
+#ifndef STATUS_RANGE_NOT_FOUND
+# define STATUS_RANGE_NOT_FOUND ((NTSTATUS) 0xC000028CL)
+#endif
+
+#ifndef STATUS_NO_RECOVERY_POLICY
+# define STATUS_NO_RECOVERY_POLICY ((NTSTATUS) 0xC000028DL)
+#endif
+
+#ifndef STATUS_NO_EFS
+# define STATUS_NO_EFS ((NTSTATUS) 0xC000028EL)
+#endif
+
+#ifndef STATUS_WRONG_EFS
+# define STATUS_WRONG_EFS ((NTSTATUS) 0xC000028FL)
+#endif
+
+#ifndef STATUS_NO_USER_KEYS
+# define STATUS_NO_USER_KEYS ((NTSTATUS) 0xC0000290L)
+#endif
+
+#ifndef STATUS_FILE_NOT_ENCRYPTED
+# define STATUS_FILE_NOT_ENCRYPTED ((NTSTATUS) 0xC0000291L)
+#endif
+
+#ifndef STATUS_NOT_EXPORT_FORMAT
+# define STATUS_NOT_EXPORT_FORMAT ((NTSTATUS) 0xC0000292L)
+#endif
+
+#ifndef STATUS_FILE_ENCRYPTED
+# define STATUS_FILE_ENCRYPTED ((NTSTATUS) 0xC0000293L)
+#endif
+
+#ifndef STATUS_WAKE_SYSTEM
+# define STATUS_WAKE_SYSTEM ((NTSTATUS) 0x40000294L)
+#endif
+
+#ifndef STATUS_WMI_GUID_NOT_FOUND
+# define STATUS_WMI_GUID_NOT_FOUND ((NTSTATUS) 0xC0000295L)
+#endif
+
+#ifndef STATUS_WMI_INSTANCE_NOT_FOUND
+# define STATUS_WMI_INSTANCE_NOT_FOUND ((NTSTATUS) 0xC0000296L)
+#endif
+
+#ifndef STATUS_WMI_ITEMID_NOT_FOUND
+# define STATUS_WMI_ITEMID_NOT_FOUND ((NTSTATUS) 0xC0000297L)
+#endif
+
+#ifndef STATUS_WMI_TRY_AGAIN
+# define STATUS_WMI_TRY_AGAIN ((NTSTATUS) 0xC0000298L)
+#endif
+
+#ifndef STATUS_SHARED_POLICY
+# define STATUS_SHARED_POLICY ((NTSTATUS) 0xC0000299L)
+#endif
+
+#ifndef STATUS_POLICY_OBJECT_NOT_FOUND
+# define STATUS_POLICY_OBJECT_NOT_FOUND ((NTSTATUS) 0xC000029AL)
+#endif
+
+#ifndef STATUS_POLICY_ONLY_IN_DS
+# define STATUS_POLICY_ONLY_IN_DS ((NTSTATUS) 0xC000029BL)
+#endif
+
+#ifndef STATUS_VOLUME_NOT_UPGRADED
+# define STATUS_VOLUME_NOT_UPGRADED ((NTSTATUS) 0xC000029CL)
+#endif
+
+#ifndef STATUS_REMOTE_STORAGE_NOT_ACTIVE
+# define STATUS_REMOTE_STORAGE_NOT_ACTIVE ((NTSTATUS) 0xC000029DL)
+#endif
+
+#ifndef STATUS_REMOTE_STORAGE_MEDIA_ERROR
+# define STATUS_REMOTE_STORAGE_MEDIA_ERROR ((NTSTATUS) 0xC000029EL)
+#endif
+
+#ifndef STATUS_NO_TRACKING_SERVICE
+# define STATUS_NO_TRACKING_SERVICE ((NTSTATUS) 0xC000029FL)
+#endif
+
+#ifndef STATUS_SERVER_SID_MISMATCH
+# define STATUS_SERVER_SID_MISMATCH ((NTSTATUS) 0xC00002A0L)
+#endif
+
+#ifndef STATUS_DS_NO_ATTRIBUTE_OR_VALUE
+# define STATUS_DS_NO_ATTRIBUTE_OR_VALUE ((NTSTATUS) 0xC00002A1L)
+#endif
+
+#ifndef STATUS_DS_INVALID_ATTRIBUTE_SYNTAX
+# define STATUS_DS_INVALID_ATTRIBUTE_SYNTAX ((NTSTATUS) 0xC00002A2L)
+#endif
+
+#ifndef STATUS_DS_ATTRIBUTE_TYPE_UNDEFINED
+# define STATUS_DS_ATTRIBUTE_TYPE_UNDEFINED ((NTSTATUS) 0xC00002A3L)
+#endif
+
+#ifndef STATUS_DS_ATTRIBUTE_OR_VALUE_EXISTS
+# define STATUS_DS_ATTRIBUTE_OR_VALUE_EXISTS ((NTSTATUS) 0xC00002A4L)
+#endif
+
+#ifndef STATUS_DS_BUSY
+# define STATUS_DS_BUSY ((NTSTATUS) 0xC00002A5L)
+#endif
+
+#ifndef STATUS_DS_UNAVAILABLE
+# define STATUS_DS_UNAVAILABLE ((NTSTATUS) 0xC00002A6L)
+#endif
+
+#ifndef STATUS_DS_NO_RIDS_ALLOCATED
+# define STATUS_DS_NO_RIDS_ALLOCATED ((NTSTATUS) 0xC00002A7L)
+#endif
+
+#ifndef STATUS_DS_NO_MORE_RIDS
+# define STATUS_DS_NO_MORE_RIDS ((NTSTATUS) 0xC00002A8L)
+#endif
+
+#ifndef STATUS_DS_INCORRECT_ROLE_OWNER
+# define STATUS_DS_INCORRECT_ROLE_OWNER ((NTSTATUS) 0xC00002A9L)
+#endif
+
+#ifndef STATUS_DS_RIDMGR_INIT_ERROR
+# define STATUS_DS_RIDMGR_INIT_ERROR ((NTSTATUS) 0xC00002AAL)
+#endif
+
+#ifndef STATUS_DS_OBJ_CLASS_VIOLATION
+# define STATUS_DS_OBJ_CLASS_VIOLATION ((NTSTATUS) 0xC00002ABL)
+#endif
+
+#ifndef STATUS_DS_CANT_ON_NON_LEAF
+# define STATUS_DS_CANT_ON_NON_LEAF ((NTSTATUS) 0xC00002ACL)
+#endif
+
+#ifndef STATUS_DS_CANT_ON_RDN
+# define STATUS_DS_CANT_ON_RDN ((NTSTATUS) 0xC00002ADL)
+#endif
+
+#ifndef STATUS_DS_CANT_MOD_OBJ_CLASS
+# define STATUS_DS_CANT_MOD_OBJ_CLASS ((NTSTATUS) 0xC00002AEL)
+#endif
+
+#ifndef STATUS_DS_CROSS_DOM_MOVE_FAILED
+# define STATUS_DS_CROSS_DOM_MOVE_FAILED ((NTSTATUS) 0xC00002AFL)
+#endif
+
+#ifndef STATUS_DS_GC_NOT_AVAILABLE
+# define STATUS_DS_GC_NOT_AVAILABLE ((NTSTATUS) 0xC00002B0L)
+#endif
+
+#ifndef STATUS_DIRECTORY_SERVICE_REQUIRED
+# define STATUS_DIRECTORY_SERVICE_REQUIRED ((NTSTATUS) 0xC00002B1L)
+#endif
+
+#ifndef STATUS_REPARSE_ATTRIBUTE_CONFLICT
+# define STATUS_REPARSE_ATTRIBUTE_CONFLICT ((NTSTATUS) 0xC00002B2L)
+#endif
+
+#ifndef STATUS_CANT_ENABLE_DENY_ONLY
+# define STATUS_CANT_ENABLE_DENY_ONLY ((NTSTATUS) 0xC00002B3L)
+#endif
+
+#ifndef STATUS_FLOAT_MULTIPLE_FAULTS
+# define STATUS_FLOAT_MULTIPLE_FAULTS ((NTSTATUS) 0xC00002B4L)
+#endif
+
+#ifndef STATUS_FLOAT_MULTIPLE_TRAPS
+# define STATUS_FLOAT_MULTIPLE_TRAPS ((NTSTATUS) 0xC00002B5L)
+#endif
+
+#ifndef STATUS_DEVICE_REMOVED
+# define STATUS_DEVICE_REMOVED ((NTSTATUS) 0xC00002B6L)
+#endif
+
+#ifndef STATUS_JOURNAL_DELETE_IN_PROGRESS
+# define STATUS_JOURNAL_DELETE_IN_PROGRESS ((NTSTATUS) 0xC00002B7L)
+#endif
+
+#ifndef STATUS_JOURNAL_NOT_ACTIVE
+# define STATUS_JOURNAL_NOT_ACTIVE ((NTSTATUS) 0xC00002B8L)
+#endif
+
+#ifndef STATUS_NOINTERFACE
+# define STATUS_NOINTERFACE ((NTSTATUS) 0xC00002B9L)
+#endif
+
+#ifndef STATUS_DS_ADMIN_LIMIT_EXCEEDED
+# define STATUS_DS_ADMIN_LIMIT_EXCEEDED ((NTSTATUS) 0xC00002C1L)
+#endif
+
+#ifndef STATUS_DRIVER_FAILED_SLEEP
+# define STATUS_DRIVER_FAILED_SLEEP ((NTSTATUS) 0xC00002C2L)
+#endif
+
+#ifndef STATUS_MUTUAL_AUTHENTICATION_FAILED
+# define STATUS_MUTUAL_AUTHENTICATION_FAILED ((NTSTATUS) 0xC00002C3L)
+#endif
+
+#ifndef STATUS_CORRUPT_SYSTEM_FILE
+# define STATUS_CORRUPT_SYSTEM_FILE ((NTSTATUS) 0xC00002C4L)
+#endif
+
+#ifndef STATUS_DATATYPE_MISALIGNMENT_ERROR
+# define STATUS_DATATYPE_MISALIGNMENT_ERROR ((NTSTATUS) 0xC00002C5L)
+#endif
+
+#ifndef STATUS_WMI_READ_ONLY
+# define STATUS_WMI_READ_ONLY ((NTSTATUS) 0xC00002C6L)
+#endif
+
+#ifndef STATUS_WMI_SET_FAILURE
+# define STATUS_WMI_SET_FAILURE ((NTSTATUS) 0xC00002C7L)
+#endif
+
+#ifndef STATUS_COMMITMENT_MINIMUM
+# define STATUS_COMMITMENT_MINIMUM ((NTSTATUS) 0xC00002C8L)
+#endif
+
+#ifndef STATUS_REG_NAT_CONSUMPTION
+# define STATUS_REG_NAT_CONSUMPTION ((NTSTATUS) 0xC00002C9L)
+#endif
+
+#ifndef STATUS_TRANSPORT_FULL
+# define STATUS_TRANSPORT_FULL ((NTSTATUS) 0xC00002CAL)
+#endif
+
+#ifndef STATUS_DS_SAM_INIT_FAILURE
+# define STATUS_DS_SAM_INIT_FAILURE ((NTSTATUS) 0xC00002CBL)
+#endif
+
+#ifndef STATUS_ONLY_IF_CONNECTED
+# define STATUS_ONLY_IF_CONNECTED ((NTSTATUS) 0xC00002CCL)
+#endif
+
+#ifndef STATUS_DS_SENSITIVE_GROUP_VIOLATION
+# define STATUS_DS_SENSITIVE_GROUP_VIOLATION ((NTSTATUS) 0xC00002CDL)
+#endif
+
+#ifndef STATUS_PNP_RESTART_ENUMERATION
+# define STATUS_PNP_RESTART_ENUMERATION ((NTSTATUS) 0xC00002CEL)
+#endif
+
+#ifndef STATUS_JOURNAL_ENTRY_DELETED
+# define STATUS_JOURNAL_ENTRY_DELETED ((NTSTATUS) 0xC00002CFL)
+#endif
+
+#ifndef STATUS_DS_CANT_MOD_PRIMARYGROUPID
+# define STATUS_DS_CANT_MOD_PRIMARYGROUPID ((NTSTATUS) 0xC00002D0L)
+#endif
+
+#ifndef STATUS_SYSTEM_IMAGE_BAD_SIGNATURE
+# define STATUS_SYSTEM_IMAGE_BAD_SIGNATURE ((NTSTATUS) 0xC00002D1L)
+#endif
+
+#ifndef STATUS_PNP_REBOOT_REQUIRED
+# define STATUS_PNP_REBOOT_REQUIRED ((NTSTATUS) 0xC00002D2L)
+#endif
+
+#ifndef STATUS_POWER_STATE_INVALID
+# define STATUS_POWER_STATE_INVALID ((NTSTATUS) 0xC00002D3L)
+#endif
+
+#ifndef STATUS_DS_INVALID_GROUP_TYPE
+# define STATUS_DS_INVALID_GROUP_TYPE ((NTSTATUS) 0xC00002D4L)
+#endif
+
+#ifndef STATUS_DS_NO_NEST_GLOBALGROUP_IN_MIXEDDOMAIN
+# define STATUS_DS_NO_NEST_GLOBALGROUP_IN_MIXEDDOMAIN ((NTSTATUS) 0xC00002D5L)
+#endif
+
+#ifndef STATUS_DS_NO_NEST_LOCALGROUP_IN_MIXEDDOMAIN
+# define STATUS_DS_NO_NEST_LOCALGROUP_IN_MIXEDDOMAIN ((NTSTATUS) 0xC00002D6L)
+#endif
+
+#ifndef STATUS_DS_GLOBAL_CANT_HAVE_LOCAL_MEMBER
+# define STATUS_DS_GLOBAL_CANT_HAVE_LOCAL_MEMBER ((NTSTATUS) 0xC00002D7L)
+#endif
+
+#ifndef STATUS_DS_GLOBAL_CANT_HAVE_UNIVERSAL_MEMBER
+# define STATUS_DS_GLOBAL_CANT_HAVE_UNIVERSAL_MEMBER ((NTSTATUS) 0xC00002D8L)
+#endif
+
+#ifndef STATUS_DS_UNIVERSAL_CANT_HAVE_LOCAL_MEMBER
+# define STATUS_DS_UNIVERSAL_CANT_HAVE_LOCAL_MEMBER ((NTSTATUS) 0xC00002D9L)
+#endif
+
+#ifndef STATUS_DS_GLOBAL_CANT_HAVE_CROSSDOMAIN_MEMBER
+# define STATUS_DS_GLOBAL_CANT_HAVE_CROSSDOMAIN_MEMBER ((NTSTATUS) 0xC00002DAL)
+#endif
+
+#ifndef STATUS_DS_LOCAL_CANT_HAVE_CROSSDOMAIN_LOCAL_MEMBER
+# define STATUS_DS_LOCAL_CANT_HAVE_CROSSDOMAIN_LOCAL_MEMBER ((NTSTATUS) 0xC00002DBL)
+#endif
+
+#ifndef STATUS_DS_HAVE_PRIMARY_MEMBERS
+# define STATUS_DS_HAVE_PRIMARY_MEMBERS ((NTSTATUS) 0xC00002DCL)
+#endif
+
+#ifndef STATUS_WMI_NOT_SUPPORTED
+# define STATUS_WMI_NOT_SUPPORTED ((NTSTATUS) 0xC00002DDL)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_POWER
+# define STATUS_INSUFFICIENT_POWER ((NTSTATUS) 0xC00002DEL)
+#endif
+
+#ifndef STATUS_SAM_NEED_BOOTKEY_PASSWORD
+# define STATUS_SAM_NEED_BOOTKEY_PASSWORD ((NTSTATUS) 0xC00002DFL)
+#endif
+
+#ifndef STATUS_SAM_NEED_BOOTKEY_FLOPPY
+# define STATUS_SAM_NEED_BOOTKEY_FLOPPY ((NTSTATUS) 0xC00002E0L)
+#endif
+
+#ifndef STATUS_DS_CANT_START
+# define STATUS_DS_CANT_START ((NTSTATUS) 0xC00002E1L)
+#endif
+
+#ifndef STATUS_DS_INIT_FAILURE
+# define STATUS_DS_INIT_FAILURE ((NTSTATUS) 0xC00002E2L)
+#endif
+
+#ifndef STATUS_SAM_INIT_FAILURE
+# define STATUS_SAM_INIT_FAILURE ((NTSTATUS) 0xC00002E3L)
+#endif
+
+#ifndef STATUS_DS_GC_REQUIRED
+# define STATUS_DS_GC_REQUIRED ((NTSTATUS) 0xC00002E4L)
+#endif
+
+#ifndef STATUS_DS_LOCAL_MEMBER_OF_LOCAL_ONLY
+# define STATUS_DS_LOCAL_MEMBER_OF_LOCAL_ONLY ((NTSTATUS) 0xC00002E5L)
+#endif
+
+#ifndef STATUS_DS_NO_FPO_IN_UNIVERSAL_GROUPS
+# define STATUS_DS_NO_FPO_IN_UNIVERSAL_GROUPS ((NTSTATUS) 0xC00002E6L)
+#endif
+
+#ifndef STATUS_DS_MACHINE_ACCOUNT_QUOTA_EXCEEDED
+# define STATUS_DS_MACHINE_ACCOUNT_QUOTA_EXCEEDED ((NTSTATUS) 0xC00002E7L)
+#endif
+
+#ifndef STATUS_MULTIPLE_FAULT_VIOLATION
+# define STATUS_MULTIPLE_FAULT_VIOLATION ((NTSTATUS) 0xC00002E8L)
+#endif
+
+#ifndef STATUS_CURRENT_DOMAIN_NOT_ALLOWED
+# define STATUS_CURRENT_DOMAIN_NOT_ALLOWED ((NTSTATUS) 0xC00002E9L)
+#endif
+
+#ifndef STATUS_CANNOT_MAKE
+# define STATUS_CANNOT_MAKE ((NTSTATUS) 0xC00002EAL)
+#endif
+
+#ifndef STATUS_SYSTEM_SHUTDOWN
+# define STATUS_SYSTEM_SHUTDOWN ((NTSTATUS) 0xC00002EBL)
+#endif
+
+#ifndef STATUS_DS_INIT_FAILURE_CONSOLE
+# define STATUS_DS_INIT_FAILURE_CONSOLE ((NTSTATUS) 0xC00002ECL)
+#endif
+
+#ifndef STATUS_DS_SAM_INIT_FAILURE_CONSOLE
+# define STATUS_DS_SAM_INIT_FAILURE_CONSOLE ((NTSTATUS) 0xC00002EDL)
+#endif
+
+#ifndef STATUS_UNFINISHED_CONTEXT_DELETED
+# define STATUS_UNFINISHED_CONTEXT_DELETED ((NTSTATUS) 0xC00002EEL)
+#endif
+
+#ifndef STATUS_NO_TGT_REPLY
+# define STATUS_NO_TGT_REPLY ((NTSTATUS) 0xC00002EFL)
+#endif
+
+#ifndef STATUS_OBJECTID_NOT_FOUND
+# define STATUS_OBJECTID_NOT_FOUND ((NTSTATUS) 0xC00002F0L)
+#endif
+
+#ifndef STATUS_NO_IP_ADDRESSES
+# define STATUS_NO_IP_ADDRESSES ((NTSTATUS) 0xC00002F1L)
+#endif
+
+#ifndef STATUS_WRONG_CREDENTIAL_HANDLE
+# define STATUS_WRONG_CREDENTIAL_HANDLE ((NTSTATUS) 0xC00002F2L)
+#endif
+
+#ifndef STATUS_CRYPTO_SYSTEM_INVALID
+# define STATUS_CRYPTO_SYSTEM_INVALID ((NTSTATUS) 0xC00002F3L)
+#endif
+
+#ifndef STATUS_MAX_REFERRALS_EXCEEDED
+# define STATUS_MAX_REFERRALS_EXCEEDED ((NTSTATUS) 0xC00002F4L)
+#endif
+
+#ifndef STATUS_MUST_BE_KDC
+# define STATUS_MUST_BE_KDC ((NTSTATUS) 0xC00002F5L)
+#endif
+
+#ifndef STATUS_STRONG_CRYPTO_NOT_SUPPORTED
+# define STATUS_STRONG_CRYPTO_NOT_SUPPORTED ((NTSTATUS) 0xC00002F6L)
+#endif
+
+#ifndef STATUS_TOO_MANY_PRINCIPALS
+# define STATUS_TOO_MANY_PRINCIPALS ((NTSTATUS) 0xC00002F7L)
+#endif
+
+#ifndef STATUS_NO_PA_DATA
+# define STATUS_NO_PA_DATA ((NTSTATUS) 0xC00002F8L)
+#endif
+
+#ifndef STATUS_PKINIT_NAME_MISMATCH
+# define STATUS_PKINIT_NAME_MISMATCH ((NTSTATUS) 0xC00002F9L)
+#endif
+
+#ifndef STATUS_SMARTCARD_LOGON_REQUIRED
+# define STATUS_SMARTCARD_LOGON_REQUIRED ((NTSTATUS) 0xC00002FAL)
+#endif
+
+#ifndef STATUS_KDC_INVALID_REQUEST
+# define STATUS_KDC_INVALID_REQUEST ((NTSTATUS) 0xC00002FBL)
+#endif
+
+#ifndef STATUS_KDC_UNABLE_TO_REFER
+# define STATUS_KDC_UNABLE_TO_REFER ((NTSTATUS) 0xC00002FCL)
+#endif
+
+#ifndef STATUS_KDC_UNKNOWN_ETYPE
+# define STATUS_KDC_UNKNOWN_ETYPE ((NTSTATUS) 0xC00002FDL)
+#endif
+
+#ifndef STATUS_SHUTDOWN_IN_PROGRESS
+# define STATUS_SHUTDOWN_IN_PROGRESS ((NTSTATUS) 0xC00002FEL)
+#endif
+
+#ifndef STATUS_SERVER_SHUTDOWN_IN_PROGRESS
+# define STATUS_SERVER_SHUTDOWN_IN_PROGRESS ((NTSTATUS) 0xC00002FFL)
+#endif
+
+#ifndef STATUS_NOT_SUPPORTED_ON_SBS
+# define STATUS_NOT_SUPPORTED_ON_SBS ((NTSTATUS) 0xC0000300L)
+#endif
+
+#ifndef STATUS_WMI_GUID_DISCONNECTED
+# define STATUS_WMI_GUID_DISCONNECTED ((NTSTATUS) 0xC0000301L)
+#endif
+
+#ifndef STATUS_WMI_ALREADY_DISABLED
+# define STATUS_WMI_ALREADY_DISABLED ((NTSTATUS) 0xC0000302L)
+#endif
+
+#ifndef STATUS_WMI_ALREADY_ENABLED
+# define STATUS_WMI_ALREADY_ENABLED ((NTSTATUS) 0xC0000303L)
+#endif
+
+#ifndef STATUS_MFT_TOO_FRAGMENTED
+# define STATUS_MFT_TOO_FRAGMENTED ((NTSTATUS) 0xC0000304L)
+#endif
+
+#ifndef STATUS_COPY_PROTECTION_FAILURE
+# define STATUS_COPY_PROTECTION_FAILURE ((NTSTATUS) 0xC0000305L)
+#endif
+
+#ifndef STATUS_CSS_AUTHENTICATION_FAILURE
+# define STATUS_CSS_AUTHENTICATION_FAILURE ((NTSTATUS) 0xC0000306L)
+#endif
+
+#ifndef STATUS_CSS_KEY_NOT_PRESENT
+# define STATUS_CSS_KEY_NOT_PRESENT ((NTSTATUS) 0xC0000307L)
+#endif
+
+#ifndef STATUS_CSS_KEY_NOT_ESTABLISHED
+# define STATUS_CSS_KEY_NOT_ESTABLISHED ((NTSTATUS) 0xC0000308L)
+#endif
+
+#ifndef STATUS_CSS_SCRAMBLED_SECTOR
+# define STATUS_CSS_SCRAMBLED_SECTOR ((NTSTATUS) 0xC0000309L)
+#endif
+
+#ifndef STATUS_CSS_REGION_MISMATCH
+# define STATUS_CSS_REGION_MISMATCH ((NTSTATUS) 0xC000030AL)
+#endif
+
+#ifndef STATUS_CSS_RESETS_EXHAUSTED
+# define STATUS_CSS_RESETS_EXHAUSTED ((NTSTATUS) 0xC000030BL)
+#endif
+
+#ifndef STATUS_PKINIT_FAILURE
+# define STATUS_PKINIT_FAILURE ((NTSTATUS) 0xC0000320L)
+#endif
+
+#ifndef STATUS_SMARTCARD_SUBSYSTEM_FAILURE
+# define STATUS_SMARTCARD_SUBSYSTEM_FAILURE ((NTSTATUS) 0xC0000321L)
+#endif
+
+#ifndef STATUS_NO_KERB_KEY
+# define STATUS_NO_KERB_KEY ((NTSTATUS) 0xC0000322L)
+#endif
+
+#ifndef STATUS_HOST_DOWN
+# define STATUS_HOST_DOWN ((NTSTATUS) 0xC0000350L)
+#endif
+
+#ifndef STATUS_UNSUPPORTED_PREAUTH
+# define STATUS_UNSUPPORTED_PREAUTH ((NTSTATUS) 0xC0000351L)
+#endif
+
+#ifndef STATUS_EFS_ALG_BLOB_TOO_BIG
+# define STATUS_EFS_ALG_BLOB_TOO_BIG ((NTSTATUS) 0xC0000352L)
+#endif
+
+#ifndef STATUS_PORT_NOT_SET
+# define STATUS_PORT_NOT_SET ((NTSTATUS) 0xC0000353L)
+#endif
+
+#ifndef STATUS_DEBUGGER_INACTIVE
+# define STATUS_DEBUGGER_INACTIVE ((NTSTATUS) 0xC0000354L)
+#endif
+
+#ifndef STATUS_DS_VERSION_CHECK_FAILURE
+# define STATUS_DS_VERSION_CHECK_FAILURE ((NTSTATUS) 0xC0000355L)
+#endif
+
+#ifndef STATUS_AUDITING_DISABLED
+# define STATUS_AUDITING_DISABLED ((NTSTATUS) 0xC0000356L)
+#endif
+
+#ifndef STATUS_PRENT4_MACHINE_ACCOUNT
+# define STATUS_PRENT4_MACHINE_ACCOUNT ((NTSTATUS) 0xC0000357L)
+#endif
+
+#ifndef STATUS_DS_AG_CANT_HAVE_UNIVERSAL_MEMBER
+# define STATUS_DS_AG_CANT_HAVE_UNIVERSAL_MEMBER ((NTSTATUS) 0xC0000358L)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_WIN_32
+# define STATUS_INVALID_IMAGE_WIN_32 ((NTSTATUS) 0xC0000359L)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_WIN_64
+# define STATUS_INVALID_IMAGE_WIN_64 ((NTSTATUS) 0xC000035AL)
+#endif
+
+#ifndef STATUS_BAD_BINDINGS
+# define STATUS_BAD_BINDINGS ((NTSTATUS) 0xC000035BL)
+#endif
+
+#ifndef STATUS_NETWORK_SESSION_EXPIRED
+# define STATUS_NETWORK_SESSION_EXPIRED ((NTSTATUS) 0xC000035CL)
+#endif
+
+#ifndef STATUS_APPHELP_BLOCK
+# define STATUS_APPHELP_BLOCK ((NTSTATUS) 0xC000035DL)
+#endif
+
+#ifndef STATUS_ALL_SIDS_FILTERED
+# define STATUS_ALL_SIDS_FILTERED ((NTSTATUS) 0xC000035EL)
+#endif
+
+#ifndef STATUS_NOT_SAFE_MODE_DRIVER
+# define STATUS_NOT_SAFE_MODE_DRIVER ((NTSTATUS) 0xC000035FL)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_DEFAULT
+# define STATUS_ACCESS_DISABLED_BY_POLICY_DEFAULT ((NTSTATUS) 0xC0000361L)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_PATH
+# define STATUS_ACCESS_DISABLED_BY_POLICY_PATH ((NTSTATUS) 0xC0000362L)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_PUBLISHER
+# define STATUS_ACCESS_DISABLED_BY_POLICY_PUBLISHER ((NTSTATUS) 0xC0000363L)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_BY_POLICY_OTHER
+# define STATUS_ACCESS_DISABLED_BY_POLICY_OTHER ((NTSTATUS) 0xC0000364L)
+#endif
+
+#ifndef STATUS_FAILED_DRIVER_ENTRY
+# define STATUS_FAILED_DRIVER_ENTRY ((NTSTATUS) 0xC0000365L)
+#endif
+
+#ifndef STATUS_DEVICE_ENUMERATION_ERROR
+# define STATUS_DEVICE_ENUMERATION_ERROR ((NTSTATUS) 0xC0000366L)
+#endif
+
+#ifndef STATUS_MOUNT_POINT_NOT_RESOLVED
+# define STATUS_MOUNT_POINT_NOT_RESOLVED ((NTSTATUS) 0xC0000368L)
+#endif
+
+#ifndef STATUS_INVALID_DEVICE_OBJECT_PARAMETER
+# define STATUS_INVALID_DEVICE_OBJECT_PARAMETER ((NTSTATUS) 0xC0000369L)
+#endif
+
+#ifndef STATUS_MCA_OCCURED
+# define STATUS_MCA_OCCURED ((NTSTATUS) 0xC000036AL)
+#endif
+
+#ifndef STATUS_DRIVER_BLOCKED_CRITICAL
+# define STATUS_DRIVER_BLOCKED_CRITICAL ((NTSTATUS) 0xC000036BL)
+#endif
+
+#ifndef STATUS_DRIVER_BLOCKED
+# define STATUS_DRIVER_BLOCKED ((NTSTATUS) 0xC000036CL)
+#endif
+
+#ifndef STATUS_DRIVER_DATABASE_ERROR
+# define STATUS_DRIVER_DATABASE_ERROR ((NTSTATUS) 0xC000036DL)
+#endif
+
+#ifndef STATUS_SYSTEM_HIVE_TOO_LARGE
+# define STATUS_SYSTEM_HIVE_TOO_LARGE ((NTSTATUS) 0xC000036EL)
+#endif
+
+#ifndef STATUS_INVALID_IMPORT_OF_NON_DLL
+# define STATUS_INVALID_IMPORT_OF_NON_DLL ((NTSTATUS) 0xC000036FL)
+#endif
+
+#ifndef STATUS_DS_SHUTTING_DOWN
+# define STATUS_DS_SHUTTING_DOWN ((NTSTATUS) 0x40000370L)
+#endif
+
+#ifndef STATUS_NO_SECRETS
+# define STATUS_NO_SECRETS ((NTSTATUS) 0xC0000371L)
+#endif
+
+#ifndef STATUS_ACCESS_DISABLED_NO_SAFER_UI_BY_POLICY
+# define STATUS_ACCESS_DISABLED_NO_SAFER_UI_BY_POLICY ((NTSTATUS) 0xC0000372L)
+#endif
+
+#ifndef STATUS_FAILED_STACK_SWITCH
+# define STATUS_FAILED_STACK_SWITCH ((NTSTATUS) 0xC0000373L)
+#endif
+
+#ifndef STATUS_HEAP_CORRUPTION
+# define STATUS_HEAP_CORRUPTION ((NTSTATUS) 0xC0000374L)
+#endif
+
+#ifndef STATUS_SMARTCARD_WRONG_PIN
+# define STATUS_SMARTCARD_WRONG_PIN ((NTSTATUS) 0xC0000380L)
+#endif
+
+#ifndef STATUS_SMARTCARD_CARD_BLOCKED
+# define STATUS_SMARTCARD_CARD_BLOCKED ((NTSTATUS) 0xC0000381L)
+#endif
+
+#ifndef STATUS_SMARTCARD_CARD_NOT_AUTHENTICATED
+# define STATUS_SMARTCARD_CARD_NOT_AUTHENTICATED ((NTSTATUS) 0xC0000382L)
+#endif
+
+#ifndef STATUS_SMARTCARD_NO_CARD
+# define STATUS_SMARTCARD_NO_CARD ((NTSTATUS) 0xC0000383L)
+#endif
+
+#ifndef STATUS_SMARTCARD_NO_KEY_CONTAINER
+# define STATUS_SMARTCARD_NO_KEY_CONTAINER ((NTSTATUS) 0xC0000384L)
+#endif
+
+#ifndef STATUS_SMARTCARD_NO_CERTIFICATE
+# define STATUS_SMARTCARD_NO_CERTIFICATE ((NTSTATUS) 0xC0000385L)
+#endif
+
+#ifndef STATUS_SMARTCARD_NO_KEYSET
+# define STATUS_SMARTCARD_NO_KEYSET ((NTSTATUS) 0xC0000386L)
+#endif
+
+#ifndef STATUS_SMARTCARD_IO_ERROR
+# define STATUS_SMARTCARD_IO_ERROR ((NTSTATUS) 0xC0000387L)
+#endif
+
+#ifndef STATUS_DOWNGRADE_DETECTED
+# define STATUS_DOWNGRADE_DETECTED ((NTSTATUS) 0xC0000388L)
+#endif
+
+#ifndef STATUS_SMARTCARD_CERT_REVOKED
+# define STATUS_SMARTCARD_CERT_REVOKED ((NTSTATUS) 0xC0000389L)
+#endif
+
+#ifndef STATUS_ISSUING_CA_UNTRUSTED
+# define STATUS_ISSUING_CA_UNTRUSTED ((NTSTATUS) 0xC000038AL)
+#endif
+
+#ifndef STATUS_REVOCATION_OFFLINE_C
+# define STATUS_REVOCATION_OFFLINE_C ((NTSTATUS) 0xC000038BL)
+#endif
+
+#ifndef STATUS_PKINIT_CLIENT_FAILURE
+# define STATUS_PKINIT_CLIENT_FAILURE ((NTSTATUS) 0xC000038CL)
+#endif
+
+#ifndef STATUS_SMARTCARD_CERT_EXPIRED
+# define STATUS_SMARTCARD_CERT_EXPIRED ((NTSTATUS) 0xC000038DL)
+#endif
+
+#ifndef STATUS_DRIVER_FAILED_PRIOR_UNLOAD
+# define STATUS_DRIVER_FAILED_PRIOR_UNLOAD ((NTSTATUS) 0xC000038EL)
+#endif
+
+#ifndef STATUS_SMARTCARD_SILENT_CONTEXT
+# define STATUS_SMARTCARD_SILENT_CONTEXT ((NTSTATUS) 0xC000038FL)
+#endif
+
+#ifndef STATUS_PER_USER_TRUST_QUOTA_EXCEEDED
+# define STATUS_PER_USER_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000401L)
+#endif
+
+#ifndef STATUS_ALL_USER_TRUST_QUOTA_EXCEEDED
+# define STATUS_ALL_USER_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000402L)
+#endif
+
+#ifndef STATUS_USER_DELETE_TRUST_QUOTA_EXCEEDED
+# define STATUS_USER_DELETE_TRUST_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000403L)
+#endif
+
+#ifndef STATUS_DS_NAME_NOT_UNIQUE
+# define STATUS_DS_NAME_NOT_UNIQUE ((NTSTATUS) 0xC0000404L)
+#endif
+
+#ifndef STATUS_DS_DUPLICATE_ID_FOUND
+# define STATUS_DS_DUPLICATE_ID_FOUND ((NTSTATUS) 0xC0000405L)
+#endif
+
+#ifndef STATUS_DS_GROUP_CONVERSION_ERROR
+# define STATUS_DS_GROUP_CONVERSION_ERROR ((NTSTATUS) 0xC0000406L)
+#endif
+
+#ifndef STATUS_VOLSNAP_PREPARE_HIBERNATE
+# define STATUS_VOLSNAP_PREPARE_HIBERNATE ((NTSTATUS) 0xC0000407L)
+#endif
+
+#ifndef STATUS_USER2USER_REQUIRED
+# define STATUS_USER2USER_REQUIRED ((NTSTATUS) 0xC0000408L)
+#endif
+
+#ifndef STATUS_STACK_BUFFER_OVERRUN
+# define STATUS_STACK_BUFFER_OVERRUN ((NTSTATUS) 0xC0000409L)
+#endif
+
+#ifndef STATUS_NO_S4U_PROT_SUPPORT
+# define STATUS_NO_S4U_PROT_SUPPORT ((NTSTATUS) 0xC000040AL)
+#endif
+
+#ifndef STATUS_CROSSREALM_DELEGATION_FAILURE
+# define STATUS_CROSSREALM_DELEGATION_FAILURE ((NTSTATUS) 0xC000040BL)
+#endif
+
+#ifndef STATUS_REVOCATION_OFFLINE_KDC
+# define STATUS_REVOCATION_OFFLINE_KDC ((NTSTATUS) 0xC000040CL)
+#endif
+
+#ifndef STATUS_ISSUING_CA_UNTRUSTED_KDC
+# define STATUS_ISSUING_CA_UNTRUSTED_KDC ((NTSTATUS) 0xC000040DL)
+#endif
+
+#ifndef STATUS_KDC_CERT_EXPIRED
+# define STATUS_KDC_CERT_EXPIRED ((NTSTATUS) 0xC000040EL)
+#endif
+
+#ifndef STATUS_KDC_CERT_REVOKED
+# define STATUS_KDC_CERT_REVOKED ((NTSTATUS) 0xC000040FL)
+#endif
+
+#ifndef STATUS_PARAMETER_QUOTA_EXCEEDED
+# define STATUS_PARAMETER_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000410L)
+#endif
+
+#ifndef STATUS_HIBERNATION_FAILURE
+# define STATUS_HIBERNATION_FAILURE ((NTSTATUS) 0xC0000411L)
+#endif
+
+#ifndef STATUS_DELAY_LOAD_FAILED
+# define STATUS_DELAY_LOAD_FAILED ((NTSTATUS) 0xC0000412L)
+#endif
+
+#ifndef STATUS_AUTHENTICATION_FIREWALL_FAILED
+# define STATUS_AUTHENTICATION_FIREWALL_FAILED ((NTSTATUS) 0xC0000413L)
+#endif
+
+#ifndef STATUS_VDM_DISALLOWED
+# define STATUS_VDM_DISALLOWED ((NTSTATUS) 0xC0000414L)
+#endif
+
+#ifndef STATUS_HUNG_DISPLAY_DRIVER_THREAD
+# define STATUS_HUNG_DISPLAY_DRIVER_THREAD ((NTSTATUS) 0xC0000415L)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_RESOURCE_FOR_SPECIFIED_SHARED_SECTION_SIZE
+# define STATUS_INSUFFICIENT_RESOURCE_FOR_SPECIFIED_SHARED_SECTION_SIZE ((NTSTATUS) 0xC0000416L)
+#endif
+
+#ifndef STATUS_INVALID_CRUNTIME_PARAMETER
+# define STATUS_INVALID_CRUNTIME_PARAMETER ((NTSTATUS) 0xC0000417L)
+#endif
+
+#ifndef STATUS_NTLM_BLOCKED
+# define STATUS_NTLM_BLOCKED ((NTSTATUS) 0xC0000418L)
+#endif
+
+#ifndef STATUS_DS_SRC_SID_EXISTS_IN_FOREST
+# define STATUS_DS_SRC_SID_EXISTS_IN_FOREST ((NTSTATUS) 0xC0000419L)
+#endif
+
+#ifndef STATUS_DS_DOMAIN_NAME_EXISTS_IN_FOREST
+# define STATUS_DS_DOMAIN_NAME_EXISTS_IN_FOREST ((NTSTATUS) 0xC000041AL)
+#endif
+
+#ifndef STATUS_DS_FLAT_NAME_EXISTS_IN_FOREST
+# define STATUS_DS_FLAT_NAME_EXISTS_IN_FOREST ((NTSTATUS) 0xC000041BL)
+#endif
+
+#ifndef STATUS_INVALID_USER_PRINCIPAL_NAME
+# define STATUS_INVALID_USER_PRINCIPAL_NAME ((NTSTATUS) 0xC000041CL)
+#endif
+
+#ifndef STATUS_FATAL_USER_CALLBACK_EXCEPTION
+# define STATUS_FATAL_USER_CALLBACK_EXCEPTION ((NTSTATUS) 0xC000041DL)
+#endif
+
+#ifndef STATUS_ASSERTION_FAILURE
+# define STATUS_ASSERTION_FAILURE ((NTSTATUS) 0xC0000420L)
+#endif
+
+#ifndef STATUS_VERIFIER_STOP
+# define STATUS_VERIFIER_STOP ((NTSTATUS) 0xC0000421L)
+#endif
+
+#ifndef STATUS_CALLBACK_POP_STACK
+# define STATUS_CALLBACK_POP_STACK ((NTSTATUS) 0xC0000423L)
+#endif
+
+#ifndef STATUS_INCOMPATIBLE_DRIVER_BLOCKED
+# define STATUS_INCOMPATIBLE_DRIVER_BLOCKED ((NTSTATUS) 0xC0000424L)
+#endif
+
+#ifndef STATUS_HIVE_UNLOADED
+# define STATUS_HIVE_UNLOADED ((NTSTATUS) 0xC0000425L)
+#endif
+
+#ifndef STATUS_COMPRESSION_DISABLED
+# define STATUS_COMPRESSION_DISABLED ((NTSTATUS) 0xC0000426L)
+#endif
+
+#ifndef STATUS_FILE_SYSTEM_LIMITATION
+# define STATUS_FILE_SYSTEM_LIMITATION ((NTSTATUS) 0xC0000427L)
+#endif
+
+#ifndef STATUS_INVALID_IMAGE_HASH
+# define STATUS_INVALID_IMAGE_HASH ((NTSTATUS) 0xC0000428L)
+#endif
+
+#ifndef STATUS_NOT_CAPABLE
+# define STATUS_NOT_CAPABLE ((NTSTATUS) 0xC0000429L)
+#endif
+
+#ifndef STATUS_REQUEST_OUT_OF_SEQUENCE
+# define STATUS_REQUEST_OUT_OF_SEQUENCE ((NTSTATUS) 0xC000042AL)
+#endif
+
+#ifndef STATUS_IMPLEMENTATION_LIMIT
+# define STATUS_IMPLEMENTATION_LIMIT ((NTSTATUS) 0xC000042BL)
+#endif
+
+#ifndef STATUS_ELEVATION_REQUIRED
+# define STATUS_ELEVATION_REQUIRED ((NTSTATUS) 0xC000042CL)
+#endif
+
+#ifndef STATUS_NO_SECURITY_CONTEXT
+# define STATUS_NO_SECURITY_CONTEXT ((NTSTATUS) 0xC000042DL)
+#endif
+
+#ifndef STATUS_PKU2U_CERT_FAILURE
+# define STATUS_PKU2U_CERT_FAILURE ((NTSTATUS) 0xC000042FL)
+#endif
+
+#ifndef STATUS_BEYOND_VDL
+# define STATUS_BEYOND_VDL ((NTSTATUS) 0xC0000432L)
+#endif
+
+#ifndef STATUS_ENCOUNTERED_WRITE_IN_PROGRESS
+# define STATUS_ENCOUNTERED_WRITE_IN_PROGRESS ((NTSTATUS) 0xC0000433L)
+#endif
+
+#ifndef STATUS_PTE_CHANGED
+# define STATUS_PTE_CHANGED ((NTSTATUS) 0xC0000434L)
+#endif
+
+#ifndef STATUS_PURGE_FAILED
+# define STATUS_PURGE_FAILED ((NTSTATUS) 0xC0000435L)
+#endif
+
+#ifndef STATUS_CRED_REQUIRES_CONFIRMATION
+# define STATUS_CRED_REQUIRES_CONFIRMATION ((NTSTATUS) 0xC0000440L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_INVALID_SERVER_RESPONSE
+# define STATUS_CS_ENCRYPTION_INVALID_SERVER_RESPONSE ((NTSTATUS) 0xC0000441L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_UNSUPPORTED_SERVER
+# define STATUS_CS_ENCRYPTION_UNSUPPORTED_SERVER ((NTSTATUS) 0xC0000442L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_EXISTING_ENCRYPTED_FILE
+# define STATUS_CS_ENCRYPTION_EXISTING_ENCRYPTED_FILE ((NTSTATUS) 0xC0000443L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_NEW_ENCRYPTED_FILE
+# define STATUS_CS_ENCRYPTION_NEW_ENCRYPTED_FILE ((NTSTATUS) 0xC0000444L)
+#endif
+
+#ifndef STATUS_CS_ENCRYPTION_FILE_NOT_CSE
+# define STATUS_CS_ENCRYPTION_FILE_NOT_CSE ((NTSTATUS) 0xC0000445L)
+#endif
+
+#ifndef STATUS_INVALID_LABEL
+# define STATUS_INVALID_LABEL ((NTSTATUS) 0xC0000446L)
+#endif
+
+#ifndef STATUS_DRIVER_PROCESS_TERMINATED
+# define STATUS_DRIVER_PROCESS_TERMINATED ((NTSTATUS) 0xC0000450L)
+#endif
+
+#ifndef STATUS_AMBIGUOUS_SYSTEM_DEVICE
+# define STATUS_AMBIGUOUS_SYSTEM_DEVICE ((NTSTATUS) 0xC0000451L)
+#endif
+
+#ifndef STATUS_SYSTEM_DEVICE_NOT_FOUND
+# define STATUS_SYSTEM_DEVICE_NOT_FOUND ((NTSTATUS) 0xC0000452L)
+#endif
+
+#ifndef STATUS_RESTART_BOOT_APPLICATION
+# define STATUS_RESTART_BOOT_APPLICATION ((NTSTATUS) 0xC0000453L)
+#endif
+
+#ifndef STATUS_INSUFFICIENT_NVRAM_RESOURCES
+# define STATUS_INSUFFICIENT_NVRAM_RESOURCES ((NTSTATUS) 0xC0000454L)
+#endif
+
+#ifndef STATUS_INVALID_TASK_NAME
+# define STATUS_INVALID_TASK_NAME ((NTSTATUS) 0xC0000500L)
+#endif
+
+#ifndef STATUS_INVALID_TASK_INDEX
+# define STATUS_INVALID_TASK_INDEX ((NTSTATUS) 0xC0000501L)
+#endif
+
+#ifndef STATUS_THREAD_ALREADY_IN_TASK
+# define STATUS_THREAD_ALREADY_IN_TASK ((NTSTATUS) 0xC0000502L)
+#endif
+
+#ifndef STATUS_CALLBACK_BYPASS
+# define STATUS_CALLBACK_BYPASS ((NTSTATUS) 0xC0000503L)
+#endif
+
+#ifndef STATUS_FAIL_FAST_EXCEPTION
+# define STATUS_FAIL_FAST_EXCEPTION ((NTSTATUS) 0xC0000602L)
+#endif
+
+#ifndef STATUS_IMAGE_CERT_REVOKED
+# define STATUS_IMAGE_CERT_REVOKED ((NTSTATUS) 0xC0000603L)
+#endif
+
+#ifndef STATUS_PORT_CLOSED
+# define STATUS_PORT_CLOSED ((NTSTATUS) 0xC0000700L)
+#endif
+
+#ifndef STATUS_MESSAGE_LOST
+# define STATUS_MESSAGE_LOST ((NTSTATUS) 0xC0000701L)
+#endif
+
+#ifndef STATUS_INVALID_MESSAGE
+# define STATUS_INVALID_MESSAGE ((NTSTATUS) 0xC0000702L)
+#endif
+
+#ifndef STATUS_REQUEST_CANCELED
+# define STATUS_REQUEST_CANCELED ((NTSTATUS) 0xC0000703L)
+#endif
+
+#ifndef STATUS_RECURSIVE_DISPATCH
+# define STATUS_RECURSIVE_DISPATCH ((NTSTATUS) 0xC0000704L)
+#endif
+
+#ifndef STATUS_LPC_RECEIVE_BUFFER_EXPECTED
+# define STATUS_LPC_RECEIVE_BUFFER_EXPECTED ((NTSTATUS) 0xC0000705L)
+#endif
+
+#ifndef STATUS_LPC_INVALID_CONNECTION_USAGE
+# define STATUS_LPC_INVALID_CONNECTION_USAGE ((NTSTATUS) 0xC0000706L)
+#endif
+
+#ifndef STATUS_LPC_REQUESTS_NOT_ALLOWED
+# define STATUS_LPC_REQUESTS_NOT_ALLOWED ((NTSTATUS) 0xC0000707L)
+#endif
+
+#ifndef STATUS_RESOURCE_IN_USE
+# define STATUS_RESOURCE_IN_USE ((NTSTATUS) 0xC0000708L)
+#endif
+
+#ifndef STATUS_HARDWARE_MEMORY_ERROR
+# define STATUS_HARDWARE_MEMORY_ERROR ((NTSTATUS) 0xC0000709L)
+#endif
+
+#ifndef STATUS_THREADPOOL_HANDLE_EXCEPTION
+# define STATUS_THREADPOOL_HANDLE_EXCEPTION ((NTSTATUS) 0xC000070AL)
+#endif
+
+#ifndef STATUS_THREADPOOL_SET_EVENT_ON_COMPLETION_FAILED
+# define STATUS_THREADPOOL_SET_EVENT_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070BL)
+#endif
+
+#ifndef STATUS_THREADPOOL_RELEASE_SEMAPHORE_ON_COMPLETION_FAILED
+# define STATUS_THREADPOOL_RELEASE_SEMAPHORE_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070CL)
+#endif
+
+#ifndef STATUS_THREADPOOL_RELEASE_MUTEX_ON_COMPLETION_FAILED
+# define STATUS_THREADPOOL_RELEASE_MUTEX_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070DL)
+#endif
+
+#ifndef STATUS_THREADPOOL_FREE_LIBRARY_ON_COMPLETION_FAILED
+# define STATUS_THREADPOOL_FREE_LIBRARY_ON_COMPLETION_FAILED ((NTSTATUS) 0xC000070EL)
+#endif
+
+#ifndef STATUS_THREADPOOL_RELEASED_DURING_OPERATION
+# define STATUS_THREADPOOL_RELEASED_DURING_OPERATION ((NTSTATUS) 0xC000070FL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_WHILE_IMPERSONATING
+# define STATUS_CALLBACK_RETURNED_WHILE_IMPERSONATING ((NTSTATUS) 0xC0000710L)
+#endif
+
+#ifndef STATUS_APC_RETURNED_WHILE_IMPERSONATING
+# define STATUS_APC_RETURNED_WHILE_IMPERSONATING ((NTSTATUS) 0xC0000711L)
+#endif
+
+#ifndef STATUS_PROCESS_IS_PROTECTED
+# define STATUS_PROCESS_IS_PROTECTED ((NTSTATUS) 0xC0000712L)
+#endif
+
+#ifndef STATUS_MCA_EXCEPTION
+# define STATUS_MCA_EXCEPTION ((NTSTATUS) 0xC0000713L)
+#endif
+
+#ifndef STATUS_CERTIFICATE_MAPPING_NOT_UNIQUE
+# define STATUS_CERTIFICATE_MAPPING_NOT_UNIQUE ((NTSTATUS) 0xC0000714L)
+#endif
+
+#ifndef STATUS_SYMLINK_CLASS_DISABLED
+# define STATUS_SYMLINK_CLASS_DISABLED ((NTSTATUS) 0xC0000715L)
+#endif
+
+#ifndef STATUS_INVALID_IDN_NORMALIZATION
+# define STATUS_INVALID_IDN_NORMALIZATION ((NTSTATUS) 0xC0000716L)
+#endif
+
+#ifndef STATUS_NO_UNICODE_TRANSLATION
+# define STATUS_NO_UNICODE_TRANSLATION ((NTSTATUS) 0xC0000717L)
+#endif
+
+#ifndef STATUS_ALREADY_REGISTERED
+# define STATUS_ALREADY_REGISTERED ((NTSTATUS) 0xC0000718L)
+#endif
+
+#ifndef STATUS_CONTEXT_MISMATCH
+# define STATUS_CONTEXT_MISMATCH ((NTSTATUS) 0xC0000719L)
+#endif
+
+#ifndef STATUS_PORT_ALREADY_HAS_COMPLETION_LIST
+# define STATUS_PORT_ALREADY_HAS_COMPLETION_LIST ((NTSTATUS) 0xC000071AL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_THREAD_PRIORITY
+# define STATUS_CALLBACK_RETURNED_THREAD_PRIORITY ((NTSTATUS) 0xC000071BL)
+#endif
+
+#ifndef STATUS_INVALID_THREAD
+# define STATUS_INVALID_THREAD ((NTSTATUS) 0xC000071CL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_TRANSACTION
+# define STATUS_CALLBACK_RETURNED_TRANSACTION ((NTSTATUS) 0xC000071DL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_LDR_LOCK
+# define STATUS_CALLBACK_RETURNED_LDR_LOCK ((NTSTATUS) 0xC000071EL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_LANG
+# define STATUS_CALLBACK_RETURNED_LANG ((NTSTATUS) 0xC000071FL)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_PRI_BACK
+# define STATUS_CALLBACK_RETURNED_PRI_BACK ((NTSTATUS) 0xC0000720L)
+#endif
+
+#ifndef STATUS_CALLBACK_RETURNED_THREAD_AFFINITY
+# define STATUS_CALLBACK_RETURNED_THREAD_AFFINITY ((NTSTATUS) 0xC0000721L)
+#endif
+
+#ifndef STATUS_DISK_REPAIR_DISABLED
+# define STATUS_DISK_REPAIR_DISABLED ((NTSTATUS) 0xC0000800L)
+#endif
+
+#ifndef STATUS_DS_DOMAIN_RENAME_IN_PROGRESS
+# define STATUS_DS_DOMAIN_RENAME_IN_PROGRESS ((NTSTATUS) 0xC0000801L)
+#endif
+
+#ifndef STATUS_DISK_QUOTA_EXCEEDED
+# define STATUS_DISK_QUOTA_EXCEEDED ((NTSTATUS) 0xC0000802L)
+#endif
+
+#ifndef STATUS_DATA_LOST_REPAIR
+# define STATUS_DATA_LOST_REPAIR ((NTSTATUS) 0x80000803L)
+#endif
+
+#ifndef STATUS_CONTENT_BLOCKED
+# define STATUS_CONTENT_BLOCKED ((NTSTATUS) 0xC0000804L)
+#endif
+
+#ifndef STATUS_BAD_CLUSTERS
+# define STATUS_BAD_CLUSTERS ((NTSTATUS) 0xC0000805L)
+#endif
+
+#ifndef STATUS_VOLUME_DIRTY
+# define STATUS_VOLUME_DIRTY ((NTSTATUS) 0xC0000806L)
+#endif
+
+#ifndef STATUS_FILE_CHECKED_OUT
+# define STATUS_FILE_CHECKED_OUT ((NTSTATUS) 0xC0000901L)
+#endif
+
+#ifndef STATUS_CHECKOUT_REQUIRED
+# define STATUS_CHECKOUT_REQUIRED ((NTSTATUS) 0xC0000902L)
+#endif
+
+#ifndef STATUS_BAD_FILE_TYPE
+# define STATUS_BAD_FILE_TYPE ((NTSTATUS) 0xC0000903L)
+#endif
+
+#ifndef STATUS_FILE_TOO_LARGE
+# define STATUS_FILE_TOO_LARGE ((NTSTATUS) 0xC0000904L)
+#endif
+
+#ifndef STATUS_FORMS_AUTH_REQUIRED
+# define STATUS_FORMS_AUTH_REQUIRED ((NTSTATUS) 0xC0000905L)
+#endif
+
+#ifndef STATUS_VIRUS_INFECTED
+# define STATUS_VIRUS_INFECTED ((NTSTATUS) 0xC0000906L)
+#endif
+
+#ifndef STATUS_VIRUS_DELETED
+# define STATUS_VIRUS_DELETED ((NTSTATUS) 0xC0000907L)
+#endif
+
+#ifndef STATUS_BAD_MCFG_TABLE
+# define STATUS_BAD_MCFG_TABLE ((NTSTATUS) 0xC0000908L)
+#endif
+
+#ifndef STATUS_CANNOT_BREAK_OPLOCK
+# define STATUS_CANNOT_BREAK_OPLOCK ((NTSTATUS) 0xC0000909L)
+#endif
+
+#ifndef STATUS_WOW_ASSERTION
+# define STATUS_WOW_ASSERTION ((NTSTATUS) 0xC0009898L)
+#endif
+
+#ifndef STATUS_INVALID_SIGNATURE
+# define STATUS_INVALID_SIGNATURE ((NTSTATUS) 0xC000A000L)
+#endif
+
+#ifndef STATUS_HMAC_NOT_SUPPORTED
+# define STATUS_HMAC_NOT_SUPPORTED ((NTSTATUS) 0xC000A001L)
+#endif
+
+#ifndef STATUS_AUTH_TAG_MISMATCH
+# define STATUS_AUTH_TAG_MISMATCH ((NTSTATUS) 0xC000A002L)
+#endif
+
+#ifndef STATUS_IPSEC_QUEUE_OVERFLOW
+# define STATUS_IPSEC_QUEUE_OVERFLOW ((NTSTATUS) 0xC000A010L)
+#endif
+
+#ifndef STATUS_ND_QUEUE_OVERFLOW
+# define STATUS_ND_QUEUE_OVERFLOW ((NTSTATUS) 0xC000A011L)
+#endif
+
+#ifndef STATUS_HOPLIMIT_EXCEEDED
+# define STATUS_HOPLIMIT_EXCEEDED ((NTSTATUS) 0xC000A012L)
+#endif
+
+#ifndef STATUS_PROTOCOL_NOT_SUPPORTED
+# define STATUS_PROTOCOL_NOT_SUPPORTED ((NTSTATUS) 0xC000A013L)
+#endif
+
+#ifndef STATUS_FASTPATH_REJECTED
+# define STATUS_FASTPATH_REJECTED ((NTSTATUS) 0xC000A014L)
+#endif
+
+#ifndef STATUS_LOST_WRITEBEHIND_DATA_NETWORK_DISCONNECTED
+# define STATUS_LOST_WRITEBEHIND_DATA_NETWORK_DISCONNECTED ((NTSTATUS) 0xC000A080L)
+#endif
+
+#ifndef STATUS_LOST_WRITEBEHIND_DATA_NETWORK_SERVER_ERROR
+# define STATUS_LOST_WRITEBEHIND_DATA_NETWORK_SERVER_ERROR ((NTSTATUS) 0xC000A081L)
+#endif
+
+#ifndef STATUS_LOST_WRITEBEHIND_DATA_LOCAL_DISK_ERROR
+# define STATUS_LOST_WRITEBEHIND_DATA_LOCAL_DISK_ERROR ((NTSTATUS) 0xC000A082L)
+#endif
+
+#ifndef STATUS_XML_PARSE_ERROR
+# define STATUS_XML_PARSE_ERROR ((NTSTATUS) 0xC000A083L)
+#endif
+
+#ifndef STATUS_XMLDSIG_ERROR
+# define STATUS_XMLDSIG_ERROR ((NTSTATUS) 0xC000A084L)
+#endif
+
+#ifndef STATUS_WRONG_COMPARTMENT
+# define STATUS_WRONG_COMPARTMENT ((NTSTATUS) 0xC000A085L)
+#endif
+
+#ifndef STATUS_AUTHIP_FAILURE
+# define STATUS_AUTHIP_FAILURE ((NTSTATUS) 0xC000A086L)
+#endif
+
+#ifndef STATUS_DS_OID_MAPPED_GROUP_CANT_HAVE_MEMBERS
+# define STATUS_DS_OID_MAPPED_GROUP_CANT_HAVE_MEMBERS ((NTSTATUS) 0xC000A087L)
+#endif
+
+#ifndef STATUS_DS_OID_NOT_FOUND
+# define STATUS_DS_OID_NOT_FOUND ((NTSTATUS) 0xC000A088L)
+#endif
+
+#ifndef STATUS_HASH_NOT_SUPPORTED
+# define STATUS_HASH_NOT_SUPPORTED ((NTSTATUS) 0xC000A100L)
+#endif
+
+#ifndef STATUS_HASH_NOT_PRESENT
+# define STATUS_HASH_NOT_PRESENT ((NTSTATUS) 0xC000A101L)
+#endif
+
+/* This is not the NTSTATUS_FROM_WIN32 that the DDK provides, because the DDK
+ * got it wrong! */
+#ifdef NTSTATUS_FROM_WIN32
+# undef NTSTATUS_FROM_WIN32
+#endif
+#define NTSTATUS_FROM_WIN32(error) ((NTSTATUS) (error) <= 0 ? \
+        ((NTSTATUS) (error)) : ((NTSTATUS) (((error) & 0x0000FFFF) | \
+        (FACILITY_NTWIN32 << 16) | ERROR_SEVERITY_WARNING)))
+
+#ifndef JOB_OBJECT_LIMIT_PROCESS_MEMORY
+# define JOB_OBJECT_LIMIT_PROCESS_MEMORY             0x00000100
+#endif
+#ifndef JOB_OBJECT_LIMIT_JOB_MEMORY
+# define JOB_OBJECT_LIMIT_JOB_MEMORY                 0x00000200
+#endif
+#ifndef JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION
+# define JOB_OBJECT_LIMIT_DIE_ON_UNHANDLED_EXCEPTION 0x00000400
+#endif
+#ifndef JOB_OBJECT_LIMIT_BREAKAWAY_OK
+# define JOB_OBJECT_LIMIT_BREAKAWAY_OK               0x00000800
+#endif
+#ifndef JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK
+# define JOB_OBJECT_LIMIT_SILENT_BREAKAWAY_OK        0x00001000
+#endif
+#ifndef JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE
+# define JOB_OBJECT_LIMIT_KILL_ON_JOB_CLOSE          0x00002000
+#endif
+
+#ifndef SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE
+# define SYMBOLIC_LINK_FLAG_ALLOW_UNPRIVILEGED_CREATE 0x00000002
+#endif
+
+/* from winternl.h */
+typedef struct _UNICODE_STRING {
+  USHORT Length;
+  USHORT MaximumLength;
+  PWSTR  Buffer;
+} UNICODE_STRING, *PUNICODE_STRING;
+
+typedef const UNICODE_STRING *PCUNICODE_STRING;
+
+/* from ntifs.h */
+#ifndef DEVICE_TYPE
+# define DEVICE_TYPE DWORD
+#endif
+
+/* MinGW already has a definition for REPARSE_DATA_BUFFER, but mingw-w64 does
+ * not.
+ */
+#if defined(_MSC_VER) || defined(__MINGW64_VERSION_MAJOR)
+  typedef struct _REPARSE_DATA_BUFFER {
+    ULONG  ReparseTag;
+    USHORT ReparseDataLength;
+    USHORT Reserved;
+    union {
+      struct {
+        USHORT SubstituteNameOffset;
+        USHORT SubstituteNameLength;
+        USHORT PrintNameOffset;
+        USHORT PrintNameLength;
+        ULONG Flags;
+        WCHAR PathBuffer[1];
+      } SymbolicLinkReparseBuffer;
+      struct {
+        USHORT SubstituteNameOffset;
+        USHORT SubstituteNameLength;
+        USHORT PrintNameOffset;
+        USHORT PrintNameLength;
+        WCHAR PathBuffer[1];
+      } MountPointReparseBuffer;
+      struct {
+        UCHAR  DataBuffer[1];
+      } GenericReparseBuffer;
+    };
+  } REPARSE_DATA_BUFFER, *PREPARSE_DATA_BUFFER;
+#endif
+
+typedef struct _IO_STATUS_BLOCK {
+  union {
+    NTSTATUS Status;
+    PVOID Pointer;
+  };
+  ULONG_PTR Information;
+} IO_STATUS_BLOCK, *PIO_STATUS_BLOCK;
+
+typedef enum _FILE_INFORMATION_CLASS {
+  FileDirectoryInformation = 1,
+  FileFullDirectoryInformation,
+  FileBothDirectoryInformation,
+  FileBasicInformation,
+  FileStandardInformation,
+  FileInternalInformation,
+  FileEaInformation,
+  FileAccessInformation,
+  FileNameInformation,
+  FileRenameInformation,
+  FileLinkInformation,
+  FileNamesInformation,
+  FileDispositionInformation,
+  FilePositionInformation,
+  FileFullEaInformation,
+  FileModeInformation,
+  FileAlignmentInformation,
+  FileAllInformation,
+  FileAllocationInformation,
+  FileEndOfFileInformation,
+  FileAlternateNameInformation,
+  FileStreamInformation,
+  FilePipeInformation,
+  FilePipeLocalInformation,
+  FilePipeRemoteInformation,
+  FileMailslotQueryInformation,
+  FileMailslotSetInformation,
+  FileCompressionInformation,
+  FileObjectIdInformation,
+  FileCompletionInformation,
+  FileMoveClusterInformation,
+  FileQuotaInformation,
+  FileReparsePointInformation,
+  FileNetworkOpenInformation,
+  FileAttributeTagInformation,
+  FileTrackingInformation,
+  FileIdBothDirectoryInformation,
+  FileIdFullDirectoryInformation,
+  FileValidDataLengthInformation,
+  FileShortNameInformation,
+  FileIoCompletionNotificationInformation,
+  FileIoStatusBlockRangeInformation,
+  FileIoPriorityHintInformation,
+  FileSfioReserveInformation,
+  FileSfioVolumeInformation,
+  FileHardLinkInformation,
+  FileProcessIdsUsingFileInformation,
+  FileNormalizedNameInformation,
+  FileNetworkPhysicalNameInformation,
+  FileIdGlobalTxDirectoryInformation,
+  FileIsRemoteDeviceInformation,
+  FileAttributeCacheInformation,
+  FileNumaNodeInformation,
+  FileStandardLinkInformation,
+  FileRemoteProtocolInformation,
+  FileMaximumInformation
+} FILE_INFORMATION_CLASS, *PFILE_INFORMATION_CLASS;
+
+typedef struct _FILE_DIRECTORY_INFORMATION {
+  ULONG NextEntryOffset;
+  ULONG FileIndex;
+  LARGE_INTEGER CreationTime;
+  LARGE_INTEGER LastAccessTime;
+  LARGE_INTEGER LastWriteTime;
+  LARGE_INTEGER ChangeTime;
+  LARGE_INTEGER EndOfFile;
+  LARGE_INTEGER AllocationSize;
+  ULONG FileAttributes;
+  ULONG FileNameLength;
+  WCHAR FileName[1];
+} FILE_DIRECTORY_INFORMATION, *PFILE_DIRECTORY_INFORMATION;
+
+typedef struct _FILE_BOTH_DIR_INFORMATION {
+  ULONG NextEntryOffset;
+  ULONG FileIndex;
+  LARGE_INTEGER CreationTime;
+  LARGE_INTEGER LastAccessTime;
+  LARGE_INTEGER LastWriteTime;
+  LARGE_INTEGER ChangeTime;
+  LARGE_INTEGER EndOfFile;
+  LARGE_INTEGER AllocationSize;
+  ULONG FileAttributes;
+  ULONG FileNameLength;
+  ULONG EaSize;
+  CCHAR ShortNameLength;
+  WCHAR ShortName[12];
+  WCHAR FileName[1];
+} FILE_BOTH_DIR_INFORMATION, *PFILE_BOTH_DIR_INFORMATION;
+
+typedef struct _FILE_BASIC_INFORMATION {
+  LARGE_INTEGER CreationTime;
+  LARGE_INTEGER LastAccessTime;
+  LARGE_INTEGER LastWriteTime;
+  LARGE_INTEGER ChangeTime;
+  DWORD FileAttributes;
+} FILE_BASIC_INFORMATION, *PFILE_BASIC_INFORMATION;
+
+typedef struct _FILE_STANDARD_INFORMATION {
+  LARGE_INTEGER AllocationSize;
+  LARGE_INTEGER EndOfFile;
+  ULONG         NumberOfLinks;
+  BOOLEAN       DeletePending;
+  BOOLEAN       Directory;
+} FILE_STANDARD_INFORMATION, *PFILE_STANDARD_INFORMATION;
+
+typedef struct _FILE_INTERNAL_INFORMATION {
+  LARGE_INTEGER IndexNumber;
+} FILE_INTERNAL_INFORMATION, *PFILE_INTERNAL_INFORMATION;
+
+typedef struct _FILE_EA_INFORMATION {
+  ULONG EaSize;
+} FILE_EA_INFORMATION, *PFILE_EA_INFORMATION;
+
+typedef struct _FILE_ACCESS_INFORMATION {
+  ACCESS_MASK AccessFlags;
+} FILE_ACCESS_INFORMATION, *PFILE_ACCESS_INFORMATION;
+
+typedef struct _FILE_POSITION_INFORMATION {
+  LARGE_INTEGER CurrentByteOffset;
+} FILE_POSITION_INFORMATION, *PFILE_POSITION_INFORMATION;
+
+typedef struct _FILE_MODE_INFORMATION {
+  ULONG Mode;
+} FILE_MODE_INFORMATION, *PFILE_MODE_INFORMATION;
+
+typedef struct _FILE_ALIGNMENT_INFORMATION {
+  ULONG AlignmentRequirement;
+} FILE_ALIGNMENT_INFORMATION, *PFILE_ALIGNMENT_INFORMATION;
+
+typedef struct _FILE_NAME_INFORMATION {
+  ULONG FileNameLength;
+  WCHAR FileName[1];
+} FILE_NAME_INFORMATION, *PFILE_NAME_INFORMATION;
+
+typedef struct _FILE_END_OF_FILE_INFORMATION {
+  LARGE_INTEGER  EndOfFile;
+} FILE_END_OF_FILE_INFORMATION, *PFILE_END_OF_FILE_INFORMATION;
+
+typedef struct _FILE_ALL_INFORMATION {
+  FILE_BASIC_INFORMATION     BasicInformation;
+  FILE_STANDARD_INFORMATION  StandardInformation;
+  FILE_INTERNAL_INFORMATION  InternalInformation;
+  FILE_EA_INFORMATION        EaInformation;
+  FILE_ACCESS_INFORMATION    AccessInformation;
+  FILE_POSITION_INFORMATION  PositionInformation;
+  FILE_MODE_INFORMATION      ModeInformation;
+  FILE_ALIGNMENT_INFORMATION AlignmentInformation;
+  FILE_NAME_INFORMATION      NameInformation;
+} FILE_ALL_INFORMATION, *PFILE_ALL_INFORMATION;
+
+typedef struct _FILE_DISPOSITION_INFORMATION {
+  BOOLEAN DeleteFile;
+} FILE_DISPOSITION_INFORMATION, *PFILE_DISPOSITION_INFORMATION;
+
+typedef struct _FILE_PIPE_LOCAL_INFORMATION {
+  ULONG NamedPipeType;
+  ULONG NamedPipeConfiguration;
+  ULONG MaximumInstances;
+  ULONG CurrentInstances;
+  ULONG InboundQuota;
+  ULONG ReadDataAvailable;
+  ULONG OutboundQuota;
+  ULONG WriteQuotaAvailable;
+  ULONG NamedPipeState;
+  ULONG NamedPipeEnd;
+} FILE_PIPE_LOCAL_INFORMATION, *PFILE_PIPE_LOCAL_INFORMATION;
+
+#define FILE_SYNCHRONOUS_IO_ALERT               0x00000010
+#define FILE_SYNCHRONOUS_IO_NONALERT            0x00000020
+
+typedef enum _FS_INFORMATION_CLASS {
+  FileFsVolumeInformation       = 1,
+  FileFsLabelInformation        = 2,
+  FileFsSizeInformation         = 3,
+  FileFsDeviceInformation       = 4,
+  FileFsAttributeInformation    = 5,
+  FileFsControlInformation      = 6,
+  FileFsFullSizeInformation     = 7,
+  FileFsObjectIdInformation     = 8,
+  FileFsDriverPathInformation   = 9,
+  FileFsVolumeFlagsInformation  = 10,
+  FileFsSectorSizeInformation   = 11
+} FS_INFORMATION_CLASS, *PFS_INFORMATION_CLASS;
+
+typedef struct _FILE_FS_VOLUME_INFORMATION {
+  LARGE_INTEGER VolumeCreationTime;
+  ULONG         VolumeSerialNumber;
+  ULONG         VolumeLabelLength;
+  BOOLEAN       SupportsObjects;
+  WCHAR         VolumeLabel[1];
+} FILE_FS_VOLUME_INFORMATION, *PFILE_FS_VOLUME_INFORMATION;
+
+typedef struct _FILE_FS_LABEL_INFORMATION {
+  ULONG VolumeLabelLength;
+  WCHAR VolumeLabel[1];
+} FILE_FS_LABEL_INFORMATION, *PFILE_FS_LABEL_INFORMATION;
+
+typedef struct _FILE_FS_SIZE_INFORMATION {
+  LARGE_INTEGER TotalAllocationUnits;
+  LARGE_INTEGER AvailableAllocationUnits;
+  ULONG         SectorsPerAllocationUnit;
+  ULONG         BytesPerSector;
+} FILE_FS_SIZE_INFORMATION, *PFILE_FS_SIZE_INFORMATION;
+
+typedef struct _FILE_FS_DEVICE_INFORMATION {
+  DEVICE_TYPE DeviceType;
+  ULONG       Characteristics;
+} FILE_FS_DEVICE_INFORMATION, *PFILE_FS_DEVICE_INFORMATION;
+
+typedef struct _FILE_FS_ATTRIBUTE_INFORMATION {
+  ULONG FileSystemAttributes;
+  LONG  MaximumComponentNameLength;
+  ULONG FileSystemNameLength;
+  WCHAR FileSystemName[1];
+} FILE_FS_ATTRIBUTE_INFORMATION, *PFILE_FS_ATTRIBUTE_INFORMATION;
+
+typedef struct _FILE_FS_CONTROL_INFORMATION {
+  LARGE_INTEGER FreeSpaceStartFiltering;
+  LARGE_INTEGER FreeSpaceThreshold;
+  LARGE_INTEGER FreeSpaceStopFiltering;
+  LARGE_INTEGER DefaultQuotaThreshold;
+  LARGE_INTEGER DefaultQuotaLimit;
+  ULONG         FileSystemControlFlags;
+} FILE_FS_CONTROL_INFORMATION, *PFILE_FS_CONTROL_INFORMATION;
+
+typedef struct _FILE_FS_FULL_SIZE_INFORMATION {
+  LARGE_INTEGER TotalAllocationUnits;
+  LARGE_INTEGER CallerAvailableAllocationUnits;
+  LARGE_INTEGER ActualAvailableAllocationUnits;
+  ULONG         SectorsPerAllocationUnit;
+  ULONG         BytesPerSector;
+} FILE_FS_FULL_SIZE_INFORMATION, *PFILE_FS_FULL_SIZE_INFORMATION;
+
+typedef struct _FILE_FS_OBJECTID_INFORMATION {
+  UCHAR ObjectId[16];
+  UCHAR ExtendedInfo[48];
+} FILE_FS_OBJECTID_INFORMATION, *PFILE_FS_OBJECTID_INFORMATION;
+
+typedef struct _FILE_FS_DRIVER_PATH_INFORMATION {
+  BOOLEAN DriverInPath;
+  ULONG   DriverNameLength;
+  WCHAR   DriverName[1];
+} FILE_FS_DRIVER_PATH_INFORMATION, *PFILE_FS_DRIVER_PATH_INFORMATION;
+
+typedef struct _FILE_FS_VOLUME_FLAGS_INFORMATION {
+  ULONG Flags;
+} FILE_FS_VOLUME_FLAGS_INFORMATION, *PFILE_FS_VOLUME_FLAGS_INFORMATION;
+
+typedef struct _FILE_FS_SECTOR_SIZE_INFORMATION {
+  ULONG LogicalBytesPerSector;
+  ULONG PhysicalBytesPerSectorForAtomicity;
+  ULONG PhysicalBytesPerSectorForPerformance;
+  ULONG FileSystemEffectivePhysicalBytesPerSectorForAtomicity;
+  ULONG Flags;
+  ULONG ByteOffsetForSectorAlignment;
+  ULONG ByteOffsetForPartitionAlignment;
+} FILE_FS_SECTOR_SIZE_INFORMATION, *PFILE_FS_SECTOR_SIZE_INFORMATION;
+
+typedef struct _SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION {
+    LARGE_INTEGER IdleTime;
+    LARGE_INTEGER KernelTime;
+    LARGE_INTEGER UserTime;
+    LARGE_INTEGER DpcTime;
+    LARGE_INTEGER InterruptTime;
+    ULONG InterruptCount;
+} SYSTEM_PROCESSOR_PERFORMANCE_INFORMATION, *PSYSTEM_PROCESSOR_PERFORMANCE_INFORMATION;
+
+#ifndef SystemProcessorPerformanceInformation
+# define SystemProcessorPerformanceInformation 8
+#endif
+
+#ifndef FILE_DEVICE_FILE_SYSTEM
+# define FILE_DEVICE_FILE_SYSTEM 0x00000009
+#endif
+
+#ifndef FILE_DEVICE_NETWORK
+# define FILE_DEVICE_NETWORK 0x00000012
+#endif
+
+#ifndef METHOD_BUFFERED
+# define METHOD_BUFFERED 0
+#endif
+
+#ifndef METHOD_IN_DIRECT
+# define METHOD_IN_DIRECT 1
+#endif
+
+#ifndef METHOD_OUT_DIRECT
+# define METHOD_OUT_DIRECT 2
+#endif
+
+#ifndef METHOD_NEITHER
+#define METHOD_NEITHER 3
+#endif
+
+#ifndef METHOD_DIRECT_TO_HARDWARE
+# define METHOD_DIRECT_TO_HARDWARE METHOD_IN_DIRECT
+#endif
+
+#ifndef METHOD_DIRECT_FROM_HARDWARE
+# define METHOD_DIRECT_FROM_HARDWARE METHOD_OUT_DIRECT
+#endif
+
+#ifndef FILE_ANY_ACCESS
+# define FILE_ANY_ACCESS 0
+#endif
+
+#ifndef FILE_SPECIAL_ACCESS
+# define FILE_SPECIAL_ACCESS (FILE_ANY_ACCESS)
+#endif
+
+#ifndef FILE_READ_ACCESS
+# define FILE_READ_ACCESS 0x0001
+#endif
+
+#ifndef FILE_WRITE_ACCESS
+# define FILE_WRITE_ACCESS 0x0002
+#endif
+
+#ifndef CTL_CODE
+# define CTL_CODE(device_type, function, method, access)                      \
+    (((device_type) << 16) | ((access) << 14) | ((function) << 2) | (method))
+#endif
+
+#ifndef FSCTL_SET_REPARSE_POINT
+# define FSCTL_SET_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,            \
+                                          41,                                 \
+                                          METHOD_BUFFERED,                    \
+                                          FILE_SPECIAL_ACCESS)
+#endif
+
+#ifndef FSCTL_GET_REPARSE_POINT
+# define FSCTL_GET_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,            \
+                                          42,                                 \
+                                          METHOD_BUFFERED,                    \
+                                          FILE_ANY_ACCESS)
+#endif
+
+#ifndef FSCTL_DELETE_REPARSE_POINT
+# define FSCTL_DELETE_REPARSE_POINT CTL_CODE(FILE_DEVICE_FILE_SYSTEM,         \
+                                             43,                              \
+                                             METHOD_BUFFERED,                 \
+                                             FILE_SPECIAL_ACCESS)
+#endif
+
+#ifndef IO_REPARSE_TAG_SYMLINK
+# define IO_REPARSE_TAG_SYMLINK (0xA000000CL)
+#endif
+
+typedef VOID (NTAPI *PIO_APC_ROUTINE)
+             (PVOID ApcContext,
+              PIO_STATUS_BLOCK IoStatusBlock,
+              ULONG Reserved);
+
+typedef ULONG (NTAPI *sRtlNtStatusToDosError)
+              (NTSTATUS Status);
+
+typedef NTSTATUS (NTAPI *sNtDeviceIoControlFile)
+                 (HANDLE FileHandle,
+                  HANDLE Event,
+                  PIO_APC_ROUTINE ApcRoutine,
+                  PVOID ApcContext,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  ULONG IoControlCode,
+                  PVOID InputBuffer,
+                  ULONG InputBufferLength,
+                  PVOID OutputBuffer,
+                  ULONG OutputBufferLength);
+
+typedef NTSTATUS (NTAPI *sNtQueryInformationFile)
+                 (HANDLE FileHandle,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  PVOID FileInformation,
+                  ULONG Length,
+                  FILE_INFORMATION_CLASS FileInformationClass);
+
+typedef NTSTATUS (NTAPI *sNtSetInformationFile)
+                 (HANDLE FileHandle,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  PVOID FileInformation,
+                  ULONG Length,
+                  FILE_INFORMATION_CLASS FileInformationClass);
+
+typedef NTSTATUS (NTAPI *sNtQueryVolumeInformationFile)
+                 (HANDLE FileHandle,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  PVOID FsInformation,
+                  ULONG Length,
+                  FS_INFORMATION_CLASS FsInformationClass);
+
+typedef NTSTATUS (NTAPI *sNtQuerySystemInformation)
+                 (UINT SystemInformationClass,
+                  PVOID SystemInformation,
+                  ULONG SystemInformationLength,
+                  PULONG ReturnLength);
+
+typedef NTSTATUS (NTAPI *sNtQueryDirectoryFile)
+                 (HANDLE FileHandle,
+                  HANDLE Event,
+                  PIO_APC_ROUTINE ApcRoutine,
+                  PVOID ApcContext,
+                  PIO_STATUS_BLOCK IoStatusBlock,
+                  PVOID FileInformation,
+                  ULONG Length,
+                  FILE_INFORMATION_CLASS FileInformationClass,
+                  BOOLEAN ReturnSingleEntry,
+                  PUNICODE_STRING FileName,
+                  BOOLEAN RestartScan
+                );
+
+/*
+ * Kernel32 headers
+ */
+#ifndef FILE_SKIP_COMPLETION_PORT_ON_SUCCESS
+# define FILE_SKIP_COMPLETION_PORT_ON_SUCCESS 0x1
+#endif
+
+#ifndef FILE_SKIP_SET_EVENT_ON_HANDLE
+# define FILE_SKIP_SET_EVENT_ON_HANDLE 0x2
+#endif
+
+#ifndef SYMBOLIC_LINK_FLAG_DIRECTORY
+# define SYMBOLIC_LINK_FLAG_DIRECTORY 0x1
+#endif
+
+#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
+  typedef struct _OVERLAPPED_ENTRY {
+      ULONG_PTR lpCompletionKey;
+      LPOVERLAPPED lpOverlapped;
+      ULONG_PTR Internal;
+      DWORD dwNumberOfBytesTransferred;
+  } OVERLAPPED_ENTRY, *LPOVERLAPPED_ENTRY;
+#endif
+
+/* from wincon.h */
+#ifndef ENABLE_INSERT_MODE
+# define ENABLE_INSERT_MODE 0x20
+#endif
+
+#ifndef ENABLE_QUICK_EDIT_MODE
+# define ENABLE_QUICK_EDIT_MODE 0x40
+#endif
+
+#ifndef ENABLE_EXTENDED_FLAGS
+# define ENABLE_EXTENDED_FLAGS 0x80
+#endif
+
+/* from winerror.h */
+#ifndef ERROR_ELEVATION_REQUIRED
+# define ERROR_ELEVATION_REQUIRED 740
+#endif
+
+#ifndef ERROR_SYMLINK_NOT_SUPPORTED
+# define ERROR_SYMLINK_NOT_SUPPORTED 1464
+#endif
+
+#ifndef ERROR_MUI_FILE_NOT_FOUND
+# define ERROR_MUI_FILE_NOT_FOUND 15100
+#endif
+
+#ifndef ERROR_MUI_INVALID_FILE
+# define ERROR_MUI_INVALID_FILE 15101
+#endif
+
+#ifndef ERROR_MUI_INVALID_RC_CONFIG
+# define ERROR_MUI_INVALID_RC_CONFIG 15102
+#endif
+
+#ifndef ERROR_MUI_INVALID_LOCALE_NAME
+# define ERROR_MUI_INVALID_LOCALE_NAME 15103
+#endif
+
+#ifndef ERROR_MUI_INVALID_ULTIMATEFALLBACK_NAME
+# define ERROR_MUI_INVALID_ULTIMATEFALLBACK_NAME 15104
+#endif
+
+#ifndef ERROR_MUI_FILE_NOT_LOADED
+# define ERROR_MUI_FILE_NOT_LOADED 15105
+#endif
+
+/* from powerbase.h */
+#ifndef DEVICE_NOTIFY_CALLBACK
+# define DEVICE_NOTIFY_CALLBACK 2
+#endif
+
+#ifndef PBT_APMRESUMEAUTOMATIC
+# define PBT_APMRESUMEAUTOMATIC 18
+#endif
+
+#ifndef PBT_APMRESUMESUSPEND
+# define PBT_APMRESUMESUSPEND 7
+#endif
+
+typedef ULONG CALLBACK _DEVICE_NOTIFY_CALLBACK_ROUTINE(
+  PVOID Context,
+  ULONG Type,
+  PVOID Setting
+);
+typedef _DEVICE_NOTIFY_CALLBACK_ROUTINE* _PDEVICE_NOTIFY_CALLBACK_ROUTINE;
+
+typedef struct _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS {
+  _PDEVICE_NOTIFY_CALLBACK_ROUTINE Callback;
+  PVOID Context;
+} _DEVICE_NOTIFY_SUBSCRIBE_PARAMETERS, *_PDEVICE_NOTIFY_SUBSCRIBE_PARAMETERS;
+
+typedef PVOID _HPOWERNOTIFY;
+typedef _HPOWERNOTIFY *_PHPOWERNOTIFY;
+
+typedef DWORD (WINAPI *sPowerRegisterSuspendResumeNotification)
+              (DWORD         Flags,
+               HANDLE        Recipient,
+               _PHPOWERNOTIFY RegistrationHandle);
+
+/* from Winuser.h */
+typedef VOID (CALLBACK* WINEVENTPROC)
+             (HWINEVENTHOOK hWinEventHook,
+              DWORD         event,
+              HWND          hwnd,
+              LONG          idObject,
+              LONG          idChild,
+              DWORD         idEventThread,
+              DWORD         dwmsEventTime);
+
+typedef HWINEVENTHOOK (WINAPI *sSetWinEventHook)
+                      (UINT         eventMin,
+                       UINT         eventMax,
+                       HMODULE      hmodWinEventProc,
+                       WINEVENTPROC lpfnWinEventProc,
+                       DWORD        idProcess,
+                       DWORD        idThread,
+                       UINT         dwflags);
+
+
+/* Ntdll function pointers */
+extern sRtlNtStatusToDosError pRtlNtStatusToDosError;
+extern sNtDeviceIoControlFile pNtDeviceIoControlFile;
+extern sNtQueryInformationFile pNtQueryInformationFile;
+extern sNtSetInformationFile pNtSetInformationFile;
+extern sNtQueryVolumeInformationFile pNtQueryVolumeInformationFile;
+extern sNtQueryDirectoryFile pNtQueryDirectoryFile;
+extern sNtQuerySystemInformation pNtQuerySystemInformation;
+
+/* Powrprof.dll function pointer */
+extern sPowerRegisterSuspendResumeNotification pPowerRegisterSuspendResumeNotification;
+
+/* User32.dll function pointer */
+extern sSetWinEventHook pSetWinEventHook;
+
+#endif /* UV_WIN_WINAPI_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winsock.cpp b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winsock.cpp
new file mode 100644
index 0000000..f4172e2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winsock.cpp
@@ -0,0 +1,593 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include <assert.h>
+#include <stdlib.h>
+
+#include "uv.h"
+#include "internal.h"
+
+
+#pragma comment(lib, "Ws2_32.lib")
+
+/* Whether there are any non-IFS LSPs stacked on TCP */
+int uv_tcp_non_ifs_lsp_ipv4;
+int uv_tcp_non_ifs_lsp_ipv6;
+
+/* Ip address used to bind to any port at any interface */
+struct sockaddr_in uv_addr_ip4_any_;
+struct sockaddr_in6 uv_addr_ip6_any_;
+
+
+/*
+ * Retrieves the pointer to a winsock extension function.
+ */
+static BOOL uv_get_extension_function(SOCKET socket, GUID guid,
+    void **target) {
+  int result;
+  DWORD bytes;
+
+  result = WSAIoctl(socket,
+                    SIO_GET_EXTENSION_FUNCTION_POINTER,
+                    &guid,
+                    sizeof(guid),
+                    (void*)target,
+                    sizeof(*target),
+                    &bytes,
+                    NULL,
+                    NULL);
+
+  if (result == SOCKET_ERROR) {
+    *target = NULL;
+    return FALSE;
+  } else {
+    return TRUE;
+  }
+}
+
+
+BOOL uv_get_acceptex_function(SOCKET socket, LPFN_ACCEPTEX* target) {
+  const GUID wsaid_acceptex = WSAID_ACCEPTEX;
+  return uv_get_extension_function(socket, wsaid_acceptex, (void**)target);
+}
+
+
+BOOL uv_get_connectex_function(SOCKET socket, LPFN_CONNECTEX* target) {
+  const GUID wsaid_connectex = WSAID_CONNECTEX;
+  return uv_get_extension_function(socket, wsaid_connectex, (void**)target);
+}
+
+
+static int error_means_no_support(DWORD error) {
+  return error == WSAEPROTONOSUPPORT || error == WSAESOCKTNOSUPPORT ||
+         error == WSAEPFNOSUPPORT || error == WSAEAFNOSUPPORT;
+}
+
+
+void uv_winsock_init(void) {
+  WSADATA wsa_data;
+  int errorno;
+  SOCKET dummy;
+  WSAPROTOCOL_INFOW protocol_info;
+  int opt_len;
+
+  /* Initialize winsock */
+  errorno = WSAStartup(MAKEWORD(2, 2), &wsa_data);
+  if (errorno != 0) {
+    uv_fatal_error(errorno, "WSAStartup");
+  }
+
+  /* Set implicit binding address used by connectEx */
+  if (uv_ip4_addr("0.0.0.0", 0, &uv_addr_ip4_any_)) {
+    abort();
+  }
+
+  if (uv_ip6_addr("::", 0, &uv_addr_ip6_any_)) {
+    abort();
+  }
+
+  /* Detect non-IFS LSPs */
+  dummy = socket(AF_INET, SOCK_STREAM, IPPROTO_IP);
+
+  if (dummy != INVALID_SOCKET) {
+    opt_len = (int) sizeof protocol_info;
+    if (getsockopt(dummy,
+                   SOL_SOCKET,
+                   SO_PROTOCOL_INFOW,
+                   (char*) &protocol_info,
+                   &opt_len) == SOCKET_ERROR)
+      uv_fatal_error(WSAGetLastError(), "getsockopt");
+
+    if (!(protocol_info.dwServiceFlags1 & XP1_IFS_HANDLES))
+      uv_tcp_non_ifs_lsp_ipv4 = 1;
+
+    if (closesocket(dummy) == SOCKET_ERROR)
+      uv_fatal_error(WSAGetLastError(), "closesocket");
+
+  } else if (!error_means_no_support(WSAGetLastError())) {
+    /* Any error other than "socket type not supported" is fatal. */
+    uv_fatal_error(WSAGetLastError(), "socket");
+  }
+
+  /* Detect IPV6 support and non-IFS LSPs */
+  dummy = socket(AF_INET6, SOCK_STREAM, IPPROTO_IP);
+
+  if (dummy != INVALID_SOCKET) {
+    opt_len = (int) sizeof protocol_info;
+    if (getsockopt(dummy,
+                   SOL_SOCKET,
+                   SO_PROTOCOL_INFOW,
+                   (char*) &protocol_info,
+                   &opt_len) == SOCKET_ERROR)
+      uv_fatal_error(WSAGetLastError(), "getsockopt");
+
+    if (!(protocol_info.dwServiceFlags1 & XP1_IFS_HANDLES))
+      uv_tcp_non_ifs_lsp_ipv6 = 1;
+
+    if (closesocket(dummy) == SOCKET_ERROR)
+      uv_fatal_error(WSAGetLastError(), "closesocket");
+
+  } else if (!error_means_no_support(WSAGetLastError())) {
+    /* Any error other than "socket type not supported" is fatal. */
+    uv_fatal_error(WSAGetLastError(), "socket");
+  }
+}
+
+
+int uv_ntstatus_to_winsock_error(NTSTATUS status) {
+  switch (status) {
+    case STATUS_SUCCESS:
+      return ERROR_SUCCESS;
+
+    case STATUS_PENDING:
+      return ERROR_IO_PENDING;
+
+    case STATUS_INVALID_HANDLE:
+    case STATUS_OBJECT_TYPE_MISMATCH:
+      return WSAENOTSOCK;
+
+    case STATUS_INSUFFICIENT_RESOURCES:
+    case STATUS_PAGEFILE_QUOTA:
+    case STATUS_COMMITMENT_LIMIT:
+    case STATUS_WORKING_SET_QUOTA:
+    case STATUS_NO_MEMORY:
+    case STATUS_QUOTA_EXCEEDED:
+    case STATUS_TOO_MANY_PAGING_FILES:
+    case STATUS_REMOTE_RESOURCES:
+      return WSAENOBUFS;
+
+    case STATUS_TOO_MANY_ADDRESSES:
+    case STATUS_SHARING_VIOLATION:
+    case STATUS_ADDRESS_ALREADY_EXISTS:
+      return WSAEADDRINUSE;
+
+    case STATUS_LINK_TIMEOUT:
+    case STATUS_IO_TIMEOUT:
+    case STATUS_TIMEOUT:
+      return WSAETIMEDOUT;
+
+    case STATUS_GRACEFUL_DISCONNECT:
+      return WSAEDISCON;
+
+    case STATUS_REMOTE_DISCONNECT:
+    case STATUS_CONNECTION_RESET:
+    case STATUS_LINK_FAILED:
+    case STATUS_CONNECTION_DISCONNECTED:
+    case STATUS_PORT_UNREACHABLE:
+    case STATUS_HOPLIMIT_EXCEEDED:
+      return WSAECONNRESET;
+
+    case STATUS_LOCAL_DISCONNECT:
+    case STATUS_TRANSACTION_ABORTED:
+    case STATUS_CONNECTION_ABORTED:
+      return WSAECONNABORTED;
+
+    case STATUS_BAD_NETWORK_PATH:
+    case STATUS_NETWORK_UNREACHABLE:
+    case STATUS_PROTOCOL_UNREACHABLE:
+      return WSAENETUNREACH;
+
+    case STATUS_HOST_UNREACHABLE:
+      return WSAEHOSTUNREACH;
+
+    case STATUS_CANCELLED:
+    case STATUS_REQUEST_ABORTED:
+      return WSAEINTR;
+
+    case STATUS_BUFFER_OVERFLOW:
+    case STATUS_INVALID_BUFFER_SIZE:
+      return WSAEMSGSIZE;
+
+    case STATUS_BUFFER_TOO_SMALL:
+    case STATUS_ACCESS_VIOLATION:
+      return WSAEFAULT;
+
+    case STATUS_DEVICE_NOT_READY:
+    case STATUS_REQUEST_NOT_ACCEPTED:
+      return WSAEWOULDBLOCK;
+
+    case STATUS_INVALID_NETWORK_RESPONSE:
+    case STATUS_NETWORK_BUSY:
+    case STATUS_NO_SUCH_DEVICE:
+    case STATUS_NO_SUCH_FILE:
+    case STATUS_OBJECT_PATH_NOT_FOUND:
+    case STATUS_OBJECT_NAME_NOT_FOUND:
+    case STATUS_UNEXPECTED_NETWORK_ERROR:
+      return WSAENETDOWN;
+
+    case STATUS_INVALID_CONNECTION:
+      return WSAENOTCONN;
+
+    case STATUS_REMOTE_NOT_LISTENING:
+    case STATUS_CONNECTION_REFUSED:
+      return WSAECONNREFUSED;
+
+    case STATUS_PIPE_DISCONNECTED:
+      return WSAESHUTDOWN;
+
+    case STATUS_CONFLICTING_ADDRESSES:
+    case STATUS_INVALID_ADDRESS:
+    case STATUS_INVALID_ADDRESS_COMPONENT:
+      return WSAEADDRNOTAVAIL;
+
+    case STATUS_NOT_SUPPORTED:
+    case STATUS_NOT_IMPLEMENTED:
+      return WSAEOPNOTSUPP;
+
+    case STATUS_ACCESS_DENIED:
+      return WSAEACCES;
+
+    default:
+      if ((status & (FACILITY_NTWIN32 << 16)) == (FACILITY_NTWIN32 << 16) &&
+          (status & (ERROR_SEVERITY_ERROR | ERROR_SEVERITY_WARNING))) {
+        /* It's a windows error that has been previously mapped to an ntstatus
+         * code. */
+        return (DWORD) (status & 0xffff);
+      } else {
+        /* The default fallback for unmappable ntstatus codes. */
+        return WSAEINVAL;
+      }
+  }
+}
+
+
+/*
+ * This function provides a workaround for a bug in the winsock implementation
+ * of WSARecv. The problem is that when SetFileCompletionNotificationModes is
+ * used to avoid IOCP notifications of completed reads, WSARecv does not
+ * reliably indicate whether we can expect a completion package to be posted
+ * when the receive buffer is smaller than the received datagram.
+ *
+ * However it is desirable to use SetFileCompletionNotificationModes because
+ * it yields a massive performance increase.
+ *
+ * This function provides a workaround for that bug, but it only works for the
+ * specific case that we need it for. E.g. it assumes that the "avoid iocp"
+ * bit has been set, and supports only overlapped operation. It also requires
+ * the user to use the default msafd driver, doesn't work when other LSPs are
+ * stacked on top of it.
+ */
+int WSAAPI uv_wsarecv_workaround(SOCKET socket, WSABUF* buffers,
+    DWORD buffer_count, DWORD* bytes, DWORD* flags, WSAOVERLAPPED *overlapped,
+    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine) {
+  NTSTATUS status;
+  void* apc_context;
+  IO_STATUS_BLOCK* iosb = (IO_STATUS_BLOCK*) &overlapped->Internal;
+  AFD_RECV_INFO info;
+  DWORD error;
+
+  if (overlapped == NULL || completion_routine != NULL) {
+    WSASetLastError(WSAEINVAL);
+    return SOCKET_ERROR;
+  }
+
+  info.BufferArray = buffers;
+  info.BufferCount = buffer_count;
+  info.AfdFlags = AFD_OVERLAPPED;
+  info.TdiFlags = TDI_RECEIVE_NORMAL;
+
+  if (*flags & MSG_PEEK) {
+    info.TdiFlags |= TDI_RECEIVE_PEEK;
+  }
+
+  if (*flags & MSG_PARTIAL) {
+    info.TdiFlags |= TDI_RECEIVE_PARTIAL;
+  }
+
+  if (!((intptr_t) overlapped->hEvent & 1)) {
+    apc_context = (void*) overlapped;
+  } else {
+    apc_context = NULL;
+  }
+
+  iosb->Status = STATUS_PENDING;
+  iosb->Pointer = 0;
+
+  status = pNtDeviceIoControlFile((HANDLE) socket,
+                                  overlapped->hEvent,
+                                  NULL,
+                                  apc_context,
+                                  iosb,
+                                  IOCTL_AFD_RECEIVE,
+                                  &info,
+                                  sizeof(info),
+                                  NULL,
+                                  0);
+
+  *flags = 0;
+  *bytes = (DWORD) iosb->Information;
+
+  switch (status) {
+    case STATUS_SUCCESS:
+      error = ERROR_SUCCESS;
+      break;
+
+    case STATUS_PENDING:
+      error = WSA_IO_PENDING;
+      break;
+
+    case STATUS_BUFFER_OVERFLOW:
+      error = WSAEMSGSIZE;
+      break;
+
+    case STATUS_RECEIVE_EXPEDITED:
+      error = ERROR_SUCCESS;
+      *flags = MSG_OOB;
+      break;
+
+    case STATUS_RECEIVE_PARTIAL_EXPEDITED:
+      error = ERROR_SUCCESS;
+      *flags = MSG_PARTIAL | MSG_OOB;
+      break;
+
+    case STATUS_RECEIVE_PARTIAL:
+      error = ERROR_SUCCESS;
+      *flags = MSG_PARTIAL;
+      break;
+
+    default:
+      error = uv_ntstatus_to_winsock_error(status);
+      break;
+  }
+
+  WSASetLastError(error);
+
+  if (error == ERROR_SUCCESS) {
+    return 0;
+  } else {
+    return SOCKET_ERROR;
+  }
+}
+
+
+/* See description of uv_wsarecv_workaround. */
+int WSAAPI uv_wsarecvfrom_workaround(SOCKET socket, WSABUF* buffers,
+    DWORD buffer_count, DWORD* bytes, DWORD* flags, struct sockaddr* addr,
+    int* addr_len, WSAOVERLAPPED *overlapped,
+    LPWSAOVERLAPPED_COMPLETION_ROUTINE completion_routine) {
+  NTSTATUS status;
+  void* apc_context;
+  IO_STATUS_BLOCK* iosb = (IO_STATUS_BLOCK*) &overlapped->Internal;
+  AFD_RECV_DATAGRAM_INFO info;
+  DWORD error;
+
+  if (overlapped == NULL || addr == NULL || addr_len == NULL ||
+      completion_routine != NULL) {
+    WSASetLastError(WSAEINVAL);
+    return SOCKET_ERROR;
+  }
+
+  info.BufferArray = buffers;
+  info.BufferCount = buffer_count;
+  info.AfdFlags = AFD_OVERLAPPED;
+  info.TdiFlags = TDI_RECEIVE_NORMAL;
+  info.Address = addr;
+  info.AddressLength = addr_len;
+
+  if (*flags & MSG_PEEK) {
+    info.TdiFlags |= TDI_RECEIVE_PEEK;
+  }
+
+  if (*flags & MSG_PARTIAL) {
+    info.TdiFlags |= TDI_RECEIVE_PARTIAL;
+  }
+
+  if (!((intptr_t) overlapped->hEvent & 1)) {
+    apc_context = (void*) overlapped;
+  } else {
+    apc_context = NULL;
+  }
+
+  iosb->Status = STATUS_PENDING;
+  iosb->Pointer = 0;
+
+  status = pNtDeviceIoControlFile((HANDLE) socket,
+                                  overlapped->hEvent,
+                                  NULL,
+                                  apc_context,
+                                  iosb,
+                                  IOCTL_AFD_RECEIVE_DATAGRAM,
+                                  &info,
+                                  sizeof(info),
+                                  NULL,
+                                  0);
+
+  *flags = 0;
+  *bytes = (DWORD) iosb->Information;
+
+  switch (status) {
+    case STATUS_SUCCESS:
+      error = ERROR_SUCCESS;
+      break;
+
+    case STATUS_PENDING:
+      error = WSA_IO_PENDING;
+      break;
+
+    case STATUS_BUFFER_OVERFLOW:
+      error = WSAEMSGSIZE;
+      break;
+
+    case STATUS_RECEIVE_EXPEDITED:
+      error = ERROR_SUCCESS;
+      *flags = MSG_OOB;
+      break;
+
+    case STATUS_RECEIVE_PARTIAL_EXPEDITED:
+      error = ERROR_SUCCESS;
+      *flags = MSG_PARTIAL | MSG_OOB;
+      break;
+
+    case STATUS_RECEIVE_PARTIAL:
+      error = ERROR_SUCCESS;
+      *flags = MSG_PARTIAL;
+      break;
+
+    default:
+      error = uv_ntstatus_to_winsock_error(status);
+      break;
+  }
+
+  WSASetLastError(error);
+
+  if (error == ERROR_SUCCESS) {
+    return 0;
+  } else {
+    return SOCKET_ERROR;
+  }
+}
+
+
+int WSAAPI uv_msafd_poll(SOCKET socket, AFD_POLL_INFO* info_in,
+    AFD_POLL_INFO* info_out, OVERLAPPED* overlapped) {
+  IO_STATUS_BLOCK iosb;
+  IO_STATUS_BLOCK* iosb_ptr;
+  HANDLE event = NULL;
+  void* apc_context;
+  NTSTATUS status;
+  DWORD error;
+
+  if (overlapped != NULL) {
+    /* Overlapped operation. */
+    iosb_ptr = (IO_STATUS_BLOCK*) &overlapped->Internal;
+    event = overlapped->hEvent;
+
+    /* Do not report iocp completion if hEvent is tagged. */
+    if ((uintptr_t) event & 1) {
+      event = (HANDLE)((uintptr_t) event & ~(uintptr_t) 1);
+      apc_context = NULL;
+    } else {
+      apc_context = overlapped;
+    }
+
+  } else {
+    /* Blocking operation. */
+    iosb_ptr = &iosb;
+    event = CreateEvent(NULL, FALSE, FALSE, NULL);
+    if (event == NULL) {
+      return SOCKET_ERROR;
+    }
+    apc_context = NULL;
+  }
+
+  iosb_ptr->Status = STATUS_PENDING;
+  status = pNtDeviceIoControlFile((HANDLE) socket,
+                                  event,
+                                  NULL,
+                                  apc_context,
+                                  iosb_ptr,
+                                  IOCTL_AFD_POLL,
+                                  info_in,
+                                  sizeof *info_in,
+                                  info_out,
+                                  sizeof *info_out);
+
+  if (overlapped == NULL) {
+    /* If this is a blocking operation, wait for the event to become signaled,
+     * and then grab the real status from the io status block. */
+    if (status == STATUS_PENDING) {
+      DWORD r = WaitForSingleObject(event, INFINITE);
+
+      if (r == WAIT_FAILED) {
+        DWORD saved_error = GetLastError();
+        CloseHandle(event);
+        WSASetLastError(saved_error);
+        return SOCKET_ERROR;
+      }
+
+      status = iosb.Status;
+    }
+
+    CloseHandle(event);
+  }
+
+  switch (status) {
+    case STATUS_SUCCESS:
+      error = ERROR_SUCCESS;
+      break;
+
+    case STATUS_PENDING:
+      error = WSA_IO_PENDING;
+      break;
+
+    default:
+      error = uv_ntstatus_to_winsock_error(status);
+      break;
+  }
+
+  WSASetLastError(error);
+
+  if (error == ERROR_SUCCESS) {
+    return 0;
+  } else {
+    return SOCKET_ERROR;
+  }
+}
+
+int uv__convert_to_localhost_if_unspecified(const struct sockaddr* addr,
+                                            struct sockaddr_storage* storage) {
+  struct sockaddr_in* dest4;
+  struct sockaddr_in6* dest6;
+
+  if (addr == NULL)
+    return UV_EINVAL;
+
+  switch (addr->sa_family) {
+  case AF_INET:
+    dest4 = (struct sockaddr_in*) storage;
+    memcpy(dest4, addr, sizeof(*dest4));
+    if (dest4->sin_addr.s_addr == 0)
+      dest4->sin_addr.s_addr = htonl(INADDR_LOOPBACK);
+    return 0;
+  case AF_INET6:
+    dest6 = (struct sockaddr_in6*) storage;
+    memcpy(dest6, addr, sizeof(*dest6));
+    if (memcmp(&dest6->sin6_addr,
+               &uv_addr_ip6_any_.sin6_addr,
+               sizeof(uv_addr_ip6_any_.sin6_addr)) == 0) {
+      struct in6_addr init_sin6_addr = IN6ADDR_LOOPBACK_INIT;
+      dest6->sin6_addr = init_sin6_addr;
+    }
+    return 0;
+  default:
+    return UV_EINVAL;
+  }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winsock.h b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winsock.h
new file mode 100644
index 0000000..7ecb755
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/libuv/win/winsock.h
@@ -0,0 +1,193 @@
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#ifndef UV_WIN_WINSOCK_H_
+#define UV_WIN_WINSOCK_H_
+
+#include <winsock2.h>
+#include <iptypes.h>
+#include <mswsock.h>
+#include <ws2tcpip.h>
+#include <windows.h>
+
+#include "winapi.h"
+
+
+/*
+ * MinGW is missing these too
+ */
+#ifndef SO_UPDATE_CONNECT_CONTEXT
+# define SO_UPDATE_CONNECT_CONTEXT 0x7010
+#endif
+
+#ifndef TCP_KEEPALIVE
+# define TCP_KEEPALIVE 3
+#endif
+
+#ifndef IPV6_V6ONLY
+# define IPV6_V6ONLY 27
+#endif
+
+#ifndef IPV6_HOPLIMIT
+# define IPV6_HOPLIMIT 21
+#endif
+
+#ifndef SIO_BASE_HANDLE
+# define SIO_BASE_HANDLE 0x48000022
+#endif
+
+/*
+ * TDI defines that are only in the DDK.
+ * We only need receive flags so far.
+ */
+#ifndef TDI_RECEIVE_NORMAL
+  #define TDI_RECEIVE_BROADCAST           0x00000004
+  #define TDI_RECEIVE_MULTICAST           0x00000008
+  #define TDI_RECEIVE_PARTIAL             0x00000010
+  #define TDI_RECEIVE_NORMAL              0x00000020
+  #define TDI_RECEIVE_EXPEDITED           0x00000040
+  #define TDI_RECEIVE_PEEK                0x00000080
+  #define TDI_RECEIVE_NO_RESPONSE_EXP     0x00000100
+  #define TDI_RECEIVE_COPY_LOOKAHEAD      0x00000200
+  #define TDI_RECEIVE_ENTIRE_MESSAGE      0x00000400
+  #define TDI_RECEIVE_AT_DISPATCH_LEVEL   0x00000800
+  #define TDI_RECEIVE_CONTROL_INFO        0x00001000
+  #define TDI_RECEIVE_FORCE_INDICATION    0x00002000
+  #define TDI_RECEIVE_NO_PUSH             0x00004000
+#endif
+
+/*
+ * The "Auxiliary Function Driver" is the windows kernel-mode driver that does
+ * TCP, UDP etc. Winsock is just a layer that dispatches requests to it.
+ * Having these definitions allows us to bypass winsock and make an AFD kernel
+ * call directly, avoiding a bug in winsock's recvfrom implementation.
+ */
+
+#define AFD_NO_FAST_IO   0x00000001
+#define AFD_OVERLAPPED   0x00000002
+#define AFD_IMMEDIATE    0x00000004
+
+#define AFD_POLL_RECEIVE_BIT            0
+#define AFD_POLL_RECEIVE                (1 << AFD_POLL_RECEIVE_BIT)
+#define AFD_POLL_RECEIVE_EXPEDITED_BIT  1
+#define AFD_POLL_RECEIVE_EXPEDITED      (1 << AFD_POLL_RECEIVE_EXPEDITED_BIT)
+#define AFD_POLL_SEND_BIT               2
+#define AFD_POLL_SEND                   (1 << AFD_POLL_SEND_BIT)
+#define AFD_POLL_DISCONNECT_BIT         3
+#define AFD_POLL_DISCONNECT             (1 << AFD_POLL_DISCONNECT_BIT)
+#define AFD_POLL_ABORT_BIT              4
+#define AFD_POLL_ABORT                  (1 << AFD_POLL_ABORT_BIT)
+#define AFD_POLL_LOCAL_CLOSE_BIT        5
+#define AFD_POLL_LOCAL_CLOSE            (1 << AFD_POLL_LOCAL_CLOSE_BIT)
+#define AFD_POLL_CONNECT_BIT            6
+#define AFD_POLL_CONNECT                (1 << AFD_POLL_CONNECT_BIT)
+#define AFD_POLL_ACCEPT_BIT             7
+#define AFD_POLL_ACCEPT                 (1 << AFD_POLL_ACCEPT_BIT)
+#define AFD_POLL_CONNECT_FAIL_BIT       8
+#define AFD_POLL_CONNECT_FAIL           (1 << AFD_POLL_CONNECT_FAIL_BIT)
+#define AFD_POLL_QOS_BIT                9
+#define AFD_POLL_QOS                    (1 << AFD_POLL_QOS_BIT)
+#define AFD_POLL_GROUP_QOS_BIT          10
+#define AFD_POLL_GROUP_QOS              (1 << AFD_POLL_GROUP_QOS_BIT)
+
+#define AFD_NUM_POLL_EVENTS             11
+#define AFD_POLL_ALL                    ((1 << AFD_NUM_POLL_EVENTS) - 1)
+
+typedef struct _AFD_RECV_DATAGRAM_INFO {
+    LPWSABUF BufferArray;
+    ULONG BufferCount;
+    ULONG AfdFlags;
+    ULONG TdiFlags;
+    struct sockaddr* Address;
+    int* AddressLength;
+} AFD_RECV_DATAGRAM_INFO, *PAFD_RECV_DATAGRAM_INFO;
+
+typedef struct _AFD_RECV_INFO {
+    LPWSABUF BufferArray;
+    ULONG BufferCount;
+    ULONG AfdFlags;
+    ULONG TdiFlags;
+} AFD_RECV_INFO, *PAFD_RECV_INFO;
+
+
+#define _AFD_CONTROL_CODE(operation, method) \
+    ((FSCTL_AFD_BASE) << 12 | (operation << 2) | method)
+
+#define FSCTL_AFD_BASE FILE_DEVICE_NETWORK
+
+#define AFD_RECEIVE            5
+#define AFD_RECEIVE_DATAGRAM   6
+#define AFD_POLL               9
+
+#define IOCTL_AFD_RECEIVE \
+    _AFD_CONTROL_CODE(AFD_RECEIVE, METHOD_NEITHER)
+
+#define IOCTL_AFD_RECEIVE_DATAGRAM \
+    _AFD_CONTROL_CODE(AFD_RECEIVE_DATAGRAM, METHOD_NEITHER)
+
+#define IOCTL_AFD_POLL \
+    _AFD_CONTROL_CODE(AFD_POLL, METHOD_BUFFERED)
+
+#if defined(__MINGW32__) && !defined(__MINGW64_VERSION_MAJOR)
+typedef struct _IP_ADAPTER_UNICAST_ADDRESS_XP {
+  /* FIXME: __C89_NAMELESS was removed */
+  /* __C89_NAMELESS */ union {
+    ULONGLONG Alignment;
+    /* __C89_NAMELESS */ struct {
+      ULONG Length;
+      DWORD Flags;
+    };
+  };
+  struct _IP_ADAPTER_UNICAST_ADDRESS_XP *Next;
+  SOCKET_ADDRESS Address;
+  IP_PREFIX_ORIGIN PrefixOrigin;
+  IP_SUFFIX_ORIGIN SuffixOrigin;
+  IP_DAD_STATE DadState;
+  ULONG ValidLifetime;
+  ULONG PreferredLifetime;
+  ULONG LeaseLifetime;
+} IP_ADAPTER_UNICAST_ADDRESS_XP,*PIP_ADAPTER_UNICAST_ADDRESS_XP;
+
+typedef struct _IP_ADAPTER_UNICAST_ADDRESS_LH {
+  union {
+    ULONGLONG Alignment;
+    struct {
+      ULONG Length;
+      DWORD Flags;
+    };
+  };
+  struct _IP_ADAPTER_UNICAST_ADDRESS_LH *Next;
+  SOCKET_ADDRESS Address;
+  IP_PREFIX_ORIGIN PrefixOrigin;
+  IP_SUFFIX_ORIGIN SuffixOrigin;
+  IP_DAD_STATE DadState;
+  ULONG ValidLifetime;
+  ULONG PreferredLifetime;
+  ULONG LeaseLifetime;
+  UINT8 OnLinkPrefixLength;
+} IP_ADAPTER_UNICAST_ADDRESS_LH,*PIP_ADAPTER_UNICAST_ADDRESS_LH;
+
+#endif
+
+int uv__convert_to_localhost_if_unspecified(const struct sockaddr* addr,
+                                            struct sockaddr_storage* storage);
+
+#endif /* UV_WIN_WINSOCK_H_ */
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/resources/bootstrap-4.1.min.js.gz b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/bootstrap-4.1.min.js.gz
new file mode 100644
index 0000000..a7797e1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/bootstrap-4.1.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/resources/coreui-2.1.min.css.gz b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/coreui-2.1.min.css.gz
new file mode 100644
index 0000000..d4f43ad
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/coreui-2.1.min.css.gz
Binary files differ
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/resources/coreui-2.1.min.js.gz b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/coreui-2.1.min.js.gz
new file mode 100644
index 0000000..cf4ccb1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/coreui-2.1.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/resources/feather-4.8.min.js.gz b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/feather-4.8.min.js.gz
new file mode 100644
index 0000000..d275865
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/feather-4.8.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/resources/jquery-3.3.slim.min.js.gz b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/jquery-3.3.slim.min.js.gz
new file mode 100644
index 0000000..712e06c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/jquery-3.3.slim.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/resources/popper-1.14.min.js.gz b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/popper-1.14.min.js.gz
new file mode 100644
index 0000000..c6ebec8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/popper-1.14.min.js.gz
Binary files differ
diff --git a/third_party/allwpilib_2019/wpiutil/src/main/native/resources/wpilib-128.png b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/wpilib-128.png
new file mode 100644
index 0000000..0169c0d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/main/native/resources/wpilib-128.png
Binary files differ
diff --git a/third_party/allwpilib_2019/wpiutil/src/netconsoleServer/native/cpp/main.cpp b/third_party/allwpilib_2019/wpiutil/src/netconsoleServer/native/cpp/main.cpp
new file mode 100644
index 0000000..c673008
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/netconsoleServer/native/cpp/main.cpp
@@ -0,0 +1,250 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#ifdef __APPLE__
+#include <util.h>
+#elif !defined(_WIN32)
+#include <pty.h>
+#endif
+
+#include "wpi/MathExtras.h"
+#include "wpi/SmallVector.h"
+#include "wpi/raw_ostream.h"
+#include "wpi/raw_uv_ostream.h"
+#include "wpi/timestamp.h"
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/Pipe.h"
+#include "wpi/uv/Process.h"
+#include "wpi/uv/Signal.h"
+#include "wpi/uv/Tcp.h"
+#include "wpi/uv/Tty.h"
+#include "wpi/uv/Udp.h"
+#include "wpi/uv/util.h"
+
+namespace uv = wpi::uv;
+
+static uint64_t startTime = wpi::Now();
+
+static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len,
+                          wpi::SmallVectorImpl<uv::Buffer>& bufs, bool tcp,
+                          uint16_t tcpSeq) {
+  // scan for last newline
+  wpi::StringRef str(buf.base, len);
+  size_t idx = str.rfind('\n');
+  if (idx == wpi::StringRef::npos) {
+    // no newline yet, just keep appending to remainder
+    rem += str;
+    return false;
+  }
+
+  // build output
+  wpi::raw_uv_ostream out(bufs, 4096);
+  wpi::StringRef toCopy = str.slice(0, idx + 1);
+  if (tcp) {
+    // Header is 2 byte len, 1 byte type, 4 byte timestamp, 2 byte sequence num
+    uint32_t ts = wpi::FloatToBits((wpi::Now() - startTime) * 1.0e-6);
+    uint16_t len = rem.size() + toCopy.size() + 1 + 4 + 2;
+    out << wpi::ArrayRef<uint8_t>({static_cast<uint8_t>((len >> 8) & 0xff),
+                                   static_cast<uint8_t>(len & 0xff), 12,
+                                   static_cast<uint8_t>((ts >> 24) & 0xff),
+                                   static_cast<uint8_t>((ts >> 16) & 0xff),
+                                   static_cast<uint8_t>((ts >> 8) & 0xff),
+                                   static_cast<uint8_t>(ts & 0xff),
+                                   static_cast<uint8_t>((tcpSeq >> 8) & 0xff),
+                                   static_cast<uint8_t>(tcpSeq & 0xff)});
+  }
+  out << rem << toCopy;
+
+  // reset remainder
+  rem = str.slice(idx + 1, wpi::StringRef::npos);
+  return true;
+}
+
+static void CopyUdp(uv::Stream& in, std::shared_ptr<uv::Udp> out,
+                    bool broadcast) {
+  sockaddr_in addr;
+  if (broadcast) {
+    out->SetBroadcast(true);
+    uv::NameToAddr("0.0.0.0", 6666, &addr);
+  } else {
+    uv::NameToAddr("127.0.0.1", 6666, &addr);
+  }
+
+  in.data.connect(
+      [ rem = std::make_shared<std::string>(), outPtr = out.get(), addr ](
+          uv::Buffer & buf, size_t len) {
+        // build buffers
+        wpi::SmallVector<uv::Buffer, 4> bufs;
+        if (!NewlineBuffer(*rem, buf, len, bufs, false, 0)) return;
+
+        // send output
+        outPtr->Send(addr, bufs, [](auto bufs2, uv::Error) {
+          for (auto buf : bufs2) buf.Deallocate();
+        });
+      },
+      out);
+}
+
+static void CopyTcp(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
+  struct StreamData {
+    std::string rem;
+    uint16_t seq = 0;
+  };
+  in.data.connect([ data = std::make_shared<StreamData>(), outPtr = out.get() ](
+                      uv::Buffer & buf, size_t len) {
+    // build buffers
+    wpi::SmallVector<uv::Buffer, 4> bufs;
+    if (!NewlineBuffer(data->rem, buf, len, bufs, true, data->seq++)) return;
+
+    // send output
+    outPtr->Write(bufs, [](auto bufs2, uv::Error) {
+      for (auto buf : bufs2) buf.Deallocate();
+    });
+  },
+                  out);
+}
+
+static void CopyStream(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
+  in.data.connect([out](uv::Buffer& buf, size_t len) {
+    uv::Buffer buf2 = buf.Dup();
+    buf2.len = len;
+    out->Write(buf2, [](auto bufs, uv::Error) {
+      for (auto buf : bufs) buf.Deallocate();
+    });
+  });
+}
+
+int main(int argc, char* argv[]) {
+  // parse arguments
+  int programArgc = 1;
+  bool useUdp = false;
+  bool broadcastUdp = false;
+  bool err = false;
+
+  while (programArgc < argc && argv[programArgc][0] == '-') {
+    if (wpi::StringRef(argv[programArgc]) == "-u") {
+      useUdp = true;
+    } else if (wpi::StringRef(argv[programArgc]) == "-b") {
+      useUdp = true;
+      broadcastUdp = true;
+    } else {
+      wpi::errs() << "unrecognized command line option " << argv[programArgc]
+                  << '\n';
+      err = true;
+    }
+    ++programArgc;
+  }
+
+  if (err || (argc - programArgc) < 1) {
+    wpi::errs()
+        << argv[0] << " [-ub] program [arguments ...]\n"
+        << "  -u  send udp to localhost port 6666 instead of using tcp\n"
+        << "  -b  broadcast udp to port 6666 instead of using tcp\n";
+    return EXIT_FAILURE;
+  }
+
+  uv::Process::DisableStdioInheritance();
+
+  auto loop = uv::Loop::Create();
+  loop->error.connect(
+      [](uv::Error err) { wpi::errs() << "uv ERROR: " << err.str() << '\n'; });
+
+  // create pipes to communicate with child
+  auto stdinPipe = uv::Pipe::Create(loop);
+  auto stdoutPipe = uv::Pipe::Create(loop);
+  auto stderrPipe = uv::Pipe::Create(loop);
+
+  // create tty to pass from our console to child's
+  auto stdinTty = uv::Tty::Create(loop, 0, true);
+  auto stdoutTty = uv::Tty::Create(loop, 1, false);
+  auto stderrTty = uv::Tty::Create(loop, 2, false);
+
+  // pass through our console to child's (bidirectional)
+  if (stdinTty) CopyStream(*stdinTty, stdinPipe);
+  if (stdoutTty) CopyStream(*stdoutPipe, stdoutTty);
+  if (stderrTty) CopyStream(*stderrPipe, stderrTty);
+
+  // when our stdin closes, also close child stdin
+  if (stdinTty) stdinTty->end.connect([stdinPipe] { stdinPipe->Close(); });
+
+  if (useUdp) {
+    auto udp = uv::Udp::Create(loop);
+    // tee stdout and stderr
+    CopyUdp(*stdoutPipe, udp, broadcastUdp);
+    CopyUdp(*stderrPipe, udp, broadcastUdp);
+  } else {
+    auto tcp = uv::Tcp::Create(loop);
+
+    // bind to listen address and port
+    tcp->Bind("", 1740);
+
+    // when we get a connection, accept it
+    tcp->connection.connect([ srv = tcp.get(), stdoutPipe, stderrPipe ] {
+      auto tcp = srv->Accept();
+      if (!tcp) return;
+
+      // close on error
+      tcp->error.connect([s = tcp.get()](wpi::uv::Error err) { s->Close(); });
+
+      // tee stdout and stderr
+      CopyTcp(*stdoutPipe, tcp);
+      CopyTcp(*stderrPipe, tcp);
+    });
+
+    // start listening for incoming connections
+    tcp->Listen();
+  }
+
+  // build process options
+  wpi::SmallVector<uv::Process::Option, 8> options;
+
+  // hook up pipes to child
+  options.emplace_back(
+      uv::Process::StdioCreatePipe(0, *stdinPipe, UV_READABLE_PIPE));
+#ifndef _WIN32
+  // create a PTY so the child does unbuffered output
+  int parentfd, childfd;
+  if (openpty(&parentfd, &childfd, nullptr, nullptr, nullptr) == 0) {
+    stdoutPipe->Open(parentfd);
+    options.emplace_back(uv::Process::StdioInherit(1, childfd));
+  } else {
+    options.emplace_back(
+        uv::Process::StdioCreatePipe(1, *stdoutPipe, UV_WRITABLE_PIPE));
+  }
+#else
+  options.emplace_back(
+      uv::Process::StdioCreatePipe(1, *stdoutPipe, UV_WRITABLE_PIPE));
+#endif
+  options.emplace_back(
+      uv::Process::StdioCreatePipe(2, *stderrPipe, UV_WRITABLE_PIPE));
+
+  // pass our args as the child args (argv[1] becomes child argv[0], etc)
+  for (int i = programArgc; i < argc; ++i) options.emplace_back(argv[i]);
+
+  auto proc = uv::Process::SpawnArray(loop, argv[programArgc], options);
+  if (!proc) {
+    wpi::errs() << "could not start subprocess\n";
+    return EXIT_FAILURE;
+  }
+  proc->exited.connect([](int64_t status, int) { std::exit(status); });
+
+  // start reading
+  if (stdinTty) stdinTty->StartRead();
+  stdoutPipe->StartRead();
+  stderrPipe->StartRead();
+
+  // pass various signals to child
+  auto sigHandler = [proc](int signum) { proc->Kill(signum); };
+  for (int signum : {SIGINT, SIGHUP, SIGTERM}) {
+    auto sig = uv::Signal::Create(loop);
+    sig->Start(signum);
+    sig->signal.connect(sigHandler);
+  }
+
+  // run the loop!
+  loop->Run();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/netconsoleTee/native/cpp/main.cpp b/third_party/allwpilib_2019/wpiutil/src/netconsoleTee/native/cpp/main.cpp
new file mode 100644
index 0000000..d14b322
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/netconsoleTee/native/cpp/main.cpp
@@ -0,0 +1,188 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/MathExtras.h"
+#include "wpi/SmallVector.h"
+#include "wpi/raw_ostream.h"
+#include "wpi/raw_uv_ostream.h"
+#include "wpi/timestamp.h"
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/Tcp.h"
+#include "wpi/uv/Tty.h"
+#include "wpi/uv/Udp.h"
+#include "wpi/uv/util.h"
+
+namespace uv = wpi::uv;
+
+static uint64_t startTime = wpi::Now();
+
+static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len,
+                          wpi::SmallVectorImpl<uv::Buffer>& bufs, bool tcp,
+                          uint16_t tcpSeq) {
+  // scan for last newline
+  wpi::StringRef str(buf.base, len);
+  size_t idx = str.rfind('\n');
+  if (idx == wpi::StringRef::npos) {
+    // no newline yet, just keep appending to remainder
+    rem += str;
+    return false;
+  }
+
+  // build output
+  wpi::raw_uv_ostream out(bufs, 4096);
+  wpi::StringRef toCopy = str.slice(0, idx + 1);
+  if (tcp) {
+    // Header is 2 byte len, 1 byte type, 4 byte timestamp, 2 byte sequence num
+    uint32_t ts = wpi::FloatToBits((wpi::Now() - startTime) * 1.0e-6);
+    uint16_t len = rem.size() + toCopy.size() + 1 + 4 + 2;
+    out << wpi::ArrayRef<uint8_t>({static_cast<uint8_t>((len >> 8) & 0xff),
+                                   static_cast<uint8_t>(len & 0xff), 12,
+                                   static_cast<uint8_t>((ts >> 24) & 0xff),
+                                   static_cast<uint8_t>((ts >> 16) & 0xff),
+                                   static_cast<uint8_t>((ts >> 8) & 0xff),
+                                   static_cast<uint8_t>(ts & 0xff),
+                                   static_cast<uint8_t>((tcpSeq >> 8) & 0xff),
+                                   static_cast<uint8_t>(tcpSeq & 0xff)});
+  }
+  out << rem << toCopy;
+
+  // reset remainder
+  rem = str.slice(idx + 1, wpi::StringRef::npos);
+  return true;
+}
+
+static void CopyUdp(uv::Stream& in, std::shared_ptr<uv::Udp> out,
+                    bool broadcast) {
+  sockaddr_in addr;
+  if (broadcast) {
+    out->SetBroadcast(true);
+    uv::NameToAddr("0.0.0.0", 6666, &addr);
+  } else {
+    uv::NameToAddr("127.0.0.1", 6666, &addr);
+  }
+
+  in.data.connect(
+      [ rem = std::make_shared<std::string>(), outPtr = out.get(), addr ](
+          uv::Buffer & buf, size_t len) {
+        // build buffers
+        wpi::SmallVector<uv::Buffer, 4> bufs;
+        if (!NewlineBuffer(*rem, buf, len, bufs, false, 0)) return;
+
+        // send output
+        outPtr->Send(addr, bufs, [](auto bufs2, uv::Error) {
+          for (auto buf : bufs2) buf.Deallocate();
+        });
+      },
+      out);
+}
+
+static void CopyTcp(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
+  struct StreamData {
+    std::string rem;
+    uint16_t seq = 0;
+  };
+  in.data.connect([ data = std::make_shared<StreamData>(), outPtr = out.get() ](
+                      uv::Buffer & buf, size_t len) {
+    // build buffers
+    wpi::SmallVector<uv::Buffer, 4> bufs;
+    if (!NewlineBuffer(data->rem, buf, len, bufs, true, data->seq++)) return;
+
+    // send output
+    outPtr->Write(bufs, [](auto bufs2, uv::Error) {
+      for (auto buf : bufs2) buf.Deallocate();
+    });
+  },
+                  out);
+}
+
+static void CopyStream(uv::Stream& in, std::shared_ptr<uv::Stream> out) {
+  in.data.connect([out](uv::Buffer& buf, size_t len) {
+    uv::Buffer buf2 = buf.Dup();
+    buf2.len = len;
+    out->Write(buf2, [](auto bufs, uv::Error) {
+      for (auto buf : bufs) buf.Deallocate();
+    });
+  });
+}
+
+int main(int argc, char* argv[]) {
+  // parse arguments
+  int arg = 1;
+  bool useUdp = false;
+  bool broadcastUdp = false;
+  bool err = false;
+
+  while (arg < argc && argv[arg][0] == '-') {
+    if (wpi::StringRef(argv[arg]) == "-u") {
+      useUdp = true;
+    } else if (wpi::StringRef(argv[arg]) == "-b") {
+      useUdp = true;
+      broadcastUdp = true;
+    } else {
+      wpi::errs() << "unrecognized command line option " << argv[arg] << '\n';
+      err = true;
+    }
+    ++arg;
+  }
+
+  if (err) {
+    wpi::errs()
+        << argv[0] << " [-ub]\n"
+        << "  -u  send udp to localhost port 6666 instead of using tcp\n"
+        << "  -b  broadcast udp to port 6666 instead of using tcp\n";
+    return EXIT_FAILURE;
+  }
+
+  auto loop = uv::Loop::Create();
+  loop->error.connect(
+      [](uv::Error err) { wpi::errs() << "uv ERROR: " << err.str() << '\n'; });
+
+  // create ttys
+  auto stdinTty = uv::Tty::Create(loop, 0, true);
+  auto stdoutTty = uv::Tty::Create(loop, 1, false);
+
+  // don't bother continuing if we don't have a stdin
+  if (!stdinTty) return EXIT_SUCCESS;
+
+  // pass through our input to output
+  if (stdoutTty) CopyStream(*stdinTty, stdoutTty);
+
+  // when our stdin closes, exit
+  stdinTty->end.connect([] { std::exit(EXIT_SUCCESS); });
+
+  if (useUdp) {
+    auto udp = uv::Udp::Create(loop);
+    // tee
+    CopyUdp(*stdinTty, udp, broadcastUdp);
+  } else {
+    auto tcp = uv::Tcp::Create(loop);
+
+    // bind to listen address and port
+    tcp->Bind("", 1740);
+
+    // when we get a connection, accept it
+    tcp->connection.connect([ srv = tcp.get(), stdinTty ] {
+      auto tcp = srv->Accept();
+      if (!tcp) return;
+
+      // close on error
+      tcp->error.connect([s = tcp.get()](wpi::uv::Error err) { s->Close(); });
+
+      // tee
+      CopyTcp(*stdinTty, tcp);
+    });
+
+    // start listening for incoming connections
+    tcp->Listen();
+  }
+
+  // start reading
+  if (stdinTty) stdinTty->StartRead();
+
+  // run the loop!
+  loop->Run();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/Base64Test.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/Base64Test.cpp
new file mode 100644
index 0000000..99aecb9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/Base64Test.cpp
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+#include "wpi/Base64.h"
+#include "wpi/SmallString.h"
+
+namespace wpi {
+
+struct Base64TestParam {
+  int plain_len;
+  const char* plain;
+  const char* encoded;
+};
+
+std::ostream& operator<<(std::ostream& os, const Base64TestParam& param) {
+  os << "Base64TestParam(Len: " << param.plain_len << ", "
+     << "Plain: \"" << param.plain << "\", "
+     << "Encoded: \"" << param.encoded << "\")";
+  return os;
+}
+
+class Base64Test : public ::testing::TestWithParam<Base64TestParam> {
+ protected:
+  StringRef GetPlain() {
+    if (GetParam().plain_len < 0)
+      return StringRef(GetParam().plain);
+    else
+      return StringRef(GetParam().plain, GetParam().plain_len);
+  }
+};
+
+TEST_P(Base64Test, EncodeStdString) {
+  std::string s;
+  Base64Encode(GetPlain(), &s);
+  ASSERT_EQ(GetParam().encoded, s);
+
+  // text already in s
+  Base64Encode(GetPlain(), &s);
+  ASSERT_EQ(GetParam().encoded, s);
+}
+
+TEST_P(Base64Test, EncodeSmallString) {
+  SmallString<128> buf;
+  ASSERT_EQ(GetParam().encoded, Base64Encode(GetPlain(), buf));
+  // reuse buf
+  ASSERT_EQ(GetParam().encoded, Base64Encode(GetPlain(), buf));
+}
+
+TEST_P(Base64Test, DecodeStdString) {
+  std::string s;
+  StringRef encoded = GetParam().encoded;
+  EXPECT_EQ(encoded.size(), Base64Decode(encoded, &s));
+  ASSERT_EQ(GetPlain(), s);
+
+  // text already in s
+  Base64Decode(encoded, &s);
+  ASSERT_EQ(GetPlain(), s);
+}
+
+TEST_P(Base64Test, DecodeSmallString) {
+  SmallString<128> buf;
+  StringRef encoded = GetParam().encoded;
+  size_t len;
+  StringRef plain = Base64Decode(encoded, &len, buf);
+  EXPECT_EQ(encoded.size(), len);
+  ASSERT_EQ(GetPlain(), plain);
+
+  // reuse buf
+  plain = Base64Decode(encoded, &len, buf);
+  ASSERT_EQ(GetPlain(), plain);
+}
+
+static Base64TestParam sample[] = {
+    {-1, "Send reinforcements", "U2VuZCByZWluZm9yY2VtZW50cw=="},
+    {-1, "Now is the time for all good coders\n to learn C++",
+     "Tm93IGlzIHRoZSB0aW1lIGZvciBhbGwgZ29vZCBjb2RlcnMKIHRvIGxlYXJuIEMrKw=="},
+    {-1,
+     "This is line one\nThis is line two\nThis is line three\nAnd so on...\n",
+     "VGhpcyBpcyBsaW5lIG9uZQpUaGlzIGlzIGxpbmUgdHdvClRoaXMgaXMgbGluZSB0aHJlZQpBb"
+     "mQgc28gb24uLi4K"},
+};
+
+INSTANTIATE_TEST_CASE_P(Base64Sample, Base64Test,
+                        ::testing::ValuesIn(sample), );
+
+static Base64TestParam standard[] = {
+    {0, "", ""},
+    {1, "\0", "AA=="},
+    {2, "\0\0", "AAA="},
+    {3, "\0\0\0", "AAAA"},
+    {1, "\377", "/w=="},
+    {2, "\377\377", "//8="},
+    {3, "\377\377\377", "////"},
+    {2, "\xff\xef", "/+8="},
+};
+
+INSTANTIATE_TEST_CASE_P(Base64Standard, Base64Test,
+                        ::testing::ValuesIn(standard), );
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/HttpParserTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/HttpParserTest.cpp
new file mode 100644
index 0000000..8de2bc6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/HttpParserTest.cpp
@@ -0,0 +1,209 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/HttpParser.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+TEST(HttpParserTest, UrlMethodHeadersComplete) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.url.connect([&](StringRef path) {
+    ASSERT_EQ(path, "/foo/bar");
+    ASSERT_EQ(p.GetUrl(), "/foo/bar");
+    ++callbacks;
+  });
+  p.Execute("GET /foo");
+  p.Execute("/bar");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute(" HTTP/1.1\r\n\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_EQ(p.GetUrl(), "/foo/bar");
+  ASSERT_EQ(p.GetMethod(), HTTP_GET);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, UrlMethodHeader) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.url.connect([&](StringRef path) {
+    ASSERT_EQ(path, "/foo/bar");
+    ASSERT_EQ(p.GetUrl(), "/foo/bar");
+    ++callbacks;
+  });
+  p.Execute("GET /foo");
+  p.Execute("/bar");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute(" HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("F");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_EQ(p.GetUrl(), "/foo/bar");
+  ASSERT_EQ(p.GetMethod(), HTTP_GET);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, StatusHeadersComplete) {
+  HttpParser p{HttpParser::kResponse};
+  int callbacks = 0;
+  p.status.connect([&](StringRef status) {
+    ASSERT_EQ(status, "OK");
+    ASSERT_EQ(p.GetStatusCode(), 200u);
+    ++callbacks;
+  });
+  p.Execute("HTTP/1.1 200");
+  p.Execute(" OK");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_EQ(p.GetStatusCode(), 200u);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, StatusHeader) {
+  HttpParser p{HttpParser::kResponse};
+  int callbacks = 0;
+  p.status.connect([&](StringRef status) {
+    ASSERT_EQ(status, "OK");
+    ASSERT_EQ(p.GetStatusCode(), 200u);
+    ++callbacks;
+  });
+  p.Execute("HTTP/1.1 200");
+  p.Execute(" OK\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("F");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_EQ(p.GetStatusCode(), 200u);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeaderFieldComplete) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.header.connect([&](StringRef name, StringRef value) {
+    ASSERT_EQ(name, "Foo");
+    ASSERT_EQ(value, "Bar");
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Fo");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("o: ");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Bar");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeaderFieldNext) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.header.connect([&](StringRef name, StringRef value) {
+    ASSERT_EQ(name, "Foo");
+    ASSERT_EQ(value, "Bar");
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Fo");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("o: ");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Bar");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("F");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeadersComplete) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool keepAlive) {
+    ASSERT_EQ(keepAlive, false);
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.0\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeadersCompleteHTTP11) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool keepAlive) {
+    ASSERT_EQ(keepAlive, true);
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeadersCompleteKeepAlive) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool keepAlive) {
+    ASSERT_EQ(keepAlive, true);
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.0\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Connection: Keep-Alive\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, HeadersCompleteUpgrade) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool) {
+    ASSERT_TRUE(p.IsUpgrade());
+    ++callbacks;
+  });
+  p.Execute("GET / HTTP/1.0\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("Connection: Upgrade\r\n");
+  p.Execute("Upgrade: websocket\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  ASSERT_FALSE(p.HasError());
+}
+
+TEST(HttpParserTest, Reset) {
+  HttpParser p{HttpParser::kRequest};
+  int callbacks = 0;
+  p.headersComplete.connect([&](bool) { ++callbacks; });
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 0);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 1);
+  p.Reset(HttpParser::kRequest);
+  p.Execute("GET / HTTP/1.1\r\n");
+  ASSERT_EQ(callbacks, 1);
+  p.Execute("\r\n");
+  ASSERT_EQ(callbacks, 2);
+  ASSERT_FALSE(p.HasError());
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/HttpUtilTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/HttpUtilTest.cpp
new file mode 100644
index 0000000..a83214d
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/HttpUtilTest.cpp
@@ -0,0 +1,105 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/HttpUtil.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+TEST(HttpMultipartScannerTest, ExecuteExact) {
+  HttpMultipartScanner scanner("foo");
+  EXPECT_TRUE(scanner.Execute("abcdefg---\r\n--foo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.GetSkipped().empty());
+}
+
+TEST(HttpMultipartScannerTest, ExecutePartial) {
+  HttpMultipartScanner scanner("foo");
+  EXPECT_TRUE(scanner.Execute("abcdefg--").empty());
+  EXPECT_FALSE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("-\r\n").empty());
+  EXPECT_FALSE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("--foo\r").empty());
+  EXPECT_FALSE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, ExecuteTrailing) {
+  HttpMultipartScanner scanner("foo");
+  EXPECT_EQ(scanner.Execute("abcdefg---\r\n--foo\r\nxyz"), "xyz");
+}
+
+TEST(HttpMultipartScannerTest, ExecutePadding) {
+  HttpMultipartScanner scanner("foo");
+  EXPECT_EQ(scanner.Execute("abcdefg---\r\n--foo    \r\nxyz"), "xyz");
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SaveSkipped) {
+  HttpMultipartScanner scanner("foo", true);
+  scanner.Execute("abcdefg---\r\n--foo\r\n");
+  EXPECT_EQ(scanner.GetSkipped(), "abcdefg---\r\n--foo\r\n");
+}
+
+TEST(HttpMultipartScannerTest, Reset) {
+  HttpMultipartScanner scanner("foo", true);
+
+  scanner.Execute("abcdefg---\r\n--foo\r\n");
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_EQ(scanner.GetSkipped(), "abcdefg---\r\n--foo\r\n");
+
+  scanner.Reset(true);
+  EXPECT_FALSE(scanner.IsDone());
+  scanner.SetBoundary("bar");
+
+  scanner.Execute("--foo\r\n--bar\r\n");
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_EQ(scanner.GetSkipped(), "--foo\r\n--bar\r\n");
+}
+
+TEST(HttpMultipartScannerTest, WithoutDashes) {
+  HttpMultipartScanner scanner("foo", true);
+
+  EXPECT_TRUE(scanner.Execute("--\r\nfoo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SeqDashesDashes) {
+  HttpMultipartScanner scanner("foo", true);
+  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SeqDashesNoDashes) {
+  HttpMultipartScanner scanner("foo", true);
+  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
+  EXPECT_FALSE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SeqNoDashesDashes) {
+  HttpMultipartScanner scanner("foo", true);
+  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\r\n--foo\r\n").empty());
+  EXPECT_FALSE(scanner.IsDone());
+}
+
+TEST(HttpMultipartScannerTest, SeqNoDashesNoDashes) {
+  HttpMultipartScanner scanner("foo", true);
+  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+  EXPECT_TRUE(scanner.Execute("\r\nfoo\r\n").empty());
+  EXPECT_TRUE(scanner.IsDone());
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/UidVectorTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/UidVectorTest.cpp
new file mode 100644
index 0000000..e11c7b2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/UidVectorTest.cpp
@@ -0,0 +1,48 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/UidVector.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+TEST(UidVectorTest, Empty) {
+  UidVector<int, 4> v;
+  ASSERT_TRUE(v.empty());
+
+  v.emplace_back(1);
+  ASSERT_FALSE(v.empty());
+}
+
+TEST(UidVectorTest, Erase) {
+  UidVector<int, 4> v;
+  size_t uid = v.emplace_back(1);
+  v.erase(uid);
+  ASSERT_TRUE(v.empty());
+}
+
+TEST(UidVectorTest, Clear) {
+  UidVector<int, 4> v;
+  v.emplace_back(1);
+  v.emplace_back(2);
+  v.clear();
+  ASSERT_TRUE(v.empty());
+}
+
+TEST(UidVectorTest, Iterate) {
+  UidVector<int, 4> v;
+  v.emplace_back(2);
+  v.emplace_back(1);
+  std::vector<int> out;
+  for (auto&& val : v) out.push_back(val);
+  ASSERT_EQ(out.size(), 2u);
+  EXPECT_EQ(out[0], 2);
+  EXPECT_EQ(out[1], 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketClientTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketClientTest.cpp
new file mode 100644
index 0000000..692e2a7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketClientTest.cpp
@@ -0,0 +1,299 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/WebSocket.h"  // NOLINT(build/include_order)
+
+#include "WebSocketTest.h"
+#include "wpi/Base64.h"
+#include "wpi/HttpParser.h"
+#include "wpi/SmallString.h"
+#include "wpi/raw_uv_ostream.h"
+#include "wpi/sha1.h"
+
+namespace wpi {
+
+class WebSocketClientTest : public WebSocketTest {
+ public:
+  WebSocketClientTest() {
+    // Bare bones server
+    req.header.connect([this](StringRef name, StringRef value) {
+      // save key (required for valid response)
+      if (name.equals_lower("sec-websocket-key")) clientKey = value;
+    });
+    req.headersComplete.connect([this](bool) {
+      // send response
+      SmallVector<uv::Buffer, 4> bufs;
+      raw_uv_ostream os{bufs, 4096};
+      os << "HTTP/1.1 101 Switching Protocols\r\n";
+      os << "Upgrade: websocket\r\n";
+      os << "Connection: Upgrade\r\n";
+
+      // accept hash
+      SHA1 hash;
+      hash.Update(clientKey);
+      hash.Update("258EAFA5-E914-47DA-95CA-C5AB0DC85B11");
+      if (mockBadAccept) hash.Update("1");
+      SmallString<64> hashBuf;
+      SmallString<64> acceptBuf;
+      os << "Sec-WebSocket-Accept: "
+         << Base64Encode(hash.RawFinal(hashBuf), acceptBuf) << "\r\n";
+
+      if (!mockProtocol.empty())
+        os << "Sec-WebSocket-Protocol: " << mockProtocol << "\r\n";
+
+      os << "\r\n";
+
+      conn->Write(bufs, [](auto bufs, uv::Error) {
+        for (auto& buf : bufs) buf.Deallocate();
+      });
+
+      serverHeadersDone = true;
+      if (connected) connected();
+    });
+
+    serverPipe->Listen([this] {
+      conn = serverPipe->Accept();
+      conn->StartRead();
+      conn->data.connect([this](uv::Buffer& buf, size_t size) {
+        StringRef data{buf.base, size};
+        if (!serverHeadersDone) {
+          data = req.Execute(data);
+          if (req.HasError()) Finish();
+          ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
+          if (data.empty()) return;
+        }
+        wireData.insert(wireData.end(), data.bytes_begin(), data.bytes_end());
+      });
+      conn->end.connect([this] { Finish(); });
+    });
+  }
+
+  bool mockBadAccept = false;
+  std::vector<uint8_t> wireData;
+  std::shared_ptr<uv::Pipe> conn;
+  HttpParser req{HttpParser::kRequest};
+  SmallString<64> clientKey;
+  std::string mockProtocol;
+  bool serverHeadersDone = false;
+  std::function<void()> connected;
+};
+
+TEST_F(WebSocketClientTest, Open) {
+  int gotOpen = 0;
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      Finish();
+      if (code != 1005 && code != 1006)
+        FAIL() << "Code: " << code << " Reason: " << reason;
+    });
+    ws->open.connect([&](StringRef protocol) {
+      ++gotOpen;
+      Finish();
+      ASSERT_TRUE(protocol.empty());
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotOpen, 1);
+}
+
+TEST_F(WebSocketClientTest, BadAccept) {
+  int gotClosed = 0;
+
+  mockBadAccept = true;
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, StringRef msg) {
+      Finish();
+      ++gotClosed;
+      ASSERT_EQ(code, 1002) << "Message: " << msg;
+    });
+    ws->open.connect([&](StringRef protocol) {
+      Finish();
+      FAIL() << "Got open";
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketClientTest, ProtocolGood) {
+  int gotOpen = 0;
+
+  mockProtocol = "myProtocol";
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(
+        *clientPipe, "/test", pipeName,
+        ArrayRef<StringRef>{"myProtocol", "myProtocol2"});
+    ws->closed.connect([&](uint16_t code, StringRef msg) {
+      Finish();
+      if (code != 1005 && code != 1006)
+        FAIL() << "Code: " << code << "Message: " << msg;
+    });
+    ws->open.connect([&](StringRef protocol) {
+      ++gotOpen;
+      Finish();
+      ASSERT_EQ(protocol, "myProtocol");
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotOpen, 1);
+}
+
+TEST_F(WebSocketClientTest, ProtocolRespNotReq) {
+  int gotClosed = 0;
+
+  mockProtocol = "myProtocol";
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, StringRef msg) {
+      Finish();
+      ++gotClosed;
+      ASSERT_EQ(code, 1003) << "Message: " << msg;
+    });
+    ws->open.connect([&](StringRef protocol) {
+      Finish();
+      FAIL() << "Got open";
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketClientTest, ProtocolReqNotResp) {
+  int gotClosed = 0;
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName,
+                                      StringRef{"myProtocol"});
+    ws->closed.connect([&](uint16_t code, StringRef msg) {
+      Finish();
+      ++gotClosed;
+      ASSERT_EQ(code, 1002) << "Message: " << msg;
+    });
+    ws->open.connect([&](StringRef protocol) {
+      Finish();
+      FAIL() << "Got open";
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotClosed, 1);
+}
+
+//
+// Send and receive data.  Most of these cases are tested in
+// WebSocketServerTest, so only spot check differences like masking.
+//
+
+class WebSocketClientDataTest : public WebSocketClientTest,
+                                public ::testing::WithParamInterface<size_t> {
+ public:
+  WebSocketClientDataTest() {
+    clientPipe->Connect(pipeName, [&] {
+      ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+      if (setupWebSocket) setupWebSocket();
+    });
+  }
+
+  std::function<void()> setupWebSocket;
+  std::shared_ptr<WebSocket> ws;
+};
+
+INSTANTIATE_TEST_CASE_P(WebSocketClientDataTests, WebSocketClientDataTest,
+                        ::testing::Values(0, 1, 125, 126, 65535, 65536), );
+
+TEST_P(WebSocketClientDataTest, SendBinary) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) {
+      ws->SendBinary(uv::Buffer(data), [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x02, true, true, data);
+  AdjustMasking(wireData);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketClientDataTest, ReceiveBinary) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->binary.connect([&](ArrayRef<uint8_t> inData, bool fin) {
+      ++gotCallback;
+      ws->Terminate();
+      ASSERT_TRUE(fin);
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x02, true, false, data);
+  connected = [&] {
+    conn->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  };
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// The client must close the connection if a masked frame is received.
+//
+
+TEST_P(WebSocketClientDataTest, ReceiveMasked) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), ' ');
+  setupWebSocket = [&] {
+    ws->text.connect([&](StringRef, bool) {
+      ws->Terminate();
+      FAIL() << "Should not have gotten masked message";
+    });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, true, true, data);
+  connected = [&] {
+    conn->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  };
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketIntegrationTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketIntegrationTest.cpp
new file mode 100644
index 0000000..f51e8fc
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketIntegrationTest.cpp
@@ -0,0 +1,148 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/WebSocketServer.h"  // NOLINT(build/include_order)
+
+#include "WebSocketTest.h"
+#include "wpi/HttpParser.h"
+#include "wpi/SmallString.h"
+
+namespace wpi {
+
+class WebSocketIntegrationTest : public WebSocketTest {};
+
+TEST_F(WebSocketIntegrationTest, Open) {
+  int gotServerOpen = 0;
+  int gotClientOpen = 0;
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto server = WebSocketServer::Create(*conn);
+    server->connected.connect([&](StringRef url, WebSocket&) {
+      ++gotServerOpen;
+      ASSERT_EQ(url, "/test");
+    });
+  });
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      Finish();
+      if (code != 1005 && code != 1006)
+        FAIL() << "Code: " << code << " Reason: " << reason;
+    });
+    ws->open.connect([&, s = ws.get() ](StringRef) {
+      ++gotClientOpen;
+      s->Close();
+    });
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotServerOpen, 1);
+  ASSERT_EQ(gotClientOpen, 1);
+}
+
+TEST_F(WebSocketIntegrationTest, Protocol) {
+  int gotServerOpen = 0;
+  int gotClientOpen = 0;
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto server = WebSocketServer::Create(*conn, {"proto1", "proto2"});
+    server->connected.connect([&](StringRef, WebSocket& ws) {
+      ++gotServerOpen;
+      ASSERT_EQ(ws.GetProtocol(), "proto1");
+    });
+  });
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws =
+        WebSocket::CreateClient(*clientPipe, "/test", pipeName, {"proto1"});
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      Finish();
+      if (code != 1005 && code != 1006)
+        FAIL() << "Code: " << code << " Reason: " << reason;
+    });
+    ws->open.connect([&, s = ws.get() ](StringRef protocol) {
+      ++gotClientOpen;
+      s->Close();
+      ASSERT_EQ(protocol, "proto1");
+    });
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotServerOpen, 1);
+  ASSERT_EQ(gotClientOpen, 1);
+}
+
+TEST_F(WebSocketIntegrationTest, ServerSendBinary) {
+  int gotData = 0;
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto server = WebSocketServer::Create(*conn);
+    server->connected.connect([&](StringRef, WebSocket& ws) {
+      ws.SendBinary(uv::Buffer{"\x03\x04", 2}, [&](auto, uv::Error) {});
+      ws.Close();
+    });
+  });
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      Finish();
+      if (code != 1005 && code != 1006)
+        FAIL() << "Code: " << code << " Reason: " << reason;
+    });
+    ws->binary.connect([&](ArrayRef<uint8_t> data, bool) {
+      ++gotData;
+      std::vector<uint8_t> recvData{data.begin(), data.end()};
+      std::vector<uint8_t> expectData{0x03, 0x04};
+      ASSERT_EQ(recvData, expectData);
+    });
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotData, 1);
+}
+
+TEST_F(WebSocketIntegrationTest, ClientSendText) {
+  int gotData = 0;
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto server = WebSocketServer::Create(*conn);
+    server->connected.connect([&](StringRef, WebSocket& ws) {
+      ws.text.connect([&](StringRef data, bool) {
+        ++gotData;
+        ASSERT_EQ(data, "hello");
+      });
+    });
+  });
+
+  clientPipe->Connect(pipeName, [&] {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      Finish();
+      if (code != 1005 && code != 1006)
+        FAIL() << "Code: " << code << " Reason: " << reason;
+    });
+    ws->open.connect([&, s = ws.get() ](StringRef) {
+      s->SendText(uv::Buffer{"hello"}, [&](auto, uv::Error) {});
+      s->Close();
+    });
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotData, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketServerTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketServerTest.cpp
new file mode 100644
index 0000000..7d723e3
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketServerTest.cpp
@@ -0,0 +1,736 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/WebSocket.h"  // NOLINT(build/include_order)
+
+#include "WebSocketTest.h"
+#include "wpi/Base64.h"
+#include "wpi/HttpParser.h"
+#include "wpi/SmallString.h"
+#include "wpi/raw_uv_ostream.h"
+#include "wpi/sha1.h"
+
+namespace wpi {
+
+class WebSocketServerTest : public WebSocketTest {
+ public:
+  WebSocketServerTest() {
+    resp.headersComplete.connect([this](bool) { headersDone = true; });
+
+    serverPipe->Listen([this]() {
+      auto conn = serverPipe->Accept();
+      ws = WebSocket::CreateServer(*conn, "foo", "13");
+      if (setupWebSocket) setupWebSocket();
+    });
+    clientPipe->Connect(pipeName, [this]() {
+      clientPipe->StartRead();
+      clientPipe->data.connect([this](uv::Buffer& buf, size_t size) {
+        StringRef data{buf.base, size};
+        if (!headersDone) {
+          data = resp.Execute(data);
+          if (resp.HasError()) Finish();
+          ASSERT_EQ(resp.GetError(), HPE_OK)
+              << http_errno_name(resp.GetError());
+          if (data.empty()) return;
+        }
+        wireData.insert(wireData.end(), data.bytes_begin(), data.bytes_end());
+        if (handleData) handleData(data);
+      });
+      clientPipe->end.connect([this]() { Finish(); });
+    });
+  }
+
+  std::function<void()> setupWebSocket;
+  std::function<void(StringRef)> handleData;
+  std::vector<uint8_t> wireData;
+  std::shared_ptr<WebSocket> ws;
+  HttpParser resp{HttpParser::kResponse};
+  bool headersDone = false;
+};
+
+//
+// Terminate closes the endpoint but doesn't send a close frame.
+//
+
+TEST_F(WebSocketServerTest, Terminate) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) { ws->Terminate(); });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1006) << "reason: " << reason;
+    });
+  };
+
+  loop->Run();
+
+  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, TerminateCode) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) { ws->Terminate(1000); });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000) << "reason: " << reason;
+    });
+  };
+
+  loop->Run();
+
+  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, TerminateReason) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) { ws->Terminate(1000, "reason"); });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000);
+      ASSERT_EQ(reason, "reason");
+    });
+  };
+
+  loop->Run();
+
+  ASSERT_TRUE(wireData.empty());  // terminate doesn't send data
+  ASSERT_EQ(gotClosed, 1);
+}
+
+//
+// Close() sends a close frame.
+//
+
+TEST_F(WebSocketServerTest, CloseBasic) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) { ws->Close(); });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1005) << "reason: " << reason;
+    });
+  };
+  // need to respond with close for server to finish shutdown
+  auto message = BuildMessage(0x08, true, true, {});
+  handleData = [&](StringRef) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x08, true, false, {});
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, CloseCode) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) { ws->Close(1000); });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000) << "reason: " << reason;
+    });
+  };
+  // need to respond with close for server to finish shutdown
+  auto message = BuildMessage(0x08, true, true, {0x03u, 0xe8u});
+  handleData = [&](StringRef) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x08, true, false, {0x03u, 0xe8u});
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, CloseReason) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) { ws->Close(1000, "hangup"); });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000);
+      ASSERT_EQ(reason, "hangup");
+    });
+  };
+  // need to respond with close for server to finish shutdown
+  auto message = BuildMessage(0x08, true, true,
+                              {0x03u, 0xe8u, 'h', 'a', 'n', 'g', 'u', 'p'});
+  handleData = [&](StringRef) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x08, true, false,
+                                 {0x03u, 0xe8u, 'h', 'a', 'n', 'g', 'u', 'p'});
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+//
+// Receiving a close frame results in closure and echoing the close frame.
+//
+
+TEST_F(WebSocketServerTest, ReceiveCloseBasic) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1005) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x08, true, true, {});
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  // the endpoint should echo the message
+  auto expectData = BuildMessage(0x08, true, false, {});
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, ReceiveCloseCode) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x08, true, true, {0x03u, 0xe8u});
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  // the endpoint should echo the message
+  auto expectData = BuildMessage(0x08, true, false, {0x03u, 0xe8u});
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketServerTest, ReceiveCloseReason) {
+  int gotClosed = 0;
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotClosed;
+      ASSERT_EQ(code, 1000);
+      ASSERT_EQ(reason, "hangup");
+    });
+  };
+  auto message = BuildMessage(0x08, true, true,
+                              {0x03u, 0xe8u, 'h', 'a', 'n', 'g', 'u', 'p'});
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  // the endpoint should echo the message
+  auto expectData = BuildMessage(0x08, true, false,
+                                 {0x03u, 0xe8u, 'h', 'a', 'n', 'g', 'u', 'p'});
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotClosed, 1);
+}
+
+//
+// If an unknown opcode is received, the receiving endpoint MUST _Fail the
+// WebSocket Connection_.
+//
+
+class WebSocketServerBadOpcodeTest
+    : public WebSocketServerTest,
+      public ::testing::WithParamInterface<uint8_t> {};
+
+INSTANTIATE_TEST_CASE_P(WebSocketServerBadOpcodeTests,
+                        WebSocketServerBadOpcodeTest,
+                        ::testing::Values(3, 4, 5, 6, 7, 0xb, 0xc, 0xd, 0xe,
+                                          0xf), );
+
+TEST_P(WebSocketServerBadOpcodeTest, Receive) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(4, 0x03);
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(GetParam(), true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// Control frames themselves MUST NOT be fragmented.
+//
+
+class WebSocketServerControlFrameTest
+    : public WebSocketServerTest,
+      public ::testing::WithParamInterface<uint8_t> {};
+
+INSTANTIATE_TEST_CASE_P(WebSocketServerControlFrameTests,
+                        WebSocketServerControlFrameTest,
+                        ::testing::Values(0x8, 0x9, 0xa), );
+
+TEST_P(WebSocketServerControlFrameTest, ReceiveFragment) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(4, 0x03);
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(GetParam(), false, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// A fragmented message consists of a single frame with the FIN bit
+// clear and an opcode other than 0, followed by zero or more frames
+// with the FIN bit clear and the opcode set to 0, and terminated by
+// a single frame with the FIN bit set and an opcode of 0.
+//
+
+// No previous message
+TEST_F(WebSocketServerTest, ReceiveFragmentInvalidNoPrevFrame) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(4, 0x03);
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x00, false, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// No previous message with FIN=1.
+TEST_F(WebSocketServerTest, ReceiveFragmentInvalidNoPrevFragment) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(4, 0x03);
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, true, true, {});  // FIN=1
+  auto message2 = BuildMessage(0x00, false, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({uv::Buffer(message), uv::Buffer(message2)},
+                      [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// Incomplete fragment
+TEST_F(WebSocketServerTest, ReceiveFragmentInvalidIncomplete) {
+  int gotCallback = 0;
+  setupWebSocket = [&] {
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, false, true, {});
+  auto message2 = BuildMessage(0x00, false, true, {});
+  auto message3 = BuildMessage(0x01, true, true, {});
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(
+        {uv::Buffer(message), uv::Buffer(message2), uv::Buffer(message3)},
+        [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// Normally fragments are combined into a single callback
+TEST_F(WebSocketServerTest, ReceiveFragment) {
+  int gotCallback = 0;
+
+  std::vector<uint8_t> data(4, 0x03);
+  std::vector<uint8_t> data2(4, 0x04);
+  std::vector<uint8_t> data3(4, 0x05);
+  std::vector<uint8_t> combData{data};
+  combData.insert(combData.end(), data2.begin(), data2.end());
+  combData.insert(combData.end(), data3.begin(), data3.end());
+
+  setupWebSocket = [&] {
+    ws->binary.connect([&](ArrayRef<uint8_t> inData, bool fin) {
+      ++gotCallback;
+      ws->Terminate();
+      ASSERT_TRUE(fin);
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(combData, recvData);
+    });
+  };
+
+  auto message = BuildMessage(0x02, false, true, data);
+  auto message2 = BuildMessage(0x00, false, true, data2);
+  auto message3 = BuildMessage(0x00, true, true, data3);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(
+        {uv::Buffer(message), uv::Buffer(message2), uv::Buffer(message3)},
+        [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// But can be configured for multiple callbacks
+TEST_F(WebSocketServerTest, ReceiveFragmentSeparate) {
+  int gotCallback = 0;
+
+  std::vector<uint8_t> data(4, 0x03);
+  std::vector<uint8_t> data2(4, 0x04);
+  std::vector<uint8_t> data3(4, 0x05);
+  std::vector<uint8_t> combData{data};
+  combData.insert(combData.end(), data2.begin(), data2.end());
+  combData.insert(combData.end(), data3.begin(), data3.end());
+
+  setupWebSocket = [&] {
+    ws->SetCombineFragments(false);
+    ws->binary.connect([&](ArrayRef<uint8_t> inData, bool fin) {
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      switch (++gotCallback) {
+        case 1:
+          ASSERT_FALSE(fin);
+          ASSERT_EQ(data, recvData);
+          break;
+        case 2:
+          ASSERT_FALSE(fin);
+          ASSERT_EQ(data2, recvData);
+          break;
+        case 3:
+          ws->Terminate();
+          ASSERT_TRUE(fin);
+          ASSERT_EQ(data3, recvData);
+          break;
+        default:
+          FAIL() << "too many callbacks";
+          break;
+      }
+    });
+  };
+
+  auto message = BuildMessage(0x02, false, true, data);
+  auto message2 = BuildMessage(0x00, false, true, data2);
+  auto message3 = BuildMessage(0x00, true, true, data3);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(
+        {uv::Buffer(message), uv::Buffer(message2), uv::Buffer(message3)},
+        [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 3);
+}
+
+//
+// Maximum message size is limited.
+//
+
+// Single message
+TEST_F(WebSocketServerTest, ReceiveTooLarge) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(2048, 0x03u);
+  setupWebSocket = [&] {
+    ws->SetMaxMessageSize(1024);
+    ws->binary.connect([&](auto, bool) {
+      ws->Terminate();
+      FAIL() << "Should not have gotten unmasked message";
+    });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1009) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+// Applied across fragments if combining
+TEST_F(WebSocketServerTest, ReceiveTooLargeFragmented) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(768, 0x03u);
+  setupWebSocket = [&] {
+    ws->SetMaxMessageSize(1024);
+    ws->binary.connect([&](auto, bool) {
+      ws->Terminate();
+      FAIL() << "Should not have gotten unmasked message";
+    });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1009) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, false, true, data);
+  auto message2 = BuildMessage(0x00, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write({uv::Buffer(message), uv::Buffer(message2)},
+                      [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// Send and receive data.
+//
+
+class WebSocketServerDataTest : public WebSocketServerTest,
+                                public ::testing::WithParamInterface<size_t> {};
+
+INSTANTIATE_TEST_CASE_P(WebSocketServerDataTests, WebSocketServerDataTest,
+                        ::testing::Values(0, 1, 125, 126, 65535, 65536), );
+
+TEST_P(WebSocketServerDataTest, SendText) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), ' ');
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) {
+      ws->SendText(uv::Buffer(data), [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x01, true, false, data);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, SendBinary) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) {
+      ws->SendBinary(uv::Buffer(data), [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x02, true, false, data);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, SendPing) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) {
+      ws->SendPing(uv::Buffer(data), [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x09, true, false, data);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, SendPong) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->open.connect([&](StringRef) {
+      ws->SendPong(uv::Buffer(data), [&](auto bufs, uv::Error) {
+        ++gotCallback;
+        ws->Terminate();
+        ASSERT_FALSE(bufs.empty());
+        ASSERT_EQ(bufs[0].base, reinterpret_cast<const char*>(data.data()));
+      });
+    });
+  };
+
+  loop->Run();
+
+  auto expectData = BuildMessage(0x0a, true, false, data);
+  ASSERT_EQ(wireData, expectData);
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, ReceiveText) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), ' ');
+  setupWebSocket = [&] {
+    ws->text.connect([&](StringRef inData, bool fin) {
+      ++gotCallback;
+      ws->Terminate();
+      ASSERT_TRUE(fin);
+      std::vector<uint8_t> recvData;
+      recvData.insert(recvData.end(), inData.bytes_begin(), inData.bytes_end());
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x01, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, ReceiveBinary) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->binary.connect([&](ArrayRef<uint8_t> inData, bool fin) {
+      ++gotCallback;
+      ws->Terminate();
+      ASSERT_TRUE(fin);
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x02, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, ReceivePing) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->ping.connect([&](ArrayRef<uint8_t> inData) {
+      ++gotCallback;
+      ws->Terminate();
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x09, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+TEST_P(WebSocketServerDataTest, ReceivePong) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), 0x03u);
+  setupWebSocket = [&] {
+    ws->pong.connect([&](ArrayRef<uint8_t> inData) {
+      ++gotCallback;
+      ws->Terminate();
+      std::vector<uint8_t> recvData{inData.begin(), inData.end()};
+      ASSERT_EQ(data, recvData);
+    });
+  };
+  auto message = BuildMessage(0x0a, true, true, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+//
+// The server must close the connection if an unmasked frame is received.
+//
+
+TEST_P(WebSocketServerDataTest, ReceiveUnmasked) {
+  int gotCallback = 0;
+  std::vector<uint8_t> data(GetParam(), ' ');
+  setupWebSocket = [&] {
+    ws->text.connect([&](StringRef, bool) {
+      ws->Terminate();
+      FAIL() << "Should not have gotten unmasked message";
+    });
+    ws->closed.connect([&](uint16_t code, StringRef reason) {
+      ++gotCallback;
+      ASSERT_EQ(code, 1002) << "reason: " << reason;
+    });
+  };
+  auto message = BuildMessage(0x01, true, false, data);
+  resp.headersComplete.connect([&](bool) {
+    clientPipe->Write(uv::Buffer(message), [&](auto bufs, uv::Error) {});
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(gotCallback, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketTest.cpp
new file mode 100644
index 0000000..c27bac0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketTest.cpp
@@ -0,0 +1,346 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/WebSocket.h"  // NOLINT(build/include_order)
+
+#include "WebSocketTest.h"
+
+#include "wpi/HttpParser.h"
+
+namespace wpi {
+
+#ifdef _WIN32
+const char* WebSocketTest::pipeName = "\\\\.\\pipe\\websocket-unit-test";
+#else
+const char* WebSocketTest::pipeName = "/tmp/websocket-unit-test";
+#endif
+const uint8_t WebSocketTest::testMask[4] = {0x11, 0x22, 0x33, 0x44};
+
+void WebSocketTest::SetUpTestCase() {
+#ifndef _WIN32
+  unlink(pipeName);
+#endif
+}
+
+std::vector<uint8_t> WebSocketTest::BuildHeader(uint8_t opcode, bool fin,
+                                                bool masking, uint64_t len) {
+  std::vector<uint8_t> data;
+  data.push_back(opcode | (fin ? 0x80u : 0x00u));
+  if (len < 126) {
+    data.push_back(len | (masking ? 0x80 : 0x00u));
+  } else if (len < 65536) {
+    data.push_back(126u | (masking ? 0x80 : 0x00u));
+    data.push_back(len >> 8);
+    data.push_back(len & 0xff);
+  } else {
+    data.push_back(127u | (masking ? 0x80u : 0x00u));
+    for (int i = 56; i >= 0; i -= 8) data.push_back((len >> i) & 0xff);
+  }
+  if (masking) data.insert(data.end(), &testMask[0], &testMask[4]);
+  return data;
+}
+
+std::vector<uint8_t> WebSocketTest::BuildMessage(uint8_t opcode, bool fin,
+                                                 bool masking,
+                                                 ArrayRef<uint8_t> data) {
+  auto finalData = BuildHeader(opcode, fin, masking, data.size());
+  size_t headerSize = finalData.size();
+  finalData.insert(finalData.end(), data.begin(), data.end());
+  if (masking) {
+    uint8_t mask[4] = {finalData[headerSize - 4], finalData[headerSize - 3],
+                       finalData[headerSize - 2], finalData[headerSize - 1]};
+    int n = 0;
+    for (size_t i = headerSize, end = finalData.size(); i < end; ++i) {
+      finalData[i] ^= mask[n++];
+      if (n >= 4) n = 0;
+    }
+  }
+  return finalData;
+}
+
+// If the message is masked, changes the mask to match the mask set by
+// BuildHeader() by unmasking and remasking.
+void WebSocketTest::AdjustMasking(MutableArrayRef<uint8_t> message) {
+  if (message.size() < 2) return;
+  if ((message[1] & 0x80) == 0) return;  // not masked
+  size_t maskPos;
+  uint8_t len = message[1] & 0x7f;
+  if (len == 126)
+    maskPos = 4;
+  else if (len == 127)
+    maskPos = 10;
+  else
+    maskPos = 2;
+  uint8_t mask[4] = {message[maskPos], message[maskPos + 1],
+                     message[maskPos + 2], message[maskPos + 3]};
+  message[maskPos] = testMask[0];
+  message[maskPos + 1] = testMask[1];
+  message[maskPos + 2] = testMask[2];
+  message[maskPos + 3] = testMask[3];
+  int n = 0;
+  for (auto& ch : message.slice(maskPos + 4)) {
+    ch ^= mask[n] ^ testMask[n];
+    if (++n >= 4) n = 0;
+  }
+}
+
+TEST_F(WebSocketTest, CreateClientBasic) {
+  int gotHost = 0;
+  int gotUpgrade = 0;
+  int gotConnection = 0;
+  int gotKey = 0;
+  int gotVersion = 0;
+
+  HttpParser req{HttpParser::kRequest};
+  req.url.connect([](StringRef url) { ASSERT_EQ(url, "/test"); });
+  req.header.connect([&](StringRef name, StringRef value) {
+    if (name.equals_lower("host")) {
+      ASSERT_EQ(value, pipeName);
+      ++gotHost;
+    } else if (name.equals_lower("upgrade")) {
+      ASSERT_EQ(value, "websocket");
+      ++gotUpgrade;
+    } else if (name.equals_lower("connection")) {
+      ASSERT_EQ(value, "Upgrade");
+      ++gotConnection;
+    } else if (name.equals_lower("sec-websocket-key")) {
+      ++gotKey;
+    } else if (name.equals_lower("sec-websocket-version")) {
+      ASSERT_EQ(value, "13");
+      ++gotVersion;
+    } else {
+      FAIL() << "unexpected header " << name.str();
+    }
+  });
+  req.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    conn->StartRead();
+    conn->data.connect([&](uv::Buffer& buf, size_t size) {
+      req.Execute(StringRef{buf.base, size});
+      if (req.HasError()) Finish();
+      ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
+    });
+  });
+  clientPipe->Connect(pipeName, [&]() {
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName);
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotHost, 1);
+  ASSERT_EQ(gotUpgrade, 1);
+  ASSERT_EQ(gotConnection, 1);
+  ASSERT_EQ(gotKey, 1);
+  ASSERT_EQ(gotVersion, 1);
+}
+
+TEST_F(WebSocketTest, CreateClientExtraHeaders) {
+  int gotExtra1 = 0;
+  int gotExtra2 = 0;
+  HttpParser req{HttpParser::kRequest};
+  req.header.connect([&](StringRef name, StringRef value) {
+    if (name.equals("Extra1")) {
+      ASSERT_EQ(value, "Data1");
+      ++gotExtra1;
+    } else if (name.equals("Extra2")) {
+      ASSERT_EQ(value, "Data2");
+      ++gotExtra2;
+    }
+  });
+  req.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    conn->StartRead();
+    conn->data.connect([&](uv::Buffer& buf, size_t size) {
+      req.Execute(StringRef{buf.base, size});
+      if (req.HasError()) Finish();
+      ASSERT_EQ(req.GetError(), HPE_OK) << http_errno_name(req.GetError());
+    });
+  });
+  clientPipe->Connect(pipeName, [&]() {
+    WebSocket::ClientOptions options;
+    SmallVector<std::pair<StringRef, StringRef>, 4> extraHeaders;
+    extraHeaders.emplace_back("Extra1", "Data1");
+    extraHeaders.emplace_back("Extra2", "Data2");
+    options.extraHeaders = extraHeaders;
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName,
+                                      ArrayRef<StringRef>{}, options);
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotExtra1, 1);
+  ASSERT_EQ(gotExtra2, 1);
+}
+
+TEST_F(WebSocketTest, CreateClientTimeout) {
+  int gotClosed = 0;
+  serverPipe->Listen([&]() { auto conn = serverPipe->Accept(); });
+  clientPipe->Connect(pipeName, [&]() {
+    WebSocket::ClientOptions options;
+    options.handshakeTimeout = uv::Timer::Time{100};
+    auto ws = WebSocket::CreateClient(*clientPipe, "/test", pipeName,
+                                      ArrayRef<StringRef>{}, options);
+    ws->closed.connect([&](uint16_t code, StringRef) {
+      Finish();
+      ++gotClosed;
+      ASSERT_EQ(code, 1006);
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotClosed, 1);
+}
+
+TEST_F(WebSocketTest, CreateServerBasic) {
+  int gotStatus = 0;
+  int gotUpgrade = 0;
+  int gotConnection = 0;
+  int gotAccept = 0;
+  int gotOpen = 0;
+
+  HttpParser resp{HttpParser::kResponse};
+  resp.status.connect([&](StringRef status) {
+    ++gotStatus;
+    ASSERT_EQ(resp.GetStatusCode(), 101u) << "status: " << status;
+  });
+  resp.header.connect([&](StringRef name, StringRef value) {
+    if (name.equals_lower("upgrade")) {
+      ASSERT_EQ(value, "websocket");
+      ++gotUpgrade;
+    } else if (name.equals_lower("connection")) {
+      ASSERT_EQ(value, "Upgrade");
+      ++gotConnection;
+    } else if (name.equals_lower("sec-websocket-accept")) {
+      ASSERT_EQ(value, "s3pPLMBiTxaQ9kYGzzhZRbK+xOo=");
+      ++gotAccept;
+    } else {
+      FAIL() << "unexpected header " << name.str();
+    }
+  });
+  resp.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto ws = WebSocket::CreateServer(*conn, "dGhlIHNhbXBsZSBub25jZQ==", "13");
+    ws->open.connect([&](StringRef protocol) {
+      ++gotOpen;
+      ASSERT_TRUE(protocol.empty());
+    });
+  });
+  clientPipe->Connect(pipeName, [&] {
+    clientPipe->StartRead();
+    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
+      resp.Execute(StringRef{buf.base, size});
+      if (resp.HasError()) Finish();
+      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotStatus, 1);
+  ASSERT_EQ(gotUpgrade, 1);
+  ASSERT_EQ(gotConnection, 1);
+  ASSERT_EQ(gotAccept, 1);
+  ASSERT_EQ(gotOpen, 1);
+}
+
+TEST_F(WebSocketTest, CreateServerProtocol) {
+  int gotProtocol = 0;
+  int gotOpen = 0;
+
+  HttpParser resp{HttpParser::kResponse};
+  resp.header.connect([&](StringRef name, StringRef value) {
+    if (name.equals_lower("sec-websocket-protocol")) {
+      ++gotProtocol;
+      ASSERT_EQ(value, "myProtocol");
+    }
+  });
+  resp.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&]() {
+    auto conn = serverPipe->Accept();
+    auto ws = WebSocket::CreateServer(*conn, "foo", "13", "myProtocol");
+    ws->open.connect([&](StringRef protocol) {
+      ++gotOpen;
+      ASSERT_EQ(protocol, "myProtocol");
+    });
+  });
+  clientPipe->Connect(pipeName, [&] {
+    clientPipe->StartRead();
+    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
+      resp.Execute(StringRef{buf.base, size});
+      if (resp.HasError()) Finish();
+      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotProtocol, 1);
+  ASSERT_EQ(gotOpen, 1);
+}
+
+TEST_F(WebSocketTest, CreateServerBadVersion) {
+  int gotStatus = 0;
+  int gotVersion = 0;
+  int gotUpgrade = 0;
+
+  HttpParser resp{HttpParser::kResponse};
+  resp.status.connect([&](StringRef status) {
+    ++gotStatus;
+    ASSERT_EQ(resp.GetStatusCode(), 426u) << "status: " << status;
+  });
+  resp.header.connect([&](StringRef name, StringRef value) {
+    if (name.equals_lower("sec-websocket-version")) {
+      ++gotVersion;
+      ASSERT_EQ(value, "13");
+    } else if (name.equals_lower("upgrade")) {
+      ++gotUpgrade;
+      ASSERT_EQ(value, "WebSocket");
+    } else {
+      FAIL() << "unexpected header " << name.str();
+    }
+  });
+  resp.headersComplete.connect([&](bool) { Finish(); });
+
+  serverPipe->Listen([&] {
+    auto conn = serverPipe->Accept();
+    auto ws = WebSocket::CreateServer(*conn, "foo", "14");
+    ws->open.connect([&](StringRef) {
+      Finish();
+      FAIL();
+    });
+  });
+  clientPipe->Connect(pipeName, [&] {
+    clientPipe->StartRead();
+    clientPipe->data.connect([&](uv::Buffer& buf, size_t size) {
+      resp.Execute(StringRef{buf.base, size});
+      if (resp.HasError()) Finish();
+      ASSERT_EQ(resp.GetError(), HPE_OK) << http_errno_name(resp.GetError());
+    });
+  });
+
+  loop->Run();
+
+  if (HasFatalFailure()) return;
+  ASSERT_EQ(gotStatus, 1);
+  ASSERT_EQ(gotVersion, 1);
+  ASSERT_EQ(gotUpgrade, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketTest.h b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketTest.h
new file mode 100644
index 0000000..8b40440
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WebSocketTest.h
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+#pragma once
+
+#include <cstdio>
+#include <memory>
+#include <vector>
+
+#include "gtest/gtest.h"
+#include "wpi/ArrayRef.h"
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/Pipe.h"
+#include "wpi/uv/Timer.h"
+
+namespace wpi {
+
+class WebSocketTest : public ::testing::Test {
+ public:
+  static const char* pipeName;
+
+  static void SetUpTestCase();
+
+  WebSocketTest() {
+    loop = uv::Loop::Create();
+    clientPipe = uv::Pipe::Create(loop);
+    serverPipe = uv::Pipe::Create(loop);
+
+    serverPipe->Bind(pipeName);
+
+#if 0
+    auto debugTimer = uv::Timer::Create(loop);
+    debugTimer->timeout.connect([this] {
+      std::printf("Active handles:\n");
+      uv_print_active_handles(loop->GetRaw(), stdout);
+    });
+    debugTimer->Start(uv::Timer::Time{100}, uv::Timer::Time{100});
+    debugTimer->Unreference();
+#endif
+
+    auto failTimer = uv::Timer::Create(loop);
+    failTimer->timeout.connect([this] {
+      loop->Stop();
+      FAIL() << "loop failed to terminate";
+    });
+    failTimer->Start(uv::Timer::Time{1000});
+    failTimer->Unreference();
+  }
+
+  ~WebSocketTest() { Finish(); }
+
+  void Finish() {
+    loop->Walk([](uv::Handle& it) { it.Close(); });
+  }
+
+  static std::vector<uint8_t> BuildHeader(uint8_t opcode, bool fin,
+                                          bool masking, uint64_t len);
+  static std::vector<uint8_t> BuildMessage(uint8_t opcode, bool fin,
+                                           bool masking,
+                                           ArrayRef<uint8_t> data);
+  static void AdjustMasking(MutableArrayRef<uint8_t> message);
+  static const uint8_t testMask[4];
+
+  std::shared_ptr<uv::Loop> loop;
+  std::shared_ptr<uv::Pipe> clientPipe;
+  std::shared_ptr<uv::Pipe> serverPipe;
+};
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WorkerThreadTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WorkerThreadTest.cpp
new file mode 100644
index 0000000..610029c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/WorkerThreadTest.cpp
@@ -0,0 +1,73 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/WorkerThread.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <thread>
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+
+TEST(WorkerThread, Future) {
+  WorkerThread<int(bool)> worker;
+  future<int> f =
+      worker.QueueWork([](bool v) -> int { return v ? 1 : 2; }, true);
+  ASSERT_EQ(f.get(), 1);
+}
+
+TEST(WorkerThread, FutureVoid) {
+  int callbacks = 0;
+  WorkerThread<void(int)> worker;
+  future<void> f = worker.QueueWork(
+      [&](int v) {
+        ++callbacks;
+        ASSERT_EQ(v, 3);
+      },
+      3);
+  f.get();
+  ASSERT_EQ(callbacks, 1);
+}
+
+TEST(WorkerThread, Loop) {
+  int callbacks = 0;
+  WorkerThread<int(bool)> worker;
+  auto loop = uv::Loop::Create();
+  worker.SetLoop(*loop);
+  worker.QueueWorkThen([](bool v) -> int { return v ? 1 : 2; },
+                       [&](int v2) {
+                         ++callbacks;
+                         loop->Stop();
+                         ASSERT_EQ(v2, 1);
+                       },
+                       true);
+  auto f = worker.QueueWork([](bool) -> int { return 2; }, true);
+  ASSERT_EQ(f.get(), 2);
+  loop->Run();
+  ASSERT_EQ(callbacks, 1);
+}
+
+TEST(WorkerThread, LoopVoid) {
+  int callbacks = 0;
+  WorkerThread<void(bool)> worker;
+  auto loop = uv::Loop::Create();
+  worker.SetLoop(*loop);
+  worker.QueueWorkThen([](bool) {},
+                       [&]() {
+                         ++callbacks;
+                         loop->Stop();
+                       },
+                       true);
+  auto f = worker.QueueWork([](bool) {}, true);
+  f.get();
+  loop->Run();
+  ASSERT_EQ(callbacks, 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/future_test.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/future_test.cpp
new file mode 100644
index 0000000..b9b79a8
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/future_test.cpp
@@ -0,0 +1,84 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/future.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <thread>
+
+namespace wpi {
+
+TEST(Future, Then) {
+  promise<bool> inPromise;
+  future<int> outFuture =
+      inPromise.get_future().then([](bool v) { return v ? 5 : 6; });
+
+  inPromise.set_value(true);
+  ASSERT_EQ(outFuture.get(), 5);
+}
+
+TEST(Future, ThenSame) {
+  promise<bool> inPromise;
+  future<bool> outFuture =
+      inPromise.get_future().then([](bool v) { return !v; });
+
+  inPromise.set_value(true);
+  ASSERT_EQ(outFuture.get(), false);
+}
+
+TEST(Future, ThenFromVoid) {
+  promise<void> inPromise;
+  future<int> outFuture = inPromise.get_future().then([] { return 5; });
+
+  inPromise.set_value();
+  ASSERT_EQ(outFuture.get(), 5);
+}
+
+TEST(Future, ThenToVoid) {
+  promise<bool> inPromise;
+  future<void> outFuture = inPromise.get_future().then([](bool v) {});
+
+  inPromise.set_value(true);
+  ASSERT_TRUE(outFuture.is_ready());
+}
+
+TEST(Future, ThenVoidVoid) {
+  promise<void> inPromise;
+  future<void> outFuture = inPromise.get_future().then([] {});
+
+  inPromise.set_value();
+  ASSERT_TRUE(outFuture.is_ready());
+}
+
+TEST(Future, Implicit) {
+  promise<bool> inPromise;
+  future<int> outFuture = inPromise.get_future();
+
+  inPromise.set_value(true);
+  ASSERT_EQ(outFuture.get(), 1);
+}
+
+TEST(Future, MoveSame) {
+  promise<bool> inPromise;
+  future<bool> outFuture1 = inPromise.get_future();
+  future<bool> outFuture(std::move(outFuture1));
+
+  inPromise.set_value(true);
+  ASSERT_EQ(outFuture.get(), true);
+}
+
+TEST(Future, MoveVoid) {
+  promise<void> inPromise;
+  future<void> outFuture1 = inPromise.get_future();
+  future<void> outFuture(std::move(outFuture1));
+
+  inPromise.set_value();
+  ASSERT_TRUE(outFuture.is_ready());
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/hostname.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/hostname.cpp
new file mode 100644
index 0000000..d5ec535
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/hostname.cpp
@@ -0,0 +1,24 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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 "wpi/hostname.h"
+
+#include "gtest/gtest.h"
+#include "wpi/SmallString.h"
+#include "wpi/SmallVector.h"
+
+namespace wpi {
+TEST(HostNameTest, HostNameNotEmpty) { ASSERT_NE(GetHostname(), ""); }
+TEST(HostNameTest, HostNameNotEmptySmallVector) {
+  SmallVector<char, 256> name;
+  ASSERT_NE(GetHostname(name), "");
+}
+TEST(HostNameTest, HostNameEq) {
+  SmallVector<char, 256> nameBuf;
+  ASSERT_EQ(GetHostname(nameBuf), GetHostname());
+}
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-algorithms.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-algorithms.cpp
new file mode 100644
index 0000000..f1a8745
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-algorithms.cpp
@@ -0,0 +1,310 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+#include <algorithm>
+
+class JsonAlgorithmsTest : public ::testing::Test {
+ protected:
+    json j_array = {13, 29, 3, {{"one", 1}, {"two", 2}}, true, false, {1, 2, 3}, "foo", "baz"};
+    json j_object = {{"one", 1}, {"two", 2}};
+};
+
+// non-modifying sequence operations
+TEST_F(JsonAlgorithmsTest, AllOf)
+{
+    EXPECT_TRUE(std::all_of(j_array.begin(), j_array.end(), [](const json & value)
+    {
+        return value.size() > 0;
+    }));
+    EXPECT_TRUE(std::all_of(j_object.begin(), j_object.end(), [](const json & value)
+    {
+        return value.type() == json::value_t::number_integer;
+    }));
+}
+
+TEST_F(JsonAlgorithmsTest, AnyOf)
+{
+    EXPECT_TRUE(std::any_of(j_array.begin(), j_array.end(), [](const json & value)
+    {
+        return value.is_string() && value.get<std::string>() == "foo";
+    }));
+    EXPECT_TRUE(std::any_of(j_object.begin(), j_object.end(), [](const json & value)
+    {
+        return value.get<int>() > 1;
+    }));
+}
+
+TEST_F(JsonAlgorithmsTest, NoneOf)
+{
+    EXPECT_TRUE(std::none_of(j_array.begin(), j_array.end(), [](const json & value)
+    {
+        return value.size() == 0;
+    }));
+    EXPECT_TRUE(std::none_of(j_object.begin(), j_object.end(), [](const json & value)
+    {
+        return value.get<int>() <= 0;
+    }));
+}
+
+TEST_F(JsonAlgorithmsTest, ForEachReading)
+{
+    int sum = 0;
+
+    std::for_each(j_array.cbegin(), j_array.cend(), [&sum](const json & value)
+    {
+        if (value.is_number())
+        {
+            sum += static_cast<int>(value);
+        }
+    });
+
+    EXPECT_EQ(sum, 45);
+}
+
+TEST_F(JsonAlgorithmsTest, ForEachWriting)
+{
+    auto add17 = [](json & value)
+    {
+        if (value.is_array())
+        {
+            value.push_back(17);
+        }
+    };
+
+    std::for_each(j_array.begin(), j_array.end(), add17);
+
+    EXPECT_EQ(j_array[6], json({1, 2, 3, 17}));
+}
+
+TEST_F(JsonAlgorithmsTest, Count)
+{
+    EXPECT_EQ(std::count(j_array.begin(), j_array.end(), json(true)), 1);
+}
+
+TEST_F(JsonAlgorithmsTest, CountIf)
+{
+    auto count1 = std::count_if(j_array.begin(), j_array.end(), [](const json & value)
+    {
+        return (value.is_number());
+    });
+    EXPECT_EQ(count1, 3);
+    auto count2 = std::count_if(j_array.begin(), j_array.end(), [](const json&)
+    {
+        return true;
+    });
+    EXPECT_EQ(count2, 9);
+}
+
+TEST_F(JsonAlgorithmsTest, Mismatch)
+{
+    json j_array2 = {13, 29, 3, {{"one", 1}, {"two", 2}, {"three", 3}}, true, false, {1, 2, 3}, "foo", "baz"};
+    auto res = std::mismatch(j_array.begin(), j_array.end(), j_array2.begin());
+    EXPECT_EQ(*res.first, json({{"one", 1}, {"two", 2}}));
+    EXPECT_EQ(*res.second, json({{"one", 1}, {"two", 2}, {"three", 3}}));
+}
+
+TEST_F(JsonAlgorithmsTest, EqualOperatorEquals)
+{
+    EXPECT_TRUE(std::equal(j_array.begin(), j_array.end(), j_array.begin()));
+    EXPECT_TRUE(std::equal(j_object.begin(), j_object.end(), j_object.begin()));
+    EXPECT_FALSE(std::equal(j_array.begin(), j_array.end(), j_object.begin()));
+}
+
+TEST_F(JsonAlgorithmsTest, EqualUserComparison)
+{
+    // compare objects only by size of its elements
+    json j_array2 = {13, 29, 3, {"Hello", "World"}, true, false, {{"one", 1}, {"two", 2}, {"three", 3}}, "foo", "baz"};
+    EXPECT_FALSE(std::equal(j_array.begin(), j_array.end(), j_array2.begin()));
+    EXPECT_TRUE(std::equal(j_array.begin(), j_array.end(), j_array2.begin(),
+                     [](const json & a, const json & b)
+    {
+        return (a.size() == b.size());
+    }));
+}
+
+TEST_F(JsonAlgorithmsTest, Find)
+{
+    auto it = std::find(j_array.begin(), j_array.end(), json(false));
+    EXPECT_EQ(std::distance(j_array.begin(), it), 5);
+}
+
+TEST_F(JsonAlgorithmsTest, FindIf)
+{
+    auto it = std::find_if(j_array.begin(), j_array.end(),
+                           [](const json & value)
+    {
+        return value.is_boolean();
+    });
+    EXPECT_EQ(std::distance(j_array.begin(), it), 4);
+}
+
+TEST_F(JsonAlgorithmsTest, FindIfNot)
+{
+    auto it = std::find_if_not(j_array.begin(), j_array.end(),
+                               [](const json & value)
+    {
+        return value.is_number();
+    });
+    EXPECT_EQ(std::distance(j_array.begin(), it), 3);
+}
+
+TEST_F(JsonAlgorithmsTest, AdjacentFind)
+{
+    EXPECT_EQ(std::adjacent_find(j_array.begin(), j_array.end()), j_array.end());
+    auto it = std::adjacent_find(j_array.begin(), j_array.end(),
+                             [](const json & v1, const json & v2)
+    {
+        return v1.type() == v2.type();
+    });
+    EXPECT_EQ(it, j_array.begin());
+}
+
+// modifying sequence operations
+TEST_F(JsonAlgorithmsTest, Reverse)
+{
+    std::reverse(j_array.begin(), j_array.end());
+    EXPECT_EQ(j_array, json({"baz", "foo", {1, 2, 3}, false, true, {{"one", 1}, {"two", 2}}, 3, 29, 13}));
+}
+
+TEST_F(JsonAlgorithmsTest, Rotate)
+{
+    std::rotate(j_array.begin(), j_array.begin() + 1, j_array.end());
+    EXPECT_EQ(j_array, json({29, 3, {{"one", 1}, {"two", 2}}, true, false, {1, 2, 3}, "foo", "baz", 13}));
+}
+
+TEST_F(JsonAlgorithmsTest, Partition)
+{
+    auto it = std::partition(j_array.begin(), j_array.end(), [](const json & v)
+    {
+        return v.is_string();
+    });
+    EXPECT_EQ(std::distance(j_array.begin(), it), 2);
+    EXPECT_FALSE(it[2].is_string());
+}
+
+// sorting operations
+TEST_F(JsonAlgorithmsTest, SortOperatorEquals)
+{
+    json j = {13, 29, 3, {{"one", 1}, {"two", 2}}, true, false, {1, 2, 3}, "foo", "baz", nullptr};
+    std::sort(j.begin(), j.end());
+    EXPECT_EQ(j, json({nullptr, false, true, 3, 13, 29, {{"one", 1}, {"two", 2}}, {1, 2, 3}, "baz", "foo"}));
+}
+
+TEST_F(JsonAlgorithmsTest, SortUserComparison)
+{
+    json j = {3, {{"one", 1}, {"two", 2}}, {1, 2, 3}, nullptr};
+    std::sort(j.begin(), j.end(), [](const json & a, const json & b)
+    {
+        return a.size() < b.size();
+    });
+    EXPECT_EQ(j, json({nullptr, 3, {{"one", 1}, {"two", 2}}, {1, 2, 3}}));
+}
+
+TEST_F(JsonAlgorithmsTest, SortObject)
+{
+    json j({{"one", 1}, {"two", 2}});
+    EXPECT_THROW_MSG(std::sort(j.begin(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+}
+
+TEST_F(JsonAlgorithmsTest, PartialSort)
+{
+    json j = {13, 29, 3, {{"one", 1}, {"two", 2}}, true, false, {1, 2, 3}, "foo", "baz", nullptr};
+    std::partial_sort(j.begin(), j.begin() + 4, j.end());
+    EXPECT_EQ(j, json({nullptr, false, true, 3, {{"one", 1}, {"two", 2}}, 29, {1, 2, 3}, "foo", "baz", 13}));
+}
+
+// set operations
+TEST_F(JsonAlgorithmsTest, Merge)
+{
+    json j1 = {2, 4, 6, 8};
+    json j2 = {1, 2, 3, 5, 7};
+    json j3;
+
+    std::merge(j1.begin(), j1.end(), j2.begin(), j2.end(), std::back_inserter(j3));
+    EXPECT_EQ(j3, json({1, 2, 2, 3, 4, 5, 6, 7, 8}));
+}
+
+TEST_F(JsonAlgorithmsTest, SetDifference)
+{
+    json j1 = {1, 2, 3, 4, 5, 6, 7, 8};
+    json j2 = {1, 2, 3, 5, 7};
+    json j3;
+
+    std::set_difference(j1.begin(), j1.end(), j2.begin(), j2.end(), std::back_inserter(j3));
+    EXPECT_EQ(j3, json({4, 6, 8}));
+}
+
+TEST_F(JsonAlgorithmsTest, SetIntersection)
+{
+    json j1 = {1, 2, 3, 4, 5, 6, 7, 8};
+    json j2 = {1, 2, 3, 5, 7};
+    json j3;
+
+    std::set_intersection(j1.begin(), j1.end(), j2.begin(), j2.end(), std::back_inserter(j3));
+    EXPECT_EQ(j3, json({1, 2, 3, 5, 7}));
+}
+
+TEST_F(JsonAlgorithmsTest, SetUnion)
+{
+    json j1 = {2, 4, 6, 8};
+    json j2 = {1, 2, 3, 5, 7};
+    json j3;
+
+    std::set_union(j1.begin(), j1.end(), j2.begin(), j2.end(), std::back_inserter(j3));
+    EXPECT_EQ(j3, json({1, 2, 3, 4, 5, 6, 7, 8}));
+}
+
+TEST_F(JsonAlgorithmsTest, SetSymmetricDifference)
+{
+    json j1 = {2, 4, 6, 8};
+    json j2 = {1, 2, 3, 5, 7};
+    json j3;
+
+    std::set_symmetric_difference(j1.begin(), j1.end(), j2.begin(), j2.end(), std::back_inserter(j3));
+    EXPECT_EQ(j3, json({1, 3, 4, 5, 6, 7, 8}));
+}
+
+TEST_F(JsonAlgorithmsTest, HeapOperations)
+{
+    std::make_heap(j_array.begin(), j_array.end());
+    EXPECT_TRUE(std::is_heap(j_array.begin(), j_array.end()));
+    std::sort_heap(j_array.begin(), j_array.end());
+    EXPECT_EQ(j_array, json({false, true, 3, 13, 29, {{"one", 1}, {"two", 2}}, {1, 2, 3}, "baz", "foo"}));
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-capacity.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-capacity.cpp
new file mode 100644
index 0000000..8f5433e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-capacity.cpp
@@ -0,0 +1,528 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+TEST(JsonEmptyTest, Boolean)
+{
+    json j = true;
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_FALSE(j.empty());
+        EXPECT_FALSE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, String)
+{
+    json j = "hello world";
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_FALSE(j.empty());
+        EXPECT_FALSE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, ArrayEmpty)
+{
+    json j = json::array();
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_TRUE(j.empty());
+        EXPECT_TRUE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, ArrayFilled)
+{
+    json j = {1, 2, 3};
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_FALSE(j.empty());
+        EXPECT_FALSE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, ObjectEmpty)
+{
+    json j = json::object();
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_TRUE(j.empty());
+        EXPECT_TRUE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, ObjectFilled)
+{
+    json j = {{"one", 1}, {"two", 2}, {"three", 3}};
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_FALSE(j.empty());
+        EXPECT_FALSE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, NumberInteger)
+{
+    json j = 23;
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_FALSE(j.empty());
+        EXPECT_FALSE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, NumberUnsigned)
+{
+    json j = 23u;
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_FALSE(j.empty());
+        EXPECT_FALSE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, NumberFloat)
+{
+    json j = 23.42;
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_FALSE(j.empty());
+        EXPECT_FALSE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonEmptyTest, Null)
+{
+    json j = nullptr;
+    json j_const(j);
+
+    // result of empty
+    {
+        EXPECT_TRUE(j.empty());
+        EXPECT_TRUE(j_const.empty());
+    }
+
+    // definition of empty
+    {
+        EXPECT_EQ(j.empty(), (j.begin() == j.end()));
+        EXPECT_EQ(j_const.empty(), (j_const.begin() == j_const.end()));
+    }
+}
+
+TEST(JsonSizeTest, Boolean)
+{
+    json j = true;
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 1u);
+        EXPECT_EQ(j_const.size(), 1u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, String)
+{
+    json j = "hello world";
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 1u);
+        EXPECT_EQ(j_const.size(), 1u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, ArrayEmpty)
+{
+    json j = json::array();
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 0u);
+        EXPECT_EQ(j_const.size(), 0u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, ArrayFilled)
+{
+    json j = {1, 2, 3};
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 3u);
+        EXPECT_EQ(j_const.size(), 3u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, ObjectEmpty)
+{
+    json j = json::object();
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 0u);
+        EXPECT_EQ(j_const.size(), 0u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, ObjectFilled)
+{
+    json j = {{"one", 1}, {"two", 2}, {"three", 3}};
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 3u);
+        EXPECT_EQ(j_const.size(), 3u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, NumberInteger)
+{
+    json j = 23;
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 1u);
+        EXPECT_EQ(j_const.size(), 1u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, NumberUnsigned)
+{
+    json j = 23u;
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 1u);
+        EXPECT_EQ(j_const.size(), 1u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, NumberFloat)
+{
+    json j = 23.42;
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 1u);
+        EXPECT_EQ(j_const.size(), 1u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonSizeTest, Null)
+{
+    json j = nullptr;
+    json j_const(j);
+
+    // result of size
+    {
+        EXPECT_EQ(j.size(), 0u);
+        EXPECT_EQ(j_const.size(), 0u);
+    }
+
+    // definition of size
+    {
+        EXPECT_EQ(std::distance(j.begin(), j.end()), static_cast<int>(j.size()));
+        EXPECT_EQ(std::distance(j_const.begin(), j_const.end()),
+                  static_cast<int>(j_const.size()));
+    }
+}
+
+TEST(JsonMaxSizeTest, Boolean)
+{
+    json j = true;
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_EQ(j.max_size(), 1u);
+        EXPECT_EQ(j_const.max_size(), 1u);
+    }
+}
+
+TEST(JsonMaxSizeTest, String)
+{
+    json j = "hello world";
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_EQ(j.max_size(), 1u);
+        EXPECT_EQ(j_const.max_size(), 1u);
+    }
+}
+
+TEST(JsonMaxSizeTest, ArrayEmpty)
+{
+    json j = json::array();
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_GE(j.max_size(), j.size());
+        EXPECT_GE(j_const.max_size(), j_const.size());
+    }
+}
+
+TEST(JsonMaxSizeTest, ArrayFilled)
+{
+    json j = {1, 2, 3};
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_GE(j.max_size(), j.size());
+        EXPECT_GE(j_const.max_size(), j_const.size());
+    }
+}
+
+TEST(JsonMaxSizeTest, ObjectEmpty)
+{
+    json j = json::object();
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_GE(j.max_size(), j.size());
+        EXPECT_GE(j_const.max_size(), j_const.size());
+    }
+}
+
+TEST(JsonMaxSizeTest, ObjectFilled)
+{
+    json j = {{"one", 1}, {"two", 2}, {"three", 3}};
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_GE(j.max_size(), j.size());
+        EXPECT_GE(j_const.max_size(), j_const.size());
+    }
+}
+
+TEST(JsonMaxSizeTest, NumberInteger)
+{
+    json j = 23;
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_EQ(j.max_size(), 1u);
+        EXPECT_EQ(j_const.max_size(), 1u);
+    }
+}
+
+TEST(JsonMaxSizeTest, NumberUnsigned)
+{
+    json j = 23u;
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_EQ(j.max_size(), 1u);
+        EXPECT_EQ(j_const.max_size(), 1u);
+    }
+}
+
+TEST(JsonMaxSizeTest, NumberFloat)
+{
+    json j = 23.42;
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_EQ(j.max_size(), 1u);
+        EXPECT_EQ(j_const.max_size(), 1u);
+    }
+}
+
+TEST(JsonMaxSizeTest, Null)
+{
+    json j = nullptr;
+    json j_const(j);
+
+    // result of max_size
+    {
+        EXPECT_EQ(j.max_size(), 0u);
+        EXPECT_EQ(j_const.max_size(), 0u);
+    }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-cbor.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-cbor.cpp
new file mode 100644
index 0000000..84e98eb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-cbor.cpp
@@ -0,0 +1,1701 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+#include <fstream>
+
+TEST(CborDiscardedTest, Case)
+{
+    // discarded values are not serialized
+    json j = json::value_t::discarded;
+    const auto result = json::to_cbor(j);
+    ASSERT_TRUE(result.empty());
+}
+
+TEST(CborNullTest, Case)
+{
+    json j = nullptr;
+    std::vector<uint8_t> expected = {0xf6};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+TEST(CborBooleanTest, True)
+{
+    json j = true;
+    std::vector<uint8_t> expected = {0xf5};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+TEST(CborBooleanTest, False)
+{
+    json j = false;
+    std::vector<uint8_t> expected = {0xf4};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// -9223372036854775808..-4294967297
+class CborSignedNeg8Test : public ::testing::TestWithParam<int64_t> {};
+TEST_P(CborSignedNeg8Test, Case)
+{
+    // create JSON value with integer number
+    json j = GetParam();
+
+    // check type
+    ASSERT_TRUE(j.is_number_integer());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0x3b));
+    uint64_t positive = static_cast<uint64_t>(-1 - GetParam());
+    expected.push_back(static_cast<uint8_t>((positive >> 56) & 0xff));
+    expected.push_back(static_cast<uint8_t>((positive >> 48) & 0xff));
+    expected.push_back(static_cast<uint8_t>((positive >> 40) & 0xff));
+    expected.push_back(static_cast<uint8_t>((positive >> 32) & 0xff));
+    expected.push_back(static_cast<uint8_t>((positive >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((positive >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((positive >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(positive & 0xff));
+
+    // compare result + size
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+    ASSERT_EQ(result.size(), 9u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], 0x3b);
+    uint64_t restored = (static_cast<uint64_t>(static_cast<uint8_t>(result[1])) << 070) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[2])) << 060) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[3])) << 050) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[4])) << 040) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[5])) << 030) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[6])) << 020) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[7])) << 010) +
+                        static_cast<uint64_t>(static_cast<uint8_t>(result[8]));
+    EXPECT_EQ(restored, positive);
+    EXPECT_EQ(-1 - static_cast<int64_t>(restored), GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+static const int64_t neg8_numbers[] = {
+    INT64_MIN,
+    -1000000000000000000,
+    -100000000000000000,
+    -10000000000000000,
+    -1000000000000000,
+    -100000000000000,
+    -10000000000000,
+    -1000000000000,
+    -100000000000,
+    -10000000000,
+    -4294967297,
+};
+
+INSTANTIATE_TEST_CASE_P(CborSignedNeg8Tests, CborSignedNeg8Test,
+                        ::testing::ValuesIn(neg8_numbers), );
+
+// -4294967296..-65537
+class CborSignedNeg4Test : public ::testing::TestWithParam<int64_t> {};
+TEST_P(CborSignedNeg4Test, Case)
+{
+    // create JSON value with integer number
+    json j = GetParam();
+
+    // check type
+    ASSERT_TRUE(j.is_number_integer());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0x3a));
+    uint32_t positive = static_cast<uint32_t>(static_cast<uint64_t>(-1 - GetParam()) & 0x00000000ffffffff);
+    expected.push_back(static_cast<uint8_t>((positive >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((positive >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((positive >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(positive & 0xff));
+
+    // compare result + size
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+    ASSERT_EQ(result.size(), 5u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], 0x3a);
+    uint32_t restored = (static_cast<uint32_t>(static_cast<uint8_t>(result[1])) << 030) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[2])) << 020) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[3])) << 010) +
+                        static_cast<uint32_t>(static_cast<uint8_t>(result[4]));
+    EXPECT_EQ(restored, positive);
+    EXPECT_EQ(-1ll - restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+static const int64_t neg4_numbers[] = {
+    -65537,
+    -100000,
+    -1000000,
+    -10000000,
+    -100000000,
+    -1000000000,
+    -4294967296,
+};
+
+INSTANTIATE_TEST_CASE_P(CborSignedNeg4Tests, CborSignedNeg4Test,
+                        ::testing::ValuesIn(neg4_numbers), );
+
+// -65536..-257
+TEST(CborSignedTest, Neg2)
+{
+    for (int32_t i = -65536; i <= -257; ++i) {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = i;
+
+        // check type
+        ASSERT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0x39));
+        uint16_t positive = static_cast<uint16_t>(-1 - i);
+        expected.push_back(static_cast<uint8_t>((positive >> 8) & 0xff));
+        expected.push_back(static_cast<uint8_t>(positive & 0xff));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 3u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], 0x39);
+        uint16_t restored = static_cast<uint16_t>(static_cast<uint8_t>(result[1]) * 256 + static_cast<uint8_t>(result[2]));
+        EXPECT_EQ(restored, positive);
+        EXPECT_EQ(-1 - restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// -9263 (int 16)
+TEST(CborSignedTest, NegInt16)
+{
+    json j = -9263;
+    std::vector<uint8_t> expected = {0x39,0x24,0x2e};
+
+    const auto result = json::to_cbor(j);
+    ASSERT_EQ(result, expected);
+
+    int16_t restored = static_cast<int16_t>(-1 - ((result[1] << 8) + result[2]));
+    EXPECT_EQ(restored, -9263);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// -256..-24
+TEST(CborSignedTest, Neg1)
+{
+    for (auto i = -256; i < -24; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = i;
+
+        // check type
+        ASSERT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0x38));
+        expected.push_back(static_cast<uint8_t>(-1 - i));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 2u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], 0x38);
+        EXPECT_EQ(static_cast<int16_t>(-1 - static_cast<uint8_t>(result[1])), i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// -24..-1
+TEST(CborSignedTest, Neg0)
+{
+    for (auto i = -24; i <= -1; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = i;
+
+        // check type
+        ASSERT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0x20 - 1 - static_cast<uint8_t>(i)));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 1u);
+
+        // check individual bytes
+        EXPECT_EQ(static_cast<int8_t>(0x20 - 1 - result[0]), i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// 0..23
+TEST(CborSignedTest, Pos0)
+{
+    for (size_t i = 0; i <= 23; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = -1;
+        j.get_ref<int64_t&>() = static_cast<int64_t>(i);
+
+        // check type
+        ASSERT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 1u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(i));
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// 24..255
+TEST(CborSignedTest, Pos1)
+{
+    for (size_t i = 24; i <= 255; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = -1;
+        j.get_ref<int64_t&>() = static_cast<int64_t>(i);
+
+        // check type
+        ASSERT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0x18));
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 2u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], 0x18);
+        EXPECT_EQ(result[1], static_cast<uint8_t>(i));
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// 256..65535
+TEST(CborSignedTest, Pos2)
+{
+    for (size_t i = 256; i <= 65535; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = -1;
+        j.get_ref<int64_t&>() = static_cast<int64_t>(i);
+
+        // check type
+        ASSERT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0x19));
+        expected.push_back(static_cast<uint8_t>((i >> 8) & 0xff));
+        expected.push_back(static_cast<uint8_t>(i & 0xff));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 3u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], 0x19);
+        uint16_t restored = static_cast<uint16_t>(static_cast<uint8_t>(result[1]) * 256 + static_cast<uint8_t>(result[2]));
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// 65536..4294967295
+class CborSignedPos4Test : public ::testing::TestWithParam<uint32_t> {};
+TEST_P(CborSignedPos4Test, Case)
+{
+    // create JSON value with integer number
+    json j = -1;
+    j.get_ref<int64_t&>() =
+        static_cast<int64_t>(GetParam());
+
+    // check type
+    ASSERT_TRUE(j.is_number_integer());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(0x1a);
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+    ASSERT_EQ(result.size(), 5u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], 0x1a);
+    uint32_t restored = (static_cast<uint32_t>(static_cast<uint8_t>(result[1])) << 030) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[2])) << 020) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[3])) << 010) +
+                        static_cast<uint32_t>(static_cast<uint8_t>(result[4]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+static const uint32_t pos4_numbers[] = {
+    65536u,
+    77777u,
+    1048576u,
+};
+
+INSTANTIATE_TEST_CASE_P(CborSignedPos4Tests, CborSignedPos4Test,
+                        ::testing::ValuesIn(pos4_numbers), );
+
+// 4294967296..4611686018427387903
+class CborSignedPos8Test : public ::testing::TestWithParam<uint64_t> {};
+TEST_P(CborSignedPos8Test, Case)
+{
+    // create JSON value with integer number
+    json j = -1;
+    j.get_ref<int64_t&>() =
+        static_cast<int64_t>(GetParam());
+
+    // check type
+    ASSERT_TRUE(j.is_number_integer());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(0x1b);
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 070) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 060) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 050) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 040) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 030) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 020) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 010) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+    ASSERT_EQ(result.size(), 9u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], 0x1b);
+    uint64_t restored = (static_cast<uint64_t>(static_cast<uint8_t>(result[1])) << 070) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[2])) << 060) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[3])) << 050) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[4])) << 040) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[5])) << 030) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[6])) << 020) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[7])) << 010) +
+                        static_cast<uint64_t>(static_cast<uint8_t>(result[8]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+static const uint64_t pos8_numbers[] = {
+    4294967296ul,
+    4611686018427387903ul
+};
+
+INSTANTIATE_TEST_CASE_P(CborSignedPos8Tests, CborSignedPos8Test,
+                        ::testing::ValuesIn(pos8_numbers), );
+
+/*
+// -32768..-129 (int 16)
+{
+    for (int16_t i = -32768; i <= -129; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = i;
+
+        // check type
+        ASSERT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(0xd1);
+        expected.push_back(static_cast<uint8_t>((i >> 8) & 0xff));
+        expected.push_back(static_cast<uint8_t>(i & 0xff));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result == expected);
+        ASSERT_EQ(result.size(), 3u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], 0xd1);
+        int16_t restored = (result[1] << 8) + result[2];
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+*/
+
+// 0..23 (Integer)
+TEST(CborUnsignedTest, Pos0)
+{
+    for (size_t i = 0; i <= 23; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with unsigned integer number
+        json j = i;
+
+        // check type
+        ASSERT_TRUE(j.is_number_unsigned());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 1u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(i));
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// 24..255 (one-byte uint8_t)
+TEST(CborUnsignedTest, Pos1)
+{
+    for (size_t i = 24; i <= 255; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with unsigned integer number
+        json j = i;
+
+        // check type
+        ASSERT_TRUE(j.is_number_unsigned());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(0x18);
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 2u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], 0x18);
+        uint8_t restored = static_cast<uint8_t>(result[1]);
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// 256..65535 (two-byte uint16_t)
+TEST(CborUnsignedTest, Pos2)
+{
+    for (size_t i = 256; i <= 65535; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with unsigned integer number
+        json j = i;
+
+        // check type
+        ASSERT_TRUE(j.is_number_unsigned());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(0x19);
+        expected.push_back(static_cast<uint8_t>((i >> 8) & 0xff));
+        expected.push_back(static_cast<uint8_t>(i & 0xff));
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), 3u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], 0x19);
+        uint16_t restored = static_cast<uint16_t>(static_cast<uint8_t>(result[1]) * 256 + static_cast<uint8_t>(result[2]));
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// 65536..4294967295 (four-byte uint32_t)
+class CborUnsignedPos4Test : public ::testing::TestWithParam<uint32_t> {};
+TEST_P(CborUnsignedPos4Test, Case)
+{
+    // create JSON value with unsigned integer number
+    json j = GetParam();
+
+    // check type
+    ASSERT_TRUE(j.is_number_unsigned());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(0x1a);
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+    ASSERT_EQ(result.size(), 5u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], 0x1a);
+    uint32_t restored = (static_cast<uint32_t>(static_cast<uint8_t>(result[1])) << 030) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[2])) << 020) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[3])) << 010) +
+                        static_cast<uint32_t>(static_cast<uint8_t>(result[4]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+INSTANTIATE_TEST_CASE_P(CborUnsignedPos4Tests, CborUnsignedPos4Test,
+                        ::testing::ValuesIn(pos4_numbers), );
+
+// 4294967296..4611686018427387903 (eight-byte uint64_t)
+class CborUnsignedPos8Test : public ::testing::TestWithParam<uint64_t> {};
+TEST_P(CborUnsignedPos8Test, Case)
+{
+    // create JSON value with integer number
+    json j = GetParam();
+
+    // check type
+    ASSERT_TRUE(j.is_number_unsigned());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(0x1b);
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 070) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 060) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 050) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 040) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 030) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 020) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 010) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+    ASSERT_EQ(result.size(), 9u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], 0x1b);
+    uint64_t restored = (static_cast<uint64_t>(static_cast<uint8_t>(result[1])) << 070) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[2])) << 060) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[3])) << 050) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[4])) << 040) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[5])) << 030) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[6])) << 020) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[7])) << 010) +
+                        static_cast<uint64_t>(static_cast<uint8_t>(result[8]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+INSTANTIATE_TEST_CASE_P(CborUnsignedPos8Tests, CborUnsignedPos8Test,
+                        ::testing::ValuesIn(pos8_numbers), );
+
+// 3.1415925
+TEST(CborFloatTest, Number)
+{
+    double v = 3.1415925;
+    json j = v;
+    std::vector<uint8_t> expected = {0xfb,0x40,0x09,0x21,0xfb,0x3f,0xa6,0xde,0xfc};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+    EXPECT_EQ(json::from_cbor(result), v);
+}
+
+TEST(CborFloatTest, HalfInfinity)
+{
+    json j = json::from_cbor(std::vector<uint8_t>({0xf9,0x7c,0x00}));
+    double d = j;
+    EXPECT_FALSE(std::isfinite(d));
+    EXPECT_EQ(j.dump(), "null");
+}
+
+TEST(CborFloatTest, HalfNaN)
+{
+    json j = json::from_cbor(std::vector<uint8_t>({0xf9,0x7c,0x01}));
+    double d = j;
+    EXPECT_TRUE(std::isnan(d));
+    EXPECT_EQ(j.dump(), "null");
+}
+
+// N = 0..23
+TEST(CborStringTest, String1)
+{
+    for (size_t N = 0; N <= 0x17; ++N)
+    {
+        SCOPED_TRACE(N);
+
+        // create JSON value with string containing of N * 'x'
+        const auto s = std::string(N, 'x');
+        json j = s;
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0x60 + N));
+        for (size_t i = 0; i < N; ++i)
+        {
+            expected.push_back('x');
+        }
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), N + 1);
+        // check that no null byte is appended
+        if (N > 0)
+        {
+            EXPECT_NE(result.back(), '\x00');
+        }
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// N = 24..255
+TEST(CborStringTest, String2)
+{
+    for (size_t N = 24; N <= 255; ++N)
+    {
+        SCOPED_TRACE(N);
+
+        // create JSON value with string containing of N * 'x'
+        const auto s = std::string(N, 'x');
+        json j = s;
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0x78));
+        expected.push_back(static_cast<uint8_t>(N));
+        for (size_t i = 0; i < N; ++i)
+        {
+            expected.push_back('x');
+        }
+
+        // compare result + size
+        const auto result = json::to_cbor(j);
+        EXPECT_EQ(result, expected);
+        ASSERT_EQ(result.size(), N + 2);
+        // check that no null byte is appended
+        EXPECT_NE(result.back(), '\x00');
+
+        // roundtrip
+        EXPECT_EQ(json::from_cbor(result), j);
+    }
+}
+
+// N = 256..65535
+class CborString3Test : public ::testing::TestWithParam<size_t> {};
+TEST_P(CborString3Test, Case)
+{
+    // create JSON value with string containing of N * 'x'
+    const auto s = std::string(GetParam(), 'x');
+    json j = s;
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(0x79);
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+    for (size_t i = 0; i < GetParam(); ++i)
+    {
+        expected.push_back('x');
+    }
+
+    // compare result + size
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+    ASSERT_EQ(result.size(), GetParam() + 3);
+    // check that no null byte is appended
+    EXPECT_NE(result.back(), '\x00');
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+static size_t string3_lens[] = {
+    256u,
+    999u,
+    1025u,
+    3333u,
+    2048u,
+    65535u
+};
+
+INSTANTIATE_TEST_CASE_P(CborString3Tests, CborString3Test,
+                        ::testing::ValuesIn(string3_lens), );
+
+// N = 65536..4294967295
+class CborString5Test : public ::testing::TestWithParam<size_t> {};
+TEST_P(CborString5Test, Case)
+{
+    // create JSON value with string containing of N * 'x'
+    const auto s = std::string(GetParam(), 'x');
+    json j = s;
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(0x7a);
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+    for (size_t i = 0; i < GetParam(); ++i)
+    {
+        expected.push_back('x');
+    }
+
+    // compare result + size
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+    ASSERT_EQ(result.size(), GetParam() + 5);
+    // check that no null byte is appended
+    EXPECT_NE(result.back(), '\x00');
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+static size_t string5_lens[] = {
+    65536u,
+    77777u,
+    1048576u
+};
+
+INSTANTIATE_TEST_CASE_P(CborString5Tests, CborString5Test,
+                        ::testing::ValuesIn(string5_lens), );
+
+TEST(CborArrayTest, Empty)
+{
+    json j = json::array();
+    std::vector<uint8_t> expected = {0x80};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// [null]
+TEST(CborArrayTest, Null)
+{
+    json j = {nullptr};
+    std::vector<uint8_t> expected = {0x81,0xf6};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// [1,2,3,4,5]
+TEST(CborArrayTest, Simple)
+{
+    json j = json::parse("[1,2,3,4,5]");
+    std::vector<uint8_t> expected = {0x85,0x01,0x02,0x03,0x04,0x05};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// [[[[]]]]
+TEST(CborArrayTest, NestEmpty)
+{
+    json j = json::parse("[[[[]]]]");
+    std::vector<uint8_t> expected = {0x81,0x81,0x81,0x80};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// array with uint16_t elements
+TEST(CborArrayTest, UInt16)
+{
+    json j(257, nullptr);
+    std::vector<uint8_t> expected(j.size() + 3, 0xf6); // all null
+    expected[0] = static_cast<char>(0x99); // array 16 bit
+    expected[1] = 0x01; // size (0x0101), byte 0
+    expected[2] = 0x01; // size (0x0101), byte 1
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// array with uint32_t elements
+TEST(CborArrayTest, UInt32)
+{
+    json j(65793, nullptr);
+    std::vector<uint8_t> expected(j.size() + 5, 0xf6); // all null
+    expected[0] = static_cast<char>(0x9a); // array 32 bit
+    expected[1] = 0x00; // size (0x00010101), byte 0
+    expected[2] = 0x01; // size (0x00010101), byte 1
+    expected[3] = 0x01; // size (0x00010101), byte 2
+    expected[4] = 0x01; // size (0x00010101), byte 3
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+/*
+// array with uint64_t elements
+TEST(CborArrayTest, UInt64)
+{
+    json j(4294967296, nullptr);
+    std::vector<uint8_t> expected(j.size() + 9, 0xf6); // all null
+    expected[0] = 0x9b; // array 64 bit
+    expected[1] = 0x00; // size (0x0000000100000000), byte 0
+    expected[2] = 0x00; // size (0x0000000100000000), byte 1
+    expected[3] = 0x00; // size (0x0000000100000000), byte 2
+    expected[4] = 0x01; // size (0x0000000100000000), byte 3
+    expected[5] = 0x00; // size (0x0000000100000000), byte 4
+    expected[6] = 0x00; // size (0x0000000100000000), byte 5
+    expected[7] = 0x00; // size (0x0000000100000000), byte 6
+    expected[8] = 0x00; // size (0x0000000100000000), byte 7
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+*/
+
+TEST(CborObjectTest, Empty)
+{
+    json j = json::object();
+    std::vector<uint8_t> expected = {0xa0};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// {"":null}
+TEST(CborObjectTest, EmptyKey)
+{
+    json j = {{"", nullptr}};
+    std::vector<uint8_t> expected = {0xa1,0x60,0xf6};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// {"a": {"b": {"c": {}}}}
+TEST(CborObjectTest, NestedEmpty)
+{
+    json j = json::parse("{\"a\": {\"b\": {\"c\": {}}}}");
+    std::vector<uint8_t> expected = {0xa1,0x61,0x61,0xa1,0x61,0x62,0xa1,0x61,0x63,0xa0};
+    const auto result = json::to_cbor(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// object with uint8_t elements
+TEST(CborObjectTest, UInt8)
+{
+    json j;
+    for (auto i = 0; i < 255; ++i)
+    {
+        // format i to a fixed width of 5
+        // each entry will need 7 bytes: 6 for string, 1 for null
+        std::stringstream ss;
+        ss << std::setw(5) << std::setfill('0') << i;
+        j.emplace(ss.str(), nullptr);
+    }
+
+    const auto result = json::to_cbor(j);
+
+    // Checking against an expected vector byte by byte is
+    // difficult, because no assumption on the order of key/value
+    // pairs are made. We therefore only check the prefix (type and
+    // size and the overall size. The rest is then handled in the
+    // roundtrip check.
+    ASSERT_EQ(result.size(), 1787u); // 1 type, 1 size, 255*7 content
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xb8)); // map 8 bit
+    EXPECT_EQ(result[1], static_cast<uint8_t>(0xff)); // size byte (0xff)
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// object with uint16_t elements
+TEST(CborObjectTest, UInt16)
+{
+    json j;
+    for (auto i = 0; i < 256; ++i)
+    {
+        // format i to a fixed width of 5
+        // each entry will need 7 bytes: 6 for string, 1 for null
+        std::stringstream ss;
+        ss << std::setw(5) << std::setfill('0') << i;
+        j.emplace(ss.str(), nullptr);
+    }
+
+    const auto result = json::to_cbor(j);
+
+    // Checking against an expected vector byte by byte is
+    // difficult, because no assumption on the order of key/value
+    // pairs are made. We therefore only check the prefix (type and
+    // size and the overall size. The rest is then handled in the
+    // roundtrip check.
+    ASSERT_EQ(result.size(), 1795u); // 1 type, 2 size, 256*7 content
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xb9)); // map 16 bit
+    EXPECT_EQ(result[1], 0x01); // byte 0 of size (0x0100)
+    EXPECT_EQ(result[2], 0x00); // byte 1 of size (0x0100)
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// object with uint32_t elements
+TEST(CborObjectTest, UInt32)
+{
+    json j;
+    for (auto i = 0; i < 65536; ++i)
+    {
+        // format i to a fixed width of 5
+        // each entry will need 7 bytes: 6 for string, 1 for null
+        std::stringstream ss;
+        ss << std::setw(5) << std::setfill('0') << i;
+        j.emplace(ss.str(), nullptr);
+    }
+
+    const auto result = json::to_cbor(j);
+
+    // Checking against an expected vector byte by byte is
+    // difficult, because no assumption on the order of key/value
+    // pairs are made. We therefore only check the prefix (type and
+    // size and the overall size. The rest is then handled in the
+    // roundtrip check.
+    ASSERT_EQ(result.size(), 458757u); // 1 type, 4 size, 65536*7 content
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xba)); // map 32 bit
+    EXPECT_EQ(result[1], 0x00); // byte 0 of size (0x00010000)
+    EXPECT_EQ(result[2], 0x01); // byte 1 of size (0x00010000)
+    EXPECT_EQ(result[3], 0x00); // byte 2 of size (0x00010000)
+    EXPECT_EQ(result[4], 0x00); // byte 3 of size (0x00010000)
+
+    // roundtrip
+    EXPECT_EQ(json::from_cbor(result), j);
+}
+
+// 0x7b (string)
+TEST(CborAdditionalDeserializationTest, Case7b)
+{
+    std::vector<uint8_t> given{0x7b,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x61};
+    json j = json::from_cbor(given);
+    EXPECT_EQ(j, "a");
+}
+
+// 0x9b (array)
+TEST(CborAdditionalDeserializationTest, Case9b)
+{
+    std::vector<uint8_t> given{0x9b,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0xf4};
+    json j = json::from_cbor(given);
+    EXPECT_EQ(j, json::parse("[false]"));
+}
+
+// 0xbb (map)
+TEST(CborAdditionalDeserializationTest, Casebb)
+{
+    std::vector<uint8_t> given{0xbb,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x01,0x60,0xf4};
+    json j = json::from_cbor(given);
+    EXPECT_EQ(j, json::parse("{\"\": false}"));
+}
+
+TEST(CborErrorTest, TooShortByteVector)
+{
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x18})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 2: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x19})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 2: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x19,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 3: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1a})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 2: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1a,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 3: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1a,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 4: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1a,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 5: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1b})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 2: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1b,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 3: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1b,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 4: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1b,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 5: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1b,0x00,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 6: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1b,0x00,0x00,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 7: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1b,0x00,0x00,0x00,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 8: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1b,0x00,0x00,0x00,0x00,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 9: unexpected end of input");
+}
+
+TEST(CborErrorTest, UnsupportedBytesConcrete)
+{
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0x1c})), json::parse_error,
+                     "[json.exception.parse_error.112] parse error at 1: error reading CBOR; last byte: 0x1c");
+    EXPECT_THROW_MSG(json::from_cbor(std::vector<uint8_t>({0xf8})), json::parse_error,
+                     "[json.exception.parse_error.112] parse error at 1: error reading CBOR; last byte: 0xf8");
+}
+
+class CborUnsupportedBytesTest : public ::testing::TestWithParam<uint8_t> {
+};
+TEST_P(CborUnsupportedBytesTest, Case)
+{
+    EXPECT_THROW(json::from_cbor(std::vector<uint8_t>({GetParam()})), json::parse_error);
+}
+
+static const uint8_t unsupported_bytes_cases[] = {
+    // ?
+    0x1c, 0x1d, 0x1e, 0x1f,
+    // ?
+    0x3c, 0x3d, 0x3e, 0x3f,
+    // byte strings
+    0x40, 0x41, 0x42, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x50, 0x51, 0x52, 0x53, 0x54, 0x55, 0x56, 0x57,
+    // byte strings
+    0x58, 0x59, 0x5a, 0x5b,
+    // ?
+    0x5c, 0x5d, 0x5e,
+    // byte string
+    0x5f,
+    // ?
+    0x7c, 0x7d, 0x7e,
+    // ?
+    0x9c, 0x9d, 0x9e,
+    // ?
+    0xbc, 0xbd, 0xbe,
+    // date/time
+    0xc0, 0xc1,
+    // bignum
+    0xc2, 0xc3,
+    // fraction
+    0xc4,
+    // bigfloat
+    0xc5,
+    // tagged item
+    0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xcb, 0xcc, 0xcd, 0xce, 0xcf, 0xd0, 0xd1, 0xd2, 0xd3, 0xd4,
+    // expected conversion
+    0xd5, 0xd6, 0xd7,
+    // more tagged items
+    0xd8, 0xd9, 0xda, 0xdb,
+    // ?
+    0xdc, 0xdd, 0xde, 0xdf,
+    // (simple value)
+    0xe0, 0xe1, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7, 0xe8, 0xe9, 0xea, 0xeb, 0xec, 0xed, 0xee, 0xef, 0xf0, 0xf1, 0xf2, 0xf3,
+    // undefined
+    0xf7,
+    // simple value
+    0xf8,
+};
+
+INSTANTIATE_TEST_CASE_P(CborUnsupportedBytesTests, CborUnsupportedBytesTest,
+                        ::testing::ValuesIn(unsupported_bytes_cases), );
+#if 0
+// use this testcase outside [hide] to run it with Valgrind
+TEST(CborRoundtripTest, Sample)
+{
+    std::string filename = "test/data/json_testsuite/sample.json";
+
+    // parse JSON file
+    std::ifstream f_json(filename);
+    json j1 = json::parse(f_json);
+
+    // parse CBOR file
+    std::ifstream f_cbor(filename + ".cbor", std::ios::binary);
+    std::vector<uint8_t> packed((std::istreambuf_iterator<char>(f_cbor)),
+                                std::istreambuf_iterator<char>());
+    json j2;
+    j2 = json::from_cbor(packed);
+
+    // compare parsed JSON values
+    EXPECT_EQ(j1, j2);
+
+    // check with different start index
+    packed.insert(packed.begin(), 5, 0xff);
+    EXPECT_EQ(j1, json::from_cbor(packed, 5));
+}
+
+/*
+The following test cases were found during a two-day session with
+AFL-Fuzz. As a result, empty byte vectors and excessive lengths are
+detected.
+*/
+class CborRegressionFuzzTest : public ::testing::TestWithParam<const char*> {};
+TEST_P(CborRegressionFuzzTest, Case)
+{
+    try
+    {
+        // parse CBOR file
+        std::ifstream f_cbor(GetParam(), std::ios::binary);
+        std::vector<uint8_t> vec1(
+            (std::istreambuf_iterator<char>(f_cbor)),
+            std::istreambuf_iterator<char>());
+        json j1 = json::from_cbor(vec1);
+
+        try
+        {
+            // step 2: round trip
+            std::string vec2 = json::to_cbor(j1);
+
+            // parse serialization
+            json j2 = json::from_cbor(vec2);
+
+            // deserializations must match
+            EXPECT_EQ(j1, j2);
+        }
+        catch (const json::parse_error&)
+        {
+            // parsing a CBOR serialization must not fail
+            FAIL();
+        }
+    }
+    catch (const json::parse_error&)
+    {
+        // parse errors are ok, because input may be random bytes
+    }
+}
+
+static const char* fuzz_test_cases[] = {
+    "test/data/cbor_regression/test01",
+    "test/data/cbor_regression/test02",
+    "test/data/cbor_regression/test03",
+    "test/data/cbor_regression/test04",
+    "test/data/cbor_regression/test05",
+    "test/data/cbor_regression/test06",
+    "test/data/cbor_regression/test07",
+    "test/data/cbor_regression/test08",
+    "test/data/cbor_regression/test09",
+    "test/data/cbor_regression/test10",
+    "test/data/cbor_regression/test11",
+    "test/data/cbor_regression/test12",
+    "test/data/cbor_regression/test13",
+    "test/data/cbor_regression/test14",
+    "test/data/cbor_regression/test15",
+    "test/data/cbor_regression/test16",
+    "test/data/cbor_regression/test17",
+    "test/data/cbor_regression/test18",
+    "test/data/cbor_regression/test19",
+    "test/data/cbor_regression/test20",
+    "test/data/cbor_regression/test21",
+};
+
+INSTANTIATE_TEST_CASE_P(CborRegressionFuzzTests, CborRegressionFuzzTest,
+                        ::testing::ValuesIn(fuzz_test_cases));
+
+class CborRegressionFlynnTest : public ::testing::TestWithParam<const char*> {};
+TEST_F(CborRegressionFlynnTest, Case)
+{
+    // parse JSON file
+    std::ifstream f_json(GetParam());
+    json j1 = json::parse(f_json);
+
+    // parse CBOR file
+    std::ifstream f_cbor(filename + ".cbor", std::ios::binary);
+    std::vector<uint8_t> packed(
+        (std::istreambuf_iterator<char>(f_cbor)),
+        std::istreambuf_iterator<char>());
+    json j2;
+    j2 = json::from_cbor(packed);
+
+    // compare parsed JSON values
+    EXPECT_EQ(j1, j2);
+}
+
+static const char* flynn_test_cases[] = {
+    "test/data/json_nlohmann_tests/all_unicode.json",
+    "test/data/json.org/1.json",
+    "test/data/json.org/2.json",
+    "test/data/json.org/3.json",
+    "test/data/json.org/4.json",
+    "test/data/json.org/5.json",
+    "test/data/json_roundtrip/roundtrip01.json",
+    "test/data/json_roundtrip/roundtrip02.json",
+    "test/data/json_roundtrip/roundtrip03.json",
+    "test/data/json_roundtrip/roundtrip04.json",
+    "test/data/json_roundtrip/roundtrip05.json",
+    "test/data/json_roundtrip/roundtrip06.json",
+    "test/data/json_roundtrip/roundtrip07.json",
+    "test/data/json_roundtrip/roundtrip08.json",
+    "test/data/json_roundtrip/roundtrip09.json",
+    "test/data/json_roundtrip/roundtrip10.json",
+    "test/data/json_roundtrip/roundtrip11.json",
+    "test/data/json_roundtrip/roundtrip12.json",
+    "test/data/json_roundtrip/roundtrip13.json",
+    "test/data/json_roundtrip/roundtrip14.json",
+    "test/data/json_roundtrip/roundtrip15.json",
+    "test/data/json_roundtrip/roundtrip16.json",
+    "test/data/json_roundtrip/roundtrip17.json",
+    "test/data/json_roundtrip/roundtrip18.json",
+    "test/data/json_roundtrip/roundtrip19.json",
+    "test/data/json_roundtrip/roundtrip20.json",
+    "test/data/json_roundtrip/roundtrip21.json",
+    "test/data/json_roundtrip/roundtrip22.json",
+    "test/data/json_roundtrip/roundtrip23.json",
+    "test/data/json_roundtrip/roundtrip24.json",
+    "test/data/json_roundtrip/roundtrip25.json",
+    "test/data/json_roundtrip/roundtrip26.json",
+    "test/data/json_roundtrip/roundtrip27.json",
+    "test/data/json_roundtrip/roundtrip28.json",
+    "test/data/json_roundtrip/roundtrip29.json",
+    "test/data/json_roundtrip/roundtrip30.json",
+    "test/data/json_roundtrip/roundtrip31.json",
+    "test/data/json_roundtrip/roundtrip32.json",
+    "test/data/json_testsuite/sample.json", // kills AppVeyor
+    "test/data/json_tests/pass1.json",
+    "test/data/json_tests/pass2.json",
+    "test/data/json_tests/pass3.json",
+    "test/data/regression/floats.json",
+    "test/data/regression/signed_ints.json",
+    "test/data/regression/unsigned_ints.json",
+    "test/data/regression/working_file.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_arraysWithSpaces.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_empty-string.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_empty.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_ending_with_newline.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_false.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_heterogeneous.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_null.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_with_1_and_newline.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_with_leading_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_with_several_null.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_with_trailing_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_0e+1.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_0e1.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_after_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_double_close_to_zero.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_double_huge_neg_exp.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_huge_exp.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_int_with_exp.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_minus_zero.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_negative_int.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_negative_one.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_negative_zero.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_capital_e.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_capital_e_neg_exp.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_capital_e_pos_exp.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_exponent.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_fraction_exponent.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_neg_exp.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_real_neg_overflow.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_pos_exponent.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_real_pos_overflow.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_underflow.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_simple_int.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_simple_real.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_too_big_neg_int.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_too_big_pos_int.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_very_big_negative_int.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_basic.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_duplicated_key.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_duplicated_key_and_value.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_empty.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_empty_key.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_escaped_null_in_key.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_extreme_numbers.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_long_strings.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_simple.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_string_unicode.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_with_newlines.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_1_2_3_bytes_UTF-8_sequences.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_UTF-16_Surrogates_U+1D11E_MUSICAL_SYMBOL_G_CLEF.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_accepted_surrogate_pair.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_accepted_surrogate_pairs.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_allowed_escapes.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_backslash_and_u_escaped_zero.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_backslash_doublequotes.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_comments.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_double_escape_a.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_double_escape_n.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_escaped_control_character.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_escaped_noncharacter.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_in_array.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_in_array_with_leading_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_last_surrogates_1_and_2.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_newline_uescaped.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_nonCharacterInUTF-8_U+10FFFF.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_nonCharacterInUTF-8_U+1FFFF.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_nonCharacterInUTF-8_U+FFFF.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_null_escape.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_one-byte-utf-8.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_pi.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_simple_ascii.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_three-byte-utf-8.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_two-byte-utf-8.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_u+2028_line_sep.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_u+2029_par_sep.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_uEscape.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unescaped_char_delete.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicodeEscapedBackslash.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode_2.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode_U+200B_ZERO_WIDTH_SPACE.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode_U+2064_invisible_plus.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode_escaped_double_quote.json",
+    // "test/data/nst_json_testsuite/test_parsing/y_string_utf16.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_utf8.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_with_del_character.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_false.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_int.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_negative_real.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_null.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_string.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_true.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_string_empty.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_trailing_newline.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_true_in_array.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_whitespace_array.json",
+};
+
+INSTANTIATE_TEST_CASE_P(CborRegressionFlynnTests, CborRegressionFlynnTest,
+                        ::testing::ValuesIn(flynn_test_cases));
+
+#endif
+TEST(CborFirstBytesTest, Unsupported)
+{
+    // these bytes will fail immediately with exception parse_error.112
+    std::set<uint8_t> unsupported =
+    {
+        //// types not supported by this library
+
+        // byte strings
+        0x40, 0x41, 0x42, 0x43, 0x44, 0x45, 0x46, 0x47,
+        0x48, 0x49, 0x4a, 0x4b, 0x4c, 0x4d, 0x4e, 0x4f,
+        0x50, 0x51, 0x52, 0x53, 0x54, 0x55, 0x56, 0x57,
+        // byte strings
+        0x58, 0x59, 0x5a, 0x5b, 0x5f,
+        // date/time
+        0xc0, 0xc1,
+        // bignum
+        0xc2, 0xc3,
+        // decimal fracion
+        0xc4,
+        // bigfloat
+        0xc5,
+        // tagged item
+        0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xcb, 0xcc, 0xcd,
+        0xce, 0xcf, 0xd0, 0xd1, 0xd2, 0xd3, 0xd4, 0xd8,
+        0xd9, 0xda, 0xdb,
+        // expected conversion
+        0xd5, 0xd6, 0xd7,
+        // simple value
+        0xe0, 0xe1, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7,
+        0xe8, 0xe9, 0xea, 0xeb, 0xec, 0xed, 0xef, 0xf0,
+        0xf1, 0xf2, 0xf3,
+        0xf8,
+        // undefined
+        0xf7,
+
+        //// bytes not specified by CBOR
+
+        0x1c, 0x1d, 0x1e, 0x1f,
+        0x3c, 0x3d, 0x3e, 0x3f,
+        0x5c, 0x5d, 0x5e,
+        0x7c, 0x7d, 0x7e,
+        0x9c, 0x9d, 0x9e,
+        0xbc, 0xbd, 0xbe,
+        0xdc, 0xdd, 0xde, 0xdf,
+        0xee,
+        0xfc, 0xfe, 0xfd,
+
+        /// break cannot be the first byte
+
+        0xff
+    };
+
+    for (auto i = 0; i < 256; ++i)
+    {
+        const auto byte = static_cast<uint8_t>(i);
+
+        try
+        {
+            json::from_cbor(std::vector<uint8_t>(1, byte));
+        }
+        catch (const json::parse_error& e)
+        {
+            // check that parse_error.112 is only thrown if the
+            // first byte is in the unsupported set
+            SCOPED_TRACE(e.what());
+            if (std::find(unsupported.begin(), unsupported.end(),
+                          static_cast<uint8_t>(byte)) != unsupported.end())
+            {
+                EXPECT_EQ(e.id, 112);
+            }
+            else
+            {
+                EXPECT_NE(e.id, 112);
+            }
+        }
+    }
+}
+
+// examples from RFC 7049 Appendix A
+namespace internal {
+struct CborRoundtripTestParam {
+  const char* plain;
+  std::vector<uint8_t> encoded;
+  bool test_encode;
+};
+}  // namespace internal
+
+class CborRoundtripTest
+    : public ::testing::TestWithParam<internal::CborRoundtripTestParam> {
+};
+TEST_P(CborRoundtripTest, Case)
+{
+    if (GetParam().test_encode)
+    {
+        EXPECT_EQ(json::to_cbor(json::parse(GetParam().plain)), GetParam().encoded);
+    }
+    EXPECT_EQ(json::parse(GetParam().plain), json::from_cbor(GetParam().encoded));
+}
+
+static const internal::CborRoundtripTestParam rfc7049_appendix_a_numbers[] = {
+    {"0", {0x00}, true},
+    {"1", {0x01}, true},
+    {"10", {0x0a}, true},
+    {"23", {0x17}, true},
+    {"24", {0x18,0x18}, true},
+    {"25", {0x18,0x19}, true},
+    {"100", {0x18,0x64}, true},
+    {"1000", {0x19,0x03,0xe8}, true},
+    {"1000000", {0x1a,0x00,0x0f,0x42,0x40}, true},
+    {"1000000000000", {0x1b,0x00,0x00,0x00,0xe8,0xd4,0xa5,0x10,0x00}, true},
+    {"18446744073709551615", {0x1b,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff}, true},
+    // positive bignum is not supported
+    //{"18446744073709551616", {0xc2,0x49,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00", 11), true},
+    //{"-18446744073709551616", {0x3b,0xff,0xff,0xff,0xff,0xff,0xff,0xff,0xff}, true},
+    // negative bignum is not supported
+    //{"-18446744073709551617", {0xc3,0x49,0x01,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00}, true},
+    {"-1", {0x20}, true},
+    {"-10", {0x29}, true},
+    {"-100", {0x38,0x63}, true},
+    {"-1000", {0x39,0x03,0xe7}, true},
+    // half-precision float
+    {"0.0", {0xf9,0x00,0x00}, false},
+    // half-precision float
+    {"-0.0", {0xf9,0x80,0x00}, false},
+    // half-precision float
+    {"1.0", {0xf9,0x3c,0x00}, false},
+    {"1.1", {0xfb,0x3f,0xf1,0x99,0x99,0x99,0x99,0x99,0x9a}, true},
+    // half-precision float
+    {"1.5", {0xf9,0x3e,0x00}, false},
+    // half-precision float
+    {"65504.0", {0xf9,0x7b,0xff}, false},
+    {"100000.0", {0xfa,0x47,0xc3,0x50,0x00}, false},
+    {"3.4028234663852886e+38", {0xfa,0x7f,0x7f,0xff,0xff}, false},
+    {"1.0e+300", {0xfb,0x7e,0x37,0xe4,0x3c,0x88,0x00,0x75,0x9c}, true},
+    // half-precision float
+    {"5.960464477539063e-8", {0xf9,0x00,0x01}, false},
+    // half-precision float
+    {"0.00006103515625", {0xf9,0x04,0x00}, false},
+    // half-precision float
+    {"-4.0", {0xf9,0xc4,0x00}, false},
+    {"-4.1", {0xfb,0xc0,0x10,0x66,0x66,0x66,0x66,0x66,0x66}, true},
+};
+
+INSTANTIATE_TEST_CASE_P(CborRfc7049AppendixANumberTests, CborRoundtripTest,
+                        ::testing::ValuesIn(rfc7049_appendix_a_numbers), );
+
+static const internal::CborRoundtripTestParam rfc7049_appendix_a_simple_values[] = {
+    {"false", {0xf4}, true},
+    {"true", {0xf5}, true},
+};
+
+INSTANTIATE_TEST_CASE_P(CborRfc7049AppendixASimpleValueTests, CborRoundtripTest,
+                        ::testing::ValuesIn(rfc7049_appendix_a_simple_values), );
+
+static const internal::CborRoundtripTestParam rfc7049_appendix_a_strings[] = {
+    {"\"\"", {0x60}, true},
+    {"\"a\"", {0x61,0x61}, true},
+    {"\"IETF\"", {0x64,0x49,0x45,0x54,0x46}, true},
+    {"\"\\u00fc\"", {0x62,0xc3,0xbc}, true},
+    {"\"\\u6c34\"", {0x63,0xe6,0xb0,0xb4}, true},
+    {"\"\\ud800\\udd51\"", {0x64,0xf0,0x90,0x85,0x91}, true},
+    // indefinite length strings
+    {"\"streaming\"", {0x7f,0x65,0x73,0x74,0x72,0x65,0x61,0x64,0x6d,0x69,0x6e,0x67,0xff}, false},
+};
+
+INSTANTIATE_TEST_CASE_P(CborRfc7049AppendixAStringTests, CborRoundtripTest,
+                        ::testing::ValuesIn(rfc7049_appendix_a_strings), );
+
+static const internal::CborRoundtripTestParam rfc7049_appendix_a_arrays[] = {
+    {"[]", {0x80}, true},
+    {"[1, 2, 3]", {0x83,0x01,0x02,0x03}, true},
+    {"[1, [2, 3], [4, 5]]", {0x83,0x01,0x82,0x02,0x03,0x82,0x04,0x05}, true},
+    {"[1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25]", {0x98,0x19,0x01,0x02,0x03,0x04,0x05,0x06,0x07,0x08,0x09,0x0a,0x0b,0x0c,0x0d,0x0e,0x0f,0x10,0x11,0x12,0x13,0x14,0x15,0x16,0x17,0x18,0x18,0x18,0x19}, true},
+    // indefinite length arrays
+    {"[]", {0x9f,0xff}, false},
+    {"[1, [2, 3], [4, 5]] ", {0x9f,0x01,0x82,0x02,0x03,0x9f,0x04,0x05,0xff,0xff}, false},
+    {"[1, [2, 3], [4, 5]]", {0x9f,0x01,0x82,0x02,0x03,0x82,0x04,0x05,0xff}, false},
+    {"[1, [2, 3], [4, 5]]", {0x83,0x01,0x82,0x02,0x03,0x9f,0x04,0x05,0xff}, false},
+    {"[1, [2, 3], [4, 5]]", {0x83,0x01,0x9f,0x02,0x03,0xff,0x82,0x04,0x05}, false},
+    {"[1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25]", {0x9f,0x01,0x02,0x03,0x04,0x05,0x06,0x07,0x08,0x09,0x0a,0x0b,0x0c,0x0d,0x0e,0x0f,0x10,0x11,0x12,0x13,0x14,0x15,0x16,0x17,0x18,0x18,0x18,0x19,0xff}, false},
+};
+
+INSTANTIATE_TEST_CASE_P(CborRfc7049AppendixAArrayTests, CborRoundtripTest,
+                        ::testing::ValuesIn(rfc7049_appendix_a_arrays), );
+
+static const internal::CborRoundtripTestParam rfc7049_appendix_a_objects[] = {
+    {"{}", {0xa0}, true},
+    {"{\"a\": 1, \"b\": [2, 3]}", {0xa2,0x61,0x61,0x01,0x61,0x62,0x82,0x02,0x03}, true},
+    {"[\"a\", {\"b\": \"c\"}]", {0x82,0x61,0x61,0xa1,0x61,0x62,0x61,0x63}, true},
+    {"{\"a\": \"A\", \"b\": \"B\", \"c\": \"C\", \"d\": \"D\", \"e\": \"E\"}", {0xa5,0x61,0x61,0x61,0x41,0x61,0x62,0x61,0x42,0x61,0x63,0x61,0x43,0x61,0x64,0x61,0x44,0x61,0x65,0x61,0x45}, true},
+    // indefinite length objects
+    {"{\"a\": 1, \"b\": [2, 3]}", {0xbf,0x61,0x61,0x01,0x61,0x62,0x9f,0x02,0x03,0xff,0xff}, false},
+    {"[\"a\", {\"b\": \"c\"}]", {0x82,0x61,0x61,0xbf,0x61,0x62,0x61,0x63,0xff}, false},
+    {"{\"Fun\": true, \"Amt\": -2}", {0xbf,0x63,0x46,0x75,0x6e,0xf5,0x63,0x41,0x6d,0x74,0x21,0xff}, false},
+};
+
+INSTANTIATE_TEST_CASE_P(CborRfc7049AppendixAObjectTests, CborRoundtripTest,
+                        ::testing::ValuesIn(rfc7049_appendix_a_objects), );
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-comparison.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-comparison.cpp
new file mode 100644
index 0000000..18934a2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-comparison.cpp
@@ -0,0 +1,250 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+class JsonComparisonTypesTest : public ::testing::Test {
+ protected:
+    std::vector<json::value_t> j_types =
+    {
+        json::value_t::null,
+        json::value_t::boolean,
+        json::value_t::number_integer,
+        json::value_t::number_unsigned,
+        json::value_t::number_float,
+        json::value_t::object,
+        json::value_t::array,
+        json::value_t::string
+    };
+};
+
+TEST_F(JsonComparisonTypesTest, Less)
+{
+    static const std::vector<std::vector<bool>> expected =
+    {
+        {false, true, true, true, true, true, true, true},
+        {false, false, true, true, true, true, true, true},
+        {false, false, false, false, false, true, true, true},
+        {false, false, false, false, false, true, true, true},
+        {false, false, false, false, false, true, true, true},
+        {false, false, false, false, false, false, true, true},
+        {false, false, false, false, false, false, false, true},
+        {false, false, false, false, false, false, false, false}
+    };
+
+    for (size_t i = 0; i < j_types.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        for (size_t j = 0; j < j_types.size(); ++j)
+        {
+            SCOPED_TRACE(j);
+            // check precomputed values
+            EXPECT_EQ(operator<(j_types[i], j_types[j]), expected[i][j]);
+        }
+    }
+}
+
+class JsonComparisonValuesTest : public ::testing::Test {
+ protected:
+    json j_values =
+    {
+        nullptr, nullptr,
+        17, 42,
+        8u, 13u,
+        3.14159, 23.42,
+        "foo", "bar",
+        true, false,
+        {1, 2, 3}, {"one", "two", "three"},
+        {{"first", 1}, {"second", 2}}, {{"a", "A"}, {"b", {"B"}}}
+    };
+};
+
+TEST_F(JsonComparisonValuesTest, Equal)
+{
+    static const std::vector<std::vector<bool>> expected =
+    {
+        {true, true, false, false, false, false, false, false, false, false, false, false, false, false, false, false},
+        {true, true, false, false, false, false, false, false, false, false, false, false, false, false, false, false},
+        {false, false, true, false, false, false, false, false, false, false, false, false, false, false, false, false},
+        {false, false, false, true, false, false, false, false, false, false, false, false, false, false, false, false},
+        {false, false, false, false, true, false, false, false, false, false, false, false, false, false, false, false},
+        {false, false, false, false, false, true, false, false, false, false, false, false, false, false, false, false},
+        {false, false, false, false, false, false, true, false, false, false, false, false, false, false, false, false},
+        {false, false, false, false, false, false, false, true, false, false, false, false, false, false, false, false},
+        {false, false, false, false, false, false, false, false, true, false, false, false, false, false, false, false},
+        {false, false, false, false, false, false, false, false, false, true, false, false, false, false, false, false},
+        {false, false, false, false, false, false, false, false, false, false, true, false, false, false, false, false},
+        {false, false, false, false, false, false, false, false, false, false, false, true, false, false, false, false},
+        {false, false, false, false, false, false, false, false, false, false, false, false, true, false, false, false},
+        {false, false, false, false, false, false, false, false, false, false, false, false, false, true, false, false},
+        {false, false, false, false, false, false, false, false, false, false, false, false, false, false, true, false},
+        {false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, true}
+    };
+
+    for (size_t i = 0; i < j_values.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        for (size_t j = 0; j < j_values.size(); ++j)
+        {
+            SCOPED_TRACE(j);
+            // check precomputed values
+            EXPECT_EQ(j_values[i] == j_values[j], expected[i][j]);
+        }
+    }
+
+    // comparison with discarded elements
+    json j_discarded(json::value_t::discarded);
+    for (size_t i = 0; i < j_values.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        EXPECT_FALSE(j_values[i] == j_discarded);
+        EXPECT_FALSE(j_discarded == j_values[i]);
+        EXPECT_FALSE(j_discarded == j_discarded);
+    }
+
+    // compare with null pointer
+    json j_null;
+    EXPECT_TRUE(j_null == nullptr);
+    EXPECT_TRUE(nullptr == j_null);
+}
+
+TEST_F(JsonComparisonValuesTest, NotEqual)
+{
+    for (size_t i = 0; i < j_values.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        for (size_t j = 0; j < j_values.size(); ++j)
+        {
+            SCOPED_TRACE(j);
+            // check definition
+            EXPECT_EQ(j_values[i] != j_values[j], !(j_values[i] == j_values[j]));
+        }
+    }
+
+    // compare with null pointer
+    json j_null;
+    EXPECT_FALSE(j_null != nullptr);
+    EXPECT_FALSE(nullptr != j_null);
+    EXPECT_EQ(j_null != nullptr, !(j_null == nullptr));
+    EXPECT_EQ(nullptr != j_null, !(nullptr == j_null));
+}
+
+TEST_F(JsonComparisonValuesTest, Less)
+{
+    static const std::vector<std::vector<bool>> expected =
+    {
+        {false, false, true, true, true, true, true, true, true, true, true, true, true, true, true, true},
+        {false, false, true, true, true, true, true, true, true, true, true, true, true, true, true, true},
+        {false, false, false, true, false, false, false, true, true, true, false, false, true, true, true, true},
+        {false, false, false, false, false, false, false, false, true, true, false, false, true, true, true, true},
+        {false, false, true, true, false, true, false, true, true, true, false, false, true, true, true, true},
+        {false, false, true, true, false, false, false, true, true, true, false, false, true, true, true, true},
+        {false, false, true, true, true, true, false, true, true, true, false, false, true, true, true, true},
+        {false, false, false, true, false, false, false, false, true, true, false, false, true, true, true, true},
+        {false, false, false, false, false, false, false, false, false, false, false, false, false, false, false, false},
+        {false, false, false, false, false, false, false, false, true, false, false, false, false, false, false, false},
+        {false, false, true, true, true, true, true, true, true, true, false, false, true, true, true, true},
+        {false, false, true, true, true, true, true, true, true, true, true, false, true, true, true, true},
+        {false, false, false, false, false, false, false, false, true, true, false, false, false, true, false, false},
+        {false, false, false, false, false, false, false, false, true, true, false, false, false, false, false, false},
+        {false, false, false, false, false, false, false, false, true, true, false, false, true, true, false, false},
+        {false, false, false, false, false, false, false, false, true, true, false, false, true, true, true, false}
+    };
+
+    for (size_t i = 0; i < j_values.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        for (size_t j = 0; j < j_values.size(); ++j)
+        {
+            SCOPED_TRACE(j);
+            // check precomputed values
+            EXPECT_EQ(j_values[i] < j_values[j], expected[i][j]);
+        }
+    }
+
+    // comparison with discarded elements
+    json j_discarded(json::value_t::discarded);
+    for (size_t i = 0; i < j_values.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        EXPECT_FALSE(j_values[i] < j_discarded);
+        EXPECT_FALSE(j_discarded < j_values[i]);
+        EXPECT_FALSE(j_discarded < j_discarded);
+    }
+}
+
+TEST_F(JsonComparisonValuesTest, LessEqual)
+{
+    for (size_t i = 0; i < j_values.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        for (size_t j = 0; j < j_values.size(); ++j)
+        {
+            SCOPED_TRACE(j);
+            // check definition
+            EXPECT_EQ(j_values[i] <= j_values[j], !(j_values[j] < j_values[i]));
+        }
+    }
+}
+
+TEST_F(JsonComparisonValuesTest, Greater)
+{
+    for (size_t i = 0; i < j_values.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        for (size_t j = 0; j < j_values.size(); ++j)
+        {
+            SCOPED_TRACE(j);
+            // check definition
+            EXPECT_EQ(j_values[i] > j_values[j], j_values[j] < j_values[i]);
+        }
+    }
+}
+
+TEST_F(JsonComparisonValuesTest, GreaterEqual)
+{
+    for (size_t i = 0; i < j_values.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        for (size_t j = 0; j < j_values.size(); ++j)
+        {
+            SCOPED_TRACE(j);
+            // check definition
+            EXPECT_EQ(j_values[i] >= j_values[j], !(j_values[i] < j_values[j]));
+        }
+    }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-concepts.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-concepts.cpp
new file mode 100644
index 0000000..4ce5a5b
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-concepts.cpp
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+TEST(JsonConceptsTest, ContainerRequirements)
+{
+    // X: container class: json
+    // T: type of objects: json
+    // a, b: values of type X: json
+
+    // TABLE 96 - Container Requirements
+
+    // X::value_type must return T
+    EXPECT_TRUE((std::is_same<json::value_type, json>::value));
+
+    // X::reference must return lvalue of T
+    EXPECT_TRUE((std::is_same<json::reference, json&>::value));
+
+    // X::const_reference must return const lvalue of T
+    EXPECT_TRUE((std::is_same<json::const_reference, const json&>::value));
+
+    // X::iterator must return iterator whose value_type is T
+    EXPECT_TRUE((std::is_same<json::iterator::value_type, json>::value));
+    // X::iterator must meet the forward iterator requirements
+    EXPECT_TRUE((std::is_base_of<std::forward_iterator_tag, typename std::iterator_traits<json::iterator>::iterator_category>::value));
+    // X::iterator must be convertible to X::const_iterator
+    EXPECT_TRUE((std::is_convertible<json::iterator, json::const_iterator>::value));
+
+    // X::const_iterator must return iterator whose value_type is T
+    EXPECT_TRUE((std::is_same<json::const_iterator::value_type, json>::value));
+    // X::const_iterator must meet the forward iterator requirements
+    EXPECT_TRUE((std::is_base_of<std::forward_iterator_tag, typename std::iterator_traits<json::const_iterator>::iterator_category>::value));
+
+    // X::difference_type must return a signed integer
+    EXPECT_TRUE((std::is_signed<json::difference_type>::value));
+    // X::difference_type must be identical to X::iterator::difference_type
+    EXPECT_TRUE((std::is_same<json::difference_type, json::iterator::difference_type>::value));
+    // X::difference_type must be identical to X::const_iterator::difference_type
+    EXPECT_TRUE((std::is_same<json::difference_type, json::const_iterator::difference_type>::value));
+
+    // X::size_type must return an unsigned integer
+    EXPECT_TRUE((std::is_unsigned<json::size_type>::value));
+    // X::size_type can represent any non-negative value of X::difference_type
+    EXPECT_TRUE(static_cast<json::size_type>(std::numeric_limits<json::difference_type>::max()) <=
+          std::numeric_limits<json::size_type>::max());
+
+    // the expression "X u" has the post-condition "u.empty()"
+    {
+        json u;
+        EXPECT_TRUE(u.empty());
+    }
+
+    // the expression "X()" has the post-condition "X().empty()"
+    EXPECT_TRUE(json().empty());
+}
+
+TEST(JsonConceptsTest, DefaultConstructible)
+{
+    EXPECT_TRUE(std::is_nothrow_default_constructible<json>::value);
+}
+
+TEST(JsonConceptsTest, MoveConstructible)
+{
+    EXPECT_TRUE(std::is_nothrow_move_constructible<json>::value);
+}
+
+TEST(JsonConceptsTest, CopyConstructible)
+{
+    EXPECT_TRUE(std::is_copy_constructible<json>::value);
+}
+
+TEST(JsonConceptsTest, MoveAssignable)
+{
+    EXPECT_TRUE(std::is_nothrow_move_assignable<json>::value);
+}
+
+TEST(JsonConceptsTest, CopyAssignable)
+{
+    EXPECT_TRUE(std::is_copy_assignable<json>::value);
+}
+
+TEST(JsonConceptsTest, Destructible)
+{
+    EXPECT_TRUE(std::is_nothrow_destructible<json>::value);
+}
+
+TEST(JsonConceptsTest, StandardLayoutType)
+{
+    EXPECT_TRUE(std::is_standard_layout<json>::value);
+}
+
+TEST(JsonIteratorConceptsTest, CopyConstructible)
+{
+    EXPECT_TRUE(std::is_nothrow_copy_constructible<json::iterator>::value);
+    EXPECT_TRUE(std::is_nothrow_copy_constructible<json::const_iterator>::value);
+}
+
+TEST(JsonIteratorConceptsTest, CopyAssignable)
+{
+    // STL iterators used by json::iterator don't pass this test in Debug mode
+#if !defined(_MSC_VER) || (_ITERATOR_DEBUG_LEVEL == 0)
+    EXPECT_TRUE(std::is_nothrow_copy_assignable<json::iterator>::value);
+    EXPECT_TRUE(std::is_nothrow_copy_assignable<json::const_iterator>::value);
+#endif
+}
+
+TEST(JsonIteratorConceptsTest, Destructible)
+{
+    EXPECT_TRUE(std::is_nothrow_destructible<json::iterator>::value);
+    EXPECT_TRUE(std::is_nothrow_destructible<json::const_iterator>::value);
+}
+
+TEST(JsonIteratorConceptsTest, Swappable)
+{
+    json j {1, 2, 3};
+    json::iterator it1 = j.begin();
+    json::iterator it2 = j.end();
+    std::swap(it1, it2);
+    EXPECT_EQ(it1, j.end());
+    EXPECT_EQ(it2, j.begin());
+}
+
+TEST(JsonIteratorConceptsTest, SwappableConst)
+{
+    json j {1, 2, 3};
+    json::const_iterator it1 = j.cbegin();
+    json::const_iterator it2 = j.cend();
+    std::swap(it1, it2);
+    EXPECT_EQ(it1, j.end());
+    EXPECT_EQ(it2, j.begin());
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-constructor1.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-constructor1.cpp
new file mode 100644
index 0000000..71c4678
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-constructor1.cpp
@@ -0,0 +1,1068 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include <array>
+#include <deque>
+#include <forward_list>
+#include <list>
+#include <map>
+#include <set>
+#include <unordered_map>
+#include <unordered_set>
+
+#include "unit-json.h"
+using wpi::json;
+using wpi::JsonTest;
+
+class JsonConstructTypeTest : public ::testing::TestWithParam<json::value_t> {};
+TEST_P(JsonConstructTypeTest, Case)
+{
+    auto t = GetParam();
+    json j(t);
+    EXPECT_EQ(j.type(), t);
+}
+
+static const json::value_t construct_type_cases[] = {
+    json::value_t::null,
+    json::value_t::discarded,
+    json::value_t::object,
+    json::value_t::array,
+    json::value_t::boolean,
+    json::value_t::string,
+    json::value_t::number_integer,
+    json::value_t::number_unsigned,
+    json::value_t::number_float,
+};
+
+INSTANTIATE_TEST_CASE_P(JsonConstructTypeTests, JsonConstructTypeTest,
+                        ::testing::ValuesIn(construct_type_cases), );
+
+
+TEST(JsonConstructNullTest, NoParameter)
+{
+    json j{};
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonConstructNullTest, Parameter)
+{
+    json j(nullptr);
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonConstructObjectExplicitTest, Empty)
+{
+    json::object_t o;
+    json j(o);
+    EXPECT_EQ(j.type(), json::value_t::object);
+}
+
+TEST(JsonConstructObjectExplicitTest, Filled)
+{
+    json::object_t o {{"a", json(1)}, {"b", json(1u)}, {"c", json(2.2)}, {"d", json(false)}, {"e", json("string")}, {"f", json()}};
+    json j(o);
+    EXPECT_EQ(j.type(), json::value_t::object);
+}
+
+class JsonConstructObjectImplicitTest : public ::testing::Test {
+ public:
+    JsonConstructObjectImplicitTest() : j_reference(o_reference) {}
+
+ protected:
+    json::object_t o_reference {{"a", json(1)}, {"b", json(1u)}, {"c", json(2.2)}, {"d", json(false)}, {"e", json("string")}, {"f", json()}};
+    json j_reference;
+};
+
+// std::map<std::string, json>
+TEST_F(JsonConstructObjectImplicitTest, StdMapStringJson)
+{
+    std::map<std::string, json> o {{"a", json(1)}, {"b", json(1u)}, {"c", json(2.2)}, {"d", json(false)}, {"e", json("string")}, {"f", json()}};
+    json j(o);
+    EXPECT_EQ(j.type(), json::value_t::object);
+    EXPECT_EQ(j, j_reference);
+}
+
+// std::pair<CompatibleString, T>
+TEST_F(JsonConstructObjectImplicitTest, StdPairStringT)
+{
+    std::pair<std::string, std::string> p{"first", "second"};
+    json j(p);
+
+    EXPECT_EQ(j.get<decltype(p)>(), p);
+
+    std::pair<std::string, int> p2{"first", 1};
+    // use char const*
+    json j2(std::make_pair("first", 1));
+
+    EXPECT_EQ(j2.get<decltype(p2)>(), p2);
+}
+
+// std::map<std::string, std::string>
+TEST_F(JsonConstructObjectImplicitTest, StdMapStringString)
+{
+    std::map<std::string, std::string> m;
+    m["a"] = "b";
+    m["c"] = "d";
+    m["e"] = "f";
+
+    json j(m);
+    EXPECT_EQ(j.get<decltype(m)>(), m);
+}
+
+// std::map<const char*, json>
+TEST_F(JsonConstructObjectImplicitTest, StdMapCharPointerJson)
+{
+    std::map<const char*, json> o {{"a", json(1)}, {"b", json(1u)}, {"c", json(2.2)}, {"d", json(false)}, {"e", json("string")}, {"f", json()}};
+    json j(o);
+    EXPECT_EQ(j.type(), json::value_t::object);
+    EXPECT_EQ(j, j_reference);
+}
+
+// std::multimap<std::string, json>
+TEST_F(JsonConstructObjectImplicitTest, StdMultiMapStringJson)
+{
+    std::multimap<std::string, json> o {{"a", json(1)}, {"b", json(1u)}, {"c", json(2.2)}, {"d", json(false)}, {"e", json("string")}, {"f", json()}};
+    json j(o);
+    EXPECT_EQ(j.type(), json::value_t::object);
+    EXPECT_EQ(j, j_reference);
+}
+
+// std::unordered_map<std::string, json>
+TEST_F(JsonConstructObjectImplicitTest, StdUnorderedMapStringJson)
+{
+    std::unordered_map<std::string, json> o {{"a", json(1)}, {"b", json(1u)}, {"c", json(2.2)}, {"d", json(false)}, {"e", json("string")}, {"f", json()}};
+    json j(o);
+    EXPECT_EQ(j.type(), json::value_t::object);
+    EXPECT_EQ(j, j_reference);
+}
+
+// std::unordered_multimap<std::string, json>
+TEST_F(JsonConstructObjectImplicitTest, StdUnorderedMultiMapStringJson)
+{
+    std::unordered_multimap<std::string, json> o {{"a", json(1)}, {"b", json(1u)}, {"c", json(2.2)}, {"d", json(false)}, {"e", json("string")}, {"f", json()}};
+    json j(o);
+    EXPECT_EQ(j.type(), json::value_t::object);
+    EXPECT_EQ(j, j_reference);
+}
+
+// associative container literal
+TEST_F(JsonConstructObjectImplicitTest, AssociativeContainerLiteral)
+{
+    json j({{"a", json(1)}, {"b", json(1u)}, {"c", json(2.2)}, {"d", json(false)}, {"e", json("string")}, {"f", json()}});
+    EXPECT_EQ(j.type(), json::value_t::object);
+    EXPECT_EQ(j, j_reference);
+}
+
+TEST(JsonConstructArrayExplicitTest, Empty)
+{
+    json::array_t a;
+    json j(a);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructArrayExplicitTest, Filled)
+{
+    json::array_t a {json(1), json(1u), json(2.2), json(false), json("string"), json()};
+    json j(a);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+template <typename T>
+class JsonConstructArrayTest : public ::testing::Test {
+ public:
+    JsonConstructArrayTest() : j_reference(a_reference) {}
+
+ protected:
+    json::array_t a_reference {json(1), json(1u), json(2.2), json(false), json("string"), json()};
+    json j_reference;
+};
+
+typedef ::testing::Types<std::list<json>, std::forward_list<json>,
+                         std::array<json, 6>, std::vector<json>,
+                         std::deque<json>>
+    JsonConstructArrayTestTypes;
+TYPED_TEST_CASE(JsonConstructArrayTest, JsonConstructArrayTestTypes);
+
+// clang warns on missing braces on the TypeParam initializer line below.
+// Suppress this warning.
+#if defined(__clang__)
+#pragma GCC diagnostic push
+#pragma GCC diagnostic ignored "-Wmissing-braces"
+#endif
+TYPED_TEST(JsonConstructArrayTest, Implicit)
+{
+    TypeParam a {json(1), json(1u), json(2.2), json(false), json("string"), json()};
+    json j(a);
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, this->j_reference);
+}
+#if defined(__clang__)
+#pragma GCC diagnostic pop
+#endif
+
+// std::set<json>
+TEST(JsonConstructArraySetTest, StdSet)
+{
+    std::set<json> a {json(1), json(1u), json(2.2), json(false), json("string"), json()};
+    json j(a);
+    EXPECT_EQ(j.type(), json::value_t::array);
+    // we cannot really check for equality here
+}
+
+// std::unordered_set<json>
+TEST(JsonConstructArraySetTest, StdUnorderedSet)
+{
+    std::unordered_set<json> a {json(1), json(1u), json(2.2), json(false), json("string"), json()};
+    json j(a);
+    EXPECT_EQ(j.type(), json::value_t::array);
+    // we cannot really check for equality here
+}
+
+// sequence container literal
+TEST(JsonConstructArrayContainerTest, Case)
+{
+    json::array_t a_reference {json(1), json(1u), json(2.2), json(false), json("string"), json()};
+    json j_reference(a_reference);
+
+    json j({json(1), json(1u), json(2.2), json(false), json("string"), json()});
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, j_reference);
+}
+
+TEST(JsonConstructStringExplicitTest, Empty)
+{
+    std::string s;
+    json j(s);
+    EXPECT_EQ(j.type(), json::value_t::string);
+}
+
+TEST(JsonConstructStringExplicitTest, Filled)
+{
+    std::string s {"Hello world"};
+    json j(s);
+    EXPECT_EQ(j.type(), json::value_t::string);
+}
+
+class JsonConstructStringTest : public ::testing::Test {
+ public:
+    JsonConstructStringTest() : j_reference(s_reference) {}
+
+ protected:
+    std::string s_reference {"Hello world"};
+    json j_reference;
+};
+
+// std::string
+TEST_F(JsonConstructStringTest, StdString)
+{
+    std::string s {"Hello world"};
+    json j(s);
+    EXPECT_EQ(j.type(), json::value_t::string);
+    EXPECT_EQ(j, j_reference);
+}
+
+// char[]
+TEST_F(JsonConstructStringTest, CharArray)
+{
+    char s[] {"Hello world"};
+    json j(s);
+    EXPECT_EQ(j.type(), json::value_t::string);
+    EXPECT_EQ(j, j_reference);
+}
+
+// const char*
+TEST_F(JsonConstructStringTest, ConstCharPointer)
+{
+    const char* s {"Hello world"};
+    json j(s);
+    EXPECT_EQ(j.type(), json::value_t::string);
+    EXPECT_EQ(j, j_reference);
+}
+
+// string literal
+TEST_F(JsonConstructStringTest, StringLiteral)
+{
+    json j("Hello world");
+    EXPECT_EQ(j.type(), json::value_t::string);
+    EXPECT_EQ(j, j_reference);
+}
+
+TEST(JsonConstructBooleanExplicitTest, Empty)
+{
+    bool b{};
+    json j(b);
+    EXPECT_EQ(j.type(), json::value_t::boolean);
+}
+
+TEST(JsonConstructBooleanExplicitTest, True)
+{
+    json j(true);
+    EXPECT_EQ(j.type(), json::value_t::boolean);
+}
+
+TEST(JsonConstructBooleanExplicitTest, False)
+{
+    json j(false);
+    EXPECT_EQ(j.type(), json::value_t::boolean);
+}
+
+TEST(JsonConstructIntegerExplicitTest, Uninitialized)
+{
+    int64_t n{};
+    json j(n);
+    EXPECT_EQ(j.type(), json::value_t::number_integer);
+}
+
+TEST(JsonConstructIntegerExplicitTest, Initialized)
+{
+    int64_t n(42);
+    json j(n);
+    EXPECT_EQ(j.type(), json::value_t::number_integer);
+}
+
+template <typename T>
+class JsonConstructIntegerTest : public ::testing::Test {
+ public:
+    JsonConstructIntegerTest()
+        : j_reference(n_reference), j_unsigned_reference(n_unsigned_reference) {}
+
+ protected:
+    int64_t n_reference = 42;
+    json j_reference;
+    uint64_t n_unsigned_reference = 42u;
+    json j_unsigned_reference;
+};
+
+typedef ::testing::Types<
+      short
+    , unsigned short
+    , int
+    , unsigned int
+    , long
+    , unsigned long
+    , long long
+    , unsigned long long
+    , int8_t
+    , int16_t
+    , int32_t
+    , int64_t
+#if 0
+    , int8_fast_t
+    , int16_fast_t
+    , int32_fast_t
+    , int64_fast_t
+    , int8_least_t
+    , int16_least_t
+    , int32_least_t
+    , int64_least_t
+#endif
+    , uint8_t
+    , uint16_t
+    , uint32_t
+    , uint64_t
+#if 0
+    , uint8_fast_t
+    , uint16_fast_t
+    , uint32_fast_t
+    , uint64_fast_t
+    , uint8_least_t
+    , uint16_least_t
+    , uint32_least_t
+    , uint64_least_t
+#endif
+    > JsonConstructIntegerTestTypes;
+
+TYPED_TEST_CASE(JsonConstructIntegerTest, JsonConstructIntegerTestTypes);
+
+TYPED_TEST(JsonConstructIntegerTest, Implicit)
+{
+    TypeParam n = 42;
+    json j(n);
+    if (std::is_unsigned<TypeParam>::value)
+    {
+        EXPECT_EQ(j.type(), json::value_t::number_unsigned);
+        EXPECT_EQ(j, this->j_unsigned_reference);
+    }
+    else
+    {
+        EXPECT_EQ(j.type(), json::value_t::number_integer);
+        EXPECT_EQ(j, this->j_reference);
+    }
+}
+
+class JsonConstructIntegerLiteralTest : public ::testing::Test {
+ public:
+    JsonConstructIntegerLiteralTest()
+        : j_reference(n_reference), j_unsigned_reference(n_unsigned_reference) {}
+
+ protected:
+    int64_t n_reference = 42;
+    json j_reference;
+    uint64_t n_unsigned_reference = 42u;
+    json j_unsigned_reference;
+};
+
+TEST_F(JsonConstructIntegerLiteralTest, None)
+{
+    json j(42);
+    EXPECT_EQ(j.type(), json::value_t::number_integer);
+    EXPECT_EQ(j, j_reference);
+}
+
+TEST_F(JsonConstructIntegerLiteralTest, U)
+{
+    json j(42u);
+    EXPECT_EQ(j.type(), json::value_t::number_unsigned);
+    EXPECT_EQ(j, j_unsigned_reference);
+}
+
+TEST_F(JsonConstructIntegerLiteralTest, L)
+{
+    json j(42l);
+    EXPECT_EQ(j.type(), json::value_t::number_integer);
+    EXPECT_EQ(j, j_reference);
+}
+
+TEST_F(JsonConstructIntegerLiteralTest, UL)
+{
+    json j(42ul);
+    EXPECT_EQ(j.type(), json::value_t::number_unsigned);
+    EXPECT_EQ(j, j_unsigned_reference);
+}
+
+TEST_F(JsonConstructIntegerLiteralTest, LL)
+{
+    json j(42ll);
+    EXPECT_EQ(j.type(), json::value_t::number_integer);
+    EXPECT_EQ(j, j_reference);
+}
+
+TEST_F(JsonConstructIntegerLiteralTest, ULL)
+{
+    json j(42ull);
+    EXPECT_EQ(j.type(), json::value_t::number_unsigned);
+    EXPECT_EQ(j, j_unsigned_reference);
+}
+
+TEST(JsonConstructFloatExplicitTest, Uninitialized)
+{
+    double n{};
+    json j(n);
+    EXPECT_EQ(j.type(), json::value_t::number_float);
+}
+
+TEST(JsonConstructFloatExplicitTest, Initialized)
+{
+    double n(42.23);
+    json j(n);
+    EXPECT_EQ(j.type(), json::value_t::number_float);
+}
+
+TEST(JsonConstructFloatExplicitTest, Infinity)
+{
+    // infinity is stored properly, but serialized to null
+    double n(std::numeric_limits<double>::infinity());
+    json j(n);
+    EXPECT_EQ(j.type(), json::value_t::number_float);
+
+    // check round trip of infinity
+    double d = j;
+    EXPECT_EQ(d, n);
+
+    // check that inf is serialized to null
+    EXPECT_EQ(j.dump(), "null");
+}
+
+template <typename T>
+class JsonConstructFloatTest : public ::testing::Test {
+ public:
+    JsonConstructFloatTest() : j_reference(n_reference) {}
+
+ protected:
+    double n_reference {42.23};
+    json j_reference;
+};
+
+typedef ::testing::Types<float, double
+#if 0
+                         , long double
+#endif
+                         >
+    JsonConstructFloatTestTypes;
+
+TYPED_TEST_CASE(JsonConstructFloatTest, JsonConstructFloatTestTypes);
+
+TYPED_TEST(JsonConstructFloatTest, Implicit)
+{
+    TypeParam n = 42.23f;
+    json j(n);
+    EXPECT_EQ(j.type(), json::value_t::number_float);
+    EXPECT_LT(std::fabs(JsonTest::GetValue(j).number_float -
+                        JsonTest::GetValue(this->j_reference).number_float),
+              0.001);
+}
+
+class JsonConstructFloatLiteralTest : public ::testing::Test {
+ public:
+    JsonConstructFloatLiteralTest() : j_reference(n_reference) {}
+
+ protected:
+    double n_reference {42.23};
+    json j_reference;
+};
+
+TEST_F(JsonConstructFloatLiteralTest, None)
+{
+    json j(42.23);
+    EXPECT_EQ(j.type(), json::value_t::number_float);
+    EXPECT_LT(std::fabs(JsonTest::GetValue(j).number_float -
+                        JsonTest::GetValue(this->j_reference).number_float),
+              0.001);
+}
+
+TEST_F(JsonConstructFloatLiteralTest, F)
+{
+    json j(42.23f);
+    EXPECT_EQ(j.type(), json::value_t::number_float);
+    EXPECT_LT(std::fabs(JsonTest::GetValue(j).number_float -
+                        JsonTest::GetValue(this->j_reference).number_float),
+              0.001);
+}
+
+#if 0
+TEST_F(JsonConstructFloatLiteralTest, L)
+{
+    json j(42.23l);
+    EXPECT_EQ(j.type(), json::value_t::number_float);
+    EXPECT_LT(std::fabs(JsonTest::GetValue(j).number_float -
+                        JsonTest::GetValue(this->j_reference).number_float),
+              0.001);
+}
+#endif
+
+TEST(JsonConstructInitializerEmptyTest, Explicit)
+{
+    json j(json::initializer_list_t{});
+    EXPECT_EQ(j.type(), json::value_t::object);
+}
+
+TEST(JsonConstructInitializerEmptyTest, Implicit)
+{
+    json j {};
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonConstructInitializerOneTest, ExplicitArray)
+{
+    std::initializer_list<json> l = {json(json::array_t())};
+    json j(l);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ImplicitArray)
+{
+    json j {json::array_t()};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ExplicitObject)
+{
+    std::initializer_list<json> l = {json(json::object_t())};
+    json j(l);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ImplicitObject)
+{
+    json j {json::object_t()};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ExplicitString)
+{
+    std::initializer_list<json> l = {json("Hello world")};
+    json j(l);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ImplicitString)
+{
+    json j {"Hello world"};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ExplicitBoolean)
+{
+    std::initializer_list<json> l = {json(true)};
+    json j(l);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ImplicitBoolean)
+{
+    json j {true};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ExplicitInteger)
+{
+    std::initializer_list<json> l = {json(1)};
+    json j(l);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ImplicitInteger)
+{
+    json j {1};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ExplicitUnsigned)
+{
+    std::initializer_list<json> l = {json(1u)};
+    json j(l);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ImplicitUnsigned)
+{
+    json j {1u};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ExplicitFloat)
+{
+    std::initializer_list<json> l = {json(42.23)};
+    json j(l);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerOneTest, ImplicitFloat)
+{
+    json j {42.23};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerManyTest, Explicit)
+{
+    std::initializer_list<json> l = {1, 1u, 42.23, true, nullptr, json::object_t(), json::array_t()};
+    json j(l);
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerManyTest, Implicit)
+{
+    json j {1, 1u, 42.23, true, nullptr, json::object_t(), json::array_t()};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerImplicitTest, Object)
+{
+    json j { {"one", 1}, {"two", 1u}, {"three", 2.2}, {"four", false} };
+    EXPECT_EQ(j.type(), json::value_t::object);
+}
+
+TEST(JsonConstructInitializerImplicitTest, Array)
+{
+    json j { {"one", 1}, {"two", 1u}, {"three", 2.2}, {"four", false}, 13 };
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerExplicitTest, EmptyObject)
+{
+    json j = json::object();
+    EXPECT_EQ(j.type(), json::value_t::object);
+}
+
+TEST(JsonConstructInitializerExplicitTest, Object)
+{
+    json j = json::object({ {"one", 1}, {"two", 1u}, {"three", 2.2}, {"four", false} });
+    EXPECT_EQ(j.type(), json::value_t::object);
+}
+
+TEST(JsonConstructInitializerExplicitTest, ObjectError)
+{
+    EXPECT_THROW_MSG(json::object({ {"one", 1}, {"two", 1u}, {"three", 2.2}, {"four", false}, 13 }),
+    json::type_error,
+    "[json.exception.type_error.301] cannot create object from initializer list");
+}
+
+// std::pair<CompatibleString, T> with error
+TEST(JsonConstructInitializerPairErrorTest, WrongFieldNumber)
+{
+    json j{{"too", "much"}, {"string", "fields"}};
+    EXPECT_THROW_MSG((j.get<std::pair<std::string, std::string>>()), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with object");
+}
+
+TEST(JsonConstructInitializerPairErrorTest, WrongJsonType)
+{
+    json j(42);
+    EXPECT_THROW_MSG((j.get<std::pair<std::string, std::string>>()), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+}
+
+TEST(JsonConstructInitializerTest, EmptyArray)
+{
+    json j = json::array();
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConstructInitializerTest, Array)
+{
+    json j = json::array({ {"one", 1}, {"two", 1u}, {"three", 2.2}, {"four", false} });
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+// create an array of n copies of a given value
+TEST(JsonConstructArrayCopyTest, Case)
+{
+    json v = {1, "foo", 34.23, {1, 2, 3}, {{"A", 1}, {"B", 2u}}};
+    json arr(3, v);
+    EXPECT_EQ(arr.size(), 3u);
+    for (auto& x : arr)
+    {
+        EXPECT_EQ(x, v);
+    }
+}
+
+// create a JSON container from an iterator range
+TEST(JsonConstructIteratorTest, ObjectBeginEnd)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+#if 0
+    json j_new(jobject.begin(), jobject.end());
+    EXPECT_EQ(j_new, jobject);
+#else
+    EXPECT_THROW(json(jobject.begin(), jobject.end()), json::invalid_iterator);
+#endif
+}
+
+TEST(JsonConstructIteratorTest, ObjectBeginEndConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+#if 0
+    json j_new(jobject.cbegin(), jobject.cend());
+    EXPECT_EQ(j_new, jobject);
+#else
+    EXPECT_THROW(json(jobject.cbegin(), jobject.cend()), json::invalid_iterator);
+#endif
+}
+
+TEST(JsonConstructIteratorTest, ObjectBeginBegin)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+#if 0
+    json j_new(jobject.begin(), jobject.begin());
+    EXPECT_EQ(j_new, json::object());
+#else
+    EXPECT_THROW(json(jobject.begin(), jobject.end()), json::invalid_iterator);
+#endif
+}
+
+TEST(JsonConstructIteratorTest, ObjectBeginBeginConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+#if 0
+    json j_new(jobject.cbegin(), jobject.cbegin());
+    EXPECT_EQ(j_new, json::object());
+#else
+    EXPECT_THROW(json(jobject.cbegin(), jobject.cend()), json::invalid_iterator);
+#endif
+}
+#if 0
+TEST(JsonConstructIteratorTest, ObjectSubrange)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}, {"d", false}, {"e", true}};
+    json j_new(jobject.find("b"), jobject.find("e"));
+    EXPECT_EQ(j_new, json({{"b", 1}, {"c", 17u}, {"d", false}}));
+}
+#endif
+TEST(JsonConstructIteratorTest, ObjectIncompatibleIterators)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}, {"d", false}, {"e", true}};
+    json jobject2 = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+    EXPECT_THROW_MSG(json(jobject.begin(), jobject2.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.201] iterators are not compatible");
+    EXPECT_THROW_MSG(json(jobject2.begin(), jobject.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.201] iterators are not compatible");
+}
+
+TEST(JsonConstructIteratorTest, ObjectIncompatibleIteratorsConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}, {"d", false}, {"e", true}};
+    json jobject2 = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+    EXPECT_THROW_MSG(json(jobject.cbegin(), jobject2.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.201] iterators are not compatible");
+    EXPECT_THROW_MSG(json(jobject2.cbegin(), jobject.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.201] iterators are not compatible");
+}
+
+TEST(JsonConstructIteratorTest, ArrayBeginEnd)
+{
+    json jarray = {1, 2, 3, 4, 5};
+    json j_new(jarray.begin(), jarray.end());
+    EXPECT_EQ(j_new, jarray);
+}
+
+TEST(JsonConstructIteratorTest, ArrayBeginEndConst)
+{
+    json jarray = {1, 2, 3, 4, 5};
+    json j_new(jarray.cbegin(), jarray.cend());
+    EXPECT_EQ(j_new, jarray);
+}
+
+TEST(JsonConstructIteratorTest, ArrayBeginBegin)
+{
+    json jarray = {1, 2, 3, 4, 5};
+    json j_new(jarray.begin(), jarray.begin());
+    EXPECT_EQ(j_new, json::array());
+}
+
+TEST(JsonConstructIteratorTest, ArrayBeginBeginConst)
+{
+    json jarray = {1, 2, 3, 4, 5};
+    json j_new(jarray.cbegin(), jarray.cbegin());
+    EXPECT_EQ(j_new, json::array());
+}
+
+TEST(JsonConstructIteratorTest, ArraySubrange)
+{
+    json jarray = {1, 2, 3, 4, 5};
+    json j_new(jarray.begin() + 1, jarray.begin() + 3);
+    EXPECT_EQ(j_new, json({2, 3}));
+}
+
+TEST(JsonConstructIteratorTest, ArraySubrangeConst)
+{
+    json jarray = {1, 2, 3, 4, 5};
+    json j_new(jarray.cbegin() + 1, jarray.cbegin() + 3);
+    EXPECT_EQ(j_new, json({2, 3}));
+}
+
+TEST(JsonConstructIteratorTest, ArrayIncompatibleIterators)
+{
+    json jarray = {1, 2, 3, 4};
+    json jarray2 = {2, 3, 4, 5};
+    EXPECT_THROW_MSG(json(jarray.begin(), jarray2.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.201] iterators are not compatible");
+    EXPECT_THROW_MSG(json(jarray2.begin(), jarray.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.201] iterators are not compatible");
+}
+
+TEST(JsonConstructIteratorTest, ArrayIncompatibleIteratorsConst)
+{
+    json jarray = {1, 2, 3, 4};
+    json jarray2 = {2, 3, 4, 5};
+    EXPECT_THROW_MSG(json(jarray.cbegin(), jarray2.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.201] iterators are not compatible");
+    EXPECT_THROW_MSG(json(jarray2.cbegin(), jarray.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.201] iterators are not compatible");
+}
+
+TEST(JsonConstructTwoValidIteratorTest, Null)
+{
+    json j;
+    EXPECT_THROW_MSG(json(j.begin(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.206] cannot construct with iterators from null");
+}
+
+TEST(JsonConstructTwoValidIteratorTest, NullConst)
+{
+    json j;
+    EXPECT_THROW_MSG(json(j.cbegin(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.206] cannot construct with iterators from null");
+}
+
+TEST(JsonConstructTwoValidIteratorTest, String)
+{
+    json j = "foo";
+    json j_new(j.begin(), j.end());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, StringConst)
+{
+    json j = "bar";
+    json j_new(j.cbegin(), j.cend());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, Boolean)
+{
+    json j = false;
+    json j_new(j.begin(), j.end());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, BooleanConst)
+{
+    json j = true;
+    json j_new(j.cbegin(), j.cend());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, Integer)
+{
+    json j = 17;
+    json j_new(j.begin(), j.end());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, IntegerConst)
+{
+    json j = 17;
+    json j_new(j.cbegin(), j.cend());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, Unsigned)
+{
+    json j = 17u;
+    json j_new(j.begin(), j.end());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, UnsignedConst)
+{
+    json j = 17u;
+    json j_new(j.cbegin(), j.cend());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, Float)
+{
+    json j = 23.42;
+    json j_new(j.begin(), j.end());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoValidIteratorTest, FloatConst)
+{
+    json j = 23.42;
+    json j_new(j.cbegin(), j.cend());
+    EXPECT_EQ(j, j_new);
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, String)
+{
+    json j = "foo";
+    EXPECT_THROW_MSG(json(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, StringConst)
+{
+    json j = "bar";
+    EXPECT_THROW_MSG(json(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, Boolean)
+{
+    json j = false;
+    EXPECT_THROW_MSG(json(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, BooleanConst)
+{
+    json j = true;
+    EXPECT_THROW_MSG(json(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, Integer)
+{
+    json j = 17;
+    EXPECT_THROW_MSG(json(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, IntegerConst)
+{
+    json j = 17;
+    EXPECT_THROW_MSG(json(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, Unsigned)
+{
+    json j = 17u;
+    EXPECT_THROW_MSG(json(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, UnsignedConst)
+{
+    json j = 17u;
+    EXPECT_THROW_MSG(json(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, Float)
+{
+    json j = 23.42;
+    EXPECT_THROW_MSG(json(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonConstructTwoInvalidIteratorTest, FloatConst)
+{
+    json j = 23.42;
+    EXPECT_THROW_MSG(json(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(json(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-constructor2.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-constructor2.cpp
new file mode 100644
index 0000000..39f1301
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-constructor2.cpp
@@ -0,0 +1,185 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+TEST(JsonCopyConstructorTest, Object)
+{
+    json j {{"foo", 1}, {"bar", false}};
+    json k(j);
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyConstructorTest, Array)
+{
+    json j {"foo", 1, 42.23, false};
+    json k(j);
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyConstructorTest, Null)
+{
+    json j(nullptr);
+    json k(j);
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyConstructorTest, Boolean)
+{
+    json j(true);
+    json k(j);
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyConstructorTest, String)
+{
+    json j("Hello world");
+    json k(j);
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyConstructorTest, Integer)
+{
+    json j(42);
+    json k(j);
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyConstructorTest, Unsigned)
+{
+    json j(42u);
+    json k(j);
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyConstructorTest, Float)
+{
+    json j(42.23);
+    json k(j);
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonMoveConstructorTest, Case)
+{
+    json j {{"foo", "bar"}, {"baz", {1, 2, 3, 4}}, {"a", 42u}, {"b", 42.23}, {"c", nullptr}};
+    EXPECT_EQ(j.type(), json::value_t::object);
+    json k(std::move(j));
+    EXPECT_EQ(k.type(), json::value_t::object);
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonCopyAssignmentTest, Object)
+{
+    json j {{"foo", 1}, {"bar", false}};
+    json k;
+    k = j;
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyAssignmentTest, Array)
+{
+    json j {"foo", 1, 42.23, false};
+    json k;
+    k = j;
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyAssignmentTest, Null)
+{
+    json j(nullptr);
+    json k;
+    k = j;
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyAssignmentTest, Boolean)
+{
+    json j(true);
+    json k;
+    k = j;
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyAssignmentTest, String)
+{
+    json j("Hello world");
+    json k;
+    k = j;
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyAssignmentTest, Integer)
+{
+    json j(42);
+    json k;
+    k = j;
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyAssignmentTest, Unsigned)
+{
+    json j(42u);
+    json k;
+    k = j;
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonCopyAssignmentTest, Float)
+{
+    json j(42.23);
+    json k;
+    k = j;
+    EXPECT_EQ(j, k);
+}
+
+TEST(JsonDestructorTest, Object)
+{
+    auto j = new json {{"foo", 1}, {"bar", false}};
+    delete j;
+}
+
+TEST(JsonDestructorTest, Array)
+{
+    auto j = new json {"foo", 1, 1u, false, 23.42};
+    delete j;
+}
+
+TEST(JsonDestructorTest, String)
+{
+    auto j = new json("Hello world");
+    delete j;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-conversions.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-conversions.cpp
new file mode 100644
index 0000000..e4981f2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-conversions.cpp
@@ -0,0 +1,560 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+using wpi::JsonTest;
+
+#include <deque>
+//#include <forward_list>
+#include <list>
+#include <map>
+#include <unordered_map>
+#include <unordered_set>
+
+template <typename T>
+class JsonGetObjectTest : public ::testing::Test {
+ public:
+    JsonGetObjectTest() : j(o_reference) {}
+
+ protected:
+    json::object_t o_reference = {{"object", json::object()}, {"array", {1, 2, 3, 4}}, {"number", 42}, {"boolean", false}, {"null", nullptr}, {"string", "Hello world"} };
+    json j;
+};
+
+typedef ::testing::Types<
+      json::object_t
+    , std::map<std::string, json>
+    , std::multimap<std::string, json>
+    , std::unordered_map<std::string, json>
+    , std::unordered_multimap<std::string, json>
+    > JsonGetObjectTestTypes;
+TYPED_TEST_CASE(JsonGetObjectTest, JsonGetObjectTestTypes);
+
+TYPED_TEST(JsonGetObjectTest, Explicit)
+{
+    TypeParam o = (this->j).template get<TypeParam>();
+    EXPECT_EQ(json(o), this->j);
+}
+
+TYPED_TEST(JsonGetObjectTest, Implicit)
+{
+    TypeParam o = this->j;
+    EXPECT_EQ(json(o), this->j);
+}
+
+// exception in case of a non-object type
+TEST(JsonGetObjectExceptionTest, TypeError)
+{
+    EXPECT_THROW_MSG(json(json::value_t::null).get<json::object_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be object, but is null");
+    EXPECT_THROW_MSG(json(json::value_t::array).get<json::object_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be object, but is array");
+    EXPECT_THROW_MSG(json(json::value_t::string).get<json::object_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be object, but is string");
+    EXPECT_THROW_MSG(json(json::value_t::boolean).get<json::object_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be object, but is boolean");
+    EXPECT_THROW_MSG(json(json::value_t::number_integer).get<json::object_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be object, but is number");
+    EXPECT_THROW_MSG(json(json::value_t::number_unsigned).get<json::object_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be object, but is number");
+    EXPECT_THROW_MSG(json(json::value_t::number_float).get<json::object_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be object, but is number");
+}
+
+template <typename T>
+class JsonGetArrayTest : public ::testing::Test {
+ public:
+    JsonGetArrayTest() : j(a_reference) {}
+
+ protected:
+    json::array_t a_reference {json(1), json(1u), json(2.2), json(false), json("string"), json()};
+    json j;
+};
+
+typedef ::testing::Types<json::array_t, std::list<json>,
+                         /*std::forward_list<json>,*/ std::vector<json>,
+                         std::deque<json>>
+    JsonGetArrayTestTypes;
+TYPED_TEST_CASE(JsonGetArrayTest, JsonGetArrayTestTypes);
+
+TYPED_TEST(JsonGetArrayTest, Explicit)
+{
+    TypeParam a = (this->j).template get<TypeParam>();
+    EXPECT_EQ(json(a), this->j);
+}
+
+TYPED_TEST(JsonGetArrayTest, Implicit)
+{
+    TypeParam a = this->j;
+    EXPECT_EQ(json(a), this->j);
+}
+
+#if !defined(JSON_NOEXCEPTION)
+// reserve is called on containers that supports it
+TEST(JsonGetArrayAdditionalTest, ExplicitStdVectorReserve)
+{
+    json::array_t a_reference {json(1), json(1u), json(2.2), json(false), json("string"), json()};
+    json j(a_reference);
+
+    // making the call to from_json throw in order to check capacity
+    std::vector<float> v;
+    EXPECT_THROW(wpi::from_json(j, v), json::type_error);
+    EXPECT_EQ(v.capacity(), j.size());
+
+    // make sure all values are properly copied
+    std::vector<int> v2 = json({1, 2, 3, 4, 5, 6, 7, 8, 9, 10});
+    EXPECT_EQ(v2.size(), 10u);
+}
+#endif
+
+// built-in arrays
+TEST(JsonGetArrayAdditionalTest, ExplicitBuiltinArray)
+{
+    const char str[] = "a string";
+    const int nbs[] = {0, 1, 2};
+
+    json j2 = nbs;
+    json j3 = str;
+
+    auto v = j2.get<std::vector<int>>();
+    auto s = j3.get<std::string>();
+    EXPECT_TRUE(std::equal(v.begin(), v.end(), std::begin(nbs)));
+    EXPECT_EQ(s, str);
+}
+#if 0
+TEST(JsonGetArrayExceptionTest, ForwardList)
+{
+    EXPECT_THROW_MSG(json(json::value_t::null).get<std::forward_list<json>>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is null");
+}
+#endif
+TEST(JsonGetArrayExceptionTest, StdVector)
+{
+    EXPECT_THROW_MSG(json(json::value_t::null).get<std::vector<json>>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is null");
+}
+
+// exception in case of a non-array type
+TEST(JsonGetArrayExceptionTest, TypeError)
+{
+    EXPECT_THROW_MSG(json(json::value_t::object).get<std::vector<int>>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is object");
+    EXPECT_THROW_MSG(json(json::value_t::null).get<json::array_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is null");
+    EXPECT_THROW_MSG(json(json::value_t::object).get<json::array_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is object");
+    EXPECT_THROW_MSG(json(json::value_t::string).get<json::array_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is string");
+    EXPECT_THROW_MSG(json(json::value_t::boolean).get<json::array_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is boolean");
+    EXPECT_THROW_MSG(json(json::value_t::number_integer).get<json::array_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is number");
+    EXPECT_THROW_MSG(json(json::value_t::number_unsigned).get<json::array_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is number");
+    EXPECT_THROW_MSG(json(json::value_t::number_float).get<json::array_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is number");
+}
+
+template <typename T>
+class JsonGetStringTest : public ::testing::Test {
+ public:
+    JsonGetStringTest() : j(s_reference) {}
+
+ protected:
+    std::string s_reference {"Hello world"};
+    json j;
+};
+
+typedef ::testing::Types<std::string, std::string> JsonGetStringTestTypes;
+TYPED_TEST_CASE(JsonGetStringTest, JsonGetStringTestTypes);
+
+TYPED_TEST(JsonGetStringTest, Explicit)
+{
+    TypeParam s = (this->j).template get<TypeParam>();
+    EXPECT_EQ(json(s), this->j);
+}
+
+TYPED_TEST(JsonGetStringTest, Implicit)
+{
+    TypeParam s = this->j;
+    EXPECT_EQ(json(s), this->j);
+}
+
+// exception in case of a non-string type
+TEST(JsonGetStringExceptionTest, TypeError)
+{
+    EXPECT_THROW_MSG(json(json::value_t::null).get<std::string>(), json::type_error,
+                     "[json.exception.type_error.302] type must be string, but is null");
+    EXPECT_THROW_MSG(json(json::value_t::object).get<std::string>(), json::type_error,
+                     "[json.exception.type_error.302] type must be string, but is object");
+    EXPECT_THROW_MSG(json(json::value_t::array).get<std::string>(), json::type_error,
+                     "[json.exception.type_error.302] type must be string, but is array");
+    EXPECT_THROW_MSG(json(json::value_t::boolean).get<std::string>(), json::type_error,
+                     "[json.exception.type_error.302] type must be string, but is boolean");
+    EXPECT_THROW_MSG(json(json::value_t::number_integer).get<std::string>(), json::type_error,
+                     "[json.exception.type_error.302] type must be string, but is number");
+    EXPECT_THROW_MSG(json(json::value_t::number_unsigned).get<std::string>(), json::type_error,
+                     "[json.exception.type_error.302] type must be string, but is number");
+    EXPECT_THROW_MSG(json(json::value_t::number_float).get<std::string>(), json::type_error,
+                     "[json.exception.type_error.302] type must be string, but is number");
+}
+
+template <typename T>
+class JsonGetBooleanTest : public ::testing::Test {
+ public:
+    JsonGetBooleanTest() : j(b_reference) {}
+
+ protected:
+    bool b_reference {true};
+    json j;
+};
+
+typedef ::testing::Types<bool, bool> JsonGetBooleanTestTypes;
+TYPED_TEST_CASE(JsonGetBooleanTest, JsonGetBooleanTestTypes);
+
+TYPED_TEST(JsonGetBooleanTest, Explicit)
+{
+    TypeParam b = (this->j).template get<TypeParam>();
+    EXPECT_EQ(json(b), this->j);
+}
+
+TYPED_TEST(JsonGetBooleanTest, Implicit)
+{
+    TypeParam b = this->j;
+    EXPECT_EQ(json(b), this->j);
+}
+
+// exception in case of a non-string type
+TEST(JsonGetBooleanExceptionTest, TypeError)
+{
+    EXPECT_THROW_MSG(json(json::value_t::null).get<bool>(), json::type_error,
+                     "[json.exception.type_error.302] type must be boolean, but is null");
+    EXPECT_THROW_MSG(json(json::value_t::object).get<bool>(), json::type_error,
+                     "[json.exception.type_error.302] type must be boolean, but is object");
+    EXPECT_THROW_MSG(json(json::value_t::array).get<bool>(), json::type_error,
+                     "[json.exception.type_error.302] type must be boolean, but is array");
+    EXPECT_THROW_MSG(json(json::value_t::string).get<bool>(), json::type_error,
+                     "[json.exception.type_error.302] type must be boolean, but is string");
+    EXPECT_THROW_MSG(json(json::value_t::number_integer).get<bool>(), json::type_error,
+                     "[json.exception.type_error.302] type must be boolean, but is number");
+    EXPECT_THROW_MSG(json(json::value_t::number_unsigned).get<bool>(), json::type_error,
+                     "[json.exception.type_error.302] type must be boolean, but is number");
+    EXPECT_THROW_MSG(json(json::value_t::number_float).get<bool>(), json::type_error,
+                     "[json.exception.type_error.302] type must be boolean, but is number");
+}
+
+template <typename T>
+class JsonGetIntegerTest : public ::testing::Test {
+ public:
+    JsonGetIntegerTest() : j(n_reference), j_unsigned(n_unsigned_reference) {}
+
+ protected:
+    int64_t n_reference {42};
+    json j;
+    uint64_t n_unsigned_reference {42u};
+    json j_unsigned;
+};
+
+typedef ::testing::Types<
+      short
+    , unsigned short
+    , int
+    , unsigned int
+    , long
+    , unsigned long
+    , long long
+    , unsigned long long
+    , int8_t
+    , int16_t
+    , int32_t
+    , int64_t
+#if 0
+    , int8_fast_t
+    , int16_fast_t
+    , int32_fast_t
+    , int64_fast_t
+    , int8_least_t
+    , int16_least_t
+    , int32_least_t
+    , int64_least_t
+#endif
+    , uint8_t
+    , uint16_t
+    , uint32_t
+    , uint64_t
+#if 0
+    , uint8_fast_t
+    , uint16_fast_t
+    , uint32_fast_t
+    , uint64_fast_t
+    , uint8_least_t
+    , uint16_least_t
+    , uint32_least_t
+    , uint64_least_t
+#endif
+    > JsonGetIntegerTestTypes;
+
+TYPED_TEST_CASE(JsonGetIntegerTest, JsonGetIntegerTestTypes);
+
+TYPED_TEST(JsonGetIntegerTest, Explicit)
+{
+    TypeParam n = (this->j).template get<TypeParam>();
+    EXPECT_EQ(json(n), this->j);
+}
+
+TYPED_TEST(JsonGetIntegerTest, Implicit)
+{
+    if (std::is_unsigned<TypeParam>::value)
+    {
+        TypeParam n = this->j_unsigned;
+        EXPECT_EQ(json(n), this->j_unsigned);
+    }
+    else
+    {
+        TypeParam n = this->j;
+        EXPECT_EQ(json(n), this->j);
+    }
+}
+
+// exception in case of a non-number type
+TEST(JsonGetIntegerExceptionTest, TypeError)
+{
+    EXPECT_THROW_MSG(json(json::value_t::null).get<int64_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is null");
+    EXPECT_THROW_MSG(json(json::value_t::object).get<int64_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is object");
+    EXPECT_THROW_MSG(json(json::value_t::array).get<int64_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is array");
+    EXPECT_THROW_MSG(json(json::value_t::string).get<int64_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is string");
+    EXPECT_THROW_MSG(json(json::value_t::boolean).get<int64_t>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is boolean");
+
+    EXPECT_NO_THROW(json(json::value_t::number_float).get<int64_t>());
+    EXPECT_NO_THROW(json(json::value_t::number_float).get<uint64_t>());
+}
+
+template <typename T>
+class JsonGetFloatTest : public ::testing::Test {
+ public:
+    JsonGetFloatTest() : j(n_reference) {}
+
+ protected:
+    double n_reference {42.23};
+    json j;
+};
+
+typedef ::testing::Types<double, float, double>
+    JsonGetFloatTestTypes;
+
+TYPED_TEST_CASE(JsonGetFloatTest, JsonGetFloatTestTypes);
+
+TYPED_TEST(JsonGetFloatTest, Explicit)
+{
+    TypeParam n = (this->j).template get<TypeParam>();
+    EXPECT_LT(std::fabs(JsonTest::GetValue(json(n)).number_float -
+                        JsonTest::GetValue(this->j).number_float), 0.001);
+}
+
+TYPED_TEST(JsonGetFloatTest, Implicit)
+{
+    TypeParam n = this->j;
+    EXPECT_LT(std::fabs(JsonTest::GetValue(json(n)).number_float -
+                        JsonTest::GetValue(this->j).number_float), 0.001);
+}
+
+// exception in case of a non-string type
+TEST(JsonGetFloatExceptionTest, TypeError)
+{
+    EXPECT_THROW_MSG(json(json::value_t::null).get<double>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is null");
+    EXPECT_THROW_MSG(json(json::value_t::object).get<double>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is object");
+    EXPECT_THROW_MSG(json(json::value_t::array).get<double>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is array");
+    EXPECT_THROW_MSG(json(json::value_t::string).get<double>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is string");
+    EXPECT_THROW_MSG(json(json::value_t::boolean).get<double>(), json::type_error,
+                     "[json.exception.type_error.302] type must be number, but is boolean");
+
+    EXPECT_NO_THROW(json(json::value_t::number_integer).get<double>());
+    EXPECT_NO_THROW(json(json::value_t::number_unsigned).get<double>());
+}
+
+TEST(JsonGetEnumTest, Case)
+{
+    enum c_enum { value_1, value_2 };
+    enum class cpp_enum { value_1, value_2 };
+
+    EXPECT_EQ(json(value_1).get<c_enum>(), value_1);
+    EXPECT_EQ(json(cpp_enum::value_1).get<cpp_enum>(), cpp_enum::value_1);
+}
+
+class JsonObjectConversionTest : public ::testing::Test {
+ protected:
+    json j1 = {{"one", 1}, {"two", 2}, {"three", 3}};
+    json j2 = {{"one", 1u}, {"two", 2u}, {"three", 3u}};
+    json j3 = {{"one", 1.1}, {"two", 2.2}, {"three", 3.3}};
+    json j4 = {{"one", true}, {"two", false}, {"three", true}};
+    json j5 = {{"one", "eins"}, {"two", "zwei"}, {"three", "drei"}};
+};
+
+TEST_F(JsonObjectConversionTest, StdMap)
+{
+    auto m1 = j1.get<std::map<std::string, int>>();
+    auto m2 = j2.get<std::map<std::string, unsigned int>>();
+    auto m3 = j3.get<std::map<std::string, double>>();
+    auto m4 = j4.get<std::map<std::string, bool>>();
+    //auto m5 = j5.get<std::map<std::string, std::string>>();
+}
+
+TEST_F(JsonObjectConversionTest, StdUnorderedMap)
+{
+    auto m1 = j1.get<std::unordered_map<std::string, int>>();
+    auto m2 = j2.get<std::unordered_map<std::string, unsigned int>>();
+    auto m3 = j3.get<std::unordered_map<std::string, double>>();
+    auto m4 = j4.get<std::unordered_map<std::string, bool>>();
+    //auto m5 = j5.get<std::unordered_map<std::string, std::string>>();
+    //CHECK(m5["one"] == "eins");
+}
+
+TEST_F(JsonObjectConversionTest, StdMultiMap)
+{
+    auto m1 = j1.get<std::multimap<std::string, int>>();
+    auto m2 = j2.get<std::multimap<std::string, unsigned int>>();
+    auto m3 = j3.get<std::multimap<std::string, double>>();
+    auto m4 = j4.get<std::multimap<std::string, bool>>();
+    //auto m5 = j5.get<std::multimap<std::string, std::string>>();
+    //CHECK(m5["one"] == "eins");
+}
+
+TEST_F(JsonObjectConversionTest, StdUnorderedMultiMap)
+{
+    auto m1 = j1.get<std::unordered_multimap<std::string, int>>();
+    auto m2 = j2.get<std::unordered_multimap<std::string, unsigned int>>();
+    auto m3 = j3.get<std::unordered_multimap<std::string, double>>();
+    auto m4 = j4.get<std::unordered_multimap<std::string, bool>>();
+    //auto m5 = j5.get<std::unordered_multimap<std::string, std::string>>();
+    //CHECK(m5["one"] == "eins");
+}
+
+// exception in case of a non-object type
+TEST_F(JsonObjectConversionTest, Exception)
+{
+    EXPECT_THROW_MSG((json().get<std::map<std::string, int>>()), json::type_error,
+                     "[json.exception.type_error.302] type must be object, but is null");
+}
+
+class JsonArrayConversionTest : public ::testing::Test {
+ protected:
+    json j1 = {1, 2, 3, 4};
+    json j2 = {1u, 2u, 3u, 4u};
+    json j3 = {1.2, 2.3, 3.4, 4.5};
+    json j4 = {true, false, true};
+    json j5 = {"one", "two", "three"};
+};
+
+TEST_F(JsonArrayConversionTest, StdList)
+{
+    auto m1 = j1.get<std::list<int>>();
+    auto m2 = j2.get<std::list<unsigned int>>();
+    auto m3 = j3.get<std::list<double>>();
+    auto m4 = j4.get<std::list<bool>>();
+    auto m5 = j5.get<std::list<std::string>>();
+}
+
+#if 0
+TEST_F(JsonArrayConversionTest, StdForwardList)
+{
+    auto m1 = j1.get<std::forward_list<int>>();
+    auto m2 = j2.get<std::forward_list<unsigned int>>();
+    auto m3 = j3.get<std::forward_list<double>>();
+    auto m4 = j4.get<std::forward_list<bool>>();
+    auto m5 = j5.get<std::forward_list<std::string>>();
+}
+#endif
+
+TEST_F(JsonArrayConversionTest, StdVector)
+{
+    auto m1 = j1.get<std::vector<int>>();
+    auto m2 = j2.get<std::vector<unsigned int>>();
+    auto m3 = j3.get<std::vector<double>>();
+    auto m4 = j4.get<std::vector<bool>>();
+    auto m5 = j5.get<std::vector<std::string>>();
+}
+
+TEST_F(JsonArrayConversionTest, StdDeque)
+{
+    auto m1 = j1.get<std::deque<int>>();
+    auto m2 = j2.get<std::deque<unsigned int>>();
+    auto m3 = j2.get<std::deque<double>>();
+    auto m4 = j4.get<std::deque<bool>>();
+    auto m5 = j5.get<std::deque<std::string>>();
+}
+
+TEST_F(JsonArrayConversionTest, StdSet)
+{
+    auto m1 = j1.get<std::set<int>>();
+    auto m2 = j2.get<std::set<unsigned int>>();
+    auto m3 = j3.get<std::set<double>>();
+    auto m4 = j4.get<std::set<bool>>();
+    auto m5 = j5.get<std::set<std::string>>();
+}
+
+TEST_F(JsonArrayConversionTest, StdUnorderedSet)
+{
+    auto m1 = j1.get<std::unordered_set<int>>();
+    auto m2 = j2.get<std::unordered_set<unsigned int>>();
+    auto m3 = j3.get<std::unordered_set<double>>();
+    auto m4 = j4.get<std::unordered_set<bool>>();
+    auto m5 = j5.get<std::unordered_set<std::string>>();
+}
+
+// exception in case of a non-object type
+TEST_F(JsonArrayConversionTest, Exception)
+{
+    EXPECT_THROW_MSG((json().get<std::list<int>>()), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is null");
+    EXPECT_THROW_MSG((json().get<std::vector<int>>()), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is null");
+    EXPECT_THROW_MSG((json().get<std::vector<json>>()), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is null");
+    EXPECT_THROW_MSG((json().get<std::list<json>>()), json::type_error,
+                     "[json.exception.type_error.302] type must be array, but is null");
+    // does type really must be an array? or it rather must not be null?
+    // that's what I thought when other test like this one broke
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-deserialization.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-deserialization.cpp
new file mode 100644
index 0000000..12ac280
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-deserialization.cpp
@@ -0,0 +1,138 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+#include "wpi/raw_istream.h"
+using wpi::json;
+
+#include <valarray>
+
+TEST(JsonDeserializationTest, SuccessfulStream)
+{
+    std::string s = "[\"foo\",1,2,3,false,{\"one\":1}]";
+    wpi::raw_mem_istream ss(s.data(), s.size());
+    json j = json::parse(ss);
+    ASSERT_EQ(j, json({"foo", 1, 2, 3, false, {{"one", 1}}}));
+}
+
+TEST(JsonDeserializationTest, SuccessfulStringLiteral)
+{
+    auto s = "[\"foo\",1,2,3,false,{\"one\":1}]";
+    json j = json::parse(s);
+    ASSERT_EQ(j, json({"foo", 1, 2, 3, false, {{"one", 1}}}));
+}
+
+TEST(JsonDeserializationTest, SuccessfulStdString)
+{
+    std::string s = "[\"foo\",1,2,3,false,{\"one\":1}]";
+    json j = json::parse(s);
+    ASSERT_EQ(j, json({"foo", 1, 2, 3, false, {{"one", 1}}}));
+}
+
+TEST(JsonDeserializationTest, SuccessfulStreamOperator)
+{
+    std::string s = "[\"foo\",1,2,3,false,{\"one\":1}]";
+    wpi::raw_mem_istream ss(s.data(), s.size());
+    json j;
+    ss >> j;
+    ASSERT_EQ(j, json({"foo", 1, 2, 3, false, {{"one", 1}}}));
+}
+
+TEST(JsonDeserializationTest, SuccessfulUserStringLiteral)
+{
+    ASSERT_EQ("[\"foo\",1,2,3,false,{\"one\":1}]"_json, json({"foo", 1, 2, 3, false, {{"one", 1}}}));
+}
+
+TEST(JsonDeserializationTest, UnsuccessfulStream)
+{
+    std::string s = "[\"foo\",1,2,3,false,{\"one\":1}";
+    wpi::raw_mem_istream ss(s.data(), s.size());
+    ASSERT_THROW_MSG(json::parse(ss), json::parse_error,
+                     "[json.exception.parse_error.101] parse error at 29: syntax error - unexpected end of input; expected ']'");
+}
+
+TEST(JsonDeserializationTest, UnsuccessfulStdString)
+{
+    std::string s = "[\"foo\",1,2,3,false,{\"one\":1}";
+    ASSERT_THROW_MSG(json::parse(s), json::parse_error,
+                     "[json.exception.parse_error.101] parse error at 29: syntax error - unexpected end of input; expected ']'");
+}
+
+TEST(JsonDeserializationTest, UnsuccessfulStreamOperator)
+{
+    std::string s = "[\"foo\",1,2,3,false,{\"one\":1}";
+    wpi::raw_mem_istream ss(s.data(), s.size());
+    json j;
+    ASSERT_THROW_MSG(ss >> j, json::parse_error,
+                     "[json.exception.parse_error.101] parse error at 29: syntax error - unexpected end of input; expected ']'");
+}
+
+TEST(JsonDeserializationTest, UnsuccessfulUserStringLiteral)
+{
+    ASSERT_THROW_MSG("[\"foo\",1,2,3,false,{\"one\":1}"_json, json::parse_error,
+                     "[json.exception.parse_error.101] parse error at 29: syntax error - unexpected end of input; expected ']'");
+}
+
+// these cases are required for 100% line coverage
+class JsonDeserializationErrorTest
+    : public ::testing::TestWithParam<const char*> {};
+
+TEST_P(JsonDeserializationErrorTest, ErrorCase)
+{
+    ASSERT_THROW(json::parse(GetParam()), json::parse_error);
+}
+
+static const char* error_cases[] = {
+    "\"aaaaaa\\u",
+    "\"aaaaaa\\u1",
+    "\"aaaaaa\\u11111111",
+    "\"aaaaaau11111111\\",
+    "\"\x7F\xC1",
+    "\"\x7F\xDF\x7F",
+    "\"\x7F\xDF\xC0",
+    "\"\x7F\xE0\x9F",
+    "\"\x7F\xEF\xC0",
+    "\"\x7F\xED\x7F",
+    "\"\x7F\xF0\x8F",
+    "\"\x7F\xF0\xC0",
+    "\"\x7F\xF3\x7F",
+    "\"\x7F\xF3\xC0",
+    "\"\x7F\xF4\x7F",
+};
+
+INSTANTIATE_TEST_CASE_P(JsonDeserializationErrorTests,
+                        JsonDeserializationErrorTest,
+                        ::testing::ValuesIn(error_cases), );
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-element_access1.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-element_access1.cpp
new file mode 100644
index 0000000..a97d6b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-element_access1.cpp
@@ -0,0 +1,873 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+class JsonElementArrayAccessTestBase {
+ public:
+    JsonElementArrayAccessTestBase() : j_const(j) {}
+
+ protected:
+    json j = {1, 1u, true, nullptr, "string", 42.23, json::object(), {1, 2, 3}};
+    const json j_const;
+};
+
+class JsonElementArrayAccessTest : public ::testing::Test,
+                                   public JsonElementArrayAccessTestBase {};
+
+TEST_F(JsonElementArrayAccessTest, AtWithinBounds)
+{
+    EXPECT_EQ(j.at(0), json(1));
+    EXPECT_EQ(j.at(1), json(1u));
+    EXPECT_EQ(j.at(2), json(true));
+    EXPECT_EQ(j.at(3), json(nullptr));
+    EXPECT_EQ(j.at(4), json("string"));
+    EXPECT_EQ(j.at(5), json(42.23));
+    EXPECT_EQ(j.at(6), json::object());
+    EXPECT_EQ(j.at(7), json({1, 2, 3}));
+
+    EXPECT_EQ(j_const.at(0), json(1));
+    EXPECT_EQ(j_const.at(1), json(1u));
+    EXPECT_EQ(j_const.at(2), json(true));
+    EXPECT_EQ(j_const.at(3), json(nullptr));
+    EXPECT_EQ(j_const.at(4), json("string"));
+    EXPECT_EQ(j_const.at(5), json(42.23));
+    EXPECT_EQ(j_const.at(6), json::object());
+    EXPECT_EQ(j_const.at(7), json({1, 2, 3}));
+}
+
+TEST_F(JsonElementArrayAccessTest, AtOutsideBounds)
+{
+    EXPECT_THROW_MSG(j.at(8), json::out_of_range,
+                     "[json.exception.out_of_range.401] array index 8 is out of range");
+    EXPECT_THROW_MSG(j_const.at(8), json::out_of_range,
+                     "[json.exception.out_of_range.401] array index 8 is out of range");
+}
+
+TEST(JsonElementNonArrayAtAccessTest, Null)
+{
+    json j_nonarray(json::value_t::null);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with null");
+    EXPECT_THROW_MSG(j_nonarray_const.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with null");
+}
+
+TEST(JsonElementNonArrayAtAccessTest, Boolean)
+{
+    json j_nonarray(json::value_t::boolean);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with boolean");
+    EXPECT_THROW_MSG(j_nonarray_const.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with boolean");
+}
+
+TEST(JsonElementNonArrayAtAccessTest, String)
+{
+    json j_nonarray(json::value_t::string);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with string");
+    EXPECT_THROW_MSG(j_nonarray_const.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with string");
+}
+
+TEST(JsonElementNonArrayAtAccessTest, Object)
+{
+    json j_nonarray(json::value_t::object);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with object");
+    EXPECT_THROW_MSG(j_nonarray_const.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with object");
+}
+
+TEST(JsonElementNonArrayAtAccessTest, Integer)
+{
+    json j_nonarray(json::value_t::number_integer);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+    EXPECT_THROW_MSG(j_nonarray_const.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+}
+
+TEST(JsonElementNonArrayAtAccessTest, Unsigned)
+{
+    json j_nonarray(json::value_t::number_unsigned);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+    EXPECT_THROW_MSG(j_nonarray_const.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+}
+
+TEST(JsonElementNonArrayAtAccessTest, Float)
+{
+    json j_nonarray(json::value_t::number_float);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+    EXPECT_THROW_MSG(j_nonarray_const.at(0), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+}
+
+TEST_F(JsonElementArrayAccessTest, FrontAndBack)
+{
+    EXPECT_EQ(j.front(), json(1));
+    EXPECT_EQ(j_const.front(), json(1));
+    EXPECT_EQ(j.back(), json({1, 2, 3}));
+    EXPECT_EQ(j_const.back(), json({1, 2, 3}));
+}
+
+TEST_F(JsonElementArrayAccessTest, OperatorWithinBounds)
+{
+    EXPECT_EQ(j[0], json(1));
+    EXPECT_EQ(j[1], json(1u));
+    EXPECT_EQ(j[2], json(true));
+    EXPECT_EQ(j[3], json(nullptr));
+    EXPECT_EQ(j[4], json("string"));
+    EXPECT_EQ(j[5], json(42.23));
+    EXPECT_EQ(j[6], json::object());
+    EXPECT_EQ(j[7], json({1, 2, 3}));
+
+    EXPECT_EQ(j_const[0], json(1));
+    EXPECT_EQ(j_const[1], json(1u));
+    EXPECT_EQ(j_const[2], json(true));
+    EXPECT_EQ(j_const[3], json(nullptr));
+    EXPECT_EQ(j_const[4], json("string"));
+    EXPECT_EQ(j_const[5], json(42.23));
+    EXPECT_EQ(j_const[6], json::object());
+    EXPECT_EQ(j_const[7], json({1, 2, 3}));
+}
+
+TEST(JsonElementNonArrayOperatorAccessTest, NullStandard)
+{
+    json j_nonarray(json::value_t::null);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_NO_THROW(j_nonarray[0]);
+    EXPECT_THROW_MSG(j_nonarray_const[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with null");
+}
+
+// implicit transformation to properly filled array
+TEST(JsonElementNonArrayOperatorAccessTest, NullImplicitFilled)
+{
+    json j_nonarray;
+    j_nonarray[3] = 42;
+    EXPECT_EQ(j_nonarray, json({nullptr, nullptr, nullptr, 42}));
+}
+
+TEST(JsonElementNonArrayOperatorAccessTest, Boolean)
+{
+    json j_nonarray(json::value_t::boolean);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with boolean");
+    EXPECT_THROW_MSG(j_nonarray_const[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with boolean");
+}
+
+TEST(JsonElementNonArrayOperatorAccessTest, String)
+{
+    json j_nonarray(json::value_t::string);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with string");
+    EXPECT_THROW_MSG(j_nonarray_const[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with string");
+}
+
+TEST(JsonElementNonArrayOperatorAccessTest, Object)
+{
+    json j_nonarray(json::value_t::object);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with object");
+    EXPECT_THROW_MSG(j_nonarray_const[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with object");
+}
+
+TEST(JsonElementNonArrayOperatorAccessTest, Integer)
+{
+    json j_nonarray(json::value_t::number_integer);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_nonarray_const[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+}
+
+TEST(JsonElementNonArrayOperatorAccessTest, Unsigned)
+{
+    json j_nonarray(json::value_t::number_unsigned);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_nonarray_const[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+}
+
+TEST(JsonElementNonArrayOperatorAccessTest, Float)
+{
+    json j_nonarray(json::value_t::number_float);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_THROW_MSG(j_nonarray[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_nonarray_const[0], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+}
+
+class JsonElementArrayRemoveTest : public ::testing::Test,
+                                   public JsonElementArrayAccessTestBase {};
+
+
+// remove element by index
+TEST_F(JsonElementArrayRemoveTest, Index0)
+{
+    j.erase(0);
+    EXPECT_EQ(j, json({1u, true, nullptr, "string", 42.23, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, Index1)
+{
+    j.erase(1);
+    EXPECT_EQ(j, json({1, true, nullptr, "string", 42.23, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, Index2)
+{
+    j.erase(2);
+    EXPECT_EQ(j, json({1, 1u, nullptr, "string", 42.23, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, Index3)
+{
+    j.erase(3);
+    EXPECT_EQ(j, json({1, 1u, true, "string", 42.23, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, Index4)
+{
+    j.erase(4);
+    EXPECT_EQ(j, json({1, 1u, true, nullptr, 42.23, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, Index5)
+{
+    j.erase(5);
+    EXPECT_EQ(j, json({1, 1u, true, nullptr, "string", json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, Index6)
+{
+    j.erase(6);
+    EXPECT_EQ(j, json({1, 1u, true, nullptr, "string", 42.23, {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, Index7)
+{
+    j.erase(7);
+    EXPECT_EQ(j, json({1, 1u, true, nullptr, "string", 42.23, json::object()}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, Index8)
+{
+    EXPECT_THROW_MSG(j.erase(8), json::out_of_range,
+                     "[json.exception.out_of_range.401] array index 8 is out of range");
+}
+
+// erase(begin())
+TEST_F(JsonElementArrayRemoveTest, Begin)
+{
+    j.erase(j.begin());
+    EXPECT_EQ(j, json({1u, true, nullptr, "string", 42.23, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, BeginConst)
+{
+    j.erase(j.cbegin());
+    EXPECT_EQ(j, json({1u, true, nullptr, "string", 42.23, json::object(), {1, 2, 3}}));
+}
+
+// erase(begin(), end())
+TEST_F(JsonElementArrayRemoveTest, BeginEnd)
+{
+    j.erase(j.begin(), j.end());
+    EXPECT_EQ(j, json::array());
+}
+TEST_F(JsonElementArrayRemoveTest, BeginEndConst)
+{
+    j.erase(j.cbegin(), j.cend());
+    EXPECT_EQ(j, json::array());
+}
+
+// erase(begin(), begin())
+TEST_F(JsonElementArrayRemoveTest, BeginBegin)
+{
+    j.erase(j.begin(), j.begin());
+    EXPECT_EQ(j, json({1, 1u, true, nullptr, "string", 42.23, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, BeginBeginConst)
+{
+    j.erase(j.cbegin(), j.cbegin());
+    EXPECT_EQ(j, json({1, 1u, true, nullptr, "string", 42.23, json::object(), {1, 2, 3}}));
+}
+
+// erase at offset
+TEST_F(JsonElementArrayRemoveTest, Offset)
+{
+    json::iterator it = j.begin() + 4;
+    j.erase(it);
+    EXPECT_EQ(j, json({1, 1u, true, nullptr, 42.23, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, OffsetConst)
+{
+    json::const_iterator it = j.cbegin() + 4;
+    j.erase(it);
+    EXPECT_EQ(j, json({1, 1u, true, nullptr, 42.23, json::object(), {1, 2, 3}}));
+}
+
+// erase subrange
+TEST_F(JsonElementArrayRemoveTest, Subrange)
+{
+    j.erase(j.begin() + 3, j.begin() + 6);
+    EXPECT_EQ(j, json({1, 1u, true, json::object(), {1, 2, 3}}));
+}
+
+TEST_F(JsonElementArrayRemoveTest, SubrangeConst)
+{
+    j.erase(j.cbegin() + 3, j.cbegin() + 6);
+    EXPECT_EQ(j, json({1, 1u, true, json::object(), {1, 2, 3}}));
+}
+
+// different arrays
+TEST_F(JsonElementArrayRemoveTest, Different)
+{
+    json j2 = {"foo", "bar"};
+    EXPECT_THROW_MSG(j.erase(j2.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+    EXPECT_THROW_MSG(j.erase(j.begin(), j2.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+    EXPECT_THROW_MSG(j.erase(j2.begin(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+    EXPECT_THROW_MSG(j.erase(j2.begin(), j2.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+}
+
+TEST_F(JsonElementArrayRemoveTest, DifferentConst)
+{
+    json j2 = {"foo", "bar"};
+    EXPECT_THROW_MSG(j.erase(j2.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+    EXPECT_THROW_MSG(j.erase(j.cbegin(), j2.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+    EXPECT_THROW_MSG(j.erase(j2.cbegin(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+    EXPECT_THROW_MSG(j.erase(j2.cbegin(), j2.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+}
+
+// remove element by index in non-array type
+TEST(JsonElementNonArrayIndexRemoveTest, Null)
+{
+    json j_nonobject(json::value_t::null);
+    EXPECT_THROW_MSG(j_nonobject.erase(0), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with null");
+}
+
+TEST(JsonElementNonArrayIndexRemoveTest, Boolean)
+{
+    json j_nonobject(json::value_t::boolean);
+    EXPECT_THROW_MSG(j_nonobject.erase(0), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with boolean");
+}
+
+TEST(JsonElementNonArrayIndexRemoveTest, String)
+{
+    json j_nonobject(json::value_t::string);
+    EXPECT_THROW_MSG(j_nonobject.erase(0), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with string");
+}
+
+TEST(JsonElementNonArrayIndexRemoveTest, Object)
+{
+    json j_nonobject(json::value_t::object);
+    EXPECT_THROW_MSG(j_nonobject.erase(0), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with object");
+}
+
+TEST(JsonElementNonArrayIndexRemoveTest, Integer)
+{
+    json j_nonobject(json::value_t::number_integer);
+    EXPECT_THROW_MSG(j_nonobject.erase(0), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with number");
+}
+
+TEST(JsonElementNonArrayIndexRemoveTest, Unsigned)
+{
+    json j_nonobject(json::value_t::number_unsigned);
+    EXPECT_THROW_MSG(j_nonobject.erase(0), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with number");
+}
+
+TEST(JsonElementNonArrayIndexRemoveTest, Float)
+{
+    json j_nonobject(json::value_t::number_float);
+    EXPECT_THROW_MSG(j_nonobject.erase(0), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with number");
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, Null)
+{
+    json j;
+    EXPECT_THROW_MSG(j.front(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(j.back(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, NullConst)
+{
+    const json j{};
+    EXPECT_THROW_MSG(j.front(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(j.back(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, String)
+{
+    json j = "foo";
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, StringConst)
+{
+    const json j = "bar";
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, Boolean)
+{
+    json j = false;
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, BooleanConst)
+{
+    const json j = true;
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, Integer)
+{
+    json j = 17;
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, IntegerConst)
+{
+    const json j = 17;
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, Unsigned)
+{
+    json j = 17u;
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, UnsignedConst)
+{
+    const json j = 17u;
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, Float)
+{
+    json j = 23.42;
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayFrontBackAccessTest, FloatConst)
+{
+    const json j = 23.42;
+    EXPECT_EQ(j.front(), j);
+    EXPECT_EQ(j.back(), j);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, Null)
+{
+    json j;
+    EXPECT_THROW_MSG(j.erase(j.begin()), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with null");
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, NullConst)
+{
+    json j;
+    EXPECT_THROW_MSG(j.erase(j.cbegin()), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with null");
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, String)
+{
+    json j = "foo";
+    j.erase(j.begin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, StringConst)
+{
+    json j = "bar";
+    j.erase(j.cbegin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, Boolean)
+{
+    json j = false;
+    j.erase(j.begin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, BooleanConst)
+{
+    json j = true;
+    j.erase(j.cbegin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, Integer)
+{
+    json j = 17;
+    j.erase(j.begin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, IntegerConst)
+{
+    json j = 17;
+    j.erase(j.cbegin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, Unsigned)
+{
+    json j = 17u;
+    j.erase(j.begin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, UnsignedConst)
+{
+    json j = 17u;
+    j.erase(j.cbegin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, Float)
+{
+    json j = 23.42;
+    j.erase(j.begin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneValidIteratorRemoveTest, FloatConst)
+{
+    json j = 23.42;
+    j.erase(j.cbegin());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, String)
+{
+    json j = "foo";
+    EXPECT_THROW_MSG(j.erase(j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, StringConst)
+{
+    json j = "bar";
+    EXPECT_THROW_MSG(j.erase(j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, Boolean)
+{
+    json j = false;
+    EXPECT_THROW_MSG(j.erase(j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, BooleanConst)
+{
+    json j = true;
+    EXPECT_THROW_MSG(j.erase(j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, Integer)
+{
+    json j = 17;
+    EXPECT_THROW_MSG(j.erase(j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, IntegerConst)
+{
+    json j = 17;
+    EXPECT_THROW_MSG(j.erase(j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, Unsigned)
+{
+    json j = 17u;
+    EXPECT_THROW_MSG(j.erase(j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, UnsignedConst)
+{
+    json j = 17u;
+    EXPECT_THROW_MSG(j.erase(j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, Float)
+{
+    json j = 23.42;
+    EXPECT_THROW_MSG(j.erase(j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayOneInvalidIteratorRemoveTest, FloatConst)
+{
+    json j = 23.42;
+    EXPECT_THROW_MSG(j.erase(j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.205] iterator out of range");
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, Null)
+{
+    json j;
+    EXPECT_THROW_MSG(j.erase(j.begin(), j.end()), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with null");
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, NullConst)
+{
+    json j;
+    EXPECT_THROW_MSG(j.erase(j.cbegin(), j.cend()), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with null");
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, String)
+{
+    json j = "foo";
+    j.erase(j.begin(), j.end());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, StringConst)
+{
+    json j = "bar";
+    j.erase(j.cbegin(), j.cend());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, Boolean)
+{
+    json j = false;
+    j.erase(j.begin(), j.end());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, BooleanConst)
+{
+    json j = true;
+    j.erase(j.cbegin(), j.cend());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, Integer)
+{
+    json j = 17;
+    j.erase(j.begin(), j.end());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, IntegerConst)
+{
+    json j = 17;
+    j.erase(j.cbegin(), j.cend());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, Unsigned)
+{
+    json j = 17u;
+    j.erase(j.begin(), j.end());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, UnsignedConst)
+{
+    json j = 17u;
+    j.erase(j.cbegin(), j.cend());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, Float)
+{
+    json j = 23.42;
+    j.erase(j.begin(), j.end());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoValidIteratorRemoveTest, FloatConst)
+{
+    json j = 23.42;
+    j.erase(j.cbegin(), j.cend());
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, String)
+{
+    json j = "foo";
+    EXPECT_THROW_MSG(j.erase(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, StringConst)
+{
+    json j = "bar";
+    EXPECT_THROW_MSG(j.erase(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, Boolean)
+{
+    json j = false;
+    EXPECT_THROW_MSG(j.erase(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, BooleanConst)
+{
+    json j = true;
+    EXPECT_THROW_MSG(j.erase(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, Integer)
+{
+    json j = 17;
+    EXPECT_THROW_MSG(j.erase(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, IntegerConst)
+{
+    json j = 17;
+    EXPECT_THROW_MSG(j.erase(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, Unsigned)
+{
+    json j = 17u;
+    EXPECT_THROW_MSG(j.erase(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, UnsignedConst)
+{
+    json j = 17u;
+    EXPECT_THROW_MSG(j.erase(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, Float)
+{
+    json j = 23.42;
+    EXPECT_THROW_MSG(j.erase(j.end(), j.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.begin(), j.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
+
+TEST(JsonElementNonArrayTwoInvalidIteratorRemoveTest, FloatConst)
+{
+    json j = 23.42;
+    EXPECT_THROW_MSG(j.erase(j.cend(), j.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+    EXPECT_THROW_MSG(j.erase(j.cbegin(), j.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.204] iterators out of range");
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-element_access2.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-element_access2.cpp
new file mode 100644
index 0000000..4b64123
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-element_access2.cpp
@@ -0,0 +1,923 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+class JsonElementObjectAccessTestBase {
+ public:
+    JsonElementObjectAccessTestBase() : j_const(j) {}
+
+ protected:
+    json j = {{"integer", 1}, {"unsigned", 1u}, {"floating", 42.23}, {"null", nullptr}, {"string", "hello world"}, {"boolean", true}, {"object", json::object()}, {"array", {1, 2, 3}}};
+    const json j_const;
+};
+
+class JsonElementObjectAccessTest : public ::testing::Test,
+                                    public JsonElementObjectAccessTestBase {};
+
+TEST_F(JsonElementObjectAccessTest, AtWithinBounds)
+{
+    EXPECT_EQ(j.at("integer"), json(1));
+    EXPECT_EQ(j.at("unsigned"), json(1u));
+    EXPECT_EQ(j.at("boolean"), json(true));
+    EXPECT_EQ(j.at("null"), json(nullptr));
+    EXPECT_EQ(j.at("string"), json("hello world"));
+    EXPECT_EQ(j.at("floating"), json(42.23));
+    EXPECT_EQ(j.at("object"), json::object());
+    EXPECT_EQ(j.at("array"), json({1, 2, 3}));
+
+    EXPECT_EQ(j_const.at("integer"), json(1));
+    EXPECT_EQ(j_const.at("unsigned"), json(1u));
+    EXPECT_EQ(j_const.at("boolean"), json(true));
+    EXPECT_EQ(j_const.at("null"), json(nullptr));
+    EXPECT_EQ(j_const.at("string"), json("hello world"));
+    EXPECT_EQ(j_const.at("floating"), json(42.23));
+    EXPECT_EQ(j_const.at("object"), json::object());
+    EXPECT_EQ(j_const.at("array"), json({1, 2, 3}));
+}
+
+TEST_F(JsonElementObjectAccessTest, AtOutsideBounds)
+{
+    EXPECT_THROW_MSG(j.at("foo"), json::out_of_range,
+                     "[json.exception.out_of_range.403] key 'foo' not found");
+    EXPECT_THROW_MSG(j_const.at("foo"), json::out_of_range,
+                     "[json.exception.out_of_range.403] key 'foo' not found");
+}
+
+TEST(JsonElementNonObjectAtAccessTest, Null)
+{
+    json j_nonobject(json::value_t::null);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with null");
+    EXPECT_THROW_MSG(j_nonobject_const.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with null");
+}
+
+TEST(JsonElementNonObjectAtAccessTest, Boolean)
+{
+    json j_nonobject(json::value_t::boolean);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with boolean");
+    EXPECT_THROW_MSG(j_nonobject_const.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with boolean");
+}
+
+TEST(JsonElementNonObjectAtAccessTest, String)
+{
+    json j_nonobject(json::value_t::string);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with string");
+    EXPECT_THROW_MSG(j_nonobject_const.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with string");
+}
+
+TEST(JsonElementNonObjectAtAccessTest, Array)
+{
+    json j_nonobject(json::value_t::array);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with array");
+    EXPECT_THROW_MSG(j_nonobject_const.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with array");
+}
+
+TEST(JsonElementNonObjectAtAccessTest, Integer)
+{
+    json j_nonobject(json::value_t::number_integer);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+}
+
+TEST(JsonElementNonObjectAtAccessTest, Unsigned)
+{
+    json j_nonobject(json::value_t::number_unsigned);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+}
+
+TEST(JsonElementNonObjectAtAccessTest, Float)
+{
+    json j_nonobject(json::value_t::number_float);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.at("foo"), json::type_error,
+                     "[json.exception.type_error.304] cannot use at() with number");
+}
+
+TEST_F(JsonElementObjectAccessTest, KeyValueExist)
+{
+    EXPECT_EQ(j.value("integer", 2), 1);
+    EXPECT_LT(std::fabs(j.value("integer", 1.0) - 1), 0.001);
+    EXPECT_EQ(j.value("unsigned", 2), 1);
+    EXPECT_LT(std::fabs(j.value("unsigned", 1.0) - 1), 0.001);
+    EXPECT_EQ(j.value("null", json(1)), json());
+    EXPECT_EQ(j.value("boolean", false), true);
+    EXPECT_EQ(j.value("string", "bar"), "hello world");
+    EXPECT_EQ(j.value("string", std::string("bar")), "hello world");
+    EXPECT_LT(std::fabs(j.value("floating", 12.34) - 42.23), 0.001);
+    EXPECT_EQ(j.value("floating", 12), 42);
+    EXPECT_EQ(j.value("object", json({{"foo", "bar"}})), json::object());
+    EXPECT_EQ(j.value("array", json({10, 100})), json({1, 2, 3}));
+
+    EXPECT_EQ(j_const.value("integer", 2), 1);
+    EXPECT_LT(std::fabs(j_const.value("integer", 1.0) - 1), 0.001);
+    EXPECT_EQ(j_const.value("unsigned", 2), 1);
+    EXPECT_LT(std::fabs(j_const.value("unsigned", 1.0) - 1), 0.001);
+    EXPECT_EQ(j_const.value("boolean", false), true);
+    EXPECT_EQ(j_const.value("string", "bar"), "hello world");
+    EXPECT_EQ(j_const.value("string", std::string("bar")), "hello world");
+    EXPECT_LT(std::fabs(j_const.value("floating", 12.34) - 42.23), 0.001);
+    EXPECT_EQ(j_const.value("floating", 12), 42);
+    EXPECT_EQ(j_const.value("object", json({{"foo", "bar"}})), json::object());
+    EXPECT_EQ(j_const.value("array", json({10, 100})), json({1, 2, 3}));
+}
+
+TEST_F(JsonElementObjectAccessTest, KeyValueNotExist)
+{
+    EXPECT_EQ(j.value("_", 2), 2);
+    EXPECT_EQ(j.value("_", 2u), 2u);
+    EXPECT_EQ(j.value("_", false), false);
+    EXPECT_EQ(j.value("_", "bar"), "bar");
+    EXPECT_LT(std::fabs(j.value("_", 12.34) - 12.34), 0.001);
+    EXPECT_EQ(j.value("_", json({{"foo", "bar"}})), json({{"foo", "bar"}}));
+    EXPECT_EQ(j.value("_", json({10, 100})), json({10, 100}));
+
+    EXPECT_EQ(j_const.value("_", 2), 2);
+    EXPECT_EQ(j_const.value("_", 2u), 2u);
+    EXPECT_EQ(j_const.value("_", false), false);
+    EXPECT_EQ(j_const.value("_", "bar"), "bar");
+    EXPECT_LT(std::fabs(j_const.value("_", 12.34) - 12.34), 0.001);
+    EXPECT_EQ(j_const.value("_", json({{"foo", "bar"}})), json({{"foo", "bar"}}));
+    EXPECT_EQ(j_const.value("_", json({10, 100})), json({10, 100}));
+}
+
+TEST(JsonElementNonObjectKeyValueAccessTest, Null)
+{
+    json j_nonobject(json::value_t::null);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with null");
+    EXPECT_THROW_MSG(j_nonobject_const.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with null");
+}
+
+TEST(JsonElementNonObjectKeyValueAccessTest, Boolean)
+{
+    json j_nonobject(json::value_t::boolean);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with boolean");
+    EXPECT_THROW_MSG(j_nonobject_const.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with boolean");
+}
+
+TEST(JsonElementNonObjectKeyValueAccessTest, String)
+{
+    json j_nonobject(json::value_t::string);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with string");
+    EXPECT_THROW_MSG(j_nonobject_const.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with string");
+}
+
+TEST(JsonElementNonObjectKeyValueAccessTest, Array)
+{
+    json j_nonobject(json::value_t::array);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with array");
+    EXPECT_THROW_MSG(j_nonobject_const.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with array");
+}
+
+TEST(JsonElementNonObjectKeyValueAccessTest, Integer)
+{
+    json j_nonobject(json::value_t::number_integer);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+}
+
+TEST(JsonElementNonObjectKeyValueAccessTest, Unsigned)
+{
+    json j_nonobject(json::value_t::number_unsigned);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+}
+
+TEST(JsonElementNonObjectKeyValueAccessTest, Float)
+{
+    json j_nonobject(json::value_t::number_float);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.value("foo", 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+}
+
+TEST_F(JsonElementObjectAccessTest, PointerValueExist)
+{
+    EXPECT_EQ(j.value("/integer"_json_pointer, 2), 1);
+    EXPECT_LT(std::fabs(j.value("/integer"_json_pointer, 1.0) - 1), 0.001);
+    EXPECT_EQ(j.value("/unsigned"_json_pointer, 2), 1);
+    EXPECT_LT(std::fabs(j.value("/unsigned"_json_pointer, 1.0) - 1), 0.001);
+    EXPECT_EQ(j.value("/null"_json_pointer, json(1)), json());
+    EXPECT_EQ(j.value("/boolean"_json_pointer, false), true);
+    EXPECT_EQ(j.value("/string"_json_pointer, "bar"), "hello world");
+    EXPECT_EQ(j.value("/string"_json_pointer, std::string("bar")), "hello world");
+    EXPECT_LT(std::fabs(j.value("/floating"_json_pointer, 12.34) - 42.23), 0.001);
+    EXPECT_EQ(j.value("/floating"_json_pointer, 12), 42);
+    EXPECT_EQ(j.value("/object"_json_pointer, json({{"foo", "bar"}})), json::object());
+    EXPECT_EQ(j.value("/array"_json_pointer, json({10, 100})), json({1, 2, 3}));
+
+    EXPECT_EQ(j_const.value("/integer"_json_pointer, 2), 1);
+    EXPECT_LT(std::fabs(j_const.value("/integer"_json_pointer, 1.0) - 1), 0.001);
+    EXPECT_EQ(j_const.value("/unsigned"_json_pointer, 2), 1);
+    EXPECT_LT(std::fabs(j_const.value("/unsigned"_json_pointer, 1.0) - 1), 0.001);
+    EXPECT_EQ(j_const.value("/boolean"_json_pointer, false), true);
+    EXPECT_EQ(j_const.value("/string"_json_pointer, "bar"), "hello world");
+    EXPECT_EQ(j_const.value("/string"_json_pointer, std::string("bar")), "hello world");
+    EXPECT_LT(std::fabs(j_const.value("/floating"_json_pointer, 12.34) - 42.23), 0.001);
+    EXPECT_EQ(j_const.value("/floating"_json_pointer, 12), 42);
+    EXPECT_EQ(j_const.value("/object"_json_pointer, json({{"foo", "bar"}})), json::object());
+    EXPECT_EQ(j_const.value("/array"_json_pointer, json({10, 100})), json({1, 2, 3}));
+}
+
+TEST(JsonElementNonObjectPointerValueAccessTest, Null)
+{
+    json j_nonobject(json::value_t::null);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with null");
+    EXPECT_THROW_MSG(j_nonobject_const.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with null");
+}
+
+TEST(JsonElementNonObjectPointerValueAccessTest, Boolean)
+{
+    json j_nonobject(json::value_t::boolean);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with boolean");
+    EXPECT_THROW_MSG(j_nonobject_const.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with boolean");
+}
+
+TEST(JsonElementNonObjectPointerValueAccessTest, String)
+{
+    json j_nonobject(json::value_t::string);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with string");
+    EXPECT_THROW_MSG(j_nonobject_const.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with string");
+}
+
+TEST(JsonElementNonObjectPointerValueAccessTest, Array)
+{
+    json j_nonobject(json::value_t::array);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with array");
+    EXPECT_THROW_MSG(j_nonobject_const.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with array");
+}
+
+TEST(JsonElementNonObjectPointerValueAccessTest, Integer)
+{
+    json j_nonobject(json::value_t::number_integer);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+}
+
+TEST(JsonElementNonObjectPointerValueAccessTest, Unsigned)
+{
+    json j_nonobject(json::value_t::number_unsigned);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+}
+
+TEST(JsonElementNonObjectPointerValueAccessTest, Float)
+{
+    json j_nonobject(json::value_t::number_float);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+    EXPECT_THROW_MSG(j_nonobject_const.value("/foo"_json_pointer, 1), json::type_error,
+                     "[json.exception.type_error.306] cannot use value() with number");
+}
+#if 0
+TEST_F(JsonElementObjectAccessTest, FrontAndBack)
+{
+    // "array" is the smallest key
+    EXPECT_EQ(j.front(), json({1, 2, 3}));
+    EXPECT_EQ(j_const.front(), json({1, 2, 3}));
+    // "unsigned" is the largest key
+    EXPECT_EQ(j.back(), json(1u));
+    EXPECT_EQ(j_const.back(), json(1u));
+}
+#endif
+TEST_F(JsonElementObjectAccessTest, OperatorWithinBounds)
+{
+    EXPECT_EQ(j["integer"], json(1));
+    EXPECT_EQ(j[json::object_t::key_type("integer")], j["integer"]);
+
+    EXPECT_EQ(j["unsigned"], json(1u));
+    EXPECT_EQ(j[json::object_t::key_type("unsigned")], j["unsigned"]);
+
+    EXPECT_EQ(j["boolean"], json(true));
+    EXPECT_EQ(j[json::object_t::key_type("boolean")], j["boolean"]);
+
+    EXPECT_EQ(j["null"], json(nullptr));
+    EXPECT_EQ(j[json::object_t::key_type("null")], j["null"]);
+
+    EXPECT_EQ(j["string"], json("hello world"));
+    EXPECT_EQ(j[json::object_t::key_type("string")], j["string"]);
+
+    EXPECT_EQ(j["floating"], json(42.23));
+    EXPECT_EQ(j[json::object_t::key_type("floating")], j["floating"]);
+
+    EXPECT_EQ(j["object"], json::object());
+    EXPECT_EQ(j[json::object_t::key_type("object")], j["object"]);
+
+    EXPECT_EQ(j["array"], json({1, 2, 3}));
+    EXPECT_EQ(j[json::object_t::key_type("array")], j["array"]);
+
+    EXPECT_EQ(j_const["integer"], json(1));
+    EXPECT_EQ(j_const[json::object_t::key_type("integer")], j["integer"]);
+
+    EXPECT_EQ(j_const["boolean"], json(true));
+    EXPECT_EQ(j_const[json::object_t::key_type("boolean")], j["boolean"]);
+
+    EXPECT_EQ(j_const["null"], json(nullptr));
+    EXPECT_EQ(j_const[json::object_t::key_type("null")], j["null"]);
+
+    EXPECT_EQ(j_const["string"], json("hello world"));
+    EXPECT_EQ(j_const[json::object_t::key_type("string")], j["string"]);
+
+    EXPECT_EQ(j_const["floating"], json(42.23));
+    EXPECT_EQ(j_const[json::object_t::key_type("floating")], j["floating"]);
+
+    EXPECT_EQ(j_const["object"], json::object());
+    EXPECT_EQ(j_const[json::object_t::key_type("object")], j["object"]);
+
+    EXPECT_EQ(j_const["array"], json({1, 2, 3}));
+    EXPECT_EQ(j_const[json::object_t::key_type("array")], j["array"]);
+}
+
+TEST(JsonElementNonObjectOperatorAccessTest, Null)
+{
+    json j_nonobject(json::value_t::null);
+    json j_nonobject2(json::value_t::null);
+    const json j_const_nonobject(j_nonobject);
+    EXPECT_NO_THROW(j_nonobject["foo"]);
+    EXPECT_NO_THROW(j_nonobject2[json::object_t::key_type("foo")]);
+    EXPECT_THROW_MSG(j_const_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with null");
+    EXPECT_THROW_MSG(j_const_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with null");
+}
+
+TEST(JsonElementNonObjectOperatorAccessTest, Boolean)
+{
+    json j_nonobject(json::value_t::boolean);
+    const json j_const_nonobject(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with boolean");
+    EXPECT_THROW_MSG(j_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with boolean");
+    EXPECT_THROW_MSG(j_const_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with boolean");
+    EXPECT_THROW_MSG(j_const_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with boolean");
+}
+
+TEST(JsonElementNonObjectOperatorAccessTest, String)
+{
+    json j_nonobject(json::value_t::string);
+    const json j_const_nonobject(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with string");
+    EXPECT_THROW_MSG(j_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with string");
+    EXPECT_THROW_MSG(j_const_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with string");
+    EXPECT_THROW_MSG(j_const_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with string");
+}
+
+TEST(JsonElementNonObjectOperatorAccessTest, Array)
+{
+    json j_nonobject(json::value_t::array);
+    const json j_const_nonobject(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with array");
+    EXPECT_THROW_MSG(j_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with array");
+    EXPECT_THROW_MSG(j_const_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with array");
+    EXPECT_THROW_MSG(j_const_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with array");
+}
+
+TEST(JsonElementNonObjectOperatorAccessTest, Integer)
+{
+    json j_nonobject(json::value_t::number_integer);
+    const json j_const_nonobject(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_const_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_const_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+}
+
+TEST(JsonElementNonObjectOperatorAccessTest, Unsigned)
+{
+    json j_nonobject(json::value_t::number_unsigned);
+    const json j_const_nonobject(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_const_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_const_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+}
+
+TEST(JsonElementNonObjectOperatorAccessTest, Float)
+{
+    json j_nonobject(json::value_t::number_float);
+    const json j_const_nonobject(j_nonobject);
+    EXPECT_THROW_MSG(j_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_const_nonobject["foo"], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+    EXPECT_THROW_MSG(j_const_nonobject[json::object_t::key_type("foo")], json::type_error,
+                     "[json.exception.type_error.305] cannot use operator[] with number");
+}
+
+class JsonElementObjectRemoveTest : public ::testing::Test,
+                                    public JsonElementObjectAccessTestBase {};
+
+TEST_F(JsonElementObjectRemoveTest, Key)
+{
+    EXPECT_NE(j.find("integer"), j.end());
+    EXPECT_EQ(j.erase("integer"), 1u);
+    EXPECT_EQ(j.find("integer"), j.end());
+    EXPECT_EQ(j.erase("integer"), 0u);
+
+    EXPECT_NE(j.find("unsigned"), j.end());
+    EXPECT_EQ(j.erase("unsigned"), 1u);
+    EXPECT_EQ(j.find("unsigned"), j.end());
+    EXPECT_EQ(j.erase("unsigned"), 0u);
+
+    EXPECT_NE(j.find("boolean"), j.end());
+    EXPECT_EQ(j.erase("boolean"), 1u);
+    EXPECT_EQ(j.find("boolean"), j.end());
+    EXPECT_EQ(j.erase("boolean"), 0u);
+
+    EXPECT_NE(j.find("null"), j.end());
+    EXPECT_EQ(j.erase("null"), 1u);
+    EXPECT_EQ(j.find("null"), j.end());
+    EXPECT_EQ(j.erase("null"), 0u);
+
+    EXPECT_NE(j.find("string"), j.end());
+    EXPECT_EQ(j.erase("string"), 1u);
+    EXPECT_EQ(j.find("string"), j.end());
+    EXPECT_EQ(j.erase("string"), 0u);
+
+    EXPECT_NE(j.find("floating"), j.end());
+    EXPECT_EQ(j.erase("floating"), 1u);
+    EXPECT_EQ(j.find("floating"), j.end());
+    EXPECT_EQ(j.erase("floating"), 0u);
+
+    EXPECT_NE(j.find("object"), j.end());
+    EXPECT_EQ(j.erase("object"), 1u);
+    EXPECT_EQ(j.find("object"), j.end());
+    EXPECT_EQ(j.erase("object"), 0u);
+
+    EXPECT_NE(j.find("array"), j.end());
+    EXPECT_EQ(j.erase("array"), 1u);
+    EXPECT_EQ(j.find("array"), j.end());
+    EXPECT_EQ(j.erase("array"), 0u);
+}
+
+// erase(begin())
+TEST_F(JsonElementObjectRemoveTest, Begin)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+    jobject.erase(jobject.begin());
+    EXPECT_EQ(jobject, json({{"b", 1}, {"c", 17u}}));
+}
+
+TEST_F(JsonElementObjectRemoveTest, BeginConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+    jobject.erase(jobject.cbegin());
+    EXPECT_EQ(jobject, json({{"b", 1}, {"c", 17u}}));
+}
+
+// erase(begin(), end())
+TEST_F(JsonElementObjectRemoveTest, BeginEnd)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+#if 0
+    json::iterator it2 = jobject.erase(jobject.begin(), jobject.end());
+    EXPECT_EQ(jobject, json::object());
+    EXPECT_EQ(it2, jobject.end());
+#else
+    EXPECT_THROW(jobject.erase(jobject.begin(), jobject.end()), json::type_error);
+#endif
+}
+
+TEST_F(JsonElementObjectRemoveTest, BeginEndConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+#if 0
+    json::const_iterator it2 = jobject.erase(jobject.cbegin(), jobject.cend());
+    EXPECT_EQ(jobject, json::object());
+    EXPECT_EQ(it2, jobject.cend());
+#else
+    EXPECT_THROW(jobject.erase(jobject.cbegin(), jobject.cend()), json::type_error);
+#endif
+}
+
+TEST_F(JsonElementObjectRemoveTest, BeginBegin)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+#if 0
+    json::iterator it2 = jobject.erase(jobject.begin(), jobject.begin());
+    EXPECT_EQ(jobject, json({{"a", "a"}, {"b", 1}, {"c", 17u}}));
+    EXPECT_EQ(*it2, json("a"));
+#else
+    EXPECT_THROW(jobject.erase(jobject.begin(), jobject.end()), json::type_error);
+#endif
+}
+
+TEST_F(JsonElementObjectRemoveTest, BeginBeginConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+#if 0
+    json::const_iterator it2 = jobject.erase(jobject.cbegin(), jobject.cbegin());
+    EXPECT_EQ(jobject, json({{"a", "a"}, {"b", 1}, {"c", 17u}}));
+    EXPECT_EQ(*it2, json("a"));
+#else
+    EXPECT_THROW(jobject.erase(jobject.cbegin(), jobject.cbegin()), json::type_error);
+#endif
+}
+
+TEST_F(JsonElementObjectRemoveTest, Offset)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+    json::iterator it = jobject.find("b");
+    jobject.erase(it);
+    EXPECT_EQ(jobject, json({{"a", "a"}, {"c", 17u}}));
+}
+
+TEST_F(JsonElementObjectRemoveTest, OffsetConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+    json::const_iterator it = jobject.find("b");
+    jobject.erase(it);
+    EXPECT_EQ(jobject, json({{"a", "a"}, {"c", 17u}}));
+}
+
+TEST_F(JsonElementObjectRemoveTest, Subrange)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}, {"d", false}, {"e", true}};
+#if 0
+    json::iterator it2 = jobject.erase(jobject.find("b"), jobject.find("e"));
+    EXPECT_EQ(jobject, json({{"a", "a"}, {"e", true}}));
+    EXPECT_EQ(*it2, json(true));
+#else
+    EXPECT_THROW(jobject.erase(jobject.find("b"), jobject.find("e")), json::type_error);
+#endif
+}
+
+TEST_F(JsonElementObjectRemoveTest, SubrangeConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}, {"d", false}, {"e", true}};
+#if 0
+    json::const_iterator it2 = jobject.erase(jobject.find("b"), jobject.find("e"));
+    EXPECT_EQ(jobject, json({{"a", "a"}, {"e", true}}));
+    EXPECT_EQ(*it2, json(true));
+#else
+    EXPECT_THROW(jobject.erase(jobject.find("b"), jobject.find("e")), json::type_error);
+#endif
+}
+
+TEST_F(JsonElementObjectRemoveTest, Different)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}, {"d", false}, {"e", true}};
+    json jobject2 = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+    EXPECT_THROW_MSG(jobject.erase(jobject2.begin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+    EXPECT_THROW_MSG(jobject.erase(jobject.begin(), jobject2.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+    EXPECT_THROW_MSG(jobject.erase(jobject2.begin(), jobject.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+    EXPECT_THROW_MSG(jobject.erase(jobject2.begin(), jobject2.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+}
+
+TEST_F(JsonElementObjectRemoveTest, DifferentConst)
+{
+    json jobject = {{"a", "a"}, {"b", 1}, {"c", 17u}, {"d", false}, {"e", true}};
+    json jobject2 = {{"a", "a"}, {"b", 1}, {"c", 17u}};
+    EXPECT_THROW_MSG(jobject.erase(jobject2.cbegin()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+    EXPECT_THROW_MSG(jobject.erase(jobject.cbegin(), jobject2.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+    EXPECT_THROW_MSG(jobject.erase(jobject2.cbegin(), jobject.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+    EXPECT_THROW_MSG(jobject.erase(jobject2.cbegin(), jobject2.cend()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.203] iterators do not fit current value");
+}
+
+// remove element by key in non-object type
+TEST(JsonElementNonObjectKeyRemoveTest, Null)
+{
+    json j_nonobject(json::value_t::null);
+    EXPECT_THROW_MSG(j_nonobject.erase("foo"), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with null");
+}
+
+TEST(JsonElementNonObjectKeyRemoveTest, Boolean)
+{
+    json j_nonobject(json::value_t::boolean);
+    EXPECT_THROW_MSG(j_nonobject.erase("foo"), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with boolean");
+}
+
+TEST(JsonElementNonObjectKeyRemoveTest, String)
+{
+    json j_nonobject(json::value_t::string);
+    EXPECT_THROW_MSG(j_nonobject.erase("foo"), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with string");
+}
+
+TEST(JsonElementNonObjectKeyRemoveTest, Array)
+{
+    json j_nonobject(json::value_t::array);
+    EXPECT_THROW_MSG(j_nonobject.erase("foo"), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with array");
+}
+
+TEST(JsonElementNonObjectKeyRemoveTest, Integer)
+{
+    json j_nonobject(json::value_t::number_integer);
+    EXPECT_THROW_MSG(j_nonobject.erase("foo"), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with number");
+}
+
+TEST(JsonElementNonObjectKeyRemoveTest, Float)
+{
+    json j_nonobject(json::value_t::number_float);
+    EXPECT_THROW_MSG(j_nonobject.erase("foo"), json::type_error,
+                     "[json.exception.type_error.307] cannot use erase() with number");
+}
+
+TEST_F(JsonElementObjectAccessTest, FindExist)
+{
+    for (auto key :
+            {"integer", "unsigned", "floating", "null", "string", "boolean", "object", "array"
+            })
+    {
+        EXPECT_NE(j.find(key), j.end());
+        EXPECT_EQ(*j.find(key), j.at(key));
+        EXPECT_NE(j_const.find(key), j_const.end());
+        EXPECT_EQ(*j_const.find(key), j_const.at(key));
+    }
+}
+
+TEST_F(JsonElementObjectAccessTest, FindNotExist)
+{
+    EXPECT_EQ(j.find("foo"), j.end());
+    EXPECT_EQ(j_const.find("foo"), j_const.end());
+}
+
+TEST(JsonElementNonObjectFindAccessTest, Null)
+{
+    json j_nonarray(json::value_t::null);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_EQ(j_nonarray.find("foo"), j_nonarray.end());
+    EXPECT_EQ(j_nonarray_const.find("foo"), j_nonarray_const.end());
+}
+
+TEST(JsonElementNonObjectFindAccessTest, String)
+{
+    json j_nonarray(json::value_t::string);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_EQ(j_nonarray.find("foo"), j_nonarray.end());
+    EXPECT_EQ(j_nonarray_const.find("foo"), j_nonarray_const.end());
+}
+
+TEST(JsonElementNonObjectFindAccessTest, Object)
+{
+    json j_nonarray(json::value_t::object);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_EQ(j_nonarray.find("foo"), j_nonarray.end());
+    EXPECT_EQ(j_nonarray_const.find("foo"), j_nonarray_const.end());
+}
+
+TEST(JsonElementNonObjectFindAccessTest, Array)
+{
+    json j_nonarray(json::value_t::array);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_EQ(j_nonarray.find("foo"), j_nonarray.end());
+    EXPECT_EQ(j_nonarray_const.find("foo"), j_nonarray_const.end());
+}
+
+TEST(JsonElementNonObjectFindAccessTest, Boolean)
+{
+    json j_nonarray(json::value_t::boolean);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_EQ(j_nonarray.find("foo"), j_nonarray.end());
+    EXPECT_EQ(j_nonarray_const.find("foo"), j_nonarray_const.end());
+}
+
+TEST(JsonElementNonObjectFindAccessTest, Integer)
+{
+    json j_nonarray(json::value_t::number_integer);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_EQ(j_nonarray.find("foo"), j_nonarray.end());
+    EXPECT_EQ(j_nonarray_const.find("foo"), j_nonarray_const.end());
+}
+
+TEST(JsonElementNonObjectFindAccessTest, Unsigned)
+{
+    json j_nonarray(json::value_t::number_unsigned);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_EQ(j_nonarray.find("foo"), j_nonarray.end());
+    EXPECT_EQ(j_nonarray_const.find("foo"), j_nonarray_const.end());
+}
+
+TEST(JsonElementNonObjectFindAccessTest, Float)
+{
+    json j_nonarray(json::value_t::number_float);
+    const json j_nonarray_const(j_nonarray);
+    EXPECT_EQ(j_nonarray.find("foo"), j_nonarray.end());
+    EXPECT_EQ(j_nonarray_const.find("foo"), j_nonarray_const.end());
+}
+
+TEST_F(JsonElementObjectAccessTest, CountExist)
+{
+    for (auto key :
+            {"integer", "unsigned", "floating", "null", "string", "boolean", "object", "array"
+            })
+    {
+        EXPECT_EQ(j.count(key), 1u);
+        EXPECT_EQ(j_const.count(key), 1u);
+    }
+}
+
+TEST_F(JsonElementObjectAccessTest, CountNotExist)
+{
+    EXPECT_EQ(j.count("foo"), 0u);
+    EXPECT_EQ(j_const.count("foo"), 0u);
+}
+
+TEST(JsonElementNonObjectCountAccessTest, Null)
+{
+    json j_nonobject(json::value_t::null);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_EQ(j_nonobject.count("foo"), 0u);
+    EXPECT_EQ(j_nonobject_const.count("foo"), 0u);
+}
+
+TEST(JsonElementNonObjectCountAccessTest, String)
+{
+    json j_nonobject(json::value_t::string);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_EQ(j_nonobject.count("foo"), 0u);
+    EXPECT_EQ(j_nonobject_const.count("foo"), 0u);
+}
+
+TEST(JsonElementNonObjectCountAccessTest, Object)
+{
+    json j_nonobject(json::value_t::object);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_EQ(j_nonobject.count("foo"), 0u);
+    EXPECT_EQ(j_nonobject_const.count("foo"), 0u);
+}
+
+TEST(JsonElementNonObjectCountAccessTest, Array)
+{
+    json j_nonobject(json::value_t::array);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_EQ(j_nonobject.count("foo"), 0u);
+    EXPECT_EQ(j_nonobject_const.count("foo"), 0u);
+}
+
+TEST(JsonElementNonObjectCountAccessTest, Boolean)
+{
+    json j_nonobject(json::value_t::boolean);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_EQ(j_nonobject.count("foo"), 0u);
+    EXPECT_EQ(j_nonobject_const.count("foo"), 0u);
+}
+
+TEST(JsonElementNonObjectCountAccessTest, Integer)
+{
+    json j_nonobject(json::value_t::number_integer);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_EQ(j_nonobject.count("foo"), 0u);
+    EXPECT_EQ(j_nonobject_const.count("foo"), 0u);
+}
+
+TEST(JsonElementNonObjectCountAccessTest, Unsigned)
+{
+    json j_nonobject(json::value_t::number_unsigned);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_EQ(j_nonobject.count("foo"), 0u);
+    EXPECT_EQ(j_nonobject_const.count("foo"), 0u);
+}
+
+TEST(JsonElementNonObjectCountAccessTest, Float)
+{
+    json j_nonobject(json::value_t::number_float);
+    const json j_nonobject_const(j_nonobject);
+    EXPECT_EQ(j_nonobject.count("foo"), 0u);
+    EXPECT_EQ(j_nonobject_const.count("foo"), 0u);
+}
+
+TEST_F(JsonElementObjectAccessTest, PointerValueNotExist)
+{
+    EXPECT_EQ(j.value("/not/existing"_json_pointer, 2), 2);
+    EXPECT_EQ(j.value("/not/existing"_json_pointer, 2u), 2u);
+    EXPECT_EQ(j.value("/not/existing"_json_pointer, false), false);
+    EXPECT_EQ(j.value("/not/existing"_json_pointer, "bar"), "bar");
+    EXPECT_LT(std::fabs(j.value("/not/existing"_json_pointer, 12.34) - 12.34), 0.001);
+    EXPECT_EQ(j.value("/not/existing"_json_pointer, json({{"foo", "bar"}})), json({{"foo", "bar"}}));
+    EXPECT_EQ(j.value("/not/existing"_json_pointer, json({10, 100})), json({10, 100}));
+
+    EXPECT_EQ(j_const.value("/not/existing"_json_pointer, 2), 2);
+    EXPECT_EQ(j_const.value("/not/existing"_json_pointer, 2u), 2u);
+    EXPECT_EQ(j_const.value("/not/existing"_json_pointer, false), false);
+    EXPECT_EQ(j_const.value("/not/existing"_json_pointer, "bar"), "bar");
+    EXPECT_LT(std::fabs(j_const.value("/not/existing"_json_pointer, 12.34) - 12.34), 0.001);
+    EXPECT_EQ(j_const.value("/not/existing"_json_pointer, json({{"foo", "bar"}})), json({{"foo", "bar"}}));
+    EXPECT_EQ(j_const.value("/not/existing"_json_pointer, json({10, 100})), json({10, 100}));
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-inspection.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-inspection.cpp
new file mode 100644
index 0000000..79c63f0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-inspection.cpp
@@ -0,0 +1,385 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+TEST(JsonConvTypeCheckTest, Object)
+{
+    json j {{"foo", 1}, {"bar", false}};
+    EXPECT_FALSE(j.is_null());
+    EXPECT_FALSE(j.is_boolean());
+    EXPECT_FALSE(j.is_number());
+    EXPECT_FALSE(j.is_number_integer());
+    EXPECT_FALSE(j.is_number_unsigned());
+    EXPECT_FALSE(j.is_number_float());
+    EXPECT_TRUE(j.is_object());
+    EXPECT_FALSE(j.is_array());
+    EXPECT_FALSE(j.is_string());
+    EXPECT_FALSE(j.is_discarded());
+    EXPECT_FALSE(j.is_primitive());
+    EXPECT_TRUE(j.is_structured());
+}
+
+TEST(JsonConvTypeCheckTest, Array)
+{
+    json j {"foo", 1, 1u, 42.23, false};
+    EXPECT_FALSE(j.is_null());
+    EXPECT_FALSE(j.is_boolean());
+    EXPECT_FALSE(j.is_number());
+    EXPECT_FALSE(j.is_number_integer());
+    EXPECT_FALSE(j.is_number_unsigned());
+    EXPECT_FALSE(j.is_number_float());
+    EXPECT_FALSE(j.is_object());
+    EXPECT_TRUE(j.is_array());
+    EXPECT_FALSE(j.is_string());
+    EXPECT_FALSE(j.is_discarded());
+    EXPECT_FALSE(j.is_primitive());
+    EXPECT_TRUE(j.is_structured());
+}
+
+TEST(JsonConvTypeCheckTest, Null)
+{
+    json j(nullptr);
+    EXPECT_TRUE(j.is_null());
+    EXPECT_FALSE(j.is_boolean());
+    EXPECT_FALSE(j.is_number());
+    EXPECT_FALSE(j.is_number_integer());
+    EXPECT_FALSE(j.is_number_unsigned());
+    EXPECT_FALSE(j.is_number_float());
+    EXPECT_FALSE(j.is_object());
+    EXPECT_FALSE(j.is_array());
+    EXPECT_FALSE(j.is_string());
+    EXPECT_FALSE(j.is_discarded());
+    EXPECT_TRUE(j.is_primitive());
+    EXPECT_FALSE(j.is_structured());
+}
+
+TEST(JsonConvTypeCheckTest, Boolean)
+{
+    json j(true);
+    EXPECT_FALSE(j.is_null());
+    EXPECT_TRUE(j.is_boolean());
+    EXPECT_FALSE(j.is_number());
+    EXPECT_FALSE(j.is_number_integer());
+    EXPECT_FALSE(j.is_number_unsigned());
+    EXPECT_FALSE(j.is_number_float());
+    EXPECT_FALSE(j.is_object());
+    EXPECT_FALSE(j.is_array());
+    EXPECT_FALSE(j.is_string());
+    EXPECT_FALSE(j.is_discarded());
+    EXPECT_TRUE(j.is_primitive());
+    EXPECT_FALSE(j.is_structured());
+}
+
+TEST(JsonConvTypeCheckTest, String)
+{
+    json j("Hello world");
+    EXPECT_FALSE(j.is_null());
+    EXPECT_FALSE(j.is_boolean());
+    EXPECT_FALSE(j.is_number());
+    EXPECT_FALSE(j.is_number_integer());
+    EXPECT_FALSE(j.is_number_unsigned());
+    EXPECT_FALSE(j.is_number_float());
+    EXPECT_FALSE(j.is_object());
+    EXPECT_FALSE(j.is_array());
+    EXPECT_TRUE(j.is_string());
+    EXPECT_FALSE(j.is_discarded());
+    EXPECT_TRUE(j.is_primitive());
+    EXPECT_FALSE(j.is_structured());
+}
+
+TEST(JsonConvTypeCheckTest, Integer)
+{
+    json j(42);
+    EXPECT_FALSE(j.is_null());
+    EXPECT_FALSE(j.is_boolean());
+    EXPECT_TRUE(j.is_number());
+    EXPECT_TRUE(j.is_number_integer());
+    EXPECT_FALSE(j.is_number_unsigned());
+    EXPECT_FALSE(j.is_number_float());
+    EXPECT_FALSE(j.is_object());
+    EXPECT_FALSE(j.is_array());
+    EXPECT_FALSE(j.is_string());
+    EXPECT_FALSE(j.is_discarded());
+    EXPECT_TRUE(j.is_primitive());
+    EXPECT_FALSE(j.is_structured());
+}
+
+TEST(JsonConvTypeCheckTest, Unsigned)
+{
+    json j(42u);
+    EXPECT_FALSE(j.is_null());
+    EXPECT_FALSE(j.is_boolean());
+    EXPECT_TRUE(j.is_number());
+    EXPECT_TRUE(j.is_number_integer());
+    EXPECT_TRUE(j.is_number_unsigned());
+    EXPECT_FALSE(j.is_number_float());
+    EXPECT_FALSE(j.is_object());
+    EXPECT_FALSE(j.is_array());
+    EXPECT_FALSE(j.is_string());
+    EXPECT_FALSE(j.is_discarded());
+    EXPECT_TRUE(j.is_primitive());
+    EXPECT_FALSE(j.is_structured());
+}
+
+TEST(JsonConvTypeCheckTest, Float)
+{
+    json j(42.23);
+    EXPECT_FALSE(j.is_null());
+    EXPECT_FALSE(j.is_boolean());
+    EXPECT_TRUE(j.is_number());
+    EXPECT_FALSE(j.is_number_integer());
+    EXPECT_FALSE(j.is_number_unsigned());
+    EXPECT_TRUE(j.is_number_float());
+    EXPECT_FALSE(j.is_object());
+    EXPECT_FALSE(j.is_array());
+    EXPECT_FALSE(j.is_string());
+    EXPECT_FALSE(j.is_discarded());
+    EXPECT_TRUE(j.is_primitive());
+    EXPECT_FALSE(j.is_structured());
+}
+
+TEST(JsonConvTypeCheckTest, Discarded)
+{
+    json j(json::value_t::discarded);
+    EXPECT_FALSE(j.is_null());
+    EXPECT_FALSE(j.is_boolean());
+    EXPECT_FALSE(j.is_number());
+    EXPECT_FALSE(j.is_number_integer());
+    EXPECT_FALSE(j.is_number_unsigned());
+    EXPECT_FALSE(j.is_number_float());
+    EXPECT_FALSE(j.is_object());
+    EXPECT_FALSE(j.is_array());
+    EXPECT_FALSE(j.is_string());
+    EXPECT_TRUE(j.is_discarded());
+    EXPECT_FALSE(j.is_primitive());
+    EXPECT_FALSE(j.is_structured());
+}
+
+class JsonConvSerializationTest : public ::testing::Test {
+ protected:
+    json j {{"object", json::object()}, {"array", {1, 2, 3, 4}}, {"number", 42}, {"boolean", false}, {"null", nullptr}, {"string", "Hello world"} };
+};
+#if 0
+// no indent / indent=-1
+TEST_F(JsonConvSerializationTest, NoIndent)
+{
+    EXPECT_EQ(j.dump(),
+          "{\"array\":[1,2,3,4],\"boolean\":false,\"null\":null,\"number\":42,\"object\":{},\"string\":\"Hello world\"}");
+
+    EXPECT_EQ(j.dump(), j.dump(-1));
+}
+
+// indent=0
+TEST_F(JsonConvSerializationTest, Indent0)
+{
+    EXPECT_EQ(j.dump(0),
+          "{\n\"array\": [\n1,\n2,\n3,\n4\n],\n\"boolean\": false,\n\"null\": null,\n\"number\": 42,\n\"object\": {},\n\"string\": \"Hello world\"\n}");
+}
+
+// indent=1, space='\t'
+TEST_F(JsonConvSerializationTest, Indent1)
+{
+    EXPECT_EQ(j.dump(1, '\t'),
+          "{\n\t\"array\": [\n\t\t1,\n\t\t2,\n\t\t3,\n\t\t4\n\t],\n\t\"boolean\": false,\n\t\"null\": null,\n\t\"number\": 42,\n\t\"object\": {},\n\t\"string\": \"Hello world\"\n}");
+}
+
+// indent=4
+TEST_F(JsonConvSerializationTest, Indent4)
+{
+    EXPECT_EQ(j.dump(4),
+          "{\n    \"array\": [\n        1,\n        2,\n        3,\n        4\n    ],\n    \"boolean\": false,\n    \"null\": null,\n    \"number\": 42,\n    \"object\": {},\n    \"string\": \"Hello world\"\n}");
+}
+#endif
+// indent=x
+TEST_F(JsonConvSerializationTest, IndentX)
+{
+    EXPECT_EQ(j.dump().size(), 94u);
+    EXPECT_EQ(j.dump(1).size(), 127u);
+    EXPECT_EQ(j.dump(2).size(), 142u);
+    EXPECT_EQ(j.dump(512).size(), 7792u);
+}
+
+// dump and floating-point numbers
+TEST_F(JsonConvSerializationTest, Float)
+{
+    auto s = json(42.23).dump();
+    EXPECT_NE(s.find("42.23"), std::string::npos);
+}
+
+// dump and small floating-point numbers
+TEST_F(JsonConvSerializationTest, SmallFloat)
+{
+    auto s = json(1.23456e-78).dump();
+    EXPECT_NE(s.find("1.23456e-78"), std::string::npos);
+}
+
+// dump and non-ASCII characters
+TEST_F(JsonConvSerializationTest, NonAscii)
+{
+    EXPECT_EQ(json("ä").dump(), "\"ä\"");
+    EXPECT_EQ(json("Ö").dump(), "\"Ö\"");
+    EXPECT_EQ(json("❤️").dump(), "\"❤️\"");
+}
+
+// serialization of discarded element
+TEST_F(JsonConvSerializationTest, Discarded)
+{
+    json j_discarded(json::value_t::discarded);
+    EXPECT_EQ(j_discarded.dump(), "<discarded>");
+}
+
+TEST(JsonConvRoundTripTest, Case)
+{
+    for (const auto& s :
+{"3.141592653589793", "1000000000000000010E5"
+})
+    {
+        SCOPED_TRACE(s);
+        json j1 = json::parse(s);
+        std::string s1 = j1.dump();
+        json j2 = json::parse(s1);
+        std::string s2 = j2.dump();
+        EXPECT_EQ(s1, s2);
+    }
+}
+
+// return the type of the object (explicit)
+TEST(JsonConvTypeExplicitTest, Null)
+{
+    json j = nullptr;
+    EXPECT_EQ(j.type(), json::value_t::null);
+}
+
+TEST(JsonConvTypeExplicitTest, Object)
+{
+    json j = {{"foo", "bar"}};
+    EXPECT_EQ(j.type(), json::value_t::object);
+}
+
+TEST(JsonConvTypeExplicitTest, Array)
+{
+    json j = {1, 2, 3, 4};
+    EXPECT_EQ(j.type(), json::value_t::array);
+}
+
+TEST(JsonConvTypeExplicitTest, Boolean)
+{
+    json j = true;
+    EXPECT_EQ(j.type(), json::value_t::boolean);
+}
+
+TEST(JsonConvTypeExplicitTest, String)
+{
+    json j = "Hello world";
+    EXPECT_EQ(j.type(), json::value_t::string);
+}
+
+TEST(JsonConvTypeExplicitTest, Integer)
+{
+    json j = 23;
+    EXPECT_EQ(j.type(), json::value_t::number_integer);
+}
+
+TEST(JsonConvTypeExplicitTest, Unsigned)
+{
+    json j = 23u;
+    EXPECT_EQ(j.type(), json::value_t::number_unsigned);
+}
+
+TEST(JsonConvTypeExplicitTest, Float)
+{
+    json j = 42.23;
+    EXPECT_EQ(j.type(), json::value_t::number_float);
+}
+
+// return the type of the object (implicit)
+TEST(JsonConvTypeImplicitTest, Null)
+{
+    json j = nullptr;
+    json::value_t t = j;
+    EXPECT_EQ(t, j.type());
+}
+
+TEST(JsonConvTypeImplicitTest, Object)
+{
+    json j = {{"foo", "bar"}};
+    json::value_t t = j;
+    EXPECT_EQ(t, j.type());
+}
+
+TEST(JsonConvTypeImplicitTest, Array)
+{
+    json j = {1, 2, 3, 4};
+    json::value_t t = j;
+    EXPECT_EQ(t, j.type());
+}
+
+TEST(JsonConvTypeImplicitTest, Boolean)
+{
+    json j = true;
+    json::value_t t = j;
+    EXPECT_EQ(t, j.type());
+}
+
+TEST(JsonConvTypeImplicitTest, String)
+{
+    json j = "Hello world";
+    json::value_t t = j;
+    EXPECT_EQ(t, j.type());
+}
+
+TEST(JsonConvTypeImplicitTest, Integer)
+{
+    json j = 23;
+    json::value_t t = j;
+    EXPECT_EQ(t, j.type());
+}
+
+TEST(JsonConvTypeImplicitTest, Unsigned)
+{
+    json j = 23u;
+    json::value_t t = j;
+    EXPECT_EQ(t, j.type());
+}
+
+TEST(JsonConvTypeImplicitTest, Float)
+{
+    json j = 42.23;
+    json::value_t t = j;
+    EXPECT_EQ(t, j.type());
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-iterators1.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-iterators1.cpp
new file mode 100644
index 0000000..bae3862
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-iterators1.cpp
@@ -0,0 +1,1617 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+using wpi::JsonTest;
+
+TEST(JsonIteratorBasicTest, Uninitialized)
+{
+    json::iterator it;
+    EXPECT_EQ(JsonTest::GetObject(it), nullptr);
+
+    json::const_iterator cit;
+    EXPECT_EQ(JsonTest::GetObject(cit), nullptr);
+}
+
+class JsonIteratorBooleanTest : public ::testing::Test {
+ public:
+    JsonIteratorBooleanTest() : j_const(j) {}
+
+ protected:
+    json j = true;
+    json j_const;
+};
+
+TEST_F(JsonIteratorBooleanTest, BeginEnd)
+{
+    json::iterator it = j.begin();
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    it--;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    --it;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorBooleanTest, ConstBeginEnd)
+{
+    json::const_iterator it = j_const.begin();
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    it--;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    --it;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+}
+
+TEST_F(JsonIteratorBooleanTest, CBeginEnd)
+{
+    json::const_iterator it = j.cbegin();
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    it--;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    --it;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorBooleanTest, ConstCBeginEnd)
+{
+    json::const_iterator it = j_const.cbegin();
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    it--;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    --it;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+}
+#if 0
+TEST_F(JsonIteratorBooleanTest, RBeginEnd)
+{
+    json::reverse_iterator it = j.rbegin();
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    it--;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    --it;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorBooleanTest, CRBeginEnd)
+{
+    json::const_reverse_iterator it = j.crbegin();
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    it--;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    --it;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorBooleanTest, ConstCRBeginEnd)
+{
+    json::const_reverse_iterator it = j_const.crbegin();
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    it--;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    --it;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+}
+#endif
+TEST_F(JsonIteratorBooleanTest, KeyValue)
+{
+    auto it = j.begin();
+    auto cit = j_const.cbegin();
+    EXPECT_THROW_MSG(it.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(it.value(), json(true));
+    EXPECT_THROW_MSG(cit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(cit.value(), json(true));
+#if 0
+    auto rit = j.rend();
+    auto crit = j.crend();
+    EXPECT_THROW_MSG(rit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(rit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(crit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(crit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+#endif
+}
+
+class JsonIteratorStringTest : public ::testing::Test {
+ public:
+    JsonIteratorStringTest() : j_const(j) {}
+
+ protected:
+    json j = "hello world";
+    json j_const;
+};
+
+TEST_F(JsonIteratorStringTest, BeginEnd)
+{
+    json::iterator it = j.begin();
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    it--;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    --it;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorStringTest, ConstBeginEnd)
+{
+    json::const_iterator it = j_const.begin();
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    it--;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    --it;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+}
+
+TEST_F(JsonIteratorStringTest, CBeginEnd)
+{
+    json::const_iterator it = j.cbegin();
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    it--;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    --it;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorStringTest, ConstCBeginEnd)
+{
+    json::const_iterator it = j_const.cbegin();
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    it--;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    --it;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+}
+#if 0
+TEST_F(JsonIteratorStringTest, RBeginEnd)
+{
+    json::reverse_iterator it = j.rbegin();
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    it--;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    --it;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorStringTest, CRBeginEnd)
+{
+    json::const_reverse_iterator it = j.crbegin();
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    it--;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    --it;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorStringTest, ConstCRBeginEnd)
+{
+    json::const_reverse_iterator it = j_const.crbegin();
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    it--;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    --it;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+}
+#endif
+TEST_F(JsonIteratorStringTest, KeyValue)
+{
+    auto it = j.begin();
+    auto cit = j_const.cbegin();
+    EXPECT_THROW_MSG(it.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(it.value(), json("hello world"));
+    EXPECT_THROW_MSG(cit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(cit.value(), json("hello world"));
+#if 0
+    auto rit = j.rend();
+    auto crit = j.crend();
+    EXPECT_THROW_MSG(rit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(rit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(crit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(crit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+#endif
+}
+
+class JsonIteratorArrayTest : public ::testing::Test {
+ public:
+    JsonIteratorArrayTest() : j_const(j) {}
+
+ protected:
+    json j = {1, 2, 3};
+    json j_const;
+};
+
+TEST_F(JsonIteratorArrayTest, BeginEnd)
+{
+    json::iterator it_begin = j.begin();
+    json::iterator it_end = j.end();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[0]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[1]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[2]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorArrayTest, ConstBeginEnd)
+{
+    json::const_iterator it_begin = j_const.begin();
+    json::const_iterator it_end = j_const.end();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const[0]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const[1]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const[2]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorArrayTest, CBeginEnd)
+{
+    json::const_iterator it_begin = j.cbegin();
+    json::const_iterator it_end = j.cend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[0]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[1]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[2]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorArrayTest, ConstCBeginEnd)
+{
+    json::const_iterator it_begin = j_const.cbegin();
+    json::const_iterator it_end = j_const.cend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[0]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[1]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[2]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+#if 0
+TEST_F(JsonIteratorArrayTest, RBeginEnd)
+{
+    json::reverse_iterator it_begin = j.rbegin();
+    json::reverse_iterator it_end = j.rend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[2]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[1]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[0]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorArrayTest, CRBeginEnd)
+{
+    json::const_reverse_iterator it_begin = j.crbegin();
+    json::const_reverse_iterator it_end = j.crend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[2]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[1]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[0]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorArrayTest, ConstCRBeginEnd)
+{
+    json::const_reverse_iterator it_begin = j_const.crbegin();
+    json::const_reverse_iterator it_end = j_const.crend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[2]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[1]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j[0]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+#endif
+TEST_F(JsonIteratorArrayTest, KeyValue)
+{
+    auto it = j.begin();
+    auto cit = j_const.cbegin();
+    EXPECT_THROW_MSG(it.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(it.value(), json(1));
+    EXPECT_THROW_MSG(cit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(cit.value(), json(1));
+}
+
+class JsonIteratorObjectTest : public ::testing::Test {
+ public:
+    JsonIteratorObjectTest() : j_const(j) {}
+
+ protected:
+    json j = {{"A", 1}, {"B", 2}, {"C", 3}};
+    json j_const;
+};
+
+TEST_F(JsonIteratorObjectTest, BeginEnd)
+{
+    json::iterator it_begin = j.begin();
+    json::iterator it_end = j.end();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["A"]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["B"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["C"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorObjectTest, ConstBeginEnd)
+{
+    json::const_iterator it_begin = j_const.begin();
+    json::const_iterator it_end = j_const.end();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const["A"]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const["B"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const["C"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorObjectTest, CBeginEnd)
+{
+    json::const_iterator it_begin = j.cbegin();
+    json::const_iterator it_end = j.cend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["A"]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["B"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["C"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorObjectTest, ConstCBeginEnd)
+{
+    json::const_iterator it_begin = j_const.cbegin();
+    json::const_iterator it_end = j_const.cend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const["A"]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const["B"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j_const["C"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+#if 0
+TEST_F(JsonIteratorObjectTest, RBeginEnd)
+{
+    json::reverse_iterator it_begin = j.rbegin();
+    json::reverse_iterator it_end = j.rend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["C"]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["B"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["A"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorObjectTest, CRBeginEnd)
+{
+    json::const_reverse_iterator it_begin = j.crbegin();
+    json::const_reverse_iterator it_end = j.crend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["C"]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["B"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["A"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+
+TEST_F(JsonIteratorObjectTest, ConstCRBeginEnd)
+{
+    json::const_reverse_iterator it_begin = j_const.crbegin();
+    json::const_reverse_iterator it_end = j_const.crend();
+
+    auto it = it_begin;
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["C"]);
+
+    it++;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["B"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_NE(it, it_end);
+    EXPECT_EQ(*it, j["A"]);
+
+    ++it;
+    EXPECT_NE(it, it_begin);
+    EXPECT_EQ(it, it_end);
+}
+#endif
+
+TEST_F(JsonIteratorObjectTest, KeyValue)
+{
+    auto it = j.begin();
+    auto cit = j_const.cbegin();
+    EXPECT_EQ(it.key(), "A");
+    EXPECT_EQ(it.value(), json(1));
+    EXPECT_EQ(cit.key(), "A");
+    EXPECT_EQ(cit.value(), json(1));
+}
+
+class JsonIteratorIntegerTest : public ::testing::Test {
+ public:
+    JsonIteratorIntegerTest() : j_const(j) {}
+
+ protected:
+    json j = 23;
+    json j_const;
+};
+
+TEST_F(JsonIteratorIntegerTest, BeginEnd)
+{
+    json::iterator it = j.begin();
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    it--;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    --it;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorIntegerTest, ConstBeginEnd)
+{
+    json::const_iterator it = j_const.begin();
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    it--;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    --it;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+}
+
+TEST_F(JsonIteratorIntegerTest, CBeginEnd)
+{
+    json::const_iterator it = j.cbegin();
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    it--;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    --it;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorIntegerTest, ConstCBeginEnd)
+{
+    json::const_iterator it = j_const.cbegin();
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    it--;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    --it;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+}
+#if 0
+TEST_F(JsonIteratorIntegerTest, RBeginEnd)
+{
+    json::reverse_iterator it = j.rbegin();
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    it--;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    --it;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorIntegerTest, CRBeginEnd)
+{
+    json::const_reverse_iterator it = j.crbegin();
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    it--;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    --it;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorIntegerTest, ConstCRBeginEnd)
+{
+    json::const_reverse_iterator it = j_const.crbegin();
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    it--;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    --it;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+}
+#endif
+TEST_F(JsonIteratorIntegerTest, KeyValue)
+{
+    auto it = j.begin();
+    auto cit = j_const.cbegin();
+    EXPECT_THROW_MSG(it.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(it.value(), json(23));
+    EXPECT_THROW_MSG(cit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(cit.value(), json(23));
+#if 0
+    auto rit = j.rend();
+    auto crit = j.crend();
+    EXPECT_THROW_MSG(rit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(rit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(crit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(crit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+#endif
+}
+
+class JsonIteratorUnsignedTest : public ::testing::Test {
+ public:
+    JsonIteratorUnsignedTest() : j_const(j) {}
+
+ protected:
+    json j = 23u;
+    json j_const;
+};
+
+TEST_F(JsonIteratorUnsignedTest, BeginEnd)
+{
+    json::iterator it = j.begin();
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    it--;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    --it;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorUnsignedTest, ConstBeginEnd)
+{
+    json::const_iterator it = j_const.begin();
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    it--;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    --it;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+}
+
+TEST_F(JsonIteratorUnsignedTest, CBeginEnd)
+{
+    json::const_iterator it = j.cbegin();
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    it--;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    --it;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorUnsignedTest, ConstCBeginEnd)
+{
+    json::const_iterator it = j_const.cbegin();
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    it--;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    --it;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+}
+#if 0
+TEST_F(JsonIteratorUnsignedTest, RBeginEnd)
+{
+    json::reverse_iterator it = j.rbegin();
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    it--;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    --it;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorUnsignedTest, CRBeginEnd)
+{
+    json::const_reverse_iterator it = j.crbegin();
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    it--;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    --it;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorUnsignedTest, ConstCRBeginEnd)
+{
+    json::const_reverse_iterator it = j_const.crbegin();
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    it--;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    --it;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+}
+#endif
+TEST_F(JsonIteratorUnsignedTest, KeyValue)
+{
+    auto it = j.begin();
+    auto cit = j_const.cbegin();
+    EXPECT_THROW_MSG(it.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(it.value(), json(23));
+    EXPECT_THROW_MSG(cit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(cit.value(), json(23));
+#if 0
+    auto rit = j.rend();
+    auto crit = j.crend();
+    EXPECT_THROW_MSG(rit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(rit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(crit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(crit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+#endif
+}
+
+class JsonIteratorFloatTest : public ::testing::Test {
+ public:
+    JsonIteratorFloatTest() : j_const(j) {}
+
+ protected:
+    json j = 23.42;
+    json j_const;
+};
+
+TEST_F(JsonIteratorFloatTest, BeginEnd)
+{
+    json::iterator it = j.begin();
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    it--;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.begin());
+    EXPECT_EQ(it, j.end());
+
+    --it;
+    EXPECT_EQ(it, j.begin());
+    EXPECT_NE(it, j.end());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorFloatTest, ConstBeginEnd)
+{
+    json::const_iterator it = j_const.begin();
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    it--;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.begin());
+    EXPECT_EQ(it, j_const.end());
+
+    --it;
+    EXPECT_EQ(it, j_const.begin());
+    EXPECT_NE(it, j_const.end());
+    EXPECT_EQ(*it, j_const);
+}
+
+TEST_F(JsonIteratorFloatTest, CBeginEnd)
+{
+    json::const_iterator it = j.cbegin();
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    it--;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.cbegin());
+    EXPECT_EQ(it, j.cend());
+
+    --it;
+    EXPECT_EQ(it, j.cbegin());
+    EXPECT_NE(it, j.cend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorFloatTest, ConstCBeginEnd)
+{
+    json::const_iterator it = j_const.cbegin();
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    it--;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.cbegin());
+    EXPECT_EQ(it, j_const.cend());
+
+    --it;
+    EXPECT_EQ(it, j_const.cbegin());
+    EXPECT_NE(it, j_const.cend());
+    EXPECT_EQ(*it, j_const);
+}
+#if 0
+TEST_F(JsonIteratorFloatTest, RBeginEnd)
+{
+    json::reverse_iterator it = j.rbegin();
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    it--;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.rbegin());
+    EXPECT_EQ(it, j.rend());
+
+    --it;
+    EXPECT_EQ(it, j.rbegin());
+    EXPECT_NE(it, j.rend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorFloatTest, CRBeginEnd)
+{
+    json::const_reverse_iterator it = j.crbegin();
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    it++;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    it--;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+
+    ++it;
+    EXPECT_NE(it, j.crbegin());
+    EXPECT_EQ(it, j.crend());
+
+    --it;
+    EXPECT_EQ(it, j.crbegin());
+    EXPECT_NE(it, j.crend());
+    EXPECT_EQ(*it, j);
+}
+
+TEST_F(JsonIteratorFloatTest, ConstCRBeginEnd)
+{
+    json::const_reverse_iterator it = j_const.crbegin();
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    it++;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    it--;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+
+    ++it;
+    EXPECT_NE(it, j_const.crbegin());
+    EXPECT_EQ(it, j_const.crend());
+
+    --it;
+    EXPECT_EQ(it, j_const.crbegin());
+    EXPECT_NE(it, j_const.crend());
+    EXPECT_EQ(*it, j_const);
+}
+#endif
+TEST_F(JsonIteratorFloatTest, KeyValue)
+{
+    auto it = j.begin();
+    auto cit = j_const.cbegin();
+    EXPECT_THROW_MSG(it.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(it.value(), json(23.42));
+    EXPECT_THROW_MSG(cit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_EQ(cit.value(), json(23.42));
+#if 0
+    auto rit = j.rend();
+    auto crit = j.crend();
+    EXPECT_THROW_MSG(rit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(rit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(crit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(crit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+#endif
+}
+
+class JsonIteratorNullTest : public ::testing::Test {
+ public:
+    JsonIteratorNullTest() : j_const(j) {}
+
+ protected:
+    json j = nullptr;
+    json j_const;
+};
+
+TEST_F(JsonIteratorNullTest, BeginEnd)
+{
+    json::iterator it = j.begin();
+    EXPECT_EQ(it, j.end());
+}
+
+TEST_F(JsonIteratorNullTest, ConstBeginEnd)
+{
+    json::const_iterator it_begin = j_const.begin();
+    json::const_iterator it_end = j_const.end();
+    EXPECT_EQ(it_begin, it_end);
+}
+
+TEST_F(JsonIteratorNullTest, CBeginEnd)
+{
+    json::const_iterator it_begin = j.cbegin();
+    json::const_iterator it_end = j.cend();
+    EXPECT_EQ(it_begin, it_end);
+}
+
+TEST_F(JsonIteratorNullTest, ConstCBeginEnd)
+{
+    json::const_iterator it_begin = j_const.cbegin();
+    json::const_iterator it_end = j_const.cend();
+    EXPECT_EQ(it_begin, it_end);
+}
+#if 0
+TEST_F(JsonIteratorNullTest, RBeginEnd)
+{
+    json::reverse_iterator it = j.rbegin();
+    EXPECT_EQ(it, j.rend());
+}
+
+TEST_F(JsonIteratorNullTest, CRBeginEnd)
+{
+    json::const_reverse_iterator it = j.crbegin();
+    EXPECT_EQ(it, j.crend());
+}
+
+TEST_F(JsonIteratorNullTest, ConstCRBeginEnd)
+{
+    json::const_reverse_iterator it = j_const.crbegin();
+    EXPECT_EQ(it, j_const.crend());
+}
+#endif
+TEST_F(JsonIteratorNullTest, KeyValue)
+{
+    auto it = j.begin();
+    auto cit = j_const.cbegin();
+    EXPECT_THROW_MSG(it.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(it.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(cit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(cit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+#if 0
+    auto rit = j.rend();
+    auto crit = j.crend();
+    EXPECT_THROW_MSG(rit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(rit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(crit.key(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.207] cannot use key() for non-object iterators");
+    EXPECT_THROW_MSG(crit.value(), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+#endif
+}
+
+TEST(JsonIteratorConstConversionTest, Boolean)
+{
+    json j = true;
+    json::const_iterator it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+    it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+}
+
+TEST(JsonIteratorConstConversionTest, String)
+{
+    json j = "hello world";
+    json::const_iterator it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+    it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+}
+
+TEST(JsonIteratorConstConversionTest, Array)
+{
+    json j = {1, 2, 3};
+    json::const_iterator it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+    it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+}
+
+TEST(JsonIteratorConstConversionTest, Object)
+{
+    json j = {{"A", 1}, {"B", 2}, {"C", 3}};
+    json::const_iterator it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+    it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+}
+
+TEST(JsonIteratorConstConversionTest, Integer)
+{
+    json j = 23;
+    json::const_iterator it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+    it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+}
+
+TEST(JsonIteratorConstConversionTest, Unsigned)
+{
+    json j = 23u;
+    json::const_iterator it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+    it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+}
+
+TEST(JsonIteratorConstConversionTest, Float)
+{
+    json j = 23.42;
+    json::const_iterator it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+    it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+}
+
+TEST(JsonIteratorConstConversionTest, Null)
+{
+    json j = nullptr;
+    json::const_iterator it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+    it = j.begin();
+    EXPECT_EQ(it, j.cbegin());
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-iterators2.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-iterators2.cpp
new file mode 100644
index 0000000..69a4dac
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-iterators2.cpp
@@ -0,0 +1,899 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+TEST(JsonIteratorTest, Comparisons)
+{
+    json j_values = {nullptr, true, 42, 42u, 23.23, {{"one", 1}, {"two", 2}}, {1, 2, 3, 4, 5}, "Hello, world"};
+
+    for (json& j : j_values)
+    {
+        SCOPED_TRACE(j.dump());
+        auto it1 = j.begin();
+        auto it2 = j.begin();
+        auto it3 = j.begin();
+        ++it2;
+        ++it3;
+        ++it3;
+        auto it1_c = j.cbegin();
+        auto it2_c = j.cbegin();
+        auto it3_c = j.cbegin();
+        ++it2_c;
+        ++it3_c;
+        ++it3_c;
+
+        // comparison: equal
+        {
+            EXPECT_TRUE(it1 == it1);
+            EXPECT_FALSE(it1 == it2);
+            EXPECT_FALSE(it1 == it3);
+            EXPECT_FALSE(it2 == it3);
+            EXPECT_TRUE(it1_c == it1_c);
+            EXPECT_FALSE(it1_c == it2_c);
+            EXPECT_FALSE(it1_c == it3_c);
+            EXPECT_FALSE(it2_c == it3_c);
+        }
+
+        // comparison: not equal
+        {
+            // check definition
+            EXPECT_EQ( (it1 != it1), !(it1 == it1) );
+            EXPECT_EQ( (it1 != it2), !(it1 == it2) );
+            EXPECT_EQ( (it1 != it3), !(it1 == it3) );
+            EXPECT_EQ( (it2 != it3), !(it2 == it3) );
+            EXPECT_EQ( (it1_c != it1_c), !(it1_c == it1_c) );
+            EXPECT_EQ( (it1_c != it2_c), !(it1_c == it2_c) );
+            EXPECT_EQ( (it1_c != it3_c), !(it1_c == it3_c) );
+            EXPECT_EQ( (it2_c != it3_c), !(it2_c == it3_c) );
+        }
+
+        // comparison: smaller
+        {
+            if (j.type() == json::value_t::object)
+            {
+                EXPECT_THROW_MSG(it1 < it1, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 < it2, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2 < it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 < it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c < it1_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c < it2_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2_c < it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c < it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+            }
+            else
+            {
+                EXPECT_FALSE(it1 < it1);
+                EXPECT_TRUE(it1 < it2);
+                EXPECT_TRUE(it1 < it3);
+                EXPECT_TRUE(it2 < it3);
+                EXPECT_FALSE(it1_c < it1_c);
+                EXPECT_TRUE(it1_c < it2_c);
+                EXPECT_TRUE(it1_c < it3_c);
+                EXPECT_TRUE(it2_c < it3_c);
+            }
+        }
+
+        // comparison: less than or equal
+        {
+            if (j.type() == json::value_t::object)
+            {
+                EXPECT_THROW_MSG(it1 <= it1, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 <= it2, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2 <= it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 <= it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c <= it1_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c <= it2_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2_c <= it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c <= it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+            }
+            else
+            {
+                // check definition
+                EXPECT_EQ( (it1 <= it1), !(it1 < it1) );
+                EXPECT_EQ( (it1 <= it2), !(it2 < it1) );
+                EXPECT_EQ( (it1 <= it3), !(it3 < it1) );
+                EXPECT_EQ( (it2 <= it3), !(it3 < it2) );
+                EXPECT_EQ( (it1_c <= it1_c), !(it1_c < it1_c) );
+                EXPECT_EQ( (it1_c <= it2_c), !(it2_c < it1_c) );
+                EXPECT_EQ( (it1_c <= it3_c), !(it3_c < it1_c) );
+                EXPECT_EQ( (it2_c <= it3_c), !(it3_c < it2_c) );
+            }
+        }
+
+        // comparison: greater than
+        {
+            if (j.type() == json::value_t::object)
+            {
+                EXPECT_THROW_MSG(it1 > it1, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 > it2, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2 > it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 > it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c > it1_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c > it2_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2_c > it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c > it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+            }
+            else
+            {
+                // check definition
+                EXPECT_EQ( (it1 > it1), (it1 < it1) );
+                EXPECT_EQ( (it1 > it2), (it2 < it1) );
+                EXPECT_EQ( (it1 > it3), (it3 < it1) );
+                EXPECT_EQ( (it2 > it3), (it3 < it2) );
+                EXPECT_EQ( (it1_c > it1_c), (it1_c < it1_c) );
+                EXPECT_EQ( (it1_c > it2_c), (it2_c < it1_c) );
+                EXPECT_EQ( (it1_c > it3_c), (it3_c < it1_c) );
+                EXPECT_EQ( (it2_c > it3_c), (it3_c < it2_c) );
+            }
+        }
+
+        // comparison: greater than or equal
+        {
+            if (j.type() == json::value_t::object)
+            {
+                EXPECT_THROW_MSG(it1 >= it1, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 >= it2, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2 >= it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 >= it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c >= it1_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c >= it2_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2_c >= it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c >= it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+            }
+            else
+            {
+                // check definition
+                EXPECT_EQ( (it1 >= it1), !(it1 < it1) );
+                EXPECT_EQ( (it1 >= it2), !(it1 < it2) );
+                EXPECT_EQ( (it1 >= it3), !(it1 < it3) );
+                EXPECT_EQ( (it2 >= it3), !(it2 < it3) );
+                EXPECT_EQ( (it1_c >= it1_c), !(it1_c < it1_c) );
+                EXPECT_EQ( (it1_c >= it2_c), !(it1_c < it2_c) );
+                EXPECT_EQ( (it1_c >= it3_c), !(it1_c < it3_c) );
+                EXPECT_EQ( (it2_c >= it3_c), !(it2_c < it3_c) );
+            }
+        }
+    }
+
+    // check exceptions if different objects are compared
+    for (auto j : j_values)
+    {
+        for (auto k : j_values)
+        {
+            if (j != k)
+            {
+                EXPECT_THROW_MSG(j.begin() == k.begin(), json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.212] cannot compare iterators of different containers");
+                EXPECT_THROW_MSG(j.cbegin() == k.cbegin(), json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.212] cannot compare iterators of different containers");
+
+                EXPECT_THROW_MSG(j.begin() < k.begin(), json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.212] cannot compare iterators of different containers");
+                EXPECT_THROW_MSG(j.cbegin() < k.cbegin(), json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.212] cannot compare iterators of different containers");
+            }
+        }
+    }
+}
+
+class JsonIteratorArithmeticTest : public ::testing::Test {
+ protected:
+    json j_object = {{"one", 1}, {"two", 2}, {"three", 3}};
+    json j_array = {1, 2, 3, 4, 5, 6};
+    json j_null = nullptr;
+    json j_value = 42;
+};
+
+TEST_F(JsonIteratorArithmeticTest, AddSubObject)
+{
+    {
+        auto it = j_object.begin();
+        EXPECT_THROW_MSG(it += 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.cbegin();
+        EXPECT_THROW_MSG(it += 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.begin();
+        EXPECT_THROW_MSG(it + 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.cbegin();
+        EXPECT_THROW_MSG(it + 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.begin();
+        EXPECT_THROW_MSG(1 + it, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.cbegin();
+        EXPECT_THROW_MSG(1 + it, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.begin();
+        EXPECT_THROW_MSG(it -= 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.cbegin();
+        EXPECT_THROW_MSG(it -= 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.begin();
+        EXPECT_THROW_MSG(it - 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.cbegin();
+        EXPECT_THROW_MSG(it - 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.begin();
+        EXPECT_THROW_MSG(it - it, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.cbegin();
+        EXPECT_THROW_MSG(it - it, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+}
+
+TEST_F(JsonIteratorArithmeticTest, AddSubArray)
+{
+    auto it = j_array.begin();
+    it += 3;
+    EXPECT_EQ((j_array.begin() + 3), it);
+    EXPECT_EQ(json::iterator(3 + j_array.begin()), it);
+    EXPECT_EQ((it - 3), j_array.begin());
+    EXPECT_EQ((it - j_array.begin()), 3);
+    EXPECT_EQ(*it, json(4));
+    it -= 2;
+    EXPECT_EQ(*it, json(2));
+}
+
+TEST_F(JsonIteratorArithmeticTest, AddSubArrayConst)
+{
+    auto it = j_array.cbegin();
+    it += 3;
+    EXPECT_EQ((j_array.cbegin() + 3), it);
+    EXPECT_EQ(json::const_iterator(3 + j_array.cbegin()), it);
+    EXPECT_EQ((it - 3), j_array.cbegin());
+    EXPECT_EQ((it - j_array.cbegin()), 3);
+    EXPECT_EQ(*it, json(4));
+    it -= 2;
+    EXPECT_EQ(*it, json(2));
+}
+
+TEST_F(JsonIteratorArithmeticTest, AddSubNull)
+{
+    auto it = j_null.begin();
+    it += 3;
+    EXPECT_EQ((j_null.begin() + 3), it);
+    EXPECT_EQ(json::iterator(3 + j_null.begin()), it);
+    EXPECT_EQ((it - 3), j_null.begin());
+    EXPECT_EQ((it - j_null.begin()), 3);
+    EXPECT_NE(it, j_null.end());
+    it -= 3;
+    EXPECT_EQ(it, j_null.end());
+}
+
+TEST_F(JsonIteratorArithmeticTest, AddSubNullConst)
+{
+    auto it = j_null.cbegin();
+    it += 3;
+    EXPECT_EQ((j_null.cbegin() + 3), it);
+    EXPECT_EQ(json::const_iterator(3 + j_null.cbegin()), it);
+    EXPECT_EQ((it - 3), j_null.cbegin());
+    EXPECT_EQ((it - j_null.cbegin()), 3);
+    EXPECT_NE(it, j_null.cend());
+    it -= 3;
+    EXPECT_EQ(it, j_null.cend());
+}
+
+TEST_F(JsonIteratorArithmeticTest, AddSubValue)
+{
+    auto it = j_value.begin();
+    it += 3;
+    EXPECT_EQ((j_value.begin() + 3), it);
+    EXPECT_EQ(json::iterator(3 + j_value.begin()), it);
+    EXPECT_EQ((it - 3), j_value.begin());
+    EXPECT_EQ((it - j_value.begin()), 3);
+    EXPECT_NE(it, j_value.end());
+    it -= 3;
+    EXPECT_EQ(*it, json(42));
+}
+
+TEST_F(JsonIteratorArithmeticTest, AddSubValueConst)
+{
+    auto it = j_value.cbegin();
+    it += 3;
+    EXPECT_EQ((j_value.cbegin() + 3), it);
+    EXPECT_EQ(json::const_iterator(3 + j_value.cbegin()), it);
+    EXPECT_EQ((it - 3), j_value.cbegin());
+    EXPECT_EQ((it - j_value.cbegin()), 3);
+    EXPECT_NE(it, j_value.cend());
+    it -= 3;
+    EXPECT_EQ(*it, json(42));
+}
+
+TEST_F(JsonIteratorArithmeticTest, SubscriptObject)
+{
+    auto it = j_object.begin();
+    EXPECT_THROW_MSG(it[0], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.208] cannot use operator[] for object iterators");
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.208] cannot use operator[] for object iterators");
+}
+
+TEST_F(JsonIteratorArithmeticTest, SubscriptObjectConst)
+{
+    auto it = j_object.cbegin();
+    EXPECT_THROW_MSG(it[0], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.208] cannot use operator[] for object iterators");
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.208] cannot use operator[] for object iterators");
+}
+
+TEST_F(JsonIteratorArithmeticTest, SubscriptArray)
+{
+    auto it = j_array.begin();
+    EXPECT_EQ(it[0], json(1));
+    EXPECT_EQ(it[1], json(2));
+    EXPECT_EQ(it[2], json(3));
+    EXPECT_EQ(it[3], json(4));
+    EXPECT_EQ(it[4], json(5));
+    EXPECT_EQ(it[5], json(6));
+}
+
+TEST_F(JsonIteratorArithmeticTest, SubscriptArrayConst)
+{
+    auto it = j_array.cbegin();
+    EXPECT_EQ(it[0], json(1));
+    EXPECT_EQ(it[1], json(2));
+    EXPECT_EQ(it[2], json(3));
+    EXPECT_EQ(it[3], json(4));
+    EXPECT_EQ(it[4], json(5));
+    EXPECT_EQ(it[5], json(6));
+}
+
+TEST_F(JsonIteratorArithmeticTest, SubscriptNull)
+{
+    auto it = j_null.begin();
+    EXPECT_THROW_MSG(it[0], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+
+TEST_F(JsonIteratorArithmeticTest, SubscriptNullConst)
+{
+    auto it = j_null.cbegin();
+    EXPECT_THROW_MSG(it[0], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+
+TEST_F(JsonIteratorArithmeticTest, SubscriptValue)
+{
+    auto it = j_value.begin();
+    EXPECT_EQ(it[0], json(42));
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+
+TEST_F(JsonIteratorArithmeticTest, SubscriptValueConst)
+{
+    auto it = j_value.cbegin();
+    EXPECT_EQ(it[0], json(42));
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+#if 0
+TEST(JsonReverseIteratorTest, Comparisons)
+{
+    json j_values = {nullptr, true, 42, 42u, 23.23, {{"one", 1}, {"two", 2}}, {1, 2, 3, 4, 5}, "Hello, world"};
+
+    for (json& j : j_values)
+    {
+        SCOPED_TRACE(j.dump());
+        auto it1 = j.rbegin();
+        auto it2 = j.rbegin();
+        auto it3 = j.rbegin();
+        ++it2;
+        ++it3;
+        ++it3;
+        auto it1_c = j.crbegin();
+        auto it2_c = j.crbegin();
+        auto it3_c = j.crbegin();
+        ++it2_c;
+        ++it3_c;
+        ++it3_c;
+
+        // comparison: equal
+        {
+            EXPECT_TRUE(it1 == it1);
+            EXPECT_FALSE(it1 == it2);
+            EXPECT_FALSE(it1 == it3);
+            EXPECT_FALSE(it2 == it3);
+            EXPECT_TRUE(it1_c == it1_c);
+            EXPECT_FALSE(it1_c == it2_c);
+            EXPECT_FALSE(it1_c == it3_c);
+            EXPECT_FALSE(it2_c == it3_c);
+        }
+
+        // comparison: not equal
+        {
+            // check definition
+            EXPECT_EQ( (it1 != it1), !(it1 == it1) );
+            EXPECT_EQ( (it1 != it2), !(it1 == it2) );
+            EXPECT_EQ( (it1 != it3), !(it1 == it3) );
+            EXPECT_EQ( (it2 != it3), !(it2 == it3) );
+            EXPECT_EQ( (it1_c != it1_c), !(it1_c == it1_c) );
+            EXPECT_EQ( (it1_c != it2_c), !(it1_c == it2_c) );
+            EXPECT_EQ( (it1_c != it3_c), !(it1_c == it3_c) );
+            EXPECT_EQ( (it2_c != it3_c), !(it2_c == it3_c) );
+        }
+
+        // comparison: smaller
+        {
+            if (j.type() == json::value_t::object)
+            {
+                EXPECT_THROW_MSG(it1 < it1, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 < it2, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2 < it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 < it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c < it1_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c < it2_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2_c < it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c < it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+            }
+            else
+            {
+                EXPECT_FALSE(it1 < it1);
+                EXPECT_TRUE(it1 < it2);
+                EXPECT_TRUE(it1 < it3);
+                EXPECT_TRUE(it2 < it3);
+                EXPECT_FALSE(it1_c < it1_c);
+                EXPECT_TRUE(it1_c < it2_c);
+                EXPECT_TRUE(it1_c < it3_c);
+                EXPECT_TRUE(it2_c < it3_c);
+            }
+        }
+
+        // comparison: less than or equal
+        {
+            if (j.type() == json::value_t::object)
+            {
+                EXPECT_THROW_MSG(it1 <= it1, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 <= it2, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2 <= it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 <= it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c <= it1_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c <= it2_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2_c <= it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c <= it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+            }
+            else
+            {
+                // check definition
+                EXPECT_EQ( (it1 <= it1), !(it1 < it1) );
+                EXPECT_EQ( (it1 <= it2), !(it2 < it1) );
+                EXPECT_EQ( (it1 <= it3), !(it3 < it1) );
+                EXPECT_EQ( (it2 <= it3), !(it3 < it2) );
+                EXPECT_EQ( (it1_c <= it1_c), !(it1_c < it1_c) );
+                EXPECT_EQ( (it1_c <= it2_c), !(it2_c < it1_c) );
+                EXPECT_EQ( (it1_c <= it3_c), !(it3_c < it1_c) );
+                EXPECT_EQ( (it2_c <= it3_c), !(it3_c < it2_c) );
+            }
+        }
+
+        // comparison: greater than
+        {
+            if (j.type() == json::value_t::object)
+            {
+                EXPECT_THROW_MSG(it1 > it1, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 > it2, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2 > it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 > it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c > it1_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c > it2_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2_c > it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c > it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+            }
+            else
+            {
+                // check definition
+                EXPECT_EQ( (it1 > it1), (it1 < it1) );
+                EXPECT_EQ( (it1 > it2), (it2 < it1) );
+                EXPECT_EQ( (it1 > it3), (it3 < it1) );
+                EXPECT_EQ( (it2 > it3), (it3 < it2) );
+                EXPECT_EQ( (it1_c > it1_c), (it1_c < it1_c) );
+                EXPECT_EQ( (it1_c > it2_c), (it2_c < it1_c) );
+                EXPECT_EQ( (it1_c > it3_c), (it3_c < it1_c) );
+                EXPECT_EQ( (it2_c > it3_c), (it3_c < it2_c) );
+            }
+        }
+
+        // comparison: greater than or equal
+        {
+            if (j.type() == json::value_t::object)
+            {
+                EXPECT_THROW_MSG(it1 >= it1, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 >= it2, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2 >= it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1 >= it3, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c >= it1_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c >= it2_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it2_c >= it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+                EXPECT_THROW_MSG(it1_c >= it3_c, json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.213] cannot compare order of object iterators");
+            }
+            else
+            {
+                // check definition
+                EXPECT_EQ( (it1 >= it1), !(it1 < it1) );
+                EXPECT_EQ( (it1 >= it2), !(it1 < it2) );
+                EXPECT_EQ( (it1 >= it3), !(it1 < it3) );
+                EXPECT_EQ( (it2 >= it3), !(it2 < it3) );
+                EXPECT_EQ( (it1_c >= it1_c), !(it1_c < it1_c) );
+                EXPECT_EQ( (it1_c >= it2_c), !(it1_c < it2_c) );
+                EXPECT_EQ( (it1_c >= it3_c), !(it1_c < it3_c) );
+                EXPECT_EQ( (it2_c >= it3_c), !(it2_c < it3_c) );
+            }
+        }
+    }
+
+    // check exceptions if different objects are compared
+    for (auto j : j_values)
+    {
+        for (auto k : j_values)
+        {
+            if (j != k)
+            {
+                EXPECT_THROW_MSG(j.rbegin() == k.rbegin(), json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.212] cannot compare iterators of different containers");
+                EXPECT_THROW_MSG(j.crbegin() == k.crbegin(), json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.212] cannot compare iterators of different containers");
+
+                EXPECT_THROW_MSG(j.rbegin() < k.rbegin(), json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.212] cannot compare iterators of different containers");
+                EXPECT_THROW_MSG(j.crbegin() < k.crbegin(), json::invalid_iterator,
+                                 "[json.exception.invalid_iterator.212] cannot compare iterators of different containers");
+            }
+        }
+    }
+}
+
+class JsonReverseIteratorArithmeticTest : public ::testing::Test {
+ protected:
+    json j_object = {{"one", 1}, {"two", 2}, {"three", 3}};
+    json j_array = {1, 2, 3, 4, 5, 6};
+    json j_null = nullptr;
+    json j_value = 42;
+};
+
+TEST_F(JsonReverseIteratorArithmeticTest, AddSubObject)
+{
+    {
+        auto it = j_object.rbegin();
+        EXPECT_THROW_MSG(it += 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.crbegin();
+        EXPECT_THROW_MSG(it += 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.rbegin();
+        EXPECT_THROW_MSG(it + 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.crbegin();
+        EXPECT_THROW_MSG(it + 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.rbegin();
+        EXPECT_THROW_MSG(1 + it, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.crbegin();
+        EXPECT_THROW_MSG(1 + it, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.rbegin();
+        EXPECT_THROW_MSG(it -= 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.crbegin();
+        EXPECT_THROW_MSG(it -= 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.rbegin();
+        EXPECT_THROW_MSG(it - 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.crbegin();
+        EXPECT_THROW_MSG(it - 1, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.rbegin();
+        EXPECT_THROW_MSG(it - it, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+    {
+        auto it = j_object.crbegin();
+        EXPECT_THROW_MSG(it - it, json::invalid_iterator,
+                         "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    }
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, AddSubArray)
+{
+    auto it = j_array.rbegin();
+    it += 3;
+    EXPECT_EQ((j_array.rbegin() + 3), it);
+    EXPECT_EQ(json::reverse_iterator(3 + j_array.rbegin()), it);
+    EXPECT_EQ((it - 3), j_array.rbegin());
+    EXPECT_EQ((it - j_array.rbegin()), 3);
+    EXPECT_EQ(*it, json(3));
+    it -= 2;
+    EXPECT_EQ(*it, json(5));
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, AddSubArrayConst)
+{
+    auto it = j_array.crbegin();
+    it += 3;
+    EXPECT_EQ((j_array.crbegin() + 3), it);
+    EXPECT_EQ(json::const_reverse_iterator(3 + j_array.crbegin()), it);
+    EXPECT_EQ((it - 3), j_array.crbegin());
+    EXPECT_EQ((it - j_array.crbegin()), 3);
+    EXPECT_EQ(*it, json(3));
+    it -= 2;
+    EXPECT_EQ(*it, json(5));
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, AddSubNull)
+{
+    auto it = j_null.rbegin();
+    it += 3;
+    EXPECT_EQ((j_null.rbegin() + 3), it);
+    EXPECT_EQ(json::reverse_iterator(3 + j_null.rbegin()), it);
+    EXPECT_EQ((it - 3), j_null.rbegin());
+    EXPECT_EQ((it - j_null.rbegin()), 3);
+    EXPECT_NE(it, j_null.rend());
+    it -= 3;
+    EXPECT_EQ(it, j_null.rend());
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, AddSubNullConst)
+{
+    auto it = j_null.crbegin();
+    it += 3;
+    EXPECT_EQ((j_null.crbegin() + 3), it);
+    EXPECT_EQ(json::const_reverse_iterator(3 + j_null.crbegin()), it);
+    EXPECT_EQ((it - 3), j_null.crbegin());
+    EXPECT_EQ((it - j_null.crbegin()), 3);
+    EXPECT_NE(it, j_null.crend());
+    it -= 3;
+    EXPECT_EQ(it, j_null.crend());
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, AddSubValue)
+{
+    auto it = j_value.rbegin();
+    it += 3;
+    EXPECT_EQ((j_value.rbegin() + 3), it);
+    EXPECT_EQ(json::reverse_iterator(3 + j_value.rbegin()), it);
+    EXPECT_EQ((it - 3), j_value.rbegin());
+    EXPECT_EQ((it - j_value.rbegin()), 3);
+    EXPECT_NE(it, j_value.rend());
+    it -= 3;
+    EXPECT_EQ(*it, json(42));
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, AddSubValueConst)
+{
+    auto it = j_value.crbegin();
+    it += 3;
+    EXPECT_EQ((j_value.crbegin() + 3), it);
+    EXPECT_EQ(json::const_reverse_iterator(3 + j_value.crbegin()), it);
+    EXPECT_EQ((it - 3), j_value.crbegin());
+    EXPECT_EQ((it - j_value.crbegin()), 3);
+    EXPECT_NE(it, j_value.crend());
+    it -= 3;
+    EXPECT_EQ(*it, json(42));
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, SubscriptObject)
+{
+    auto it = j_object.rbegin();
+    EXPECT_THROW_MSG(it[0], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, SubscriptObjectConst)
+{
+    auto it = j_object.crbegin();
+    EXPECT_THROW_MSG(it[0], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.209] cannot use offsets with object iterators");
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, SubscriptArray)
+{
+    auto it = j_array.rbegin();
+    EXPECT_EQ(it[0], json(6));
+    EXPECT_EQ(it[1], json(5));
+    EXPECT_EQ(it[2], json(4));
+    EXPECT_EQ(it[3], json(3));
+    EXPECT_EQ(it[4], json(2));
+    EXPECT_EQ(it[5], json(1));
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, SubscriptArrayConst)
+{
+    auto it = j_array.crbegin();
+    EXPECT_EQ(it[0], json(6));
+    EXPECT_EQ(it[1], json(5));
+    EXPECT_EQ(it[2], json(4));
+    EXPECT_EQ(it[3], json(3));
+    EXPECT_EQ(it[4], json(2));
+    EXPECT_EQ(it[5], json(1));
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, SubscriptNull)
+{
+    auto it = j_null.rbegin();
+    EXPECT_THROW_MSG(it[0], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, SubscriptNullConst)
+{
+    auto it = j_null.crbegin();
+    EXPECT_THROW_MSG(it[0], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, SubscriptValue)
+{
+    auto it = j_value.rbegin();
+    EXPECT_EQ(it[0], json(42));
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+
+TEST_F(JsonReverseIteratorArithmeticTest, SubscriptValueConst)
+{
+    auto it = j_value.crbegin();
+    EXPECT_EQ(it[0], json(42));
+    EXPECT_THROW_MSG(it[1], json::invalid_iterator,
+                     "[json.exception.invalid_iterator.214] cannot get value");
+}
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-json.h b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-json.h
new file mode 100644
index 0000000..5a764b7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-json.h
@@ -0,0 +1,88 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/#ifndef UNIT_JSON_H_
+#define UNIT_JSON_H_
+
+#include <ostream>
+
+#include "wpi/json.h"
+
+namespace wpi {
+
+inline
+void PrintTo(const json& j, std::ostream* os) {
+  *os << j.dump();
+}
+
+class JsonTest {
+ public:
+  static const json::json_value& GetValue(const json& j) {
+    return j.m_value;
+  }
+  static json::pointer GetObject(json::iterator it) {
+    return it.m_object;
+  }
+  static json::const_pointer GetObject(json::const_iterator it) {
+    return it.m_object;
+  }
+  static std::string pop_back(json::json_pointer& p) {
+    return p.pop_back();
+  }
+  static json::json_pointer top(const json::json_pointer& p) {
+    return p.top();
+  }
+};
+
+}  // namespace wpi
+
+// clang warns on TEST_THROW_MSG(x == y, ...) saying the result is unused.
+// suppress this warning.
+#if defined(__clang__)
+#pragma GCC diagnostic ignored "-Wunused-comparison"
+#endif
+
+// variant of GTEST_TEST_THROW_ that also checks the exception's message.
+#define TEST_THROW_MSG(statement, expected_exception, expected_msg, fail) \
+  GTEST_AMBIGUOUS_ELSE_BLOCKER_ \
+  if (::testing::internal::ConstCharPtr gtest_msg = "") { \
+    bool gtest_caught_expected = false; \
+    try { \
+      GTEST_SUPPRESS_UNREACHABLE_CODE_WARNING_BELOW_(statement); \
+    } \
+    catch (expected_exception const& gtest_ex) { \
+      gtest_caught_expected = true; \
+      if (::std::string(gtest_ex.what()) != expected_msg) { \
+        ::testing::AssertionResult gtest_ar = ::testing::AssertionFailure(); \
+        gtest_ar \
+            << "Expected: " #statement " throws an exception with message \"" \
+            << expected_msg "\".\n  Actual: it throws message \"" \
+            << gtest_ex.what() << "\"."; \
+        fail(gtest_ar.failure_message()); \
+      } \
+    } \
+    catch (...) { \
+      gtest_msg.value = \
+          "Expected: " #statement " throws an exception of type " \
+          #expected_exception ".\n  Actual: it throws a different type."; \
+      goto GTEST_CONCAT_TOKEN_(gtest_label_testthrow_, __LINE__); \
+    } \
+    if (!gtest_caught_expected) { \
+      gtest_msg.value = \
+          "Expected: " #statement " throws an exception of type " \
+          #expected_exception ".\n  Actual: it throws nothing."; \
+      goto GTEST_CONCAT_TOKEN_(gtest_label_testthrow_, __LINE__); \
+    } \
+  } else \
+    GTEST_CONCAT_TOKEN_(gtest_label_testthrow_, __LINE__): \
+      fail(gtest_msg.value)
+
+#define EXPECT_THROW_MSG(statement, expected_exception, expected_msg) \
+  TEST_THROW_MSG(statement, expected_exception, expected_msg, GTEST_NONFATAL_FAILURE_)
+
+#define ASSERT_THROW_MSG(statement, expected_exception, expected_msg) \
+  TEST_THROW_MSG(statement, expected_exception, expected_msg, GTEST_FATAL_FAILURE_)
+
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-json_pointer.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-json_pointer.cpp
new file mode 100644
index 0000000..d54fd6a
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-json_pointer.cpp
@@ -0,0 +1,402 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+using wpi::JsonTest;
+
+TEST(JsonPointerTest, Errors)
+{
+    EXPECT_THROW_MSG(json::json_pointer("foo"), json::parse_error,
+                     "[json.exception.parse_error.107] parse error at 1: JSON pointer must be empty or begin with '/' - was: 'foo'");
+
+    EXPECT_THROW_MSG(json::json_pointer("/~~"), json::parse_error,
+                     "[json.exception.parse_error.108] parse error: escape character '~' must be followed with '0' or '1'");
+
+    EXPECT_THROW_MSG(json::json_pointer("/~"), json::parse_error,
+                     "[json.exception.parse_error.108] parse error: escape character '~' must be followed with '0' or '1'");
+
+    json::json_pointer p;
+    EXPECT_THROW_MSG(JsonTest::top(p), json::out_of_range,
+                     "[json.exception.out_of_range.405] JSON pointer has no parent");
+    EXPECT_THROW_MSG(JsonTest::pop_back(p), json::out_of_range,
+                     "[json.exception.out_of_range.405] JSON pointer has no parent");
+}
+
+// examples from RFC 6901
+TEST(JsonPointerTest, AccessNonConst)
+{
+    json j = R"(
+    {
+        "foo": ["bar", "baz"],
+        "": 0,
+        "a/b": 1,
+        "c%d": 2,
+        "e^f": 3,
+        "g|h": 4,
+        "i\\j": 5,
+        "k\"l": 6,
+        " ": 7,
+        "m~n": 8
+    }
+    )"_json;
+
+    // the whole document
+    EXPECT_EQ(j[json::json_pointer()], j);
+    EXPECT_EQ(j[json::json_pointer("")], j);
+
+    // array access
+    EXPECT_EQ(j[json::json_pointer("/foo")], j["foo"]);
+    EXPECT_EQ(j[json::json_pointer("/foo/0")], j["foo"][0]);
+    EXPECT_EQ(j[json::json_pointer("/foo/1")], j["foo"][1]);
+    EXPECT_EQ(j["/foo/1"_json_pointer], j["foo"][1]);
+
+    // checked array access
+    EXPECT_EQ(j.at(json::json_pointer("/foo/0")), j["foo"][0]);
+    EXPECT_EQ(j.at(json::json_pointer("/foo/1")), j["foo"][1]);
+
+    // empty string access
+    EXPECT_EQ(j[json::json_pointer("/")], j[""]);
+
+    // other cases
+    EXPECT_EQ(j[json::json_pointer("/ ")], j[" "]);
+    EXPECT_EQ(j[json::json_pointer("/c%d")], j["c%d"]);
+    EXPECT_EQ(j[json::json_pointer("/e^f")], j["e^f"]);
+    EXPECT_EQ(j[json::json_pointer("/g|h")], j["g|h"]);
+    EXPECT_EQ(j[json::json_pointer("/i\\j")], j["i\\j"]);
+    EXPECT_EQ(j[json::json_pointer("/k\"l")], j["k\"l"]);
+
+    // checked access
+    EXPECT_EQ(j.at(json::json_pointer("/ ")), j[" "]);
+    EXPECT_EQ(j.at(json::json_pointer("/c%d")), j["c%d"]);
+    EXPECT_EQ(j.at(json::json_pointer("/e^f")), j["e^f"]);
+    EXPECT_EQ(j.at(json::json_pointer("/g|h")), j["g|h"]);
+    EXPECT_EQ(j.at(json::json_pointer("/i\\j")), j["i\\j"]);
+    EXPECT_EQ(j.at(json::json_pointer("/k\"l")), j["k\"l"]);
+
+    // escaped access
+    EXPECT_EQ(j[json::json_pointer("/a~1b")], j["a/b"]);
+    EXPECT_EQ(j[json::json_pointer("/m~0n")], j["m~n"]);
+
+    // unescaped access
+    // access to nonexisting values yield object creation
+    EXPECT_NO_THROW(j[json::json_pointer("/a/b")] = 42);
+    EXPECT_EQ(j["a"]["b"], json(42));
+    EXPECT_NO_THROW(j[json::json_pointer("/a/c/1")] = 42);
+    EXPECT_EQ(j["a"]["c"], json({nullptr, 42}));
+    EXPECT_NO_THROW(j[json::json_pointer("/a/d/-")] = 42);
+    EXPECT_EQ(j["a"]["d"], json::array({42}));
+    // "/a/b" works for JSON {"a": {"b": 42}}
+    EXPECT_EQ(json({{"a", {{"b", 42}}}})[json::json_pointer("/a/b")], json(42));
+
+    // unresolved access
+    json j_primitive = 1;
+    EXPECT_THROW_MSG(j_primitive["/foo"_json_pointer], json::out_of_range,
+                     "[json.exception.out_of_range.404] unresolved reference token 'foo'");
+    EXPECT_THROW_MSG(j_primitive.at("/foo"_json_pointer), json::out_of_range,
+                     "[json.exception.out_of_range.404] unresolved reference token 'foo'");
+}
+
+TEST(JsonPointerTest, AccessConst)
+{
+    const json j = R"(
+    {
+        "foo": ["bar", "baz"],
+        "": 0,
+        "a/b": 1,
+        "c%d": 2,
+        "e^f": 3,
+        "g|h": 4,
+        "i\\j": 5,
+        "k\"l": 6,
+        " ": 7,
+        "m~n": 8
+    }
+    )"_json;
+
+    // the whole document
+    EXPECT_EQ(j[json::json_pointer()], j);
+    EXPECT_EQ(j[json::json_pointer("")], j);
+
+    // array access
+    EXPECT_EQ(j[json::json_pointer("/foo")], j["foo"]);
+    EXPECT_EQ(j[json::json_pointer("/foo/0")], j["foo"][0]);
+    EXPECT_EQ(j[json::json_pointer("/foo/1")], j["foo"][1]);
+    EXPECT_EQ(j["/foo/1"_json_pointer], j["foo"][1]);
+
+    // checked array access
+    EXPECT_EQ(j.at(json::json_pointer("/foo/0")), j["foo"][0]);
+    EXPECT_EQ(j.at(json::json_pointer("/foo/1")), j["foo"][1]);
+
+    // empty string access
+    EXPECT_EQ(j[json::json_pointer("/")], j[""]);
+
+    // other cases
+    EXPECT_EQ(j[json::json_pointer("/ ")], j[" "]);
+    EXPECT_EQ(j[json::json_pointer("/c%d")], j["c%d"]);
+    EXPECT_EQ(j[json::json_pointer("/e^f")], j["e^f"]);
+    EXPECT_EQ(j[json::json_pointer("/g|h")], j["g|h"]);
+    EXPECT_EQ(j[json::json_pointer("/i\\j")], j["i\\j"]);
+    EXPECT_EQ(j[json::json_pointer("/k\"l")], j["k\"l"]);
+
+    // checked access
+    EXPECT_EQ(j.at(json::json_pointer("/ ")), j[" "]);
+    EXPECT_EQ(j.at(json::json_pointer("/c%d")), j["c%d"]);
+    EXPECT_EQ(j.at(json::json_pointer("/e^f")), j["e^f"]);
+    EXPECT_EQ(j.at(json::json_pointer("/g|h")), j["g|h"]);
+    EXPECT_EQ(j.at(json::json_pointer("/i\\j")), j["i\\j"]);
+    EXPECT_EQ(j.at(json::json_pointer("/k\"l")), j["k\"l"]);
+
+    // escaped access
+    EXPECT_EQ(j[json::json_pointer("/a~1b")], j["a/b"]);
+    EXPECT_EQ(j[json::json_pointer("/m~0n")], j["m~n"]);
+
+    // unescaped access
+    EXPECT_THROW_MSG(j.at(json::json_pointer("/a/b")), json::out_of_range,
+                     "[json.exception.out_of_range.403] key 'a' not found");
+
+    // unresolved access
+    const json j_primitive = 1;
+    EXPECT_THROW_MSG(j_primitive["/foo"_json_pointer], json::out_of_range,
+                     "[json.exception.out_of_range.404] unresolved reference token 'foo'");
+    EXPECT_THROW_MSG(j_primitive.at("/foo"_json_pointer), json::out_of_range,
+                     "[json.exception.out_of_range.404] unresolved reference token 'foo'");
+}
+
+TEST(JsonPointerTest, UserStringLiteral)
+{
+    json j = R"(
+    {
+        "foo": ["bar", "baz"],
+        "": 0,
+        "a/b": 1,
+        "c%d": 2,
+        "e^f": 3,
+        "g|h": 4,
+        "i\\j": 5,
+        "k\"l": 6,
+        " ": 7,
+        "m~n": 8
+    }
+    )"_json;
+
+    // the whole document
+    EXPECT_EQ(j[""_json_pointer], j);
+
+    // array access
+    EXPECT_EQ(j["/foo"_json_pointer], j["foo"]);
+    EXPECT_EQ(j["/foo/0"_json_pointer], j["foo"][0]);
+    EXPECT_EQ(j["/foo/1"_json_pointer], j["foo"][1]);
+}
+
+TEST(JsonPointerTest, ArrayNonConst)
+{
+    json j = {1, 2, 3};
+    const json j_const = j;
+
+    // check reading access
+    EXPECT_EQ(j["/0"_json_pointer], j[0]);
+    EXPECT_EQ(j["/1"_json_pointer], j[1]);
+    EXPECT_EQ(j["/2"_json_pointer], j[2]);
+
+    // assign to existing index
+    j["/1"_json_pointer] = 13;
+    EXPECT_EQ(j[1], json(13));
+
+    // assign to nonexisting index
+    j["/3"_json_pointer] = 33;
+    EXPECT_EQ(j[3], json(33));
+
+    // assign to nonexisting index (with gap)
+    j["/5"_json_pointer] = 55;
+    EXPECT_EQ(j, json({1, 13, 3, 33, nullptr, 55}));
+
+    // error with leading 0
+    EXPECT_THROW_MSG(j["/01"_json_pointer], json::parse_error,
+                     "[json.exception.parse_error.106] parse error: array index '01' must not begin with '0'");
+    EXPECT_THROW_MSG(j_const["/01"_json_pointer], json::parse_error,
+                     "[json.exception.parse_error.106] parse error: array index '01' must not begin with '0'");
+    EXPECT_THROW_MSG(j.at("/01"_json_pointer), json::parse_error,
+                     "[json.exception.parse_error.106] parse error: array index '01' must not begin with '0'");
+    EXPECT_THROW_MSG(j_const.at("/01"_json_pointer), json::parse_error,
+                     "[json.exception.parse_error.106] parse error: array index '01' must not begin with '0'");
+
+    // error with incorrect numbers
+    EXPECT_THROW_MSG(j["/one"_json_pointer] = 1, json::parse_error,
+                     "[json.exception.parse_error.109] parse error: array index 'one' is not a number");
+    EXPECT_THROW_MSG(j_const["/one"_json_pointer] == 1, json::parse_error,
+                     "[json.exception.parse_error.109] parse error: array index 'one' is not a number");
+
+    EXPECT_THROW_MSG(j.at("/one"_json_pointer) = 1, json::parse_error,
+                     "[json.exception.parse_error.109] parse error: array index 'one' is not a number");
+    EXPECT_THROW_MSG(j_const.at("/one"_json_pointer) == 1, json::parse_error,
+                     "[json.exception.parse_error.109] parse error: array index 'one' is not a number");
+
+    EXPECT_THROW_MSG(json({{"/list/0", 1}, {"/list/1", 2}, {"/list/three", 3}}).unflatten(), json::parse_error,
+                     "[json.exception.parse_error.109] parse error: array index 'three' is not a number");
+
+    // assign to "-"
+    j["/-"_json_pointer] = 99;
+    EXPECT_EQ(j, json({1, 13, 3, 33, nullptr, 55, 99}));
+
+    // error when using "-" in const object
+    EXPECT_THROW_MSG(j_const["/-"_json_pointer], json::out_of_range,
+                     "[json.exception.out_of_range.402] array index '-' (3) is out of range");
+
+    // error when using "-" with at
+    EXPECT_THROW_MSG(j.at("/-"_json_pointer), json::out_of_range,
+                     "[json.exception.out_of_range.402] array index '-' (7) is out of range");
+    EXPECT_THROW_MSG(j_const.at("/-"_json_pointer), json::out_of_range,
+                     "[json.exception.out_of_range.402] array index '-' (3) is out of range");
+}
+
+TEST(JsonPointerTest, ArrayConst)
+{
+    const json j = {1, 2, 3};
+
+    // check reading access
+    EXPECT_EQ(j["/0"_json_pointer], j[0]);
+    EXPECT_EQ(j["/1"_json_pointer], j[1]);
+    EXPECT_EQ(j["/2"_json_pointer], j[2]);
+
+    // assign to nonexisting index
+    EXPECT_THROW_MSG(j.at("/3"_json_pointer), json::out_of_range,
+                     "[json.exception.out_of_range.401] array index 3 is out of range");
+
+    // assign to nonexisting index (with gap)
+    EXPECT_THROW_MSG(j.at("/5"_json_pointer), json::out_of_range,
+                     "[json.exception.out_of_range.401] array index 5 is out of range");
+
+    // assign to "-"
+    EXPECT_THROW_MSG(j["/-"_json_pointer], json::out_of_range,
+                     "[json.exception.out_of_range.402] array index '-' (3) is out of range");
+    EXPECT_THROW_MSG(j.at("/-"_json_pointer), json::out_of_range,
+                     "[json.exception.out_of_range.402] array index '-' (3) is out of range");
+}
+
+TEST(JsonPointerTest, Flatten)
+{
+    json j =
+    {
+        {"pi", 3.141},
+        {"happy", true},
+        {"name", "Niels"},
+        {"nothing", nullptr},
+        {
+            "answer", {
+                {"everything", 42}
+            }
+        },
+        {"list", {1, 0, 2}},
+        {
+            "object", {
+                {"currency", "USD"},
+                {"value", 42.99},
+                {"", "empty string"},
+                {"/", "slash"},
+                {"~", "tilde"},
+                {"~1", "tilde1"}
+            }
+        }
+    };
+
+    json j_flatten =
+    {
+        {"/pi", 3.141},
+        {"/happy", true},
+        {"/name", "Niels"},
+        {"/nothing", nullptr},
+        {"/answer/everything", 42},
+        {"/list/0", 1},
+        {"/list/1", 0},
+        {"/list/2", 2},
+        {"/object/currency", "USD"},
+        {"/object/value", 42.99},
+        {"/object/", "empty string"},
+        {"/object/~1", "slash"},
+        {"/object/~0", "tilde"},
+        {"/object/~01", "tilde1"}
+    };
+
+    // check if flattened result is as expected
+    EXPECT_EQ(j.flatten(), j_flatten);
+
+    // check if unflattened result is as expected
+    EXPECT_EQ(j_flatten.unflatten(), j);
+
+    // error for nonobjects
+    EXPECT_THROW_MSG(json(1).unflatten(), json::type_error,
+                     "[json.exception.type_error.314] only objects can be unflattened");
+
+    // error for nonprimitve values
+    EXPECT_THROW_MSG(json({{"/1", {1, 2, 3}}}).unflatten(), json::type_error,
+                     "[json.exception.type_error.315] values in object must be primitive");
+
+    // error for conflicting values
+    json j_error = {{"", 42}, {"/foo", 17}};
+    EXPECT_THROW_MSG(j_error.unflatten(), json::type_error,
+                     "[json.exception.type_error.313] invalid value to unflatten");
+
+    // explicit roundtrip check
+    EXPECT_EQ(j.flatten().unflatten(), j);
+
+    // roundtrip for primitive values
+    json j_null;
+    EXPECT_EQ(j_null.flatten().unflatten(), j_null);
+    json j_number = 42;
+    EXPECT_EQ(j_number.flatten().unflatten(), j_number);
+    json j_boolean = false;
+    EXPECT_EQ(j_boolean.flatten().unflatten(), j_boolean);
+    json j_string = "foo";
+    EXPECT_EQ(j_string.flatten().unflatten(), j_string);
+
+    // roundtrip for empty structured values (will be unflattened to null)
+    json j_array(json::value_t::array);
+    EXPECT_EQ(j_array.flatten().unflatten(), json());
+    json j_object(json::value_t::object);
+    EXPECT_EQ(j_object.flatten().unflatten(), json());
+}
+
+TEST(JsonPointerTest, StringRepresentation)
+{
+    for (auto ptr :
+            {"", "/foo", "/foo/0", "/", "/a~1b", "/c%d", "/e^f", "/g|h", "/i\\j", "/k\"l", "/ ", "/m~0n"
+            })
+    {
+        SCOPED_TRACE(ptr);
+        EXPECT_EQ(json::json_pointer(ptr).to_string(), ptr);
+    }
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-meta.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-meta.cpp
new file mode 100644
index 0000000..45daf8f
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-meta.cpp
@@ -0,0 +1,54 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2016 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+TEST(JsonVersionTest, Meta)
+{
+    json j = json::meta();
+
+    EXPECT_EQ(j["name"], "WPI version of JSON for Modern C++");
+    EXPECT_EQ(j["copyright"], "(C) 2013-2017 Niels Lohmann, (C) 2017-2018 FIRST");
+    EXPECT_EQ(j["url"], "https://github.com/wpilibsuite/allwpilib");
+    EXPECT_EQ(j["version"], json(
+    {
+        {"string", "3.1.2"},
+        {"major", 3},
+        {"minor", 1},
+        {"patch", 2}
+    }));
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-modifiers.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-modifiers.cpp
new file mode 100644
index 0000000..4125858
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-modifiers.cpp
@@ -0,0 +1,739 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+TEST(JsonClearTest, Boolean)
+{
+    json j = true;
+
+    j.clear();
+    EXPECT_EQ(j, json(json::value_t::boolean));
+}
+
+TEST(JsonClearTest, String)
+{
+    json j = "hello world";
+
+    j.clear();
+    EXPECT_EQ(j, json(json::value_t::string));
+}
+
+TEST(JsonClearTest, ArrayEmpty)
+{
+    json j = json::array();
+
+    j.clear();
+    EXPECT_TRUE(j.empty());
+    EXPECT_EQ(j, json(json::value_t::array));
+}
+
+TEST(JsonClearTest, ArrayFilled)
+{
+    json j = {1, 2, 3};
+
+    j.clear();
+    EXPECT_TRUE(j.empty());
+    EXPECT_EQ(j, json(json::value_t::array));
+}
+
+TEST(JsonClearTest, ObjectEmpty)
+{
+    json j = json::object();
+
+    j.clear();
+    EXPECT_TRUE(j.empty());
+    EXPECT_EQ(j, json(json::value_t::object));
+}
+
+TEST(JsonClearTest, ObjectFilled)
+{
+    json j = {{"one", 1}, {"two", 2}, {"three", 3}};
+
+    j.clear();
+    EXPECT_TRUE(j.empty());
+    EXPECT_EQ(j, json(json::value_t::object));
+}
+
+TEST(JsonClearTest, Integer)
+{
+    json j = 23;
+
+    j.clear();
+    EXPECT_EQ(j, json(json::value_t::number_integer));
+}
+
+TEST(JsonClearTest, Unsigned)
+{
+    json j = 23u;
+
+    j.clear();
+    EXPECT_EQ(j, json(json::value_t::number_integer));
+}
+
+TEST(JsonClearTest, Float)
+{
+    json j = 23.42;
+
+    j.clear();
+    EXPECT_EQ(j, json(json::value_t::number_float));
+}
+
+TEST(JsonClearTest, Null)
+{
+    json j = nullptr;
+
+    j.clear();
+    EXPECT_EQ(j, json(json::value_t::null));
+}
+
+TEST(JsonPushBackArrayTest, RRefNull)
+{
+    json j;
+    j.push_back(1);
+    j.push_back(2);
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 2}));
+}
+
+TEST(JsonPushBackArrayTest, RRefArray)
+{
+    json j = {1, 2, 3};
+    j.push_back("Hello");
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 2, 3, "Hello"}));
+}
+
+TEST(JsonPushBackArrayTest, RRefOther)
+{
+    json j = 1;
+    EXPECT_THROW_MSG(j.push_back("Hello"), json::type_error,
+                     "[json.exception.type_error.308] cannot use push_back() with number");
+}
+
+TEST(JsonPushBackArrayTest, LRefNull)
+{
+    json j;
+    json k(1);
+    j.push_back(k);
+    j.push_back(k);
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 1}));
+}
+
+TEST(JsonPushBackArrayTest, LRefArray)
+{
+    json j = {1, 2, 3};
+    json k("Hello");
+    j.push_back(k);
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 2, 3, "Hello"}));
+}
+
+TEST(JsonPushBackArrayTest, LRefOther)
+{
+    json j = 1;
+    json k("Hello");
+    EXPECT_THROW_MSG(j.push_back(k), json::type_error,
+                     "[json.exception.type_error.308] cannot use push_back() with number");
+}
+#if 0
+TEST(JsonPushBackObjectTest, Null)
+{
+    json j;
+    j.push_back(json::object_t::value_type({"one", 1}));
+    j.push_back(json::object_t::value_type({"two", 2}));
+    EXPECT_EQ(j.type(), json::value_t::object);
+    EXPECT_EQ(j.size(), 2u);
+    EXPECT_EQ(j["one"], json(1));
+    EXPECT_EQ(j["two"], json(2));
+}
+
+TEST(JsonPushBackObjectTest, Object)
+{
+    json j(json::value_t::object);
+    j.push_back(json::object_t::value_type({"one", 1}));
+    j.push_back(json::object_t::value_type({"two", 2}));
+    EXPECT_EQ(j.size(), 2u);
+    EXPECT_EQ(j["one"], json(1));
+    EXPECT_EQ(j["two"], json(2));
+}
+
+TEST(JsonPushBackObjectTest, Other)
+{
+    json j = 1;
+    json k("Hello");
+    EXPECT_THROW_MSG(j.push_back(json::object_t::value_type({"one", 1})), json::type_error,
+                     "[json.exception.type_error.308] cannot use push_back() with number");
+}
+#endif
+TEST(JsonPushBackInitListTest, Null)
+{
+    json j;
+    j.push_back({"foo", "bar"});
+    EXPECT_EQ(j, json::array({{"foo", "bar"}}));
+
+    json k;
+    k.push_back({1, 2, 3});
+    EXPECT_EQ(k, json::array({{1, 2, 3}}));
+}
+
+TEST(JsonPushBackInitListTest, Array)
+{
+    json j = {1, 2, 3};
+    j.push_back({"foo", "bar"});
+    EXPECT_EQ(j, json({1, 2, 3, {"foo", "bar"}}));
+
+    json k = {1, 2, 3};
+    k.push_back({1, 2, 3});
+    EXPECT_EQ(k, json({1, 2, 3, {1, 2, 3}}));
+}
+
+TEST(JsonPushBackInitListTest, Object)
+{
+    json j = {{"key1", 1}};
+    j.push_back({"key2", "bar"});
+    EXPECT_EQ(j, json({{"key1", 1}, {"key2", "bar"}}));
+
+    json k = {{"key1", 1}};
+    EXPECT_THROW_MSG(k.push_back({1, 2, 3, 4}), json::type_error,
+                     "[json.exception.type_error.308] cannot use push_back() with object");
+}
+
+TEST(JsonEmplaceBackArrayTest, Null)
+{
+    json j;
+    j.emplace_back(1);
+    j.emplace_back(2);
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 2}));
+}
+
+TEST(JsonEmplaceBackArrayTest, Array)
+{
+    json j = {1, 2, 3};
+    j.emplace_back("Hello");
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 2, 3, "Hello"}));
+}
+
+TEST(JsonEmplaceBackArrayTest, MultipleValues)
+{
+    json j;
+    j.emplace_back(3, "foo");
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({{"foo", "foo", "foo"}}));
+}
+
+TEST(JsonEmplaceBackArrayTest, Other)
+{
+    json j = 1;
+    EXPECT_THROW_MSG(j.emplace_back("Hello"), json::type_error,
+                     "[json.exception.type_error.311] cannot use emplace_back() with number");
+}
+
+TEST(JsonEmplaceObjectTest, Null)
+{
+    // start with a null value
+    json j;
+
+    // add a new key
+    auto res1 = j.emplace("foo", "bar");
+    EXPECT_EQ(res1.second, true);
+    EXPECT_EQ(*res1.first, "bar");
+
+    // the null value is changed to an object
+    EXPECT_EQ(j.type(), json::value_t::object);
+
+    // add a new key
+    auto res2 = j.emplace("baz", "bam");
+    EXPECT_EQ(res2.second, true);
+    EXPECT_EQ(*res2.first, "bam");
+
+    // we try to insert at given key - no change
+    auto res3 = j.emplace("baz", "bad");
+    EXPECT_EQ(res3.second, false);
+    EXPECT_EQ(*res3.first, "bam");
+
+    // the final object
+    EXPECT_EQ(j, json({{"baz", "bam"}, {"foo", "bar"}}));
+}
+
+TEST(JsonEmplaceObjectTest, Object)
+{
+    // start with an object
+    json j = {{"foo", "bar"}};
+
+    // add a new key
+    auto res1 = j.emplace("baz", "bam");
+    EXPECT_EQ(res1.second, true);
+    EXPECT_EQ(*res1.first, "bam");
+
+    // add an existing key
+    auto res2 = j.emplace("foo", "bad");
+    EXPECT_EQ(res2.second, false);
+    EXPECT_EQ(*res2.first, "bar");
+
+    // check final object
+    EXPECT_EQ(j, json({{"baz", "bam"}, {"foo", "bar"}}));
+}
+
+TEST(JsonEmplaceObjectTest, Other)
+{
+    json j = 1;
+    EXPECT_THROW_MSG(j.emplace("foo", "bar"), json::type_error,
+                     "[json.exception.type_error.311] cannot use emplace() with number");
+}
+
+TEST(JsonPlusEqualArrayTest, RRefNull)
+{
+    json j;
+    j += 1;
+    j += 2;
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 2}));
+}
+
+TEST(JsonPlusEqualArrayTest, RRefArray)
+{
+    json j = {1, 2, 3};
+    j += "Hello";
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 2, 3, "Hello"}));
+}
+
+TEST(JsonPlusEqualArrayTest, RRefOther)
+{
+    json j = 1;
+    EXPECT_THROW_MSG(j += "Hello", json::type_error,
+                     "[json.exception.type_error.308] cannot use push_back() with number");
+}
+
+TEST(JsonPlusEqualArrayTest, LRefNull)
+{
+    json j;
+    json k(1);
+    j += k;
+    j += k;
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 1}));
+}
+
+TEST(JsonPlusEqualArrayTest, LRefArray)
+{
+    json j = {1, 2, 3};
+    json k("Hello");
+    j += k;
+    EXPECT_EQ(j.type(), json::value_t::array);
+    EXPECT_EQ(j, json({1, 2, 3, "Hello"}));
+}
+
+TEST(JsonPlusEqualArrayTest, LRefOther)
+{
+    json j = 1;
+    json k("Hello");
+    EXPECT_THROW_MSG(j += k, json::type_error,
+                     "[json.exception.type_error.308] cannot use push_back() with number");
+}
+#if 0
+TEST(JsonPlusEqualObjectTest, Null)
+{
+    json j;
+    j += json::object_t::value_type({"one", 1});
+    j += json::object_t::value_type({"two", 2});
+    EXPECT_EQ(j.type(), json::value_t::object);
+    EXPECT_EQ(j.size(), 2u);
+    EXPECT_EQ(j["one"], json(1));
+    EXPECT_EQ(j["two"], json(2));
+}
+
+TEST(JsonPlusEqualObjectTest, Object)
+{
+    json j(json::value_t::object);
+    j += json::object_t::value_type({"one", 1});
+    j += json::object_t::value_type({"two", 2});
+    EXPECT_EQ(j.size(), 2u);
+    EXPECT_EQ(j["one"], json(1));
+    EXPECT_EQ(j["two"], json(2));
+}
+
+TEST(JsonPlusEqualObjectTest, Other)
+{
+    json j = 1;
+    json k("Hello");
+    EXPECT_THROW_MSG(j += json::object_t::value_type({"one", 1}), json::type_error,
+                     "[json.exception.type_error.308] cannot use push_back() with number");
+}
+#endif
+TEST(JsonPlusEqualInitListTest, Null)
+{
+    json j;
+    j += {"foo", "bar"};
+    EXPECT_EQ(j, json::array({{"foo", "bar"}}));
+
+    json k;
+    k += {1, 2, 3};
+    EXPECT_EQ(k, json::array({{1, 2, 3}}));
+}
+
+TEST(JsonPlusEqualInitListTest, Array)
+{
+    json j = {1, 2, 3};
+    j += {"foo", "bar"};
+    EXPECT_EQ(j, json({1, 2, 3, {"foo", "bar"}}));
+
+    json k = {1, 2, 3};
+    k += {1, 2, 3};
+    EXPECT_EQ(k, json({1, 2, 3, {1, 2, 3}}));
+}
+
+TEST(JsonPlusEqualInitListTest, Object)
+{
+    json j = {{"key1", 1}};
+    j += {"key2", "bar"};
+    EXPECT_EQ(j, json({{"key1", 1}, {"key2", "bar"}}));
+
+    json k = {{"key1", 1}};
+    EXPECT_THROW_MSG((k += {1, 2, 3, 4}), json::type_error,
+                     "[json.exception.type_error.308] cannot use push_back() with object");
+}
+
+class JsonInsertTest : public ::testing::Test {
+ protected:
+    json j_array = {1, 2, 3, 4};
+    json j_value = 5;
+    json j_other_array = {"first", "second"};
+    json j_object1 = {{"one", "eins"}, {"two", "zwei"}};
+    json j_object2 = {{"eleven", "elf"}, {"seventeen", "siebzehn"}};
+};
+
+TEST_F(JsonInsertTest, ValueBegin)
+{
+    auto it = j_array.insert(j_array.begin(), j_value);
+    EXPECT_EQ(j_array.size(), 5u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ(j_array.begin(), it);
+    EXPECT_EQ(j_array, json({5, 1, 2, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, ValueMiddle)
+{
+    auto it = j_array.insert(j_array.begin() + 2, j_value);
+    EXPECT_EQ(j_array.size(), 5u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ((it - j_array.begin()), 2);
+    EXPECT_EQ(j_array, json({1, 2, 5, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, ValueEnd)
+{
+    auto it = j_array.insert(j_array.end(), j_value);
+    EXPECT_EQ(j_array.size(), 5u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ((j_array.end() - it), 1);
+    EXPECT_EQ(j_array, json({1, 2, 3, 4, 5}));
+}
+
+TEST_F(JsonInsertTest, RvalueBegin)
+{
+    auto it = j_array.insert(j_array.begin(), 5);
+    EXPECT_EQ(j_array.size(), 5u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ(j_array.begin(), it);
+    EXPECT_EQ(j_array, json({5, 1, 2, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, RvalueMiddle)
+{
+    auto it = j_array.insert(j_array.begin() + 2, 5);
+    EXPECT_EQ(j_array.size(), 5u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ((it - j_array.begin()), 2);
+    EXPECT_EQ(j_array, json({1, 2, 5, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, RvalueEnd)
+{
+    auto it = j_array.insert(j_array.end(), 5);
+    EXPECT_EQ(j_array.size(), 5u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ((j_array.end() - it), 1);
+    EXPECT_EQ(j_array, json({1, 2, 3, 4, 5}));
+}
+
+TEST_F(JsonInsertTest, CopyBegin)
+{
+    auto it = j_array.insert(j_array.begin(), 3, 5);
+    EXPECT_EQ(j_array.size(), 7u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ(j_array.begin(), it);
+    EXPECT_EQ(j_array, json({5, 5, 5, 1, 2, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, CopyMiddle)
+{
+    auto it = j_array.insert(j_array.begin() + 2, 3, 5);
+    EXPECT_EQ(j_array.size(), 7u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ((it - j_array.begin()), 2);
+    EXPECT_EQ(j_array, json({1, 2, 5, 5, 5, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, CopyEnd)
+{
+    auto it = j_array.insert(j_array.end(), 3, 5);
+    EXPECT_EQ(j_array.size(), 7u);
+    EXPECT_EQ(*it, j_value);
+    EXPECT_EQ((j_array.end() - it), 3);
+    EXPECT_EQ(j_array, json({1, 2, 3, 4, 5, 5, 5}));
+}
+
+TEST_F(JsonInsertTest, CopyNothing)
+{
+    auto it = j_array.insert(j_array.end(), 0, 5);
+    EXPECT_EQ(j_array.size(), 4u);
+    // the returned iterator points to the first inserted element;
+    // there were 4 elements, so it should point to the 5th
+    EXPECT_EQ(it, j_array.begin() + 4);
+    EXPECT_EQ(j_array, json({1, 2, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, RangeForArrayProper)
+{
+    auto it = j_array.insert(j_array.end(), j_other_array.begin(), j_other_array.end());
+    EXPECT_EQ(j_array.size(), 6u);
+    EXPECT_EQ(*it, *j_other_array.begin());
+    EXPECT_EQ((j_array.end() - it), 2);
+    EXPECT_EQ(j_array, json({1, 2, 3, 4, "first", "second"}));
+}
+
+TEST_F(JsonInsertTest, RangeForArrayEmpty)
+{
+    auto it = j_array.insert(j_array.end(), j_other_array.begin(), j_other_array.begin());
+    EXPECT_EQ(j_array.size(), 4u);
+    EXPECT_EQ(it, j_array.end());
+    EXPECT_EQ(j_array, json({1, 2, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, RangeForArrayInvalid)
+{
+    json j_other_array2 = {"first", "second"};
+
+    EXPECT_THROW_MSG(j_array.insert(j_array.end(), j_array.begin(), j_array.end()),
+                    json::invalid_iterator,
+                    "[json.exception.invalid_iterator.211] passed iterators may not belong to container");
+    EXPECT_THROW_MSG(j_array.insert(j_array.end(), j_other_array.begin(), j_other_array2.end()),
+                    json::invalid_iterator,
+                    "[json.exception.invalid_iterator.210] iterators do not fit");
+}
+
+TEST_F(JsonInsertTest, RangeForObjectProper)
+{
+    j_object1.insert(j_object2.begin(), j_object2.end());
+    EXPECT_EQ(j_object1.size(), 4u);
+}
+
+TEST_F(JsonInsertTest, RangeForObjectEmpty)
+{
+    j_object1.insert(j_object2.begin(), j_object2.begin());
+    EXPECT_EQ(j_object1.size(), 2u);
+}
+
+TEST_F(JsonInsertTest, RangeForObjectInvalid)
+{
+    json j_other_array2 = {"first", "second"};
+
+    EXPECT_THROW_MSG(j_array.insert(j_object2.begin(), j_object2.end()), json::type_error,
+                     "[json.exception.type_error.309] cannot use insert() with array");
+    EXPECT_THROW_MSG(j_object1.insert(j_object1.begin(), j_object2.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.210] iterators do not fit");
+    EXPECT_THROW_MSG(j_object1.insert(j_array.begin(), j_array.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterators first and last must point to objects");
+}
+
+TEST_F(JsonInsertTest, InitListBegin)
+{
+    auto it = j_array.insert(j_array.begin(), {7, 8, 9});
+    EXPECT_EQ(j_array.size(), 7u);
+    EXPECT_EQ(*it, json(7));
+    EXPECT_EQ(j_array.begin(), it);
+    EXPECT_EQ(j_array, json({7, 8, 9, 1, 2, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, InitListMiddle)
+{
+    auto it = j_array.insert(j_array.begin() + 2, {7, 8, 9});
+    EXPECT_EQ(j_array.size(), 7u);
+    EXPECT_EQ(*it, json(7));
+    EXPECT_EQ((it - j_array.begin()), 2);
+    EXPECT_EQ(j_array, json({1, 2, 7, 8, 9, 3, 4}));
+}
+
+TEST_F(JsonInsertTest, InitListEnd)
+{
+    auto it = j_array.insert(j_array.end(), {7, 8, 9});
+    EXPECT_EQ(j_array.size(), 7u);
+    EXPECT_EQ(*it, json(7));
+    EXPECT_EQ((j_array.end() - it), 3);
+    EXPECT_EQ(j_array, json({1, 2, 3, 4, 7, 8, 9}));
+}
+
+TEST_F(JsonInsertTest, InvalidIterator)
+{
+    // pass iterator to a different array
+    json j_another_array = {1, 2};
+    json j_yet_another_array = {"first", "second"};
+    EXPECT_THROW_MSG(j_array.insert(j_another_array.end(), 10), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+    EXPECT_THROW_MSG(j_array.insert(j_another_array.end(), j_value), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+    EXPECT_THROW_MSG(j_array.insert(j_another_array.end(), 10, 11), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+    EXPECT_THROW_MSG(j_array.insert(j_another_array.end(), j_yet_another_array.begin(), j_yet_another_array.end()), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+    EXPECT_THROW_MSG(j_array.insert(j_another_array.end(), {1, 2, 3, 4}), json::invalid_iterator,
+                     "[json.exception.invalid_iterator.202] iterator does not fit current value");
+}
+
+TEST_F(JsonInsertTest, NonArray)
+{
+    // call insert on a non-array type
+    json j_nonarray = 3;
+    json j_yet_another_array = {"first", "second"};
+    EXPECT_THROW_MSG(j_nonarray.insert(j_nonarray.end(), 10), json::type_error,
+                     "[json.exception.type_error.309] cannot use insert() with number");
+    EXPECT_THROW_MSG(j_nonarray.insert(j_nonarray.end(), j_value), json::type_error,
+                     "[json.exception.type_error.309] cannot use insert() with number");
+    EXPECT_THROW_MSG(j_nonarray.insert(j_nonarray.end(), 10, 11), json::type_error,
+                     "[json.exception.type_error.309] cannot use insert() with number");
+    EXPECT_THROW_MSG(j_nonarray.insert(j_nonarray.end(), j_yet_another_array.begin(),
+                                       j_yet_another_array.end()), json::type_error,
+                     "[json.exception.type_error.309] cannot use insert() with number");
+    EXPECT_THROW_MSG(j_nonarray.insert(j_nonarray.end(), {1, 2, 3, 4}), json::type_error,
+                     "[json.exception.type_error.309] cannot use insert() with number");
+}
+
+TEST(JsonSwapTest, JsonMember)
+{
+    json j("hello world");
+    json k(42.23);
+
+    j.swap(k);
+
+    EXPECT_EQ(j, json(42.23));
+    EXPECT_EQ(k, json("hello world"));
+}
+
+TEST(JsonSwapTest, JsonNonMember)
+{
+    json j("hello world");
+    json k(42.23);
+
+    std::swap(j, k);
+
+    EXPECT_EQ(j, json(42.23));
+    EXPECT_EQ(k, json("hello world"));
+}
+
+TEST(JsonSwapTest, ArrayT)
+{
+    json j = {1, 2, 3, 4};
+    json::array_t a = {"foo", "bar", "baz"};
+
+    j.swap(a);
+
+    EXPECT_EQ(j, json({"foo", "bar", "baz"}));
+
+    j.swap(a);
+
+    EXPECT_EQ(j, json({1, 2, 3, 4}));
+}
+
+TEST(JsonSwapTest, NonArrayT)
+{
+    json j = 17;
+    json::array_t a = {"foo", "bar", "baz"};
+
+    EXPECT_THROW_MSG(j.swap(a), json::type_error,
+                     "[json.exception.type_error.310] cannot use swap() with number");
+}
+
+TEST(JsonSwapTest, ObjectT)
+{
+    json j = {{"one", 1}, {"two", 2}};
+    json::object_t o = {{"cow", "Kuh"}, {"chicken", "Huhn"}};
+
+    j.swap(o);
+
+    EXPECT_EQ(j, json({{"cow", "Kuh"}, {"chicken", "Huhn"}}));
+
+    j.swap(o);
+
+    EXPECT_EQ(j, json({{"one", 1}, {"two", 2}}));
+}
+
+TEST(JsonSwapTest, NonObjectT)
+{
+    json j = 17;
+    json::object_t o = {{"cow", "Kuh"}, {"chicken", "Huhn"}};
+
+    EXPECT_THROW_MSG(j.swap(o), json::type_error,
+                     "[json.exception.type_error.310] cannot use swap() with number");
+}
+
+TEST(JsonSwapTest, StringT)
+{
+    json j = "Hello world";
+    std::string s = "Hallo Welt";
+
+    j.swap(s);
+
+    EXPECT_EQ(j, json("Hallo Welt"));
+
+    j.swap(s);
+
+    EXPECT_EQ(j, json("Hello world"));
+}
+
+TEST(JsonSwapTest, NonStringT)
+{
+    json j = 17;
+    std::string s = "Hallo Welt";
+
+    EXPECT_THROW_MSG(j.swap(s), json::type_error,
+                     "[json.exception.type_error.310] cannot use swap() with number");
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-msgpack.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-msgpack.cpp
new file mode 100644
index 0000000..0c03ee0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-msgpack.cpp
@@ -0,0 +1,1269 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+#include <fstream>
+
+TEST(MessagePackDiscardedTest, Case)
+{
+    // discarded values are not serialized
+    json j = json::value_t::discarded;
+    const auto result = json::to_msgpack(j);
+    EXPECT_TRUE(result.empty());
+}
+
+TEST(MessagePackNullTest, Case)
+{
+    json j = nullptr;
+    std::vector<uint8_t> expected = {0xc0};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+TEST(MessagePackBooleanTest, True)
+{
+    json j = true;
+    std::vector<uint8_t> expected = {0xc3};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+TEST(MessagePackBooleanTest, False)
+{
+    json j = false;
+    std::vector<uint8_t> expected = {0xc2};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// -32..-1 (negative fixnum)
+TEST(MessagePackSignedTest, Neg0)
+{
+    for (auto i = -32; i <= -1; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = i;
+
+        // check type
+        EXPECT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 1u);
+
+        // check individual bytes
+        EXPECT_EQ(static_cast<int8_t>(result[0]), i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// 0..127 (positive fixnum)
+TEST(MessagePackSignedTest, Pos0)
+{
+    for (size_t i = 0; i <= 127; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = -1;
+        j.get_ref<int64_t&>() = static_cast<int64_t>(i);
+
+        // check type
+        EXPECT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 1u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(i));
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// 128..255 (int 8)
+TEST(MessagePackSignedTest, Pos1)
+{
+    for (size_t i = 128; i <= 255; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = -1;
+        j.get_ref<int64_t&>() = static_cast<int64_t>(i);
+
+        // check type
+        EXPECT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0xcc));
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 2u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(0xcc));
+        uint8_t restored = static_cast<uint8_t>(result[1]);
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// 256..65535 (int 16)
+TEST(MessagePackSignedTest, Pos2)
+{
+    for (size_t i = 256; i <= 65535; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = -1;
+        j.get_ref<int64_t&>() = static_cast<int64_t>(i);
+
+        // check type
+        EXPECT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0xcd));
+        expected.push_back(static_cast<uint8_t>((i >> 8) & 0xff));
+        expected.push_back(static_cast<uint8_t>(i & 0xff));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 3u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(0xcd));
+        uint16_t restored = static_cast<uint16_t>(static_cast<uint8_t>(result[1]) * 256 + static_cast<uint8_t>(result[2]));
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// 65536..4294967295 (int 32)
+class MessagePackSignedPos4Test : public ::testing::TestWithParam<uint32_t> {};
+TEST_P(MessagePackSignedPos4Test, Case)
+{
+    // create JSON value with integer number
+    json j = -1;
+    j.get_ref<int64_t&>() = static_cast<int64_t>(GetParam());
+
+    // check type
+    EXPECT_TRUE(j.is_number_integer());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0xce));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+    EXPECT_EQ(result.size(), 5u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xce));
+    uint32_t restored = (static_cast<uint32_t>(static_cast<uint8_t>(result[1])) << 030) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[2])) << 020) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[3])) << 010) +
+                        static_cast<uint32_t>(static_cast<uint8_t>(result[4]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+static const uint32_t pos4_numbers[] = {
+    65536u,
+    77777u,
+    1048576u,
+    4294967295u,
+};
+
+INSTANTIATE_TEST_CASE_P(MessagePackSignedPos4Tests, MessagePackSignedPos4Test,
+                        ::testing::ValuesIn(pos4_numbers), );
+
+// 4294967296..9223372036854775807 (int 64)
+class MessagePackSignedPos8Test : public ::testing::TestWithParam<uint64_t> {};
+TEST_P(MessagePackSignedPos8Test, Case)
+{
+    // create JSON value with integer number
+    json j = -1;
+    j.get_ref<int64_t&>() =
+        static_cast<int64_t>(GetParam());
+
+    // check type
+    EXPECT_TRUE(j.is_number_integer());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0xcf));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 070) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 060) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 050) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 040) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 030) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 020) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 010) & 0xff));
+    expected.push_back(static_cast<char>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+    EXPECT_EQ(result.size(), 9u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xcf));
+    uint64_t restored = (static_cast<uint64_t>(static_cast<uint8_t>(result[1])) << 070) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[2])) << 060) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[3])) << 050) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[4])) << 040) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[5])) << 030) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[6])) << 020) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[7])) << 010) +
+                        static_cast<uint64_t>(static_cast<uint8_t>(result[8]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+static const uint64_t pos8_numbers[] = {
+    4294967296lu,
+    9223372036854775807lu,
+};
+
+INSTANTIATE_TEST_CASE_P(MessagePackSignedPos8Tests, MessagePackSignedPos8Test,
+                        ::testing::ValuesIn(pos8_numbers), );
+
+// -128..-33 (int 8)
+TEST(MessagePackSignedTest, Neg1)
+{
+    for (auto i = -128; i <= -33; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = i;
+
+        // check type
+        EXPECT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0xd0));
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 2u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(0xd0));
+        EXPECT_EQ(static_cast<int8_t>(result[1]), i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// -32768..-129 (int 16)
+TEST(MessagePackSignedTest, Neg2)
+{
+    for (int16_t i = -32768; i <= -129; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with integer number
+        json j = i;
+
+        // check type
+        EXPECT_TRUE(j.is_number_integer());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0xd1));
+        expected.push_back(static_cast<uint8_t>((i >> 8) & 0xff));
+        expected.push_back(static_cast<uint8_t>(i & 0xff));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 3u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(0xd1));
+        int16_t restored = static_cast<int16_t>((static_cast<uint8_t>(result[1]) << 8) +
+                                                static_cast<uint8_t>(result[2]));
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// -32769..-2147483648
+class MessagePackSignedNeg4Test : public ::testing::TestWithParam<int32_t> {};
+TEST_P(MessagePackSignedNeg4Test, Case)
+{
+    // create JSON value with integer number
+    json j = GetParam();
+
+    // check type
+    EXPECT_TRUE(j.is_number_integer());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0xd2));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+    EXPECT_EQ(result.size(), 5u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xd2));
+    uint32_t restored = (static_cast<uint32_t>(static_cast<uint8_t>(result[1])) << 030) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[2])) << 020) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[3])) << 010) +
+                        static_cast<uint32_t>(static_cast<uint8_t>(result[4]));
+    EXPECT_EQ(static_cast<int32_t>(restored), GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+static const int32_t neg4_numbers[] = {
+    -32769,
+    -65536,
+    -77777,
+    -1048576,
+    -2147483648ll,
+};
+
+INSTANTIATE_TEST_CASE_P(MessagePackSignedNeg4Tests, MessagePackSignedNeg4Test,
+                        ::testing::ValuesIn(neg4_numbers), );
+
+// -9223372036854775808..-2147483649 (int 64)
+class MessagePackSignedNeg8Test : public ::testing::TestWithParam<int64_t> {};
+TEST_P(MessagePackSignedNeg8Test, Case)
+{
+    // create JSON value with unsigned integer number
+    json j = GetParam();
+
+    // check type
+    EXPECT_TRUE(j.is_number_integer());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0xd3));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 070) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 060) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 050) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 040) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 030) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 020) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 010) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+    EXPECT_EQ(result.size(), 9u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xd3));
+    int64_t restored = (static_cast<int64_t>(static_cast<uint8_t>(result[1])) << 070) +
+                       (static_cast<int64_t>(static_cast<uint8_t>(result[2])) << 060) +
+                       (static_cast<int64_t>(static_cast<uint8_t>(result[3])) << 050) +
+                       (static_cast<int64_t>(static_cast<uint8_t>(result[4])) << 040) +
+                       (static_cast<int64_t>(static_cast<uint8_t>(result[5])) << 030) +
+                       (static_cast<int64_t>(static_cast<uint8_t>(result[6])) << 020) +
+                       (static_cast<int64_t>(static_cast<uint8_t>(result[7])) << 010) +
+                       static_cast<int64_t>(static_cast<uint8_t>(result[8]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+static const int64_t neg8_numbers[] = {
+    INT64_MIN,
+    -2147483649ll,
+};
+
+INSTANTIATE_TEST_CASE_P(MessagePackSignedNeg8Tests, MessagePackSignedNeg8Test,
+                        ::testing::ValuesIn(neg8_numbers), );
+
+// 0..127 (positive fixnum)
+TEST(MessagePackUnsignedTest, Pos0)
+{
+    for (size_t i = 0; i <= 127; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with unsigned integer number
+        json j = i;
+
+        // check type
+        EXPECT_TRUE(j.is_number_unsigned());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 1u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(i));
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// 128..255 (uint 8)
+TEST(MessagePackUnsignedTest, Pos1)
+{
+    for (size_t i = 128; i <= 255; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with unsigned integer number
+        json j = i;
+
+        // check type
+        EXPECT_TRUE(j.is_number_unsigned());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0xcc));
+        expected.push_back(static_cast<uint8_t>(i));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 2u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(0xcc));
+        uint8_t restored = static_cast<uint8_t>(result[1]);
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// 256..65535 (uint 16)
+TEST(MessagePackUnsignedTest, Pos2)
+{
+    for (size_t i = 256; i <= 65535; ++i)
+    {
+        SCOPED_TRACE(i);
+
+        // create JSON value with unsigned integer number
+        json j = i;
+
+        // check type
+        EXPECT_TRUE(j.is_number_unsigned());
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0xcd));
+        expected.push_back(static_cast<uint8_t>((i >> 8) & 0xff));
+        expected.push_back(static_cast<uint8_t>(i & 0xff));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), 3u);
+
+        // check individual bytes
+        EXPECT_EQ(result[0], static_cast<uint8_t>(0xcd));
+        uint16_t restored = static_cast<uint16_t>(static_cast<uint8_t>(result[1]) * 256 + static_cast<uint8_t>(result[2]));
+        EXPECT_EQ(restored, i);
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// 65536..4294967295 (uint 32)
+class MessagePackUnsignedPos4Test : public ::testing::TestWithParam<uint32_t> {};
+TEST_P(MessagePackUnsignedPos4Test, Case)
+{
+    // create JSON value with unsigned integer number
+    json j = GetParam();
+
+    // check type
+    EXPECT_TRUE(j.is_number_unsigned());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0xce));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+    EXPECT_EQ(result.size(), 5u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xce));
+    uint32_t restored = (static_cast<uint32_t>(static_cast<uint8_t>(result[1])) << 030) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[2])) << 020) +
+                        (static_cast<uint32_t>(static_cast<uint8_t>(result[3])) << 010) +
+                        static_cast<uint32_t>(static_cast<uint8_t>(result[4]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+INSTANTIATE_TEST_CASE_P(MessagePackUnsignedPos4Tests,
+                        MessagePackUnsignedPos4Test,
+                        ::testing::ValuesIn(pos4_numbers), );
+
+// 4294967296..18446744073709551615 (uint 64)
+class MessagePackUnsignedPos8Test : public ::testing::TestWithParam<uint64_t> {};
+TEST_P(MessagePackUnsignedPos8Test, Case)
+{
+    // create JSON value with unsigned integer number
+    json j = GetParam();
+
+    // check type
+    EXPECT_TRUE(j.is_number_unsigned());
+
+    // create expected byte vector
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0xcf));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 070) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 060) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 050) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 040) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 030) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 020) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 010) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+
+    // compare result + size
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+    EXPECT_EQ(result.size(), 9u);
+
+    // check individual bytes
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xcf));
+    uint64_t restored = (static_cast<uint64_t>(static_cast<uint8_t>(result[1])) << 070) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[2])) << 060) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[3])) << 050) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[4])) << 040) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[5])) << 030) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[6])) << 020) +
+                        (static_cast<uint64_t>(static_cast<uint8_t>(result[7])) << 010) +
+                        static_cast<uint64_t>(static_cast<uint8_t>(result[8]));
+    EXPECT_EQ(restored, GetParam());
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+INSTANTIATE_TEST_CASE_P(MessagePackUnsignedPos8Tests,
+                        MessagePackUnsignedPos8Test,
+                        ::testing::ValuesIn(pos8_numbers), );
+
+// 3.1415925
+TEST(MessagePackFloatTest, Number)
+{
+    double v = 3.1415925;
+    json j = v;
+    std::vector<uint8_t> expected = {0xcb,0x40,0x09,0x21,0xfb,0x3f,0xa6,0xde,0xfc};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+    EXPECT_EQ(json::from_msgpack(result), v);
+}
+
+// N = 0..31
+TEST(MessagePackStringTest, String1)
+{
+    // explicitly enumerate the first byte for all 32 strings
+    const std::vector<uint8_t> first_bytes =
+    {
+        0xa0, 0xa1, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8,
+        0xa9, 0xaa, 0xab, 0xac, 0xad, 0xae, 0xaf, 0xb0, 0xb1,
+        0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba,
+        0xbb, 0xbc, 0xbd, 0xbe, 0xbf
+    };
+
+    for (size_t N = 0; N < first_bytes.size(); ++N)
+    {
+        SCOPED_TRACE(N);
+
+        // create JSON value with string containing of N * 'x'
+        const auto s = std::string(N, 'x');
+        json j = s;
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(first_bytes[N]));
+        for (size_t i = 0; i < N; ++i)
+        {
+            expected.push_back('x');
+        }
+
+        // check first byte
+        EXPECT_EQ((first_bytes[N] & 0x1f), static_cast<uint8_t>(N));
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), N + 1);
+        // check that no null byte is appended
+        if (N > 0)
+        {
+            EXPECT_NE(result.back(), '\x00');
+        }
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// N = 32..255
+TEST(MessagePackStringTest, String2)
+{
+    for (size_t N = 32; N <= 255; ++N)
+    {
+        SCOPED_TRACE(N);
+
+        // create JSON value with string containing of N * 'x'
+        const auto s = std::string(N, 'x');
+        json j = s;
+
+        // create expected byte vector
+        std::vector<uint8_t> expected;
+        expected.push_back(static_cast<uint8_t>(0xd9));
+        expected.push_back(static_cast<uint8_t>(N));
+        for (size_t i = 0; i < N; ++i)
+        {
+            expected.push_back('x');
+        }
+
+        // compare result + size
+        const auto result = json::to_msgpack(j);
+        EXPECT_EQ(result, expected);
+        EXPECT_EQ(result.size(), N + 2);
+        // check that no null byte is appended
+        EXPECT_NE(result.back(), '\x00');
+
+        // roundtrip
+        EXPECT_EQ(json::from_msgpack(result), j);
+    }
+}
+
+// N = 256..65535
+class MessagePackString3Test : public ::testing::TestWithParam<size_t> {};
+TEST_P(MessagePackString3Test, Case)
+{
+    // create JSON value with string containing of N * 'x'
+    const auto s = std::string(GetParam(), 'x');
+    json j = s;
+
+    // create expected byte vector (hack: create string first)
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0xda));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+    for (size_t i = 0; i < GetParam(); ++i)
+    {
+        expected.push_back('x');
+    }
+
+    // compare result + size
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+    EXPECT_EQ(result.size(), GetParam() + 3);
+    // check that no null byte is appended
+    EXPECT_NE(result.back(), '\x00');
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+static size_t string3_lens[] = {
+    256u,
+    999u,
+    1025u,
+    3333u,
+    2048u,
+    65535u
+};
+
+INSTANTIATE_TEST_CASE_P(MessagePackString3Tests, MessagePackString3Test,
+                        ::testing::ValuesIn(string3_lens), );
+
+
+// N = 65536..4294967295
+class MessagePackString5Test : public ::testing::TestWithParam<size_t> {};
+TEST_P(MessagePackString5Test, Case)
+{
+    // create JSON value with string containing of N * 'x'
+    const auto s = std::string(GetParam(), 'x');
+    json j = s;
+
+    // create expected byte vector (hack: create string first)
+    std::vector<uint8_t> expected;
+    expected.push_back(static_cast<uint8_t>(0xdb));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 24) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 16) & 0xff));
+    expected.push_back(static_cast<uint8_t>((GetParam() >> 8) & 0xff));
+    expected.push_back(static_cast<uint8_t>(GetParam() & 0xff));
+    for (size_t i = 0; i < GetParam(); ++i)
+    {
+        expected.push_back('x');
+    }
+
+    // compare result + size
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+    EXPECT_EQ(result.size(), GetParam() + 5);
+    // check that no null byte is appended
+    EXPECT_NE(result.back(), '\x00');
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+static size_t string5_lens[] = {
+    65536u,
+    77777u,
+    1048576u
+};
+
+INSTANTIATE_TEST_CASE_P(MessagePackString5Tests, MessagePackString5Test,
+                        ::testing::ValuesIn(string5_lens), );
+
+TEST(MessagePackArrayTest, Empty)
+{
+    json j = json::array();
+    std::vector<uint8_t> expected = {0x90};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// [null]
+TEST(MessagePackArrayTest, Null)
+{
+    json j = {nullptr};
+    std::vector<uint8_t> expected = {0x91,0xc0};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// [1,2,3,4,5]
+TEST(MessagePackArrayTest, Simple)
+{
+    json j = json::parse("[1,2,3,4,5]");
+    std::vector<uint8_t> expected = {0x95,0x01,0x02,0x03,0x04,0x05};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// [[[[]]]]
+TEST(MessagePackArrayTest, NestEmpty)
+{
+    json j = json::parse("[[[[]]]]");
+    std::vector<uint8_t> expected = {0x91,0x91,0x91,0x90};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// array 16
+TEST(MessagePackArrayTest, UInt16)
+{
+    json j(16, nullptr);
+    std::vector<uint8_t> expected(j.size() + 3, static_cast<uint8_t>(0xc0)); // all null
+    expected[0] = static_cast<uint8_t>(0xdc); // array 16
+    expected[1] = 0x00; // size (0x0010), byte 0
+    expected[2] = 0x10; // size (0x0010), byte 1
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// array 32
+TEST(MessagePackArrayTest, UInt32)
+{
+    json j(65536, nullptr);
+    std::vector<uint8_t> expected(j.size() + 5, static_cast<uint8_t>(0xc0)); // all null
+    expected[0] = static_cast<uint8_t>(0xdd); // array 32
+    expected[1] = 0x00; // size (0x00100000), byte 0
+    expected[2] = 0x01; // size (0x00100000), byte 1
+    expected[3] = 0x00; // size (0x00100000), byte 2
+    expected[4] = 0x00; // size (0x00100000), byte 3
+    const auto result = json::to_msgpack(j);
+    //EXPECT_EQ(result, expected);
+
+    EXPECT_EQ(result.size(), expected.size());
+    for (size_t i = 0; i < expected.size(); ++i)
+    {
+        SCOPED_TRACE(i);
+        EXPECT_EQ(result[i], expected[i]);
+    }
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+TEST(MessagePackObjectTest, Empty)
+{
+    json j = json::object();
+    std::vector<uint8_t> expected = {0x80};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// {"":null}
+TEST(MessagePackObjectTest, EmptyKey)
+{
+    json j = {{"", nullptr}};
+    std::vector<uint8_t> expected = {0x81,0xa0,0xc0};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// {"a": {"b": {"c": {}}}}
+TEST(MessagePackObjectTest, NestedEmpty)
+{
+    json j = json::parse("{\"a\": {\"b\": {\"c\": {}}}}");
+    std::vector<uint8_t> expected = {0x81,0xa1,0x61,0x81,0xa1,0x62,0x81,0xa1,0x63,0x80};
+    const auto result = json::to_msgpack(j);
+    EXPECT_EQ(result, expected);
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// map 16
+TEST(MessagePackObjectTest, UInt16)
+{
+    json j = R"({"00": null, "01": null, "02": null, "03": null,
+                 "04": null, "05": null, "06": null, "07": null,
+                 "08": null, "09": null, "10": null, "11": null,
+                 "12": null, "13": null, "14": null, "15": null})"_json;
+
+    const auto result = json::to_msgpack(j);
+
+    // Checking against an expected vector byte by byte is
+    // difficult, because no assumption on the order of key/value
+    // pairs are made. We therefore only check the prefix (type and
+    // size and the overall size. The rest is then handled in the
+    // roundtrip check.
+    EXPECT_EQ(result.size(), 67u); // 1 type, 2 size, 16*4 content
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xde)); // map 16
+    EXPECT_EQ(result[1], 0x00); // byte 0 of size (0x0010)
+    EXPECT_EQ(result[2], 0x10); // byte 1 of size (0x0010)
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// map 32
+TEST(MessagePackObjectTest, UInt32)
+{
+    json j;
+    for (auto i = 0; i < 65536; ++i)
+    {
+        // format i to a fixed width of 5
+        // each entry will need 7 bytes: 6 for fixstr, 1 for null
+        std::stringstream ss;
+        ss << std::setw(5) << std::setfill('0') << i;
+        j.emplace(ss.str(), nullptr);
+    }
+
+    const auto result = json::to_msgpack(j);
+
+    // Checking against an expected vector byte by byte is
+    // difficult, because no assumption on the order of key/value
+    // pairs are made. We therefore only check the prefix (type and
+    // size and the overall size. The rest is then handled in the
+    // roundtrip check.
+    EXPECT_EQ(result.size(), 458757u); // 1 type, 4 size, 65536*7 content
+    EXPECT_EQ(result[0], static_cast<uint8_t>(0xdf)); // map 32
+    EXPECT_EQ(result[1], 0x00); // byte 0 of size (0x00010000)
+    EXPECT_EQ(result[2], 0x01); // byte 1 of size (0x00010000)
+    EXPECT_EQ(result[3], 0x00); // byte 2 of size (0x00010000)
+    EXPECT_EQ(result[4], 0x00); // byte 3 of size (0x00010000)
+
+    // roundtrip
+    EXPECT_EQ(json::from_msgpack(result), j);
+}
+
+// from float32
+TEST(MessagePackFloat32Test, Case)
+{
+    auto given = std::vector<uint8_t>({0xca,0x41,0xc8,0x00,0x01});
+    json j = json::from_msgpack(given);
+    EXPECT_LT(std::fabs(j.get<double>() - 25), 0.001);
+}
+
+TEST(MessagePackErrorTest, TooShortByteVector)
+{
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcc})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 2: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcd})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 2: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcd,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 3: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xce})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 2: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xce,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 3: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xce,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 4: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xce,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 5: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcf})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 2: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcf,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 3: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcf,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 4: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcf,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 5: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcf,0x00,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 6: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcf,0x00,0x00,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 7: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcf,0x00,0x00,0x00,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 8: unexpected end of input");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xcf,0x00,0x00,0x00,0x00,0x00,0x00,0x00})), json::parse_error,
+                     "[json.exception.parse_error.110] parse error at 9: unexpected end of input");
+}
+
+TEST(MessagePackErrorTest, UnsupportedBytesConcrete)
+{
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xc1})), json::parse_error,
+                     "[json.exception.parse_error.112] parse error at 1: error reading MessagePack; last byte: 0xc1");
+    EXPECT_THROW_MSG(json::from_msgpack(std::vector<uint8_t>({0xc6})), json::parse_error,
+                     "[json.exception.parse_error.112] parse error at 1: error reading MessagePack; last byte: 0xc6");
+}
+
+TEST(MessagePackErrorTest, UnsupportedBytesAll)
+{
+    for (auto byte :
+            {
+                // never used
+                0xc1,
+                // bin
+                0xc4, 0xc5, 0xc6,
+                // ext
+                0xc7, 0xc8, 0xc9,
+                // fixext
+                0xd4, 0xd5, 0xd6, 0xd7, 0xd8
+            })
+    {
+        EXPECT_THROW(json::from_msgpack(std::vector<uint8_t>({static_cast<uint8_t>(byte)})), json::parse_error);
+    }
+}
+#if 0
+// use this testcase outside [hide] to run it with Valgrind
+TEST(MessagePackRoundtripTest, Sample)
+{
+    std::string filename = "test/data/json_testsuite/sample.json";
+
+    // parse JSON file
+    std::ifstream f_json(filename);
+    json j1 = json::parse(f_json);
+
+    // parse MessagePack file
+    std::ifstream f_msgpack(filename + ".msgpack", std::ios::binary);
+    std::vector<uint8_t> packed((std::istreambuf_iterator<char>(f_msgpack)),
+                                std::istreambuf_iterator<char>());
+    json j2;
+    EXPECT_NO_THROW(j2 = json::from_msgpack(packed));
+
+    // compare parsed JSON values
+    EXPECT_EQ(j1, j2);
+
+    // check with different start index
+    packed.insert(packed.begin(), 5, 0xff);
+    EXPECT_EQ(j1, json::from_msgpack(packed, 5));
+}
+
+class MessagePackRegressionTest : public ::testing::TestWithParam<const char*> {};
+TEST_P(MessagePackRegressionTest, Case)
+{
+    // parse JSON file
+    std::ifstream f_json(GetParam());
+    json j1 = json::parse(f_json);
+
+    // parse MessagePack file
+    std::ifstream f_msgpack(filename + ".msgpack", std::ios::binary);
+    std::vector<uint8_t> packed((std::istreambuf_iterator<char>(f_msgpack)),
+                                std::istreambuf_iterator<char>());
+    json j2;
+    EXPECT_NO_THROW(j2 = json::from_msgpack(packed));
+
+    // compare parsed JSON values
+    EXPECT_EQ(j1, j2);
+}
+
+static const char* regression_test_cases[] = {
+    "test/data/json_nlohmann_tests/all_unicode.json",
+    "test/data/json.org/1.json",
+    "test/data/json.org/2.json",
+    "test/data/json.org/3.json",
+    "test/data/json.org/4.json",
+    "test/data/json.org/5.json",
+    "test/data/json_roundtrip/roundtrip01.json",
+    "test/data/json_roundtrip/roundtrip02.json",
+    "test/data/json_roundtrip/roundtrip03.json",
+    "test/data/json_roundtrip/roundtrip04.json",
+    "test/data/json_roundtrip/roundtrip05.json",
+    "test/data/json_roundtrip/roundtrip06.json",
+    "test/data/json_roundtrip/roundtrip07.json",
+    "test/data/json_roundtrip/roundtrip08.json",
+    "test/data/json_roundtrip/roundtrip09.json",
+    "test/data/json_roundtrip/roundtrip10.json",
+    "test/data/json_roundtrip/roundtrip11.json",
+    "test/data/json_roundtrip/roundtrip12.json",
+    "test/data/json_roundtrip/roundtrip13.json",
+    "test/data/json_roundtrip/roundtrip14.json",
+    "test/data/json_roundtrip/roundtrip15.json",
+    "test/data/json_roundtrip/roundtrip16.json",
+    "test/data/json_roundtrip/roundtrip17.json",
+    "test/data/json_roundtrip/roundtrip18.json",
+    "test/data/json_roundtrip/roundtrip19.json",
+    "test/data/json_roundtrip/roundtrip20.json",
+    "test/data/json_roundtrip/roundtrip21.json",
+    "test/data/json_roundtrip/roundtrip22.json",
+    "test/data/json_roundtrip/roundtrip23.json",
+    "test/data/json_roundtrip/roundtrip24.json",
+    "test/data/json_roundtrip/roundtrip25.json",
+    "test/data/json_roundtrip/roundtrip26.json",
+    "test/data/json_roundtrip/roundtrip27.json",
+    "test/data/json_roundtrip/roundtrip28.json",
+    "test/data/json_roundtrip/roundtrip29.json",
+    "test/data/json_roundtrip/roundtrip30.json",
+    "test/data/json_roundtrip/roundtrip31.json",
+    "test/data/json_roundtrip/roundtrip32.json",
+    "test/data/json_testsuite/sample.json", // kills AppVeyor
+    "test/data/json_tests/pass1.json",
+    "test/data/json_tests/pass2.json",
+    "test/data/json_tests/pass3.json",
+    "test/data/regression/floats.json",
+    "test/data/regression/signed_ints.json",
+    "test/data/regression/unsigned_ints.json",
+    "test/data/regression/working_file.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_arraysWithSpaces.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_empty-string.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_empty.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_ending_with_newline.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_false.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_heterogeneous.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_null.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_with_1_and_newline.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_with_leading_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_with_several_null.json",
+    "test/data/nst_json_testsuite/test_parsing/y_array_with_trailing_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_0e+1.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_0e1.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_after_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_double_close_to_zero.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_double_huge_neg_exp.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_huge_exp.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_int_with_exp.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_minus_zero.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_negative_int.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_negative_one.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_negative_zero.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_capital_e.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_capital_e_neg_exp.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_capital_e_pos_exp.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_exponent.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_fraction_exponent.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_neg_exp.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_real_neg_overflow.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_pos_exponent.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_real_pos_overflow.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_real_underflow.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_simple_int.json",
+    "test/data/nst_json_testsuite/test_parsing/y_number_simple_real.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_too_big_neg_int.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_too_big_pos_int.json",
+    //"test/data/nst_json_testsuite/test_parsing/y_number_very_big_negative_int.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_basic.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_duplicated_key.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_duplicated_key_and_value.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_empty.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_empty_key.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_escaped_null_in_key.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_extreme_numbers.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_long_strings.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_simple.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_string_unicode.json",
+    "test/data/nst_json_testsuite/test_parsing/y_object_with_newlines.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_1_2_3_bytes_UTF-8_sequences.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_UTF-16_Surrogates_U+1D11E_MUSICAL_SYMBOL_G_CLEF.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_accepted_surrogate_pair.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_accepted_surrogate_pairs.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_allowed_escapes.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_backslash_and_u_escaped_zero.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_backslash_doublequotes.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_comments.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_double_escape_a.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_double_escape_n.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_escaped_control_character.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_escaped_noncharacter.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_in_array.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_in_array_with_leading_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_last_surrogates_1_and_2.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_newline_uescaped.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_nonCharacterInUTF-8_U+10FFFF.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_nonCharacterInUTF-8_U+1FFFF.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_nonCharacterInUTF-8_U+FFFF.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_null_escape.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_one-byte-utf-8.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_pi.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_simple_ascii.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_space.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_three-byte-utf-8.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_two-byte-utf-8.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_u+2028_line_sep.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_u+2029_par_sep.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_uEscape.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unescaped_char_delete.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicodeEscapedBackslash.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode_2.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode_U+200B_ZERO_WIDTH_SPACE.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode_U+2064_invisible_plus.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_unicode_escaped_double_quote.json",
+    // "test/data/nst_json_testsuite/test_parsing/y_string_utf16.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_utf8.json",
+    "test/data/nst_json_testsuite/test_parsing/y_string_with_del_character.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_false.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_int.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_negative_real.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_null.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_string.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_lonely_true.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_string_empty.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_trailing_newline.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_true_in_array.json",
+    "test/data/nst_json_testsuite/test_parsing/y_structure_whitespace_array.json",
+};
+
+INSTANTIATE_TEST_CASE_P(MessagePackRegressionTests, MessagePackRegressionTest,
+                        ::testing::ValuesIn(regression_test_cases));
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-pointer_access.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-pointer_access.cpp
new file mode 100644
index 0000000..a1a7fa4
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-pointer_access.cpp
@@ -0,0 +1,463 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+TEST(JsonPointerTest, TypesCreate)
+{
+    // create a JSON value with different types
+    json json_types =
+    {
+        {"boolean", true},
+        {
+            "number", {
+                {"integer", 42},
+                {"unsigned", 42u},
+                {"floating-point", 17.23}
+            }
+        },
+        {"string", "Hello, world!"},
+        {"array", {1, 2, 3, 4, 5}},
+        {"null", nullptr}
+    };
+}
+
+// pointer access to object_t
+TEST(JsonPointerTest, ObjectT)
+{
+    using test_type = json::object_t;
+    json value = {{"one", 1}, {"two", 2}};
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_NE(value.get_ptr<json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<double*>(), nullptr);
+}
+
+// pointer access to const object_t
+TEST(JsonPointerTest, ConstObjectT)
+{
+    using test_type = const json::object_t;
+    const json value = {{"one", 1}, {"two", 2}};
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_NE(value.get_ptr<const json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const double*>(), nullptr);
+}
+
+// pointer access to array_t
+TEST(JsonPointerTest, ArrayT)
+{
+    using test_type = json::array_t;
+    json value = {1, 2, 3, 4};
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<json::object_t*>(), nullptr);
+    EXPECT_NE(value.get_ptr<json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<double*>(), nullptr);
+}
+
+// pointer access to const array_t
+TEST(JsonPointerTest, ConstArrayT)
+{
+    using test_type = const json::array_t;
+    const json value = {1, 2, 3, 4};
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<const json::object_t*>(), nullptr);
+    EXPECT_NE(value.get_ptr<const json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const double*>(), nullptr);
+}
+
+// pointer access to string_t
+TEST(JsonPointerTest, StringT)
+{
+    using test_type = std::string;
+    json value = "hello";
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<json::array_t*>(), nullptr);
+    EXPECT_NE(value.get_ptr<std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<double*>(), nullptr);
+}
+
+// pointer access to const string_t
+TEST(JsonPointerTest, ConstStringT)
+{
+    using test_type = const std::string;
+    const json value = "hello";
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<const json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const json::array_t*>(), nullptr);
+    EXPECT_NE(value.get_ptr<const std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const double*>(), nullptr);
+}
+
+// pointer access to boolean_t
+TEST(JsonPointerTest, BooleanT)
+{
+    using test_type = bool;
+    json value = false;
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<std::string*>(), nullptr);
+    EXPECT_NE(value.get_ptr<bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<double*>(), nullptr);
+}
+
+// pointer access to const boolean_t
+TEST(JsonPointerTest, ConstBooleanT)
+{
+    using test_type = const bool;
+    const json value = false;
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    //EXPECT_EQ(*p1, value.get<test_type>());
+
+    //const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    //EXPECT_EQ(*p2, value.get<test_type>());
+
+    //const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    //EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<const json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const std::string*>(), nullptr);
+    EXPECT_NE(value.get_ptr<const bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const double*>(), nullptr);
+}
+
+// pointer access to number_integer_t
+TEST(JsonPointerTest, IntegerT)
+{
+    using test_type = int64_t;
+    json value = 23;
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<bool*>(), nullptr);
+    EXPECT_NE(value.get_ptr<int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<double*>(), nullptr);
+}
+
+// pointer access to const number_integer_t
+TEST(JsonPointerTest, ConstIntegerT)
+{
+    using test_type = const int64_t;
+    const json value = 23;
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<const json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const bool*>(), nullptr);
+    EXPECT_NE(value.get_ptr<const int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const double*>(), nullptr);
+}
+
+// pointer access to number_unsigned_t
+TEST(JsonPointerTest, UnsignedT)
+{
+    using test_type = uint64_t;
+    json value = 23u;
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<bool*>(), nullptr);
+    EXPECT_NE(value.get_ptr<int64_t*>(), nullptr);
+    EXPECT_NE(value.get_ptr<uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<double*>(), nullptr);
+}
+
+// pointer access to const number_unsigned_t
+TEST(JsonPointerTest, ConstUnsignedT)
+{
+    using test_type = const uint64_t;
+    const json value = 23u;
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(*p1, value.get<test_type>());
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_EQ(*p2, value.get<test_type>());
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_EQ(*p3, value.get<test_type>());
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<const json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const bool*>(), nullptr);
+    EXPECT_NE(value.get_ptr<const int64_t*>(), nullptr);
+    EXPECT_NE(value.get_ptr<const uint64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const double*>(), nullptr);
+}
+
+// pointer access to number_float_t
+TEST(JsonPointerTest, FloatT)
+{
+    using test_type = double;
+    json value = 42.23;
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_LT(std::fabs(*p1 - value.get<test_type>()), 0.001);
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_LT(std::fabs(*p2 - value.get<test_type>()), 0.001);
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_LT(std::fabs(*p3 - value.get<test_type>()), 0.001);
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<uint64_t*>(), nullptr);
+    EXPECT_NE(value.get_ptr<double*>(), nullptr);
+}
+
+// pointer access to const number_float_t
+TEST(JsonPointerTest, ConstFloatT)
+{
+    using test_type = const double;
+    const json value = 42.23;
+
+    // check if pointers are returned correctly
+    test_type* p1 = value.get_ptr<test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<test_type*>());
+    EXPECT_LT(std::fabs(*p1 - value.get<test_type>()), 0.001);
+
+    const test_type* p2 = value.get_ptr<const test_type*>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type*>());
+    EXPECT_LT(std::fabs(*p2 - value.get<test_type>()), 0.001);
+
+    const test_type* const p3 = value.get_ptr<const test_type* const>();
+    EXPECT_EQ(p1, value.get_ptr<const test_type* const>());
+    EXPECT_LT(std::fabs(*p3 - value.get<test_type>()), 0.001);
+
+    // check if null pointers are returned correctly
+    EXPECT_EQ(value.get_ptr<const json::object_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const json::array_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const std::string*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const bool*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const int64_t*>(), nullptr);
+    EXPECT_EQ(value.get_ptr<const uint64_t*>(), nullptr);
+    EXPECT_NE(value.get_ptr<const double*>(), nullptr);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-readme.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-readme.cpp
new file mode 100644
index 0000000..ecb7f79
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-readme.cpp
@@ -0,0 +1,327 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+#include <array>
+#include <deque>
+#include <forward_list>
+#include <list>
+#include <map>
+#include <unordered_map>
+#include <unordered_set>
+
+#include "wpi/raw_ostream.h"
+
+TEST(JsonReadmeTest, Basic)
+{
+    // create an empty structure (null)
+    json j;
+
+    // add a number that is stored as double (note the implicit conversion of j to an object)
+    j["pi"] = 3.141;
+
+    // add a Boolean that is stored as bool
+    j["happy"] = true;
+
+    // add a string that is stored as std::string
+    j["name"] = "Niels";
+
+    // add another null object by passing nullptr
+    j["nothing"] = nullptr;
+
+    // add an object inside the object
+    j["answer"]["everything"] = 42;
+
+    // add an array that is stored as std::vector (using an initializer list)
+    j["list"] = { 1, 0, 2 };
+
+    // add another object (using an initializer list of pairs)
+    j["object"] = { {"currency", "USD"}, {"value", 42.99} };
+
+    // instead, you could also write (which looks very similar to the JSON above)
+    json j2 =
+    {
+        {"pi", 3.141},
+        {"happy", true},
+        {"name", "Niels"},
+        {"nothing", nullptr},
+        {
+            "answer", {
+                {"everything", 42}
+            }
+        },
+        {"list", {1, 0, 2}},
+        {
+            "object", {
+                {"currency", "USD"},
+                {"value", 42.99}
+            }
+        }
+    };
+}
+
+TEST(JsonReadmeTest, Other)
+{
+    // ways to express the empty array []
+    json empty_array_implicit = {{}};
+    json empty_array_explicit = json::array();
+
+    // a way to express the empty object {}
+    json empty_object_explicit = json::object();
+
+    // a way to express an _array_ of key/value pairs [["currency", "USD"], ["value", 42.99]]
+    json array_not_object = { json::array({"currency", "USD"}), json::array({"value", 42.99}) };
+}
+
+TEST(JsonReadmeTest, FromToString)
+{
+    // create object from string literal
+    json j = "{ \"happy\": true, \"pi\": 3.141 }"_json;
+
+    // or even nicer with a raw string literal
+    auto j2 = R"(
+  {
+    "happy": true,
+    "pi": 3.141
+  }
+)"_json;
+
+    // or explicitly
+    auto j3 = json::parse("{ \"happy\": true, \"pi\": 3.141 }");
+
+    // explicit conversion to string
+    std::string s;
+    wpi::raw_string_ostream os(s);
+    j.dump(os);    // {\"happy\":true,\"pi\":3.141}
+    EXPECT_EQ(os.str(), "{\"happy\":true,\"pi\":3.141}");
+
+    // serialization with pretty printing
+    // pass in the amount of spaces to indent
+    std::string s2;
+    wpi::raw_string_ostream os2(s2);
+    j2.dump(os2, 4);
+    EXPECT_EQ(os2.str(), "{\n    \"happy\": true,\n    \"pi\": 3.141\n}");
+    // {
+    //     "happy": true,
+    //     "pi": 3.141
+    // }
+}
+
+TEST(JsonReadmeTest, Basic2)
+{
+    // create an array using push_back
+    json j;
+    j.push_back("foo");
+    j.push_back(1);
+    j.push_back(true);
+
+    std::string s;
+    wpi::raw_string_ostream os(s);
+
+    // iterate the array
+    for (json::iterator it = j.begin(); it != j.end(); ++it)
+    {
+        os << *it << '\n';
+    }
+
+    // range-based for
+    for (auto element : j)
+    {
+        os << element << '\n';
+    }
+
+    // comparison
+    bool x = (j == "[\"foo\", 1, true]"_json);  // true
+    EXPECT_EQ(x, true);
+
+    // getter/setter
+    const std::string tmp = j[0];
+    j[1] = 42;
+    bool foo = j.at(2);
+    EXPECT_EQ(foo, true);
+
+    // other stuff
+    EXPECT_EQ(j.size(), 3u);        // 3 entries
+    EXPECT_EQ(j.empty(), false);
+    EXPECT_EQ(j.type(), json::value_t::array);
+    j.clear();    // the array is empty again
+    EXPECT_EQ(j.size(), 0u);
+    EXPECT_EQ(j.empty(), true);
+
+    // create an object
+    json o;
+    o["foo"] = 23;
+    o["bar"] = false;
+    o["baz"] = 3.141;
+
+    // find an entry
+    if (o.find("foo") != o.end())
+    {
+        // there is an entry with key "foo"
+    }
+}
+
+TEST(JsonReadmeTest, OtherContainer)
+{
+    std::vector<int> c_vector {1, 2, 3, 4};
+    json j_vec(c_vector);
+    json j_vec2(wpi::makeArrayRef(c_vector));
+    // [1, 2, 3, 4]
+
+    std::deque<float> c_deque {1.2f, 2.3f, 3.4f, 5.6f};
+    json j_deque(c_deque);
+    // [1.2, 2.3, 3.4, 5.6]
+
+    std::list<bool> c_list {true, true, false, true};
+    json j_list(c_list);
+    // [true, true, false, true]
+
+    std::forward_list<int64_t> c_flist {12345678909876, 23456789098765, 34567890987654, 45678909876543};
+    json j_flist(c_flist);
+    // [12345678909876, 23456789098765, 34567890987654, 45678909876543]
+
+    std::array<unsigned long, 4> c_array {{1, 2, 3, 4}};
+    json j_array(c_array);
+    // [1, 2, 3, 4]
+
+    std::set<std::string> c_set {"one", "two", "three", "four", "one"};
+    json j_set(c_set); // only one entry for "one" is used
+    // ["four", "one", "three", "two"]
+
+    std::unordered_set<std::string> c_uset {"one", "two", "three", "four", "one"};
+    json j_uset(c_uset); // only one entry for "one" is used
+    // maybe ["two", "three", "four", "one"]
+
+    std::multiset<std::string> c_mset {"one", "two", "one", "four"};
+    json j_mset(c_mset); // both entries for "one" are used
+    // maybe ["one", "two", "one", "four"]
+
+    std::unordered_multiset<std::string> c_umset {"one", "two", "one", "four"};
+    json j_umset(c_umset); // both entries for "one" are used
+    // maybe ["one", "two", "one", "four"]
+}
+
+TEST(JsonReadmeTest, MapContainer)
+{
+    std::map<std::string, int> c_map { {"one", 1}, {"two", 2}, {"three", 3} };
+    json j_map(c_map);
+    // {"one": 1, "two": 2, "three": 3}
+
+#if 0
+    std::unordered_map<const char*, float> c_umap { {"one", 1.2f}, {"two", 2.3f}, {"three", 3.4f} };
+    json j_umap(c_umap);
+    // {"one": 1.2, "two": 2.3, "three": 3.4}
+#endif
+
+    std::multimap<std::string, bool> c_mmap { {"one", true}, {"two", true}, {"three", false}, {"three", true} };
+    json j_mmap(c_mmap); // only one entry for key "three" is used
+    // maybe {"one": true, "two": true, "three": true}
+
+    std::unordered_multimap<std::string, bool> c_ummap { {"one", true}, {"two", true}, {"three", false}, {"three", true} };
+    json j_ummap(c_ummap); // only one entry for key "three" is used
+    // maybe {"one": true, "two": true, "three": true}
+}
+
+TEST(JsonReadmeTest, Values)
+{
+    // strings
+    std::string s1 = "Hello, world!";
+    json js = s1;
+    std::string s2 = js;
+    EXPECT_EQ(s1, s2);
+
+    // Booleans
+    bool b1 = true;
+    json jb = b1;
+    bool b2 = jb;
+    EXPECT_EQ(b1, b2);
+
+    // numbers
+    int i = 42;
+    json jn = i;
+    double f = jn;
+    EXPECT_EQ(i, f);
+
+    // etc.
+
+    std::string vs = js.get<std::string>();
+    bool vb = jb.get<bool>();
+    int vi = jn.get<int>();
+    EXPECT_EQ(s1, vs);
+    EXPECT_EQ(b1, vb);
+    EXPECT_EQ(i, vi);
+
+    // etc.
+}
+
+#if 0
+TEST(JsonReadmeTest, DiffPatch)
+{
+    // a JSON value
+    json j_original = R"({
+  "baz": ["one", "two", "three"],
+  "foo": "bar"
+})"_json;
+
+    // access members with a JSON pointer (RFC 6901)
+    j_original["/baz/1"_json_pointer];
+    // "two"
+
+    // a JSON patch (RFC 6902)
+    json j_patch = R"([
+  { "op": "replace", "path": "/baz", "value": "boo" },
+  { "op": "add", "path": "/hello", "value": ["world"] },
+  { "op": "remove", "path": "/foo"}
+])"_json;
+
+    // apply the patch
+    json j_result = j_original.patch(j_patch);
+    // {
+    //    "baz": "boo",
+    //    "hello": ["world"]
+    // }
+
+    // calculate a JSON patch from two JSON values
+    json::diff(j_result, j_original);
+    // [
+    //   { "op":" replace", "path": "/baz", "value": ["one", "two", "three"] },
+    //   { "op":"remove","path":"/hello" },
+    //   { "op":"add","path":"/foo","value":"bar" }
+    // ]
+}
+#endif
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-reference_access.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-reference_access.cpp
new file mode 100644
index 0000000..7c3cfb1
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-reference_access.cpp
@@ -0,0 +1,197 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+// reference access to object_t
+TEST(JsonReferenceTest, ObjectT)
+{
+    using test_type = json::object_t;
+    json value = {{"one", 1}, {"two", 2}};
+
+    // check if references are returned correctly
+    test_type& p1 = value.get_ref<test_type&>();
+    EXPECT_EQ(&p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(p1, value.get<test_type>());
+
+    const test_type& p2 = value.get_ref<const test_type&>();
+    EXPECT_EQ(&p2, value.get_ptr<const test_type*>());
+    EXPECT_EQ(p2, value.get<test_type>());
+
+    // check if mismatching references throw correctly
+    EXPECT_NO_THROW(value.get_ref<json::object_t&>());
+    EXPECT_ANY_THROW(value.get_ref<json::array_t&>());
+    EXPECT_ANY_THROW(value.get_ref<std::string&>());
+    EXPECT_ANY_THROW(value.get_ref<bool&>());
+    EXPECT_ANY_THROW(value.get_ref<int64_t&>());
+    EXPECT_ANY_THROW(value.get_ref<double&>());
+}
+
+// const reference access to const object_t
+TEST(JsonReferenceTest, ConstObjectT)
+{
+    using test_type = json::object_t;
+    const json value = {{"one", 1}, {"two", 2}};
+
+    // this should not compile
+    // test_type& p1 = value.get_ref<test_type&>();
+
+    // check if references are returned correctly
+    const test_type& p2 = value.get_ref<const test_type&>();
+    EXPECT_EQ(&p2, value.get_ptr<const test_type*>());
+    EXPECT_EQ(p2, value.get<test_type>());
+}
+
+// reference access to array_t
+TEST(JsonReferenceTest, ArrayT)
+{
+    using test_type = json::array_t;
+    json value = {1, 2, 3, 4};
+
+    // check if references are returned correctly
+    test_type& p1 = value.get_ref<test_type&>();
+    EXPECT_EQ(&p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(p1, value.get<test_type>());
+
+    const test_type& p2 = value.get_ref<const test_type&>();
+    EXPECT_EQ(&p2, value.get_ptr<const test_type*>());
+    EXPECT_EQ(p2, value.get<test_type>());
+
+    // check if mismatching references throw correctly
+    EXPECT_ANY_THROW(value.get_ref<json::object_t&>());
+    EXPECT_NO_THROW(value.get_ref<json::array_t&>());
+    EXPECT_ANY_THROW(value.get_ref<std::string&>());
+    EXPECT_ANY_THROW(value.get_ref<bool&>());
+    EXPECT_ANY_THROW(value.get_ref<int64_t&>());
+    EXPECT_ANY_THROW(value.get_ref<double&>());
+}
+
+// reference access to string_t
+TEST(JsonReferenceTest, StringT)
+{
+    using test_type = std::string;
+    json value = "hello";
+
+    // check if references are returned correctly
+    test_type& p1 = value.get_ref<test_type&>();
+    EXPECT_EQ(&p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(p1, value.get<test_type>());
+
+    const test_type& p2 = value.get_ref<const test_type&>();
+    EXPECT_EQ(&p2, value.get_ptr<const test_type*>());
+    EXPECT_EQ(p2, value.get<test_type>());
+
+    // check if mismatching references throw correctly
+    EXPECT_ANY_THROW(value.get_ref<json::object_t&>());
+    EXPECT_ANY_THROW(value.get_ref<json::array_t&>());
+    EXPECT_NO_THROW(value.get_ref<std::string&>());
+    EXPECT_ANY_THROW(value.get_ref<bool&>());
+    EXPECT_ANY_THROW(value.get_ref<int64_t&>());
+    EXPECT_ANY_THROW(value.get_ref<double&>());
+}
+
+// reference access to boolean_t
+TEST(JsonReferenceTest, BooleanT)
+{
+    using test_type = bool;
+    json value = false;
+
+    // check if references are returned correctly
+    test_type& p1 = value.get_ref<test_type&>();
+    EXPECT_EQ(&p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(p1, value.get<test_type>());
+
+    const test_type& p2 = value.get_ref<const test_type&>();
+    EXPECT_EQ(&p2, value.get_ptr<const test_type*>());
+    EXPECT_EQ(p2, value.get<test_type>());
+
+    // check if mismatching references throw correctly
+    EXPECT_ANY_THROW(value.get_ref<json::object_t&>());
+    EXPECT_ANY_THROW(value.get_ref<json::array_t&>());
+    EXPECT_ANY_THROW(value.get_ref<std::string&>());
+    EXPECT_NO_THROW(value.get_ref<bool&>());
+    EXPECT_ANY_THROW(value.get_ref<int64_t&>());
+    EXPECT_ANY_THROW(value.get_ref<double&>());
+}
+
+// reference access to number_integer_t
+TEST(JsonReferenceTest, IntegerT)
+{
+    using test_type = int64_t;
+    json value = 23;
+
+    // check if references are returned correctly
+    test_type& p1 = value.get_ref<test_type&>();
+    EXPECT_EQ(&p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(p1, value.get<test_type>());
+
+    const test_type& p2 = value.get_ref<const test_type&>();
+    EXPECT_EQ(&p2, value.get_ptr<const test_type*>());
+    EXPECT_EQ(p2, value.get<test_type>());
+
+    // check if mismatching references throw correctly
+    EXPECT_ANY_THROW(value.get_ref<json::object_t&>());
+    EXPECT_ANY_THROW(value.get_ref<json::array_t&>());
+    EXPECT_ANY_THROW(value.get_ref<std::string&>());
+    EXPECT_ANY_THROW(value.get_ref<bool&>());
+    EXPECT_NO_THROW(value.get_ref<int64_t&>());
+    EXPECT_ANY_THROW(value.get_ref<double&>());
+}
+
+// reference access to number_float_t
+TEST(JsonReferenceTest, FloatT)
+{
+    using test_type = double;
+    json value = 42.23;
+
+    // check if references are returned correctly
+    test_type& p1 = value.get_ref<test_type&>();
+    EXPECT_EQ(&p1, value.get_ptr<test_type*>());
+    EXPECT_EQ(p1, value.get<test_type>());
+
+    const test_type& p2 = value.get_ref<const test_type&>();
+    EXPECT_EQ(&p2, value.get_ptr<const test_type*>());
+    EXPECT_EQ(p2, value.get<test_type>());
+
+    // check if mismatching references throw correctly
+    EXPECT_ANY_THROW(value.get_ref<json::object_t&>());
+    EXPECT_ANY_THROW(value.get_ref<json::array_t&>());
+    EXPECT_ANY_THROW(value.get_ref<std::string&>());
+    EXPECT_ANY_THROW(value.get_ref<bool&>());
+    EXPECT_ANY_THROW(value.get_ref<int64_t&>());
+    EXPECT_NO_THROW(value.get_ref<double&>());
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-unicode.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-unicode.cpp
new file mode 100644
index 0000000..e0179b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/json/unit-unicode.cpp
@@ -0,0 +1,1093 @@
+/*----------------------------------------------------------------------------*/
+/* Modifications Copyright (c) FIRST 2017. 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.                                                               */
+/*----------------------------------------------------------------------------*/
+/*
+    __ _____ _____ _____
+ __|  |   __|     |   | |  JSON for Modern C++ (test suite)
+|  |  |__   |  |  | | | |  version 2.1.1
+|_____|_____|_____|_|___|  https://github.com/nlohmann/json
+
+Licensed under the MIT License <http://opensource.org/licenses/MIT>.
+Copyright (c) 2013-2017 Niels Lohmann <http://nlohmann.me>.
+
+Permission is hereby  granted, free of charge, to any  person obtaining a copy
+of this software and associated  documentation files (the "Software"), to deal
+in the Software  without restriction, including without  limitation the rights
+to  use, copy,  modify, merge,  publish, distribute,  sublicense, and/or  sell
+copies  of  the Software,  and  to  permit persons  to  whom  the Software  is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE  IS PROVIDED "AS  IS", WITHOUT WARRANTY  OF ANY KIND,  EXPRESS OR
+IMPLIED,  INCLUDING BUT  NOT  LIMITED TO  THE  WARRANTIES OF  MERCHANTABILITY,
+FITNESS FOR  A PARTICULAR PURPOSE AND  NONINFRINGEMENT. IN NO EVENT  SHALL THE
+AUTHORS  OR COPYRIGHT  HOLDERS  BE  LIABLE FOR  ANY  CLAIM,  DAMAGES OR  OTHER
+LIABILITY, WHETHER IN AN ACTION OF  CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE  OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+*/
+
+#include "gtest/gtest.h"
+
+#include "unit-json.h"
+using wpi::json;
+
+#include "wpi/Format.h"
+#include "wpi/StringExtras.h"
+#include "wpi/raw_ostream.h"
+
+#include <fstream>
+
+// create and check a JSON string with up to four UTF-8 bytes
+::testing::AssertionResult check_utf8string(bool success_expected, int byte1, int byte2 = -1, int byte3 = -1, int byte4 = -1)
+{
+    std::string json_string = "\"";
+
+    json_string += std::string(1, static_cast<char>(byte1));
+
+    if (byte2 != -1)
+    {
+        json_string += std::string(1, static_cast<char>(byte2));
+    }
+
+    if (byte3 != -1)
+    {
+        json_string += std::string(1, static_cast<char>(byte3));
+    }
+
+    if (byte4 != -1)
+    {
+        json_string += std::string(1, static_cast<char>(byte4));
+    }
+
+    json_string += "\"";
+
+    const char* basemsg = "";
+
+    try {
+        json::parse(json_string);
+    } catch (json::parse_error&) {
+        if (success_expected)
+        {
+            basemsg = "parse_error";
+            goto error;
+        }
+        return ::testing::AssertionSuccess();
+    } catch (...) {
+        basemsg = "other exception";
+        goto error;
+    }
+
+    if (success_expected)
+    {
+        return ::testing::AssertionSuccess();
+    }
+    basemsg = "expected failure";
+
+error:
+    auto result = ::testing::AssertionFailure();
+    result << basemsg << " with {" << wpi::utohexstr(byte1);
+    if (byte2 != -1)
+    {
+        result << ',' << wpi::utohexstr(byte2);
+    }
+    if (byte3 != -1)
+    {
+        result << ',' << wpi::utohexstr(byte3);
+    }
+    if (byte4 != -1)
+    {
+        result << ',' << wpi::utohexstr(byte4);
+    }
+    result << '}';
+    return result;
+}
+
+/*
+RFC 3629 describes in Sect. 4 the syntax of UTF-8 byte sequences as
+follows:
+
+    A UTF-8 string is a sequence of octets representing a sequence of UCS
+    characters.  An octet sequence is valid UTF-8 only if it matches the
+    following syntax, which is derived from the rules for encoding UTF-8
+    and is expressed in the ABNF of [RFC2234].
+
+    UTF8-octets = *( UTF8-char )
+    UTF8-char   = UTF8-1 / UTF8-2 / UTF8-3 / UTF8-4
+    UTF8-1      = %x00-7F
+    UTF8-2      = %xC2-DF UTF8-tail
+    UTF8-3      = %xE0 %xA0-BF UTF8-tail / %xE1-EC 2( UTF8-tail ) /
+                  %xED %x80-9F UTF8-tail / %xEE-EF 2( UTF8-tail )
+    UTF8-4      = %xF0 %x90-BF 2( UTF8-tail ) / %xF1-F3 3( UTF8-tail ) /
+                  %xF4 %x80-8F 2( UTF8-tail )
+    UTF8-tail   = %x80-BF
+*/
+
+// ill-formed first byte
+TEST(JsonUnicodeRfc3629Test, IllFormedFirstByte)
+{
+    for (int byte1 = 0x80; byte1 <= 0xC1; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+
+    for (int byte1 = 0xF5; byte1 <= 0xFF; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// UTF8-1 (x00-x7F), well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_1WellFormed)
+{
+    for (int byte1 = 0x00; byte1 <= 0x7F; ++byte1)
+    {
+        // unescaped control characters are parse errors in JSON
+        if (0x00 <= byte1 && byte1 <= 0x1F)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1));
+            continue;
+        }
+
+        // a single quote is a parse error in JSON
+        if (byte1 == 0x22)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1));
+            continue;
+        }
+
+        // a single backslash is a parse error in JSON
+        if (byte1 == 0x5C)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1));
+            continue;
+        }
+
+        // all other characters are OK
+        EXPECT_TRUE(check_utf8string(true, byte1));
+    }
+}
+
+// UTF8-2 (xC2-xDF UTF8-tail)
+// well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_2WellFormed)
+{
+    for (int byte1 = 0xC2; byte1 <= 0xDF; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            EXPECT_TRUE(check_utf8string(true, byte1, byte2));
+        }
+    }
+}
+
+// ill-formed: missing second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_2Missing2)
+{
+    for (int byte1 = 0xC2; byte1 <= 0xDF; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// ill-formed: wrong second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_2Wrong2)
+{
+    for (int byte1 = 0xC2; byte1 <= 0xDF; ++byte1)
+    {
+        for (int byte2 = 0x00; byte2 <= 0xFF; ++byte2)
+        {
+            // skip correct second byte
+            if (0x80 <= byte2 && byte2 <= 0xBF)
+            {
+                continue;
+            }
+
+            EXPECT_TRUE(check_utf8string(false, byte1, byte2));
+        }
+    }
+}
+
+// UTF8-3 (xE0 xA0-BF UTF8-tail)
+// well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_3AWellFormed)
+{
+    for (int byte1 = 0xE0; byte1 <= 0xE0; ++byte1)
+    {
+        for (int byte2 = 0xA0; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(true, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: missing second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3AMissing2)
+{
+    for (int byte1 = 0xE0; byte1 <= 0xE0; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// ill-formed: missing third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3AMissing3)
+{
+    for (int byte1 = 0xE0; byte1 <= 0xE0; ++byte1)
+    {
+        for (int byte2 = 0xA0; byte2 <= 0xBF; ++byte2)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1, byte2));
+        }
+    }
+}
+
+// ill-formed: wrong second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3AWrong2)
+{
+    for (int byte1 = 0xE0; byte1 <= 0xE0; ++byte1)
+    {
+        for (int byte2 = 0x00; byte2 <= 0xFF; ++byte2)
+        {
+            // skip correct second byte
+            if (0xA0 <= byte2 && byte2 <= 0xBF)
+            {
+                continue;
+            }
+
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: wrong third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3AWrong3)
+{
+    for (int byte1 = 0xE0; byte1 <= 0xE0; ++byte1)
+    {
+        for (int byte2 = 0xA0; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x00; byte3 <= 0xFF; ++byte3)
+            {
+                // skip correct third byte
+                if (0x80 <= byte3 && byte3 <= 0xBF)
+                {
+                    continue;
+                }
+
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// UTF8-3 (xE1-xEC UTF8-tail UTF8-tail)
+// well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_3BWellFormed)
+{
+    for (int byte1 = 0xE1; byte1 <= 0xEC; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(true, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: missing second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3BMissing2)
+{
+    for (int byte1 = 0xE1; byte1 <= 0xEC; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// ill-formed: missing third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3BMissing3)
+{
+    for (int byte1 = 0xE1; byte1 <= 0xEC; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1, byte2));
+        }
+    }
+}
+
+// ill-formed: wrong second byte
+TEST(JsonUnicodeRfc3629Test, DISABLED_Utf8_3BWrong2)
+{
+    for (int byte1 = 0xE1; byte1 <= 0xEC; ++byte1)
+    {
+        for (int byte2 = 0x00; byte2 <= 0xFF; ++byte2)
+        {
+            // skip correct second byte
+            if (0x80 <= byte2 && byte2 <= 0xBF)
+            {
+                continue;
+            }
+
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: wrong third byte
+TEST(JsonUnicodeRfc3629Test, DISABLED_Utf8_3BWrong3)
+{
+    for (int byte1 = 0xE1; byte1 <= 0xEC; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x00; byte3 <= 0xFF; ++byte3)
+            {
+                // skip correct third byte
+                if (0x80 <= byte3 && byte3 <= 0xBF)
+                {
+                    continue;
+                }
+
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// UTF8-3 (xED x80-9F UTF8-tail)
+// well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_3CWellFormed)
+{
+    for (int byte1 = 0xED; byte1 <= 0xED; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0x9F; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(true, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: missing second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3CMissing2)
+{
+    for (int byte1 = 0xED; byte1 <= 0xED; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// ill-formed: missing third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3CMissing3)
+{
+    for (int byte1 = 0xED; byte1 <= 0xED; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0x9F; ++byte2)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1, byte2));
+        }
+    }
+}
+
+// ill-formed: wrong second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3CWrong2)
+{
+    for (int byte1 = 0xED; byte1 <= 0xED; ++byte1)
+    {
+        for (int byte2 = 0x00; byte2 <= 0xFF; ++byte2)
+        {
+            // skip correct second byte
+            if (0x80 <= byte2 && byte2 <= 0x9F)
+            {
+                continue;
+            }
+
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: wrong third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3CWrong3)
+{
+    for (int byte1 = 0xED; byte1 <= 0xED; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0x9F; ++byte2)
+        {
+            for (int byte3 = 0x00; byte3 <= 0xFF; ++byte3)
+            {
+                // skip correct third byte
+                if (0x80 <= byte3 && byte3 <= 0xBF)
+                {
+                    continue;
+                }
+
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// UTF8-3 (xEE-xEF UTF8-tail UTF8-tail)
+// well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_3DWellFormed)
+{
+    for (int byte1 = 0xEE; byte1 <= 0xEF; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(true, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: missing second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3DMissing2)
+{
+    for (int byte1 = 0xEE; byte1 <= 0xEF; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// ill-formed: missing third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3DMissing3)
+{
+    for (int byte1 = 0xEE; byte1 <= 0xEF; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1, byte2));
+        }
+    }
+}
+
+// ill-formed: wrong second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3DWrong2)
+{
+    for (int byte1 = 0xEE; byte1 <= 0xEF; ++byte1)
+    {
+        for (int byte2 = 0x00; byte2 <= 0xFF; ++byte2)
+        {
+            // skip correct second byte
+            if (0x80 <= byte2 && byte2 <= 0xBF)
+            {
+                continue;
+            }
+
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: wrong third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_3DWrong3)
+{
+    for (int byte1 = 0xEE; byte1 <= 0xEF; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x00; byte3 <= 0xFF; ++byte3)
+            {
+                // skip correct third byte
+                if (0x80 <= byte3 && byte3 <= 0xBF)
+                {
+                    continue;
+                }
+
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// UTF8-4 (xF0 x90-BF UTF8-tail UTF8-tail)
+// well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_4AWellFormed)
+{
+    for (int byte1 = 0xF0; byte1 <= 0xF0; ++byte1)
+    {
+        for (int byte2 = 0x90; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(true, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: missing second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4AMissing2)
+{
+    for (int byte1 = 0xF0; byte1 <= 0xF0; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// ill-formed: missing third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4AMissing3)
+{
+    for (int byte1 = 0xF0; byte1 <= 0xF0; ++byte1)
+    {
+        for (int byte2 = 0x90; byte2 <= 0xBF; ++byte2)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1, byte2));
+        }
+    }
+}
+
+// ill-formed: missing fourth byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4AMissing4)
+{
+    for (int byte1 = 0xF0; byte1 <= 0xF0; ++byte1)
+    {
+        for (int byte2 = 0x90; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: wrong second byte
+TEST(JsonUnicodeRfc3629Test, DISABLED_Utf8_4AWrong2)
+{
+    for (int byte1 = 0xF0; byte1 <= 0xF0; ++byte1)
+    {
+        for (int byte2 = 0x00; byte2 <= 0xFF; ++byte2)
+        {
+            // skip correct second byte
+            if (0x90 <= byte2 && byte2 <= 0xBF)
+            {
+                continue;
+            }
+
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: wrong third byte
+TEST(JsonUnicodeRfc3629Test, DISABLED_Utf8_4AWrong3)
+{
+    for (int byte1 = 0xF0; byte1 <= 0xF0; ++byte1)
+    {
+        for (int byte2 = 0x90; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x00; byte3 <= 0xFF; ++byte3)
+            {
+                // skip correct third byte
+                if (0x80 <= byte3 && byte3 <= 0xBF)
+                {
+                    continue;
+                }
+
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: wrong fourth byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4AWrong4)
+{
+    for (int byte1 = 0xF0; byte1 <= 0xF0; ++byte1)
+    {
+        for (int byte2 = 0x90; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x00; byte4 <= 0xFF; ++byte4)
+                {
+                    // skip fourth second byte
+                    if (0x80 <= byte3 && byte3 <= 0xBF)
+                    {
+                        continue;
+                    }
+
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// UTF8-4 (xF1-F3 UTF8-tail UTF8-tail UTF8-tail)
+// well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_4BWellFormed)
+{
+    for (int byte1 = 0xF1; byte1 <= 0xF3; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(true, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: missing second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4BMissing2)
+{
+    for (int byte1 = 0xF1; byte1 <= 0xF3; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// ill-formed: missing third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4BMissing3)
+{
+    for (int byte1 = 0xF1; byte1 <= 0xF3; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1, byte2));
+        }
+    }
+}
+
+// ill-formed: missing fourth byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4BMissing4)
+{
+    for (int byte1 = 0xF1; byte1 <= 0xF3; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: wrong second byte
+TEST(JsonUnicodeRfc3629Test, DISABLED_Utf8_4BWrong2)
+{
+    for (int byte1 = 0xF1; byte1 <= 0xF3; ++byte1)
+    {
+        for (int byte2 = 0x00; byte2 <= 0xFF; ++byte2)
+        {
+            // skip correct second byte
+            if (0x80 <= byte2 && byte2 <= 0xBF)
+            {
+                continue;
+            }
+
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: wrong third byte
+TEST(JsonUnicodeRfc3629Test, DISABLED_Utf8_4BWrong3)
+{
+    for (int byte1 = 0xF1; byte1 <= 0xF3; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x00; byte3 <= 0xFF; ++byte3)
+            {
+                // skip correct third byte
+                if (0x80 <= byte3 && byte3 <= 0xBF)
+                {
+                    continue;
+                }
+
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: wrong fourth byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4BWrong4)
+{
+    for (int byte1 = 0xF1; byte1 <= 0xF3; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0xBF; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x00; byte4 <= 0xFF; ++byte4)
+                {
+                    // skip correct fourth byte
+                    if (0x80 <= byte3 && byte3 <= 0xBF)
+                    {
+                        continue;
+                    }
+
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// UTF8-4 (xF4 x80-8F UTF8-tail UTF8-tail)
+// well-formed
+TEST(JsonUnicodeRfc3629Test, Utf8_4CWellFormed)
+{
+    for (int byte1 = 0xF4; byte1 <= 0xF4; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0x8F; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(true, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: missing second byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4CMissing2)
+{
+    for (int byte1 = 0xF4; byte1 <= 0xF4; ++byte1)
+    {
+        EXPECT_TRUE(check_utf8string(false, byte1));
+    }
+}
+
+// ill-formed: missing third byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4CMissing3)
+{
+    for (int byte1 = 0xF4; byte1 <= 0xF4; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0x8F; ++byte2)
+        {
+            EXPECT_TRUE(check_utf8string(false, byte1, byte2));
+        }
+    }
+}
+
+// ill-formed: missing fourth byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4CMissing4)
+{
+    for (int byte1 = 0xF4; byte1 <= 0xF4; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0x8F; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3));
+            }
+        }
+    }
+}
+
+// ill-formed: wrong second byte
+TEST(JsonUnicodeRfc3629Test, DISABLED_Utf8_4CWrong2)
+{
+    for (int byte1 = 0xF4; byte1 <= 0xF4; ++byte1)
+    {
+        for (int byte2 = 0x00; byte2 <= 0xFF; ++byte2)
+        {
+            // skip correct second byte
+            if (0x80 <= byte2 && byte2 <= 0x8F)
+            {
+                continue;
+            }
+
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: wrong third byte
+TEST(JsonUnicodeRfc3629Test, DISABLED_Utf8_4CWrong3)
+{
+    for (int byte1 = 0xF4; byte1 <= 0xF4; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0x8F; ++byte2)
+        {
+            for (int byte3 = 0x00; byte3 <= 0xFF; ++byte3)
+            {
+                // skip correct third byte
+                if (0x80 <= byte3 && byte3 <= 0xBF)
+                {
+                    continue;
+                }
+
+                for (int byte4 = 0x80; byte4 <= 0xBF; ++byte4)
+                {
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// ill-formed: wrong fourth byte
+TEST(JsonUnicodeRfc3629Test, Utf8_4CWrong4)
+{
+    for (int byte1 = 0xF4; byte1 <= 0xF4; ++byte1)
+    {
+        for (int byte2 = 0x80; byte2 <= 0x8F; ++byte2)
+        {
+            for (int byte3 = 0x80; byte3 <= 0xBF; ++byte3)
+            {
+                for (int byte4 = 0x00; byte4 <= 0xFF; ++byte4)
+                {
+                    // skip correct fourth byte
+                    if (0x80 <= byte3 && byte3 <= 0xBF)
+                    {
+                        continue;
+                    }
+
+                    EXPECT_TRUE(check_utf8string(false, byte1, byte2, byte3, byte4));
+                }
+            }
+        }
+    }
+}
+
+// \\uxxxx sequences
+
+// create an escaped string from a code point
+static std::string codepoint_to_unicode(std::size_t cp)
+{
+    // code points are represented as a six-character sequence: a
+    // reverse solidus, followed by the lowercase letter u, followed
+    // by four hexadecimal digits that encode the character's code
+    // point
+    std::string s;
+    wpi::raw_string_ostream ss(s);
+    ss << "\\u" << wpi::format_hex_no_prefix(cp, 4);
+    ss.flush();
+    return s;
+}
+
+// correct sequences
+TEST(JsonUnicodeCodepointTest, DISABLED_Correct)
+{
+    // generate all UTF-8 code points; in total, 1112064 code points are
+    // generated: 0x1FFFFF code points - 2048 invalid values between
+    // 0xD800 and 0xDFFF.
+    for (std::size_t cp = 0; cp <= 0x10FFFFu; ++cp)
+    {
+        // string to store the code point as in \uxxxx format
+        std::string json_text = "\"";
+
+        // decide whether to use one or two \uxxxx sequences
+        if (cp < 0x10000u)
+        {
+            // The Unicode standard permanently reserves these code point
+            // values for UTF-16 encoding of the high and low surrogates, and
+            // they will never be assigned a character, so there should be no
+            // reason to encode them. The official Unicode standard says that
+            // no UTF forms, including UTF-16, can encode these code points.
+            if (cp >= 0xD800u && cp <= 0xDFFFu)
+            {
+                // if we would not skip these code points, we would get a
+                // "missing low surrogate" exception
+                continue;
+            }
+
+            // code points in the Basic Multilingual Plane can be
+            // represented with one \uxxxx sequence
+            json_text += codepoint_to_unicode(cp);
+        }
+        else
+        {
+            // To escape an extended character that is not in the Basic
+            // Multilingual Plane, the character is represented as a
+            // 12-character sequence, encoding the UTF-16 surrogate pair
+            const auto codepoint1 = 0xd800u + (((cp - 0x10000u) >> 10) & 0x3ffu);
+            const auto codepoint2 = 0xdc00u + ((cp - 0x10000u) & 0x3ffu);
+            json_text += codepoint_to_unicode(codepoint1) + codepoint_to_unicode(codepoint2);
+        }
+
+        json_text += "\"";
+        SCOPED_TRACE(json_text);
+        EXPECT_NO_THROW(json::parse(json_text));
+    }
+}
+
+#if 0
+// incorrect sequences
+// high surrogate without low surrogate
+TEST(JsonUnicodeCodepointTest, IncorrectHighMissingLow)
+{
+    // D800..DBFF are high surrogates and must be followed by low
+    // surrogates DC00..DFFF; here, nothing follows
+    for (std::size_t cp = 0xD800u; cp <= 0xDBFFu; ++cp)
+    {
+        std::string json_text = "\"" + codepoint_to_unicode(cp) + "\"";
+        SCOPED_TRACE(json_text);
+        EXPECT_THROW(json::parse(json_text), json::parse_error);
+    }
+}
+
+// high surrogate with wrong low surrogate
+TEST(JsonUnicodeCodepointTest, IncorrectHighWrongLow)
+{
+    // D800..DBFF are high surrogates and must be followed by low
+    // surrogates DC00..DFFF; here a different sequence follows
+    for (std::size_t cp1 = 0xD800u; cp1 <= 0xDBFFu; ++cp1)
+    {
+        for (std::size_t cp2 = 0x0000u; cp2 <= 0xFFFFu; ++cp2)
+        {
+            if (0xDC00u <= cp2 && cp2 <= 0xDFFFu)
+            {
+                continue;
+            }
+
+            std::string json_text = "\"" + codepoint_to_unicode(cp1) + codepoint_to_unicode(cp2) + "\"";
+            SCOPED_TRACE(json_text);
+            EXPECT_THROW(json::parse(json_text), json::parse_error);
+        }
+    }
+}
+
+// low surrogate without high surrogate
+TEST(JsonUnicodeCodepointTest, IncorrectLowMissingHigh)
+{
+    // low surrogates DC00..DFFF must follow high surrogates; here,
+    // they occur alone
+    for (std::size_t cp = 0xDC00u; cp <= 0xDFFFu; ++cp)
+    {
+        std::string json_text = "\"" + codepoint_to_unicode(cp) + "\"";
+        SCOPED_TRACE(json_text);
+        EXPECT_THROW(json::parse(json_text), json::parse_error);
+    }
+}
+#endif
+
+#if 0
+// read all unicode characters
+TEST(JsonUnicodeTest, ReadAllUnicode)
+{
+    // read a file with all unicode characters stored as single-character
+    // strings in a JSON array
+    std::ifstream f("test/data/json_nlohmann_tests/all_unicode.json");
+    json j;
+    CHECK_NOTHROW(f >> j);
+
+    // the array has 1112064 + 1 elemnts (a terminating "null" value)
+    // Note: 1112064 = 0x1FFFFF code points - 2048 invalid values between
+    // 0xD800 and 0xDFFF.
+    CHECK(j.size() == 1112065);
+
+    SECTION("check JSON Pointers")
+    {
+        for (auto s : j)
+        {
+            // skip non-string JSON values
+            if (not s.is_string())
+            {
+                continue;
+            }
+
+            std::string ptr = s;
+
+            // tilde must be followed by 0 or 1
+            if (ptr == "~")
+            {
+                ptr += "0";
+            }
+
+            // JSON Pointers must begin with "/"
+            ptr = "/" + ptr;
+
+            CHECK_NOTHROW(json::json_pointer("/" + ptr));
+
+            // check escape/unescape roundtrip
+            auto escaped = json::json_pointer::escape(ptr);
+            json::json_pointer::unescape(escaped);
+            CHECK(escaped == ptr);
+        }
+    }
+}
+
+// ignore byte-order-mark
+// in a stream
+TEST(JsonUnicodeTest, IgnoreBOMStream)
+{
+    // read a file with a UTF-8 BOM
+    std::ifstream f("test/data/json_nlohmann_tests/bom.json");
+    json j;
+    EXPECT_NO_THROW(f >> j);
+}
+
+// with an iterator
+TEST(JsonUnicodeTest, IgnoreBOMIterator)
+{
+    std::string i = "\xef\xbb\xbf{\n   \"foo\": true\n}";
+    EXPECT_NO_THROW(json::parse(i.begin(), i.end()));
+}
+#endif
+// error for incomplete/wrong BOM
+TEST(JsonUnicodeTest, WrongBOM)
+{
+    EXPECT_THROW(json::parse("\xef\xbb"), json::parse_error);
+    EXPECT_THROW(json::parse("\xef\xbb\xbb"), json::parse_error);
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/leb128Test.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/leb128Test.cpp
new file mode 100644
index 0000000..a3a7ed0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/leb128Test.cpp
@@ -0,0 +1,112 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+//===- llvm/unittest/Support/LEB128Test.cpp - LEB128 function tests -------===//
+//
+//                     The LLVM Compiler Infrastructure
+//
+// This file is distributed under the University of Illinois Open Source
+// License. See LICENSE.TXT for details.
+//
+//===----------------------------------------------------------------------===//
+
+#include <stdint.h>
+
+#include <string>
+
+#include "gtest/gtest.h"
+#include "wpi/SmallString.h"
+#include "wpi/StringRef.h"
+#include "wpi/leb128.h"
+#include "wpi/raw_istream.h"
+
+namespace wpi {
+
+TEST(LEB128Test, WriteUleb128) {
+#define EXPECT_ULEB128_EQ(EXPECTED, VALUE, PAD)         \
+  do {                                                  \
+    StringRef expected(EXPECTED, sizeof(EXPECTED) - 1); \
+    SmallString<32> buf;                                \
+    size_t size = WriteUleb128(buf, VALUE);             \
+    EXPECT_EQ(size, buf.size());                        \
+    EXPECT_EQ(expected, buf.str());                     \
+  } while (0)
+
+  // Write ULEB128
+  EXPECT_ULEB128_EQ("\x00", 0, 0);
+  EXPECT_ULEB128_EQ("\x01", 1, 0);
+  EXPECT_ULEB128_EQ("\x3f", 63, 0);
+  EXPECT_ULEB128_EQ("\x40", 64, 0);
+  EXPECT_ULEB128_EQ("\x7f", 0x7f, 0);
+  EXPECT_ULEB128_EQ("\x80\x01", 0x80, 0);
+  EXPECT_ULEB128_EQ("\x81\x01", 0x81, 0);
+  EXPECT_ULEB128_EQ("\x90\x01", 0x90, 0);
+  EXPECT_ULEB128_EQ("\xff\x01", 0xff, 0);
+  EXPECT_ULEB128_EQ("\x80\x02", 0x100, 0);
+  EXPECT_ULEB128_EQ("\x81\x02", 0x101, 0);
+
+#undef EXPECT_ULEB128_EQ
+}
+
+TEST(LEB128Test, ReadUleb128) {
+#define EXPECT_READ_ULEB128_EQ(EXPECTED, VALUE) \
+  do {                                          \
+    uint64_t val = 0;                           \
+    size_t size = ReadUleb128(VALUE, &val);     \
+    EXPECT_EQ(sizeof(VALUE) - 1, size);         \
+    EXPECT_EQ(EXPECTED, val);                   \
+  } while (0)
+
+  // Read ULEB128
+  EXPECT_READ_ULEB128_EQ(0u, "\x00");
+  EXPECT_READ_ULEB128_EQ(1u, "\x01");
+  EXPECT_READ_ULEB128_EQ(63u, "\x3f");
+  EXPECT_READ_ULEB128_EQ(64u, "\x40");
+  EXPECT_READ_ULEB128_EQ(0x7fu, "\x7f");
+  EXPECT_READ_ULEB128_EQ(0x80u, "\x80\x01");
+  EXPECT_READ_ULEB128_EQ(0x81u, "\x81\x01");
+  EXPECT_READ_ULEB128_EQ(0x90u, "\x90\x01");
+  EXPECT_READ_ULEB128_EQ(0xffu, "\xff\x01");
+  EXPECT_READ_ULEB128_EQ(0x100u, "\x80\x02");
+  EXPECT_READ_ULEB128_EQ(0x101u, "\x81\x02");
+  EXPECT_READ_ULEB128_EQ(8320u, "\x80\xc1\x80\x80\x10");
+
+#undef EXPECT_READ_ULEB128_EQ
+}
+
+TEST(LEB128Test, SizeUleb128) {
+  // Testing Plan:
+  // (1) 128 ^ n ............ need (n+1) bytes
+  // (2) 128 ^ n * 64 ....... need (n+1) bytes
+  // (3) 128 ^ (n+1) - 1 .... need (n+1) bytes
+
+  EXPECT_EQ(1u, SizeUleb128(0));  // special case
+
+  EXPECT_EQ(1u, SizeUleb128(0x1UL));
+  EXPECT_EQ(1u, SizeUleb128(0x40UL));
+  EXPECT_EQ(1u, SizeUleb128(0x7fUL));
+
+  EXPECT_EQ(2u, SizeUleb128(0x80UL));
+  EXPECT_EQ(2u, SizeUleb128(0x2000UL));
+  EXPECT_EQ(2u, SizeUleb128(0x3fffUL));
+
+  EXPECT_EQ(3u, SizeUleb128(0x4000UL));
+  EXPECT_EQ(3u, SizeUleb128(0x100000UL));
+  EXPECT_EQ(3u, SizeUleb128(0x1fffffUL));
+
+  EXPECT_EQ(4u, SizeUleb128(0x200000UL));
+  EXPECT_EQ(4u, SizeUleb128(0x8000000UL));
+  EXPECT_EQ(4u, SizeUleb128(0xfffffffUL));
+
+  EXPECT_EQ(5u, SizeUleb128(0x10000000UL));
+  EXPECT_EQ(5u, SizeUleb128(0x40000000UL));
+  EXPECT_EQ(5u, SizeUleb128(0x7fffffffUL));
+
+  EXPECT_EQ(5u, SizeUleb128(UINT32_MAX));
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/main.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/main.cpp
new file mode 100644
index 0000000..1e5ecf0
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/main.cpp
@@ -0,0 +1,14 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2015-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 "gtest/gtest.h"
+
+int main(int argc, char** argv) {
+  ::testing::InitGoogleTest(&argc, argv);
+  int ret = RUN_ALL_TESTS();
+  return ret;
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/priority_mutex_test.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/priority_mutex_test.cpp
new file mode 100644
index 0000000..c5c86b6
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/priority_mutex_test.cpp
@@ -0,0 +1,271 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2016-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 <wpi/priority_mutex.h>  // NOLINT(build/include_order)
+
+#include <atomic>
+#include <condition_variable>
+#include <thread>
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+#ifdef WPI_HAVE_PRIORITY_MUTEX
+
+using std::chrono::system_clock;
+
+// Threading primitive used to notify many threads that a condition is now true.
+// The condition can not be cleared.
+class Notification {
+ public:
+  // Efficiently waits until the Notification has been notified once.
+  void Wait() {
+    std::unique_lock<priority_mutex> lock(m_mutex);
+    while (!m_set) {
+      m_condition.wait(lock);
+    }
+  }
+  // Sets the condition to true, and wakes all waiting threads.
+  void Notify() {
+    std::lock_guard<priority_mutex> lock(m_mutex);
+    m_set = true;
+    m_condition.notify_all();
+  }
+
+ private:
+  // priority_mutex used for the notification and to protect the bit.
+  priority_mutex m_mutex;
+  // Condition for threads to sleep on.
+  std::condition_variable_any m_condition;
+  // Bool which is true when the notification has been notified.
+  bool m_set = false;
+};
+
+void SetProcessorAffinity(int32_t core_id) {
+  cpu_set_t cpuset;
+  CPU_ZERO(&cpuset);
+  CPU_SET(core_id, &cpuset);
+
+  pthread_t current_thread = pthread_self();
+  ASSERT_EQ(pthread_setaffinity_np(current_thread, sizeof(cpu_set_t), &cpuset),
+            0);
+}
+
+void SetThreadRealtimePriorityOrDie(int32_t priority) {
+  struct sched_param param;
+  // Set realtime priority for this thread
+  param.sched_priority = priority + sched_get_priority_min(SCHED_RR);
+  ASSERT_EQ(pthread_setschedparam(pthread_self(), SCHED_RR, &param), 0)
+      << ": Failed to set scheduler priority.";
+}
+
+// This thread holds the mutex and spins until signaled to release it and stop.
+template <typename MutexType>
+class LowPriorityThread {
+ public:
+  explicit LowPriorityThread(MutexType* mutex)
+      : m_mutex(mutex), m_hold_mutex(1), m_success(0) {}
+
+  void operator()() {
+    SetProcessorAffinity(0);
+    SetThreadRealtimePriorityOrDie(20);
+    m_mutex->lock();
+    m_started.Notify();
+    while (m_hold_mutex.test_and_set()) {
+    }
+    m_mutex->unlock();
+    m_success.store(1);
+  }
+
+  void WaitForStartup() { m_started.Wait(); }
+  void release_mutex() { m_hold_mutex.clear(); }
+  bool success() { return m_success.load(); }
+
+ private:
+  // priority_mutex to grab and release.
+  MutexType* m_mutex;
+  Notification m_started;
+  // Atomic type used to signal when the thread should unlock the mutex.
+  // Using a mutex to protect something could cause other issues, and a delay
+  // between setting and reading isn't a problem as long as the set is atomic.
+  std::atomic_flag m_hold_mutex;
+  std::atomic<int> m_success;
+};
+
+// This thread spins forever until signaled to stop.
+class BusyWaitingThread {
+ public:
+  BusyWaitingThread() : m_run(1), m_success(0) {}
+
+  void operator()() {
+    SetProcessorAffinity(0);
+    SetThreadRealtimePriorityOrDie(21);
+    system_clock::time_point start_time = system_clock::now();
+    m_started.Notify();
+    while (m_run.test_and_set()) {
+      // Have the busy waiting thread time out after a while.  If it times out,
+      // the test failed.
+      if (system_clock::now() - start_time > std::chrono::milliseconds(50)) {
+        return;
+      }
+    }
+    m_success.store(1);
+  }
+
+  void quit() { m_run.clear(); }
+  void WaitForStartup() { m_started.Wait(); }
+  bool success() { return m_success.load(); }
+
+ private:
+  // Use an atomic type to signal if the thread should be running or not.  A
+  // mutex could affect the scheduler, which isn't worth it.  A delay between
+  // setting and reading the new value is fine.
+  std::atomic_flag m_run;
+
+  Notification m_started;
+
+  std::atomic<int> m_success;
+};
+
+// This thread starts up, grabs the mutex, and then exits.
+template <typename MutexType>
+class HighPriorityThread {
+ public:
+  explicit HighPriorityThread(MutexType* mutex) : m_mutex(mutex) {}
+
+  void operator()() {
+    SetProcessorAffinity(0);
+    SetThreadRealtimePriorityOrDie(22);
+    m_started.Notify();
+    m_mutex->lock();
+    m_success.store(1);
+  }
+
+  void WaitForStartup() { m_started.Wait(); }
+  bool success() { return m_success.load(); }
+
+ private:
+  Notification m_started;
+  MutexType* m_mutex;
+  std::atomic<int> m_success{0};
+};
+
+// Class to test a MutexType to see if it solves the priority inheritance
+// problem.
+//
+// To run the test, we need 3 threads, and then 1 thread to kick the test off.
+// The threads must all run on the same core, otherwise they wouldn't starve
+// eachother. The threads and their roles are as follows:
+//
+// Low priority thread:
+//   Holds a lock that the high priority thread needs, and releases it upon
+//   request.
+// Medium priority thread:
+//   Hogs the processor so that the low priority thread will never run if it's
+//   priority doesn't get bumped.
+// High priority thread:
+//   Starts up and then goes to grab the lock that the low priority thread has.
+//
+// Control thread:
+//   Sets the deadlock up so that it will happen 100% of the time by making sure
+//   that each thread in order gets to the point that it needs to be at to cause
+//   the deadlock.
+template <typename MutexType>
+class InversionTestRunner {
+ public:
+  void operator()() {
+    // This thread must run at the highest priority or it can't coordinate the
+    // inversion.  This means that it can't busy wait or everything could
+    // starve.
+    SetThreadRealtimePriorityOrDie(23);
+
+    MutexType m;
+
+    // Start the lowest priority thread and wait until it holds the lock.
+    LowPriorityThread<MutexType> low(&m);
+    std::thread low_thread(std::ref(low));
+    low.WaitForStartup();
+
+    // Start the busy waiting thread and let it get to the loop.
+    BusyWaitingThread busy;
+    std::thread busy_thread(std::ref(busy));
+    busy.WaitForStartup();
+
+    // Start the high priority thread and let it become blocked on the lock.
+    HighPriorityThread<MutexType> high(&m);
+    std::thread high_thread(std::ref(high));
+    high.WaitForStartup();
+    // Startup and locking the mutex in the high priority thread aren't atomic,
+    // but pretty close.  Wait a bit to let it happen.
+    std::this_thread::sleep_for(std::chrono::milliseconds(10));
+
+    // Release the mutex in the low priority thread.  If done right, everything
+    // should finish now.
+    low.release_mutex();
+
+    // Wait for everything to finish and compute success.
+    high_thread.join();
+    busy.quit();
+    busy_thread.join();
+    low_thread.join();
+    m_success = low.success() && busy.success() && high.success();
+  }
+
+  bool success() { return m_success; }
+
+ private:
+  bool m_success = false;
+};
+
+// TODO: Fix roborio permissions to run as root.
+
+// Priority inversion test.
+TEST(MutexTest, DISABLED_PriorityInversionTest) {
+  InversionTestRunner<priority_mutex> runner;
+  std::thread runner_thread(std::ref(runner));
+  runner_thread.join();
+  EXPECT_TRUE(runner.success());
+}
+
+// Verify that the non-priority inversion mutex doesn't pass the test.
+TEST(MutexTest, DISABLED_StdMutexPriorityInversionTest) {
+  InversionTestRunner<std::mutex> runner;
+  std::thread runner_thread(std::ref(runner));
+  runner_thread.join();
+  EXPECT_FALSE(runner.success());
+}
+
+// Smoke test to make sure that mutexes lock and unlock.
+TEST(MutexTest, TryLock) {
+  priority_mutex m;
+  m.lock();
+  EXPECT_FALSE(m.try_lock());
+  m.unlock();
+  EXPECT_TRUE(m.try_lock());
+}
+
+// Priority inversion test.
+TEST(MutexTest, DISABLED_ReentrantPriorityInversionTest) {
+  InversionTestRunner<priority_recursive_mutex> runner;
+  std::thread runner_thread(std::ref(runner));
+  runner_thread.join();
+  EXPECT_TRUE(runner.success());
+}
+
+// Smoke test to make sure that mutexes lock and unlock.
+TEST(MutexTest, ReentrantTryLock) {
+  priority_recursive_mutex m;
+  m.lock();
+  EXPECT_TRUE(m.try_lock());
+  m.unlock();
+  EXPECT_TRUE(m.try_lock());
+}
+
+#endif  // WPI_HAVE_PRIORITY_MUTEX
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/raw_uv_stream_test.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/raw_uv_stream_test.cpp
new file mode 100644
index 0000000..d1a0f6c
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/raw_uv_stream_test.cpp
@@ -0,0 +1,58 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/raw_uv_ostream.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+
+TEST(RawUvStreamTest, BasicWrite) {
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os(bufs, 1024);
+  os << "12";
+  os << "34";
+  ASSERT_EQ(bufs.size(), 1u);
+  ASSERT_EQ(bufs[0].len, 4u);
+  ASSERT_EQ(bufs[0].base[0], '1');
+  ASSERT_EQ(bufs[0].base[1], '2');
+  ASSERT_EQ(bufs[0].base[2], '3');
+  ASSERT_EQ(bufs[0].base[3], '4');
+}
+
+TEST(RawUvStreamTest, BoundaryWrite) {
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os(bufs, 4);
+  ASSERT_EQ(bufs.size(), 0u);
+  os << "12";
+  ASSERT_EQ(bufs.size(), 1u);
+  os << "34";
+  ASSERT_EQ(bufs.size(), 1u);
+  os << "56";
+  ASSERT_EQ(bufs.size(), 2u);
+}
+
+TEST(RawUvStreamTest, LargeWrite) {
+  SmallVector<uv::Buffer, 4> bufs;
+  raw_uv_ostream os(bufs, 4);
+  os << "123456";
+  ASSERT_EQ(bufs.size(), 2u);
+  ASSERT_EQ(bufs[1].len, 2u);
+  ASSERT_EQ(bufs[1].base[0], '5');
+}
+
+TEST(RawUvStreamTest, PrevDataWrite) {
+  SmallVector<uv::Buffer, 4> bufs;
+  bufs.emplace_back(uv::Buffer::Allocate(1024));
+  raw_uv_ostream os(bufs, 1024);
+  os << "1234";
+  ASSERT_EQ(bufs.size(), 2u);
+  ASSERT_EQ(bufs[0].len, 1024u);
+  ASSERT_EQ(bufs[1].len, 4u);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sha1Test.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sha1Test.cpp
new file mode 100644
index 0000000..08d85fe
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sha1Test.cpp
@@ -0,0 +1,92 @@
+/*----------------------------------------------------------------------------*/
+/* Copyright (c) 2017-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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+    test_sha1.cpp - test program of
+
+    ============
+    SHA-1 in C++
+    ============
+
+    100% Public Domain.
+
+    Original C Code
+        -- Steve Reid <steve@edmweb.com>
+    Small changes to fit into bglibs
+        -- Bruce Guenter <bruce@untroubled.org>
+    Translation to simpler C++ Code
+        -- Volker Grabsch <vog@notjusthosting.com>
+*/
+
+#include <string>
+
+#include "gtest/gtest.h"
+#include "wpi/sha1.h"
+
+namespace wpi {
+
+/*
+ * The 3 test vectors from FIPS PUB 180-1
+ */
+
+TEST(SHA1Test, Standard1) {
+  SHA1 checksum;
+  checksum.Update("abc");
+  ASSERT_EQ(checksum.Final(), "a9993e364706816aba3e25717850c26c9cd0d89d");
+}
+
+TEST(SHA1Test, Standard2) {
+  SHA1 checksum;
+  checksum.Update("abcdbcdecdefdefgefghfghighijhijkijkljklmklmnlmnomnopnopq");
+  ASSERT_EQ(checksum.Final(), "84983e441c3bd26ebaae4aa1f95129e5e54670f1");
+}
+
+TEST(SHA1Test, Standard3) {
+  SHA1 checksum;
+  // A million repetitions of 'a'
+  for (int i = 0; i < 1000000 / 200; ++i) {
+    checksum.Update(
+        "aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa"
+        "aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa"
+        "aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa"
+        "aaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaaa");
+  }
+  ASSERT_EQ(checksum.Final(), "34aa973cd4c4daa4f61eeb2bdbad27316534016f");
+}
+
+/*
+ * Other tests
+ */
+
+TEST(SHA1Test, OtherNoString) {
+  SHA1 checksum;
+  ASSERT_EQ(checksum.Final(), "da39a3ee5e6b4b0d3255bfef95601890afd80709");
+}
+
+TEST(SHA1Test, OtherEmptyString) {
+  SHA1 checksum;
+  checksum.Update("");
+  ASSERT_EQ(checksum.Final(), "da39a3ee5e6b4b0d3255bfef95601890afd80709");
+}
+
+TEST(SHA1Test, OtherABCDE) {
+  SHA1 checksum;
+  checksum.Update("abcde");
+  ASSERT_EQ(checksum.Final(), "03de6c570bfe24bfc328ccd7ca46b76eadaf4334");
+}
+
+TEST(SHA1Test, Concurrent) {
+  // Two concurrent checksum calculations
+  SHA1 checksum1, checksum2;
+  checksum1.Update("abc");
+  ASSERT_EQ(checksum2.Final(),
+            "da39a3ee5e6b4b0d3255bfef95601890afd80709"); /* "" */
+  ASSERT_EQ(checksum1.Final(),
+            "a9993e364706816aba3e25717850c26c9cd0d89d"); /* "abc" */
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/function-traits.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/function-traits.cpp
new file mode 100644
index 0000000..240e688
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/function-traits.cpp
@@ -0,0 +1,135 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+
+Sigslot, a signal-slot library
+
+https://github.com/palacaze/sigslot
+
+MIT License
+
+Copyright (c) 2017 Pierre-Antoine Lacaze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+ */
+
+#include "wpi/Signal.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <type_traits>
+
+using namespace wpi::sig::trait;
+
+namespace {
+
+void f1(int, char, float) {}
+void f2(int, char, float) noexcept {}
+
+struct oo {
+  void operator()(int) {}
+  void operator()(int, char, float) {}
+};
+
+struct s {
+  static void s1(int, char, float) {}
+  static void s2(int, char, float) noexcept {}
+
+  void f1(int, char, float) {}
+  void f2(int, char, float) const {}
+  void f3(int, char, float) volatile {}
+  void f4(int, char, float) const volatile {}
+  void f5(int, char, float) noexcept {}
+  void f6(int, char, float) const noexcept {}
+  void f7(int, char, float) volatile noexcept {}
+  void f8(int, char, float) const volatile noexcept {}
+};
+
+struct o1 {
+  void operator()(int, char, float) {}
+};
+struct o2 {
+  void operator()(int, char, float) const {}
+};
+struct o3 {
+  void operator()(int, char, float) volatile {}
+};
+struct o4 {
+  void operator()(int, char, float) const volatile {}
+};
+struct o5 {
+  void operator()(int, char, float) noexcept {}
+};
+struct o6 {
+  void operator()(int, char, float) const noexcept {}
+};
+struct o7 {
+  void operator()(int, char, float) volatile noexcept {}
+};
+struct o8 {
+  void operator()(int, char, float) const volatile noexcept {}
+};
+
+using t = typelist<int, char, float>;
+
+static_assert(is_callable_v<t, decltype(f1)>, "");
+static_assert(is_callable_v<t, decltype(f2)>, "");
+static_assert(is_callable_v<t, decltype(&s::s1)>, "");
+static_assert(is_callable_v<t, decltype(&s::s2)>, "");
+static_assert(is_callable_v<t, oo>, "");
+static_assert(is_callable_v<t, decltype(&s::f1), s*>, "");
+static_assert(is_callable_v<t, decltype(&s::f2), s*>, "");
+static_assert(is_callable_v<t, decltype(&s::f3), s*>, "");
+static_assert(is_callable_v<t, decltype(&s::f4), s*>, "");
+static_assert(is_callable_v<t, decltype(&s::f5), s*>, "");
+static_assert(is_callable_v<t, decltype(&s::f6), s*>, "");
+static_assert(is_callable_v<t, decltype(&s::f7), s*>, "");
+static_assert(is_callable_v<t, decltype(&s::f8), s*>, "");
+static_assert(is_callable_v<t, o1>, "");
+static_assert(is_callable_v<t, o2>, "");
+static_assert(is_callable_v<t, o3>, "");
+static_assert(is_callable_v<t, o4>, "");
+static_assert(is_callable_v<t, o5>, "");
+static_assert(is_callable_v<t, o6>, "");
+static_assert(is_callable_v<t, o7>, "");
+static_assert(is_callable_v<t, o8>, "");
+
+}  // namespace
+
+namespace wpi {
+
+TEST(Signal, FunctionTraits) {
+  auto l1 = [](int, char, float) {};
+  auto l2 = [&](int, char, float) mutable {};
+  auto l3 = [&](auto...) mutable {};
+
+  static_assert(is_callable_v<t, decltype(l1)>, "");
+  static_assert(is_callable_v<t, decltype(l2)>, "");
+  static_assert(is_callable_v<t, decltype(l3)>, "");
+
+  f1(0, '0', 0.0);
+  f2(0, '0', 0.0);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/recursive.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/recursive.cpp
new file mode 100644
index 0000000..85ae9a9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/recursive.cpp
@@ -0,0 +1,97 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+
+Sigslot, a signal-slot library
+
+https://github.com/palacaze/sigslot
+
+MIT License
+
+Copyright (c) 2017 Pierre-Antoine Lacaze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+ */
+
+#include "wpi/Signal.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace {
+
+template <typename T>
+struct object {
+  object(T i) : v{i} {}  // NOLINT(runtime/explicit)
+
+  void inc_val(const T& i) {
+    if (i != v) {
+      v++;
+      sig(v);
+    }
+  }
+
+  void dec_val(const T& i) {
+    if (i != v) {
+      v--;
+      sig(v);
+    }
+  }
+
+  T v;
+  wpi::sig::Signal_r<T> sig;
+};
+
+}  // namespace
+
+namespace wpi {
+
+TEST(Signal, Recursive) {
+  object<int> i1(-1);
+  object<int> i2(10);
+
+  i1.sig.connect(&object<int>::dec_val, &i2);
+  i2.sig.connect(&object<int>::inc_val, &i1);
+
+  i1.inc_val(0);
+
+  ASSERT_EQ(i1.v, i2.v);
+}
+
+TEST(Signal, SelfRecursive) {
+  int i = 0;
+
+  wpi::sig::Signal_r<int> s;
+  s.connect([&](int v) {
+    if (i < 10) {
+      i++;
+      s(v + 1);
+    }
+  });
+
+  s(0);
+
+  ASSERT_EQ(i, 10);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-extended.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-extended.cpp
new file mode 100644
index 0000000..1ebbc8e
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-extended.cpp
@@ -0,0 +1,140 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+
+Sigslot, a signal-slot library
+
+https://github.com/palacaze/sigslot
+
+MIT License
+
+Copyright (c) 2017 Pierre-Antoine Lacaze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+ */
+
+#include "wpi/Signal.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+using namespace wpi::sig;
+
+namespace {
+
+int sum = 0;
+
+void f(Connection& c, int i) {
+  sum += i;
+  c.disconnect();
+}
+
+struct s {
+  static void sf(Connection& c, int i) {
+    sum += i;
+    c.disconnect();
+  }
+  void f(Connection& c, int i) {
+    sum += i;
+    c.disconnect();
+  }
+};
+
+struct o {
+  void operator()(Connection& c, int i) {
+    sum += i;
+    c.disconnect();
+  }
+};
+
+}  // namespace
+
+namespace wpi {
+
+TEST(SignalExtended, FreeConnection) {
+  sum = 0;
+  Signal<int> sig;
+  sig.connect_extended(f);
+
+  sig(1);
+  ASSERT_EQ(sum, 1);
+  sig(1);
+  ASSERT_EQ(sum, 1);
+}
+
+TEST(SignalExtended, StaticConnection) {
+  sum = 0;
+  Signal<int> sig;
+  sig.connect_extended(&s::sf);
+
+  sig(1);
+  ASSERT_EQ(sum, 1);
+  sig(1);
+  ASSERT_EQ(sum, 1);
+}
+
+TEST(SignalExtended, PmfConnection) {
+  sum = 0;
+  Signal<int> sig;
+  s p;
+  sig.connect_extended(&s::f, &p);
+
+  sig(1);
+  ASSERT_EQ(sum, 1);
+  sig(1);
+  ASSERT_EQ(sum, 1);
+}
+
+TEST(SignalExtended, FunctionObjectConnection) {
+  sum = 0;
+  Signal<int> sig;
+  sig.connect_extended(o{});
+
+  sig(1);
+  ASSERT_EQ(sum, 1);
+  sig(1);
+  ASSERT_EQ(sum, 1);
+}
+
+TEST(SignalExtended, LambdaConnection) {
+  sum = 0;
+  Signal<int> sig;
+
+  sig.connect_extended([&](Connection& c, int i) {
+    sum += i;
+    c.disconnect();
+  });
+  sig(1);
+  ASSERT_EQ(sum, 1);
+
+  sig.connect_extended([&](Connection& c, int i) mutable {
+    sum += 2 * i;
+    c.disconnect();
+  });
+  sig(1);
+  ASSERT_EQ(sum, 3);
+  sig(1);
+  ASSERT_EQ(sum, 3);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-threaded.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-threaded.cpp
new file mode 100644
index 0000000..c4f7cdb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-threaded.cpp
@@ -0,0 +1,93 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+
+Sigslot, a signal-slot library
+
+https://github.com/palacaze/sigslot
+
+MIT License
+
+Copyright (c) 2017 Pierre-Antoine Lacaze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+ */
+
+#include "wpi/Signal.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <array>
+#include <atomic>
+#include <thread>
+
+using namespace wpi::sig;
+
+namespace {
+
+std::atomic<int> sum{0};
+
+void f(int i) { sum += i; }
+
+void emit_many(Signal_mt<int>& sig) {
+  for (int i = 0; i < 10000; ++i) sig(1);
+}
+
+void connect_emit(Signal_mt<int>& sig) {
+  for (int i = 0; i < 100; ++i) {
+    auto s = sig.connect_scoped(f);
+    for (int j = 0; j < 100; ++j) sig(1);
+  }
+}
+
+}  // namespace
+
+namespace wpi {
+
+TEST(Signal, ThreadedMix) {
+  sum = 0;
+
+  Signal_mt<int> sig;
+
+  std::array<std::thread, 10> threads;
+  for (auto& t : threads) t = std::thread(connect_emit, std::ref(sig));
+
+  for (auto& t : threads) t.join();
+}
+
+TEST(Signal, ThreadedEmission) {
+  sum = 0;
+
+  Signal_mt<int> sig;
+  sig.connect(f);
+
+  std::array<std::thread, 10> threads;
+  for (auto& t : threads) t = std::thread(emit_many, std::ref(sig));
+
+  for (auto& t : threads) t.join();
+
+  ASSERT_EQ(sum, 100000);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-tracking.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-tracking.cpp
new file mode 100644
index 0000000..89ffd36
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal-tracking.cpp
@@ -0,0 +1,181 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+
+Sigslot, a signal-slot library
+
+https://github.com/palacaze/sigslot
+
+MIT License
+
+Copyright (c) 2017 Pierre-Antoine Lacaze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+ */
+
+#include "wpi/Signal.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <cmath>
+#include <sstream>
+#include <string>
+
+using namespace wpi::sig;
+
+namespace {
+
+int sum = 0;
+
+void f1(int i) { sum += i; }
+struct o1 {
+  void operator()(int i) { sum += 2 * i; }
+};
+
+struct s {
+  void f1(int i) { sum += i; }
+  void f2(int i) const { sum += 2 * i; }
+};
+
+struct oo {
+  void operator()(int i) { sum += i; }
+  void operator()(double i) { sum += std::round(4 * i); }
+};
+
+struct dummy {};
+
+static_assert(trait::is_callable_v<trait::typelist<int>, decltype(&s::f1),
+                                   std::shared_ptr<s>>,
+              "");
+
+}  // namespace
+
+namespace wpi {
+
+TEST(Signal, TrackShared) {
+  sum = 0;
+  Signal<int> sig;
+
+  auto s1 = std::make_shared<s>();
+  sig.connect(&s::f1, s1);
+
+  auto s2 = std::make_shared<s>();
+  std::weak_ptr<s> w2 = s2;
+  sig.connect(&s::f2, w2);
+
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  s1.reset();
+  sig(1);
+  ASSERT_EQ(sum, 5);
+
+  s2.reset();
+  sig(1);
+  ASSERT_EQ(sum, 5);
+}
+
+TEST(Signal, TrackOther) {
+  sum = 0;
+  Signal<int> sig;
+
+  auto d1 = std::make_shared<dummy>();
+  sig.connect(f1, d1);
+
+  auto d2 = std::make_shared<dummy>();
+  std::weak_ptr<dummy> w2 = d2;
+  sig.connect(o1(), w2);
+
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  d1.reset();
+  sig(1);
+  ASSERT_EQ(sum, 5);
+
+  d2.reset();
+  sig(1);
+  ASSERT_EQ(sum, 5);
+}
+
+TEST(Signal, TrackOverloadedFunctionObject) {
+  sum = 0;
+  Signal<int> sig;
+  Signal<double> sig1;
+
+  auto d1 = std::make_shared<dummy>();
+  sig.connect(oo{}, d1);
+  sig(1);
+  ASSERT_EQ(sum, 1);
+
+  d1.reset();
+  sig(1);
+  ASSERT_EQ(sum, 1);
+
+  auto d2 = std::make_shared<dummy>();
+  std::weak_ptr<dummy> w2 = d2;
+  sig1.connect(oo{}, w2);
+  sig1(1);
+  ASSERT_EQ(sum, 5);
+
+  d2.reset();
+  sig1(1);
+  ASSERT_EQ(sum, 5);
+}
+
+TEST(Signal, TrackGenericLambda) {
+  std::stringstream s;
+
+  auto f = [&](auto a, auto... args) {
+    using result_t = int[];
+    s << a;
+    result_t r{
+        1,
+        ((void)(s << args), 1)...,
+    };
+    (void)r;
+  };
+
+  Signal<int> sig1;
+  Signal<std::string> sig2;
+  Signal<double> sig3;
+
+  auto d1 = std::make_shared<dummy>();
+  sig1.connect(f, d1);
+  sig2.connect(f, d1);
+  sig3.connect(f, d1);
+
+  sig1(1);
+  sig2("foo");
+  sig3(4.1);
+  ASSERT_EQ(s.str(), "1foo4.1");
+
+  d1.reset();
+  sig1(2);
+  sig2("bar");
+  sig3(3.0);
+  ASSERT_EQ(s.str(), "1foo4.1");
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal.cpp
new file mode 100644
index 0000000..a4f9208
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/sigslot/signal.cpp
@@ -0,0 +1,540 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/*
+
+Sigslot, a signal-slot library
+
+https://github.com/palacaze/sigslot
+
+MIT License
+
+Copyright (c) 2017 Pierre-Antoine Lacaze
+
+Permission is hereby granted, free of charge, to any person obtaining a copy
+of this software and associated documentation files (the "Software"), to deal
+in the Software without restriction, including without limitation the rights
+to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+copies of the Software, and to permit persons to whom the Software is
+furnished to do so, subject to the following conditions:
+
+The above copyright notice and this permission notice shall be included in all
+copies or substantial portions of the Software.
+
+THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
+SOFTWARE.
+ */
+
+#include "wpi/Signal.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <cmath>
+#include <sstream>
+#include <string>
+
+using namespace wpi::sig;
+
+namespace {
+
+int sum = 0;
+
+void f1(int i) { sum += i; }
+void f2(int i) /*noexcept*/ { sum += 2 * i; }
+
+struct s {
+  static void s1(int i) { sum += i; }
+  static void s2(int i) noexcept { sum += 2 * i; }
+
+  void f1(int i) { sum += i; }
+  void f2(int i) const { sum += i; }
+  void f3(int i) volatile { sum += i; }
+  void f4(int i) const volatile { sum += i; }
+  void f5(int i) noexcept { sum += i; }
+  void f6(int i) const noexcept { sum += i; }
+  void f7(int i) volatile noexcept { sum += i; }
+  void f8(int i) const volatile noexcept { sum += i; }
+};
+
+struct oo {
+  void operator()(int i) { sum += i; }
+  void operator()(double i) { sum += std::round(4 * i); }
+};
+
+struct o1 {
+  void operator()(int i) { sum += i; }
+};
+struct o2 {
+  void operator()(int i) const { sum += i; }
+};
+struct o3 {
+  void operator()(int i) volatile { sum += i; }
+};
+struct o4 {
+  void operator()(int i) const volatile { sum += i; }
+};
+struct o5 {
+  void operator()(int i) noexcept { sum += i; }
+};
+struct o6 {
+  void operator()(int i) const noexcept { sum += i; }
+};
+struct o7 {
+  void operator()(int i) volatile noexcept { sum += i; }
+};
+struct o8 {
+  void operator()(int i) const volatile noexcept { sum += i; }
+};
+
+}  // namespace
+
+namespace wpi {
+
+TEST(Signal, FreeConnection) {
+  sum = 0;
+  Signal<int> sig;
+
+  auto c1 = sig.connect_connection(f1);
+  sig(1);
+  ASSERT_EQ(sum, 1);
+
+  sig.connect(f2);
+  sig(1);
+  ASSERT_EQ(sum, 4);
+}
+
+TEST(Signal, StaticConnection) {
+  sum = 0;
+  Signal<int> sig;
+
+  sig.connect(&s::s1);
+  sig(1);
+  ASSERT_EQ(sum, 1);
+
+  sig.connect(&s::s2);
+  sig(1);
+  ASSERT_EQ(sum, 4);
+}
+
+TEST(Signal, PmfConnection) {
+  sum = 0;
+  Signal<int> sig;
+  s p;
+
+  sig.connect(&s::f1, &p);
+  sig.connect(&s::f2, &p);
+  sig.connect(&s::f3, &p);
+  sig.connect(&s::f4, &p);
+  sig.connect(&s::f5, &p);
+  sig.connect(&s::f6, &p);
+  sig.connect(&s::f7, &p);
+  sig.connect(&s::f8, &p);
+
+  sig(1);
+  ASSERT_EQ(sum, 8);
+}
+
+TEST(Signal, ConstPmfConnection) {
+  sum = 0;
+  Signal<int> sig;
+  const s p;
+
+  sig.connect(&s::f2, &p);
+  sig.connect(&s::f4, &p);
+  sig.connect(&s::f6, &p);
+  sig.connect(&s::f8, &p);
+
+  sig(1);
+  ASSERT_EQ(sum, 4);
+}
+
+TEST(Signal, FunctionObjectConnection) {
+  sum = 0;
+  Signal<int> sig;
+
+  sig.connect(o1{});
+  sig.connect(o2{});
+  sig.connect(o3{});
+  sig.connect(o4{});
+  sig.connect(o5{});
+  sig.connect(o6{});
+  sig.connect(o7{});
+  sig.connect(o8{});
+
+  sig(1);
+  ASSERT_EQ(sum, 8);
+}
+
+TEST(Signal, OverloadedFunctionObjectConnection) {
+  sum = 0;
+  Signal<int> sig;
+  Signal<double> sig1;
+
+  sig.connect(oo{});
+  sig(1);
+  ASSERT_EQ(sum, 1);
+
+  sig1.connect(oo{});
+  sig1(1);
+  ASSERT_EQ(sum, 5);
+}
+
+TEST(Signal, LambdaConnection) {
+  sum = 0;
+  Signal<int> sig;
+
+  sig.connect([&](int i) { sum += i; });
+  sig(1);
+  ASSERT_EQ(sum, 1);
+
+  sig.connect([&](int i) mutable { sum += 2 * i; });
+  sig(1);
+  ASSERT_EQ(sum, 4);
+}
+
+TEST(Signal, GenericLambdaConnection) {
+  std::stringstream s;
+
+  auto f = [&](auto a, auto... args) {
+    using result_t = int[];
+    s << a;
+    result_t r{
+        1,
+        ((void)(s << args), 1)...,
+    };
+    (void)r;
+  };
+
+  Signal<int> sig1;
+  Signal<std::string> sig2;
+  Signal<double> sig3;
+
+  sig1.connect(f);
+  sig2.connect(f);
+  sig3.connect(f);
+  sig1(1);
+  sig2("foo");
+  sig3(4.1);
+
+  ASSERT_EQ(s.str(), "1foo4.1");
+}
+
+TEST(Signal, LvalueEmission) {
+  sum = 0;
+  Signal<int> sig;
+
+  auto c1 = sig.connect_connection(f1);
+  int v = 1;
+  sig(v);
+  ASSERT_EQ(sum, 1);
+
+  sig.connect(f2);
+  sig(v);
+  ASSERT_EQ(sum, 4);
+}
+
+TEST(Signal, Mutation) {
+  int res = 0;
+  Signal<int&> sig;
+
+  sig.connect([](int& r) { r += 1; });
+  sig(res);
+  ASSERT_EQ(res, 1);
+
+  sig.connect([](int& r) mutable { r += 2; });
+  sig(res);
+  ASSERT_EQ(res, 4);
+}
+
+TEST(Signal, CompatibleArgs) {
+  long ll = 0;  // NOLINT(runtime/int)
+  std::string ss;
+  short ii = 0;  // NOLINT(runtime/int)
+
+  auto f = [&](long l, const std::string& s, short i) {  // NOLINT(runtime/int)
+    ll = l;
+    ss = s;
+    ii = i;
+  };
+
+  Signal<int, std::string, bool> sig;
+  sig.connect(f);
+  sig('0', "foo", true);
+
+  ASSERT_EQ(ll, 48);
+  ASSERT_EQ(ss, "foo");
+  ASSERT_EQ(ii, 1);
+}
+
+TEST(Signal, Disconnection) {
+  // test removing only connected
+  {
+    sum = 0;
+    Signal<int> sig;
+
+    auto sc = sig.connect_connection(f1);
+    sig(1);
+    ASSERT_EQ(sum, 1);
+
+    sc.disconnect();
+    sig(1);
+    ASSERT_EQ(sum, 1);
+  }
+
+  // test removing first connected
+  {
+    sum = 0;
+    Signal<int> sig;
+
+    auto sc = sig.connect_connection(f1);
+    sig(1);
+    ASSERT_EQ(sum, 1);
+
+    sig.connect(f2);
+    sig(1);
+    ASSERT_EQ(sum, 4);
+
+    sc.disconnect();
+    sig(1);
+    ASSERT_EQ(sum, 6);
+  }
+
+  // test removing last connected
+  {
+    sum = 0;
+    Signal<int> sig;
+
+    sig.connect(f1);
+    sig(1);
+    ASSERT_EQ(sum, 1);
+
+    auto sc = sig.connect_connection(f2);
+    sig(1);
+    ASSERT_EQ(sum, 4);
+
+    sc.disconnect();
+    sig(1);
+    ASSERT_EQ(sum, 5);
+  }
+}
+
+TEST(Signal, ScopedConnection) {
+  sum = 0;
+  Signal<int> sig;
+
+  {
+    auto sc1 = sig.connect_scoped(f1);
+    sig(1);
+    ASSERT_EQ(sum, 1);
+
+    auto sc2 = sig.connect_scoped(f2);
+    sig(1);
+    ASSERT_EQ(sum, 4);
+  }
+
+  sig(1);
+  ASSERT_EQ(sum, 4);
+
+  sum = 0;
+
+  {
+    ScopedConnection sc1 = sig.connect_connection(f1);
+    sig(1);
+    ASSERT_EQ(sum, 1);
+
+    ScopedConnection sc2 = sig.connect_connection(f2);
+    sig(1);
+    ASSERT_EQ(sum, 4);
+  }
+
+  sig(1);
+  ASSERT_EQ(sum, 4);
+}
+
+TEST(Signal, ConnectionBlocking) {
+  sum = 0;
+  Signal<int> sig;
+
+  auto c1 = sig.connect_connection(f1);
+  sig.connect(f2);
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  c1.block();
+  sig(1);
+  ASSERT_EQ(sum, 5);
+
+  c1.unblock();
+  sig(1);
+  ASSERT_EQ(sum, 8);
+}
+
+TEST(Signal, ConnectionBlocker) {
+  sum = 0;
+  Signal<int> sig;
+
+  auto c1 = sig.connect_connection(f1);
+  sig.connect(f2);
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  {
+    auto cb = c1.blocker();
+    sig(1);
+    ASSERT_EQ(sum, 5);
+  }
+
+  sig(1);
+  ASSERT_EQ(sum, 8);
+}
+
+TEST(Signal, SignalBlocking) {
+  sum = 0;
+  Signal<int> sig;
+
+  sig.connect(f1);
+  sig.connect(f2);
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  sig.block();
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  sig.unblock();
+  sig(1);
+  ASSERT_EQ(sum, 6);
+}
+
+TEST(Signal, AllDisconnection) {
+  sum = 0;
+  Signal<int> sig;
+
+  sig.connect(f1);
+  sig.connect(f2);
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  sig.disconnect_all();
+  sig(1);
+  ASSERT_EQ(sum, 3);
+}
+
+TEST(Signal, ConnectionCopyingMoving) {
+  sum = 0;
+  Signal<int> sig;
+
+  auto sc1 = sig.connect_connection(f1);
+  auto sc2 = sig.connect_connection(f2);
+
+  auto sc3 = sc1;
+  auto sc4{sc2};
+
+  auto sc5 = std::move(sc3);
+  auto sc6{std::move(sc4)};
+
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  sc5.block();
+  sig(1);
+  ASSERT_EQ(sum, 5);
+
+  sc1.unblock();
+  sig(1);
+  ASSERT_EQ(sum, 8);
+
+  sc6.disconnect();
+  sig(1);
+  ASSERT_EQ(sum, 9);
+}
+
+TEST(Signal, ScopedConnectionMoving) {
+  sum = 0;
+  Signal<int> sig;
+
+  {
+    auto sc1 = sig.connect_scoped(f1);
+    sig(1);
+    ASSERT_EQ(sum, 1);
+
+    auto sc2 = sig.connect_scoped(f2);
+    sig(1);
+    ASSERT_EQ(sum, 4);
+
+    auto sc3 = std::move(sc1);
+    sig(1);
+    ASSERT_EQ(sum, 7);
+
+    auto sc4{std::move(sc2)};
+    sig(1);
+    ASSERT_EQ(sum, 10);
+  }
+
+  sig(1);
+  ASSERT_EQ(sum, 10);
+}
+
+TEST(Signal, SignalMoving) {
+  sum = 0;
+  Signal<int> sig;
+
+  sig.connect(f1);
+  sig.connect(f2);
+
+  sig(1);
+  ASSERT_EQ(sum, 3);
+
+  auto sig2 = std::move(sig);
+  sig2(1);
+  ASSERT_EQ(sum, 6);
+
+  auto sig3 = std::move(sig2);
+  sig3(1);
+  ASSERT_EQ(sum, 9);
+}
+
+template <typename T>
+struct object {
+  object();
+  object(T i) : v{i} {}  // NOLINT(runtime/explicit)
+
+  const T& val() const { return v; }
+  T& val() { return v; }
+  void set_val(const T& i) {
+    if (i != v) {
+      v = i;
+      s(i);
+    }
+  }
+
+  Signal<T>& sig() { return s; }
+
+ private:
+  T v;
+  Signal<T> s;
+};
+
+TEST(Signal, Loop) {
+  object<int> i1(0);
+  object<int> i2(3);
+
+  i1.sig().connect(&object<int>::set_val, &i2);
+  i2.sig().connect(&object<int>::set_val, &i1);
+
+  i1.set_val(1);
+
+  ASSERT_EQ(i1.val(), 1);
+  ASSERT_EQ(i2.val(), 1);
+}
+
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/spinlock_bench.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/spinlock_bench.cpp
new file mode 100644
index 0000000..2280a44
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/spinlock_bench.cpp
@@ -0,0 +1,166 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/spinlock.h"  // NOLINT(build/include_order)
+
+#include <chrono>
+#include <iostream>
+#include <mutex>
+#include <thread>
+
+#include "gtest/gtest.h"
+#include "wpi/mutex.h"
+
+static std::mutex std_mutex;
+static std::recursive_mutex std_recursive_mutex;
+static wpi::mutex wpi_mutex;
+static wpi::recursive_mutex wpi_recursive_mutex;
+static wpi::spinlock spinlock;
+static wpi::recursive_spinlock1 recursive_spinlock1;
+static wpi::recursive_spinlock2 recursive_spinlock2;
+static wpi::recursive_spinlock recursive_spinlock;
+
+TEST(SpinlockTest, Benchmark) {
+  using std::chrono::duration_cast;
+  using std::chrono::high_resolution_clock;
+  using std::chrono::microseconds;
+
+  // warmup
+  std::thread thr([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 10000000; i++) {
+      std::lock_guard<std::mutex> lock(std_mutex);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    (void)start;
+    (void)stop;
+  });
+  thr.join();
+
+  std::thread thrb([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 1000000; i++) {
+      std::lock_guard<std::mutex> lock(std_mutex);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    std::cout << "std::mutex sizeof: " << sizeof(std_mutex)
+              << " time: " << duration_cast<microseconds>(stop - start).count()
+              << " value: " << value << "\n";
+  });
+  thrb.join();
+
+  std::thread thrb2([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 1000000; i++) {
+      std::lock_guard<std::recursive_mutex> lock(std_recursive_mutex);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    std::cout << "std::recursive_mutex sizeof: " << sizeof(std_recursive_mutex)
+              << " time: " << duration_cast<microseconds>(stop - start).count()
+              << " value: " << value << "\n";
+  });
+  thrb2.join();
+
+  std::thread thr2([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 1000000; i++) {
+      std::lock_guard<wpi::mutex> lock(wpi_mutex);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    std::cout << "wpi::mutex sizeof: " << sizeof(wpi_mutex)
+              << " time: " << duration_cast<microseconds>(stop - start).count()
+              << " value: " << value << "\n";
+  });
+  thr2.join();
+
+  std::thread thr2b([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 1000000; i++) {
+      std::lock_guard<wpi::recursive_mutex> lock(wpi_recursive_mutex);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    std::cout << "wpi::recursive_mutex sizeof: " << sizeof(wpi_recursive_mutex)
+              << " time: " << duration_cast<microseconds>(stop - start).count()
+              << " value: " << value << "\n";
+  });
+  thr2b.join();
+
+  std::thread thr3([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 1000000; i++) {
+      std::lock_guard<wpi::spinlock> lock(spinlock);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    std::cout << "spinlock sizeof: " << sizeof(spinlock)
+              << " time: " << duration_cast<microseconds>(stop - start).count()
+              << " value: " << value << "\n";
+  });
+  thr3.join();
+
+  std::thread thr4([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 1000000; i++) {
+      std::lock_guard<wpi::recursive_spinlock1> lock(recursive_spinlock1);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    std::cout << "recursive_spinlock1 sizeof: " << sizeof(recursive_spinlock1)
+              << " time: " << duration_cast<microseconds>(stop - start).count()
+              << " value: " << value << "\n";
+  });
+  thr4.join();
+
+  std::thread thr4b([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 1000000; i++) {
+      std::lock_guard<wpi::recursive_spinlock2> lock(recursive_spinlock2);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    std::cout << "recursive_spinlock2 sizeof: " << sizeof(recursive_spinlock2)
+              << " time: " << duration_cast<microseconds>(stop - start).count()
+              << " value: " << value << "\n";
+  });
+  thr4b.join();
+
+  std::thread thr4c([]() {
+    int value = 0;
+
+    auto start = high_resolution_clock::now();
+    for (int i = 0; i < 1000000; i++) {
+      std::lock_guard<wpi::recursive_spinlock> lock(recursive_spinlock);
+      ++value;
+    }
+    auto stop = high_resolution_clock::now();
+    std::cout << "recursive_spinlock sizeof: " << sizeof(recursive_spinlock)
+              << " time: " << duration_cast<microseconds>(stop - start).count()
+              << " value: " << value << "\n";
+  });
+  thr4c.join();
+}
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/test_optional.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/test_optional.cpp
new file mode 100644
index 0000000..e64f0c2
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/test_optional.cpp
@@ -0,0 +1,1523 @@
+// Copyright (C) 2011 - 2017 Andrzej Krzemienski.
+//
+// Use, modification, and distribution is subject to the Boost Software
+// License, Version 1.0. (See accompanying file LICENSE_1_0.txt or copy at
+// http://www.boost.org/LICENSE_1_0.txt)
+//
+// The idea and interface is based on Boost.Optional library
+// authored by Fernando Luis Cacciola Carballal
+
+# include "wpi/optional.h"
+
+#include "gtest/gtest.h"
+
+# include <vector>
+# include <iostream>
+# include <functional>
+# include <complex>
+
+
+
+enum  State 
+{
+    sDefaultConstructed,
+    sValueCopyConstructed,
+    sValueMoveConstructed,
+    sCopyConstructed,
+    sMoveConstructed,
+    sMoveAssigned,
+    sCopyAssigned,
+    sValueCopyAssigned,
+    sValueMoveAssigned,
+    sMovedFrom,
+    sValueConstructed
+};
+
+struct OracleVal
+{
+    State s;
+    int i;
+    OracleVal(int i = 0) : s(sValueConstructed), i(i) {}
+};
+
+struct Oracle
+{
+    State s;
+    OracleVal val;
+
+    Oracle() : s(sDefaultConstructed) {}
+    Oracle(const OracleVal& v) : s(sValueCopyConstructed), val(v) {}
+    Oracle(OracleVal&& v) : s(sValueMoveConstructed), val(std::move(v)) {v.s = sMovedFrom;}
+    Oracle(const Oracle& o) : s(sCopyConstructed), val(o.val) {}
+    Oracle(Oracle&& o) : s(sMoveConstructed), val(std::move(o.val)) {o.s = sMovedFrom;}
+
+    Oracle& operator=(const OracleVal& v) { s = sValueCopyConstructed; val = v; return *this; }
+    Oracle& operator=(OracleVal&& v) { s = sValueMoveConstructed; val = std::move(v); v.s = sMovedFrom; return *this; }
+    Oracle& operator=(const Oracle& o) { s = sCopyConstructed; val = o.val; return *this; }
+    Oracle& operator=(Oracle&& o) { s = sMoveConstructed; val = std::move(o.val); o.s = sMovedFrom; return *this; }
+};
+
+struct Guard
+{
+    std::string val;
+    Guard() : val{} {}
+    explicit Guard(std::string s, int = 0) : val(s) {}
+    Guard(const Guard&) = delete;
+    Guard(Guard&&) = delete;
+    void operator=(const Guard&) = delete;
+    void operator=(Guard&&) = delete;
+};
+
+struct ExplicitStr
+{
+    std::string s;
+    explicit ExplicitStr(const char* chp) : s(chp) {};
+};
+
+struct Date
+{
+    int i;
+    Date() = delete;
+    Date(int i) : i{i} {};
+    Date(Date&& d) : i(d.i) { d.i = 0; }
+    Date(const Date&) = delete;
+    Date& operator=(const Date&) = delete;
+    Date& operator=(Date&& d) { i = d.i; d.i = 0; return *this;};
+};
+
+bool operator==( Oracle const& a, Oracle const& b ) { return a.val.i == b.val.i; }
+bool operator!=( Oracle const& a, Oracle const& b ) { return a.val.i != b.val.i; }
+
+
+namespace tr2 = wpi;
+
+
+TEST(Optional, disengaged_ctor)
+{
+    tr2::optional<int> o1;
+    assert (!o1);
+
+    tr2::optional<int> o2 = tr2::nullopt;
+    assert (!o2);
+
+    tr2::optional<int> o3 = o2;
+    assert (!o3);
+
+    assert (o1 == tr2::nullopt);
+    assert (o1 == tr2::optional<int>{});
+    assert (!o1);
+    assert (bool(o1) == false);
+
+    assert (o2 == tr2::nullopt);
+    assert (o2 == tr2::optional<int>{});
+    assert (!o2);
+    assert (bool(o2) == false);
+
+    assert (o3 == tr2::nullopt);
+    assert (o3 == tr2::optional<int>{});
+    assert (!o3);
+    assert (bool(o3) == false);
+
+    assert (o1 == o2);
+    assert (o2 == o1);
+    assert (o1 == o3);
+    assert (o3 == o1);
+    assert (o2 == o3);
+    assert (o3 == o2);
+}
+
+
+TEST(Optional, value_ctor)
+{
+  OracleVal v;
+  tr2::optional<Oracle> oo1(v);
+  assert (oo1 != tr2::nullopt);
+  assert (oo1 != tr2::optional<Oracle>{});
+  assert (oo1 == tr2::optional<Oracle>{v});
+  assert (!!oo1);
+  assert (bool(oo1));
+  // NA: assert (oo1->s == sValueCopyConstructed);
+  assert (oo1->s == sMoveConstructed);
+  assert (v.s == sValueConstructed);
+  
+  tr2::optional<Oracle> oo2(std::move(v));
+  assert (oo2 != tr2::nullopt);
+  assert (oo2 != tr2::optional<Oracle>{});
+  assert (oo2 == oo1);
+  assert (!!oo2);
+  assert (bool(oo2));
+  // NA: assert (oo2->s == sValueMoveConstructed);
+  assert (oo2->s == sMoveConstructed);
+  assert (v.s == sMovedFrom);
+
+  {
+      OracleVal v;
+      tr2::optional<Oracle> oo1{tr2::in_place, v};
+      assert (oo1 != tr2::nullopt);
+      assert (oo1 != tr2::optional<Oracle>{});
+      assert (oo1 == tr2::optional<Oracle>{v});
+      assert (!!oo1);
+      assert (bool(oo1));
+      assert (oo1->s == sValueCopyConstructed);
+      assert (v.s == sValueConstructed);
+
+      tr2::optional<Oracle> oo2{tr2::in_place, std::move(v)};
+      assert (oo2 != tr2::nullopt);
+      assert (oo2 != tr2::optional<Oracle>{});
+      assert (oo2 == oo1);
+      assert (!!oo2);
+      assert (bool(oo2));
+      assert (oo2->s == sValueMoveConstructed);
+      assert (v.s == sMovedFrom);
+  }
+}
+
+
+TEST(Optional, assignment)
+{
+    tr2::optional<int> oi;
+    oi = tr2::optional<int>{1};
+    assert (*oi == 1);
+
+    oi = tr2::nullopt;
+    assert (!oi);
+
+    oi = 2;
+    assert (*oi == 2);
+
+    oi = {};
+    assert (!oi);
+}
+
+
+template <class T>
+struct MoveAware
+{
+  T val;
+  bool moved;
+  MoveAware(T val) : val(val), moved(false) {}
+  MoveAware(MoveAware const&) = delete;
+  MoveAware(MoveAware&& rhs) : val(rhs.val), moved(rhs.moved) {
+    rhs.moved = true;
+  }
+  MoveAware& operator=(MoveAware const&) = delete;
+  MoveAware& operator=(MoveAware&& rhs) {
+    val = (rhs.val);
+    moved = (rhs.moved);
+    rhs.moved = true;
+    return *this;
+  }
+};
+
+TEST(Optional, moved_from_state)
+{
+  // first, test mock:
+  MoveAware<int> i{1}, j{2};
+  assert (i.val == 1);
+  assert (!i.moved);
+  assert (j.val == 2);
+  assert (!j.moved);
+  
+  MoveAware<int> k = std::move(i);
+  assert (k.val == 1);
+  assert (!k.moved);
+  assert (i.val == 1);
+  assert (i.moved);
+  
+  k = std::move(j);
+  assert (k.val == 2);
+  assert (!k.moved);
+  assert (j.val == 2);
+  assert (j.moved);
+  
+  // now, test optional
+  tr2::optional<MoveAware<int>> oi{1}, oj{2};
+  assert (oi);
+  assert (!oi->moved);
+  assert (oj);
+  assert (!oj->moved);
+  
+  tr2::optional<MoveAware<int>> ok = std::move(oi);
+  assert (ok);
+  assert (!ok->moved);
+  assert (oi);
+  assert (oi->moved);
+  
+  ok = std::move(oj);
+  assert (ok);
+  assert (!ok->moved);
+  assert (oj);
+  assert (oj->moved);
+}
+
+
+TEST(Optional, copy_move_ctor_optional_int)
+{
+  tr2::optional<int> oi;
+  tr2::optional<int> oj = oi;
+  
+  assert (!oj);
+  assert (oj == oi);
+  assert (oj == tr2::nullopt);
+  assert (!bool(oj));
+  
+  oi = 1;
+  tr2::optional<int> ok = oi;
+  assert (!!ok);
+  assert (bool(ok));
+  assert (ok == oi);
+  assert (ok != oj);
+  assert (*ok == 1);
+  
+  tr2::optional<int> ol = std::move(oi);
+  assert (!!ol);
+  assert (bool(ol));
+  assert (ol == oi);
+  assert (ol != oj);
+  assert (*ol == 1);
+}
+
+
+TEST(Optional, optional_optional)
+{
+  tr2::optional<tr2::optional<int>> oi1 = tr2::nullopt;
+  assert (oi1 == tr2::nullopt);
+  assert (!oi1);
+  
+  {
+  tr2::optional<tr2::optional<int>> oi2 {tr2::in_place};
+  assert (oi2 != tr2::nullopt);
+  assert (bool(oi2));
+  assert (*oi2 == tr2::nullopt);
+  //assert (!(*oi2));
+  //std::cout << typeid(**oi2).name() << std::endl;
+  }
+  
+  {
+  tr2::optional<tr2::optional<int>> oi2 {tr2::in_place, tr2::nullopt};
+  assert (oi2 != tr2::nullopt);
+  assert (bool(oi2));
+  assert (*oi2 == tr2::nullopt);
+  assert (!*oi2);
+  }
+  
+  {
+  tr2::optional<tr2::optional<int>> oi2 {tr2::optional<int>{}};
+  assert (oi2 != tr2::nullopt);
+  assert (bool(oi2));
+  assert (*oi2 == tr2::nullopt);
+  assert (!*oi2);
+  }
+  
+  tr2::optional<int> oi;
+  auto ooi = tr2::make_optional(oi);
+  static_assert( std::is_same<tr2::optional<tr2::optional<int>>, decltype(ooi)>::value, "");
+
+}
+
+TEST(Optional, example_guard)
+{
+  using namespace tr2;
+  //FAILS: optional<Guard> ogx(Guard("res1")); 
+  //FAILS: optional<Guard> ogx = "res1"; 
+  //FAILS: optional<Guard> ogx("res1"); 
+  optional<Guard> oga;                     // Guard is non-copyable (and non-moveable)     
+  optional<Guard> ogb(in_place, "res1");   // initialzes the contained value with "res1"  
+  assert (bool(ogb));
+  assert (ogb->val == "res1");
+            
+  optional<Guard> ogc(in_place);           // default-constructs the contained value
+  assert (bool(ogc));
+  assert (ogc->val == "");
+
+  oga.emplace("res1");                     // initialzes the contained value with "res1"  
+  assert (bool(oga));
+  assert (oga->val == "res1");
+  
+  oga.emplace();                           // destroys the contained value and 
+                                           // default-constructs the new one
+  assert (bool(oga));
+  assert (oga->val == "");
+  
+  oga = nullopt;                        // OK: make disengaged the optional Guard
+  assert (!(oga));
+  //FAILS: ogb = {};                          // ERROR: Guard is not Moveable
+}
+
+
+void process(){}
+void process(int ){}
+void processNil(){}
+
+
+TEST(Optional, example1)
+{
+  using namespace tr2;
+  optional<int> oi;                 // create disengaged object
+  optional<int> oj = nullopt;          // alternative syntax
+  oi = oj;                          // assign disengaged object
+  optional<int> ok = oj;            // ok is disengaged
+
+  if (oi)  assert(false);           // 'if oi is engaged...'
+  if (!oi) assert(true);            // 'if oi is disengaged...'
+
+  if (oi != nullopt) assert(false);    // 'if oi is engaged...'
+  if (oi == nullopt) assert(true);     // 'if oi is disengaged...'
+
+  assert(oi == ok);                 // two disengaged optionals compare equal
+  
+  ///////////////////////////////////////////////////////////////////////////
+  optional<int> ol{1};              // ol is engaged; its contained value is 1
+  ok = 2;                           // ok becomes engaged; its contained value is 2
+  oj = ol;                          // oj becomes engaged; its contained value is 1
+
+  assert(oi != ol);                 // disengaged != engaged
+  assert(ok != ol);                 // different contained values
+  assert(oj == ol);                 // same contained value
+  assert(oi < ol);                  // disengaged < engaged
+  assert(ol < ok);                  // less by contained value
+  
+  /////////////////////////////////////////////////////////////////////////////
+  optional<int> om{1};              // om is engaged; its contained value is 1
+  optional<int> on = om;            // on is engaged; its contained value is 1
+  om = 2;                           // om is engaged; its contained value is 2
+  assert (on != om);                // on still contains 3. They are not pointers
+
+  /////////////////////////////////////////////////////////////////////////////
+  int i = *ol;                      // i obtains the value contained in ol
+  assert (i == 1);
+  *ol = 9;                          // the object contained in ol becomes 9
+  assert(*ol == 9);
+  assert(ol == make_optional(9));  
+  
+  ///////////////////////////////////
+  int p = 1;
+  optional<int> op = p;
+  assert(*op == 1);
+  p = 2;                         
+  assert(*op == 1);                 // value contained in op is separated from p
+
+  ////////////////////////////////
+  if (ol)                      
+    process(*ol);                   // use contained value if present
+  else
+    process();                      // proceed without contained value
+    
+  if (!om)   
+    processNil();
+  else  
+    process(*om);   
+  
+  /////////////////////////////////////////
+  process(ol.value_or(0));     // use 0 if ol is disengaged
+  
+  ////////////////////////////////////////////
+  ok = nullopt;                         // if ok was engaged calls T's dtor
+  oj = {};                           // assigns a temporary disengaged optional
+}
+
+
+TEST(Optional, example_guard2)
+{
+  using wpi::optional;
+  const optional<int> c = 4; 
+  int i = *c;                        // i becomes 4
+  assert (i == 4);
+  // FAILS: *c = i;                            // ERROR: cannot assign to const int&
+}
+
+
+TEST(Optional, example_ref)
+{
+  using namespace wpi;
+  int i = 1;
+  int j = 2;
+  optional<int&> ora;                 // disengaged optional reference to int
+  optional<int&> orb = i;             // contained reference refers to object i
+
+  *orb = 3;                          // i becomes 3
+  // FAILS: ora = j;                           // ERROR: optional refs do not have assignment from T
+  // FAILS: ora = {j};                         // ERROR: optional refs do not have copy/move assignment
+  // FAILS: ora = orb;                         // ERROR: no copy/move assignment
+  ora.emplace(j);                    // OK: contained reference refers to object j
+  ora.emplace(i);                    // OK: contained reference now refers to object i
+
+  ora = nullopt;                        // OK: ora becomes disengaged
+}
+
+
+template <typename T>
+T getValue( tr2::optional<T> newVal = tr2::nullopt, tr2::optional<T&> storeHere = tr2::nullopt )
+{
+  T cached{};
+  
+  if (newVal) {
+    cached = *newVal;
+    
+    if (storeHere) {
+      *storeHere = *newVal; // LEGAL: assigning T to T
+    }      
+  }
+  return cached;      
+}
+
+TEST(Optional, example_optional_arg)
+{
+  int iii = 0;
+  iii = getValue<int>(iii, iii);
+  iii = getValue<int>(iii);
+  iii = getValue<int>();
+  
+  {
+    using namespace wpi;
+    optional<Guard> grd1{in_place, "res1", 1};   // guard 1 initialized
+    optional<Guard> grd2;
+
+    grd2.emplace("res2", 2);                     // guard 2 initialized
+    grd1 = nullopt;                                 // guard 1 released
+
+  }                                              // guard 2 released (in dtor)
+}
+
+
+std::tuple<Date, Date, Date> getStartMidEnd() { return std::tuple<Date, Date, Date>{Date{1}, Date{2}, Date{3}}; }
+void run(Date const&, Date const&, Date const&) {}
+
+TEST(Optional, example_date)
+{
+  using namespace wpi;
+  optional<Date> start, mid, end;           // Date doesn't have default ctor (no good default date)
+
+  std::tie(start, mid, end) = getStartMidEnd();
+  run(*start, *mid, *end); 
+}
+
+
+wpi::optional<char> readNextChar(){ return{}; }
+
+void run(wpi::optional<std::string>) {}
+void run(std::complex<double>) {}
+
+
+template <class T>
+void assign_norebind(tr2::optional<T&>& optref, T& obj)
+{
+  if (optref) *optref = obj;
+  else        optref.emplace(obj);
+}
+
+template <typename T> void unused(T&&) {}
+
+TEST(Optional, example_conceptual_model)
+{
+  using namespace wpi;
+  
+  optional<int> oi = 0;
+  optional<int> oj = 1;
+  optional<int> ok = nullopt;
+
+  oi = 1;
+  oj = nullopt;
+  ok = 0;
+
+  unused(oi == nullopt);
+  unused(oj == 0);
+  unused(ok == 1);
+}
+
+TEST(Optional, example_rationale)
+{
+  using namespace wpi;
+  if (optional<char> ch = readNextChar()) {
+    unused(ch);
+    // ...
+  }
+  
+  //////////////////////////////////
+  optional<int> opt1 = nullopt; 
+  optional<int> opt2 = {}; 
+
+  opt1 = nullopt;
+  opt2 = {};
+
+  if (opt1 == nullopt) {}
+  if (!opt2) {}
+  if (opt2 == optional<int>{}) {}
+  
+  
+  
+  ////////////////////////////////
+
+  run(nullopt);            // pick the second overload
+  // FAILS: run({});              // ambiguous
+
+  if (opt1 == nullopt) {} // fine
+  // FAILS: if (opt2 == {}) {}   // ilegal
+  
+  ////////////////////////////////
+  assert (optional<unsigned>{}  < optional<unsigned>{0});
+  assert (optional<unsigned>{0} < optional<unsigned>{1});
+  assert (!(optional<unsigned>{}  < optional<unsigned>{}) );
+  assert (!(optional<unsigned>{1} < optional<unsigned>{1}));
+
+  assert (optional<unsigned>{}  != optional<unsigned>{0});
+  assert (optional<unsigned>{0} != optional<unsigned>{1});
+  assert (optional<unsigned>{}  == optional<unsigned>{} );
+  assert (optional<unsigned>{0} == optional<unsigned>{0});
+  
+  /////////////////////////////////
+  optional<int> o;
+  o = make_optional(1);         // copy/move assignment
+  o = 1;           // assignment from T
+  o.emplace(1);    // emplacement 
+  
+  ////////////////////////////////////
+  int isas = 0, i = 9;
+  optional<int&> asas = i;
+  assign_norebind(asas, isas);
+  
+  /////////////////////////////////////
+  ////tr2::optional<std::vector<int>> ov2 = {2, 3};
+  ////assert (bool(ov2));
+  ////assert ((*ov2)[1] == 3);
+  ////
+  ////////////////////////////////
+  ////std::vector<int> v = {1, 2, 4, 8};
+  ////optional<std::vector<int>> ov = {1, 2, 4, 8};
+
+  ////assert (v == *ov);
+  ////
+  ////ov = {1, 2, 4, 8};
+
+  ////std::allocator<int> a;
+  ////optional<std::vector<int>> ou { in_place, {1, 2, 4, 8}, a };
+
+  ////assert (ou == ov);
+
+  //////////////////////////////
+  // inconvenient syntax:
+  {
+    
+      tr2::optional<std::vector<int>> ov2{tr2::in_place, {2, 3}};
+    
+      assert (bool(ov2));
+      assert ((*ov2)[1] == 3);
+  
+      ////////////////////////////
+
+      std::vector<int> v = {1, 2, 4, 8};
+      optional<std::vector<int>> ov{tr2::in_place, {1, 2, 4, 8}};
+
+      assert (v == *ov);
+  
+      ov.emplace({1, 2, 4, 8});
+/*
+      std::allocator<int> a;
+      optional<std::vector<int>> ou { in_place, {1, 2, 4, 8}, a };
+
+      assert (ou == ov);
+*/
+  }
+
+  /////////////////////////////////
+  {
+  typedef int T;
+  optional<optional<T>> ot {in_place};
+  optional<optional<T>> ou {in_place, nullopt};
+  optional<optional<T>> ov {optional<T>{}};
+
+  (void) ot;
+  (void) ou;
+  
+  optional<int> oi;
+  auto ooi = make_optional(oi);
+  static_assert( std::is_same<optional<optional<int>>, decltype(ooi)>::value, "");
+  }
+}
+
+
+bool fun(std::string , wpi::optional<int> oi = wpi::nullopt) 
+{
+  return bool(oi);
+}
+
+TEST(Optional, example_converting_ctor)
+{
+  using namespace wpi;
+  
+  assert (true == fun("dog", 2));
+  assert (false == fun("dog"));
+  assert (false == fun("dog", nullopt)); // just to be explicit
+}
+
+
+TEST(Optional, bad_comparison)
+{
+  tr2::optional<int> oi, oj;
+  int i;
+  bool b = (oi == oj);
+  b = (oi >= i);
+  b = (oi == i);
+  unused(b);
+}
+
+
+//// NOT APPLICABLE ANYMORE
+////TEST(Optional, perfect_ctor)
+////{
+////  //tr2::optional<std::string> ois = "OS";
+////  assert (*ois == "OS");
+////  
+////  // FAILS: tr2::optional<ExplicitStr> oes = "OS"; 
+////  tr2::optional<ExplicitStr> oes{"OS"};
+////  assert (oes->s == "OS");
+////}
+
+TEST(Optional, value_or)
+{
+  tr2::optional<int> oi = 1;
+  int i = oi.value_or(0);
+  assert (i == 1);
+  
+  oi = tr2::nullopt;
+  assert (oi.value_or(3) == 3);
+  
+  tr2::optional<std::string> os{"AAA"};
+  assert (os.value_or("BBB") == "AAA");
+  os = {};
+  assert (os.value_or("BBB") == "BBB");
+}
+
+TEST(Optional, reset)
+{
+  using namespace wpi;
+  optional<int> oi {1};
+  oi.reset();
+  assert (!oi);
+
+  int i = 1;
+  optional<const int&> oir {i};
+  oir.reset();
+  assert (!oir);
+}
+
+TEST(Optional, mixed_order)
+{
+  using namespace wpi;
+  
+  optional<int> oN {nullopt};
+  optional<int> o0 {0};
+  optional<int> o1 {1};
+  
+  assert ( (oN <   0));
+  assert ( (oN <   1));
+  assert (!(o0 <   0));
+  assert ( (o0 <   1));
+  assert (!(o1 <   0));
+  assert (!(o1 <   1));
+  
+  assert (!(oN >=  0));
+  assert (!(oN >=  1));
+  assert ( (o0 >=  0));
+  assert (!(o0 >=  1));
+  assert ( (o1 >=  0));
+  assert ( (o1 >=  1));
+  
+  assert (!(oN >   0));
+  assert (!(oN >   1));
+  assert (!(o0 >   0));
+  assert (!(o0 >   1));
+  assert ( (o1 >   0));
+  assert (!(o1 >   1));
+  
+  assert ( (oN <=  0));
+  assert ( (oN <=  1));
+  assert ( (o0 <=  0));
+  assert ( (o0 <=  1));
+  assert (!(o1 <=  0));
+  assert ( (o1 <=  1));
+  
+  assert ( (0 >  oN));
+  assert ( (1 >  oN));
+  assert (!(0 >  o0));
+  assert ( (1 >  o0));
+  assert (!(0 >  o1));
+  assert (!(1 >  o1));
+  
+  assert (!(0 <= oN));
+  assert (!(1 <= oN));
+  assert ( (0 <= o0));
+  assert (!(1 <= o0));
+  assert ( (0 <= o1));
+  assert ( (1 <= o1));
+  
+  assert (!(0 <  oN));
+  assert (!(1 <  oN));
+  assert (!(0 <  o0));
+  assert (!(1 <  o0));
+  assert ( (0 <  o1));
+  assert (!(1 <  o1));
+  
+  assert ( (0 >= oN));
+  assert ( (1 >= oN));
+  assert ( (0 >= o0));
+  assert ( (1 >= o0));
+  assert (!(0 >= o1));
+  assert ( (1 >= o1));
+}
+
+struct BadRelops
+{
+  int i;
+};
+
+constexpr bool operator<(BadRelops a, BadRelops b) { return a.i < b.i; }
+constexpr bool operator>(BadRelops a, BadRelops b) { return a.i < b.i; } // intentional error!
+
+TEST(Optional, bad_relops)
+{
+  using namespace wpi;
+  BadRelops a{1}, b{2};
+  assert (a < b);
+  assert (a > b);
+  
+  optional<BadRelops> oa = a, ob = b;
+  assert (oa < ob);
+  assert (!(oa > ob));
+  
+  assert (oa < b);
+  assert (oa > b);
+  
+  optional<BadRelops&> ra = a, rb = b;
+  assert (ra < rb);
+  assert (!(ra > rb));
+  
+  assert (ra < b);
+  assert (ra > b);
+}
+
+
+TEST(Optional, mixed_equality)
+{
+  using namespace wpi;
+  
+  assert (make_optional(0) == 0);
+  assert (make_optional(1) == 1);
+  assert (make_optional(0) != 1);
+  assert (make_optional(1) != 0);
+  
+  optional<int> oN {nullopt};
+  optional<int> o0 {0};
+  optional<int> o1 {1};
+  
+  assert (o0 ==  0);
+  assert ( 0 == o0);
+  assert (o1 ==  1);
+  assert ( 1 == o1);
+  assert (o1 !=  0);
+  assert ( 0 != o1);
+  assert (o0 !=  1);
+  assert ( 1 != o0);
+  
+  assert ( 1 != oN);
+  assert ( 0 != oN);
+  assert (oN !=  1);
+  assert (oN !=  0);
+  assert (!( 1 == oN));
+  assert (!( 0 == oN));
+  assert (!(oN ==  1));
+  assert (!(oN ==  0));
+  
+  std::string cat{"cat"}, dog{"dog"};
+  optional<std::string> oNil{}, oDog{"dog"}, oCat{"cat"};
+  
+  assert (oCat ==  cat);
+  assert ( cat == oCat);
+  assert (oDog ==  dog);
+  assert ( dog == oDog);
+  assert (oDog !=  cat);
+  assert ( cat != oDog);
+  assert (oCat !=  dog);
+  assert ( dog != oCat);
+  
+  assert ( dog != oNil);
+  assert ( cat != oNil);
+  assert (oNil !=  dog);
+  assert (oNil !=  cat);
+  assert (!( dog == oNil));
+  assert (!( cat == oNil));
+  assert (!(oNil ==  dog));
+  assert (!(oNil ==  cat));
+}
+
+TEST(Optional, const_propagation)
+{
+  using namespace wpi;
+  
+  optional<int> mmi{0};
+  static_assert(std::is_same<decltype(*mmi), int&>::value, "WTF");
+  
+  const optional<int> cmi{0};
+  static_assert(std::is_same<decltype(*cmi), const int&>::value, "WTF");
+  
+  optional<const int> mci{0};
+  static_assert(std::is_same<decltype(*mci), const int&>::value, "WTF");
+  
+  optional<const int> cci{0};
+  static_assert(std::is_same<decltype(*cci), const int&>::value, "WTF");
+}
+
+
+static_assert(std::is_base_of<std::logic_error, wpi::bad_optional_access>::value, "");
+
+TEST(Optional, safe_value)
+{
+  using namespace wpi;
+  
+  try {
+    optional<int> ovN{}, ov1{1};
+    
+    int& r1 = ov1.value();
+    assert (r1 == 1);
+    
+    try { 
+      ovN.value();
+      assert (false);
+    }
+    catch (bad_optional_access const&) {
+    }
+    
+    { // ref variant
+      int i1 = 1;
+      optional<int&> orN{}, or1{i1};
+      
+      int& r2 = or1.value();
+      assert (r2 == 1);
+      
+      try { 
+        orN.value();
+        assert (false);
+      }
+      catch (bad_optional_access const&) {
+      }
+    }
+  }  
+  catch(...) {
+    assert (false);
+  }
+}
+
+TEST(Optional, optional_ref)
+{
+  using namespace tr2;
+  // FAILS: optional<int&&> orr;
+  // FAILS: optional<nullopt_t&> on;
+  int i = 8;
+  optional<int&> ori;
+  assert (!ori);
+  ori.emplace(i);
+  assert (bool(ori));
+  assert (*ori == 8);
+  assert (&*ori == &i);
+  *ori = 9;
+  assert (i == 9);
+  
+  // FAILS: int& ir = ori.value_or(i);
+  int ii = ori.value_or(i);
+  assert (ii == 9);
+  ii = 7;
+  assert (*ori == 9);
+  
+  int j = 22;
+  auto&& oj = make_optional(std::ref(j));
+  *oj = 23;
+  assert (&*oj == &j);
+  assert (j == 23);
+}
+
+TEST(Optional, optional_ref_const_propagation)
+{
+  using namespace wpi;
+  
+  int i = 9;
+  const optional<int&> mi = i;
+  int& r = *mi; 
+  optional<const int&> ci = i;
+  static_assert(std::is_same<decltype(*mi), int&>::value, "WTF");
+  static_assert(std::is_same<decltype(*ci), const int&>::value, "WTF");
+  
+  unused(r);
+}
+
+TEST(Optional, optional_ref_assign)
+{
+  using namespace wpi;
+  
+  int i = 9;
+  optional<int&> ori = i;
+  
+  int j = 1;
+  ori = optional<int&>{j};
+  ori = {j};
+  // FAILS: ori = j;
+  
+  optional<int&> orx = ori;
+  ori = orx;
+  
+  optional<int&> orj = j;
+  
+  assert (ori);
+  assert (*ori == 1);
+  assert (ori == orj);
+  assert (i == 9);
+  
+  *ori = 2;
+  assert (*ori == 2);
+  assert (ori == 2);
+  assert (2 == ori);
+  assert (ori != 3);
+  
+  assert (ori == orj);
+  assert (j == 2);
+  assert (i == 9);
+  
+  ori = {};
+  assert (!ori);
+  assert (ori != orj);
+  assert (j == 2);
+  assert (i == 9);
+}
+
+TEST(Optional, optional_swap)
+{
+  namespace tr2 = wpi;
+  tr2::optional<int> oi {1}, oj {};
+  swap(oi, oj);
+  assert (oj);
+  assert (*oj == 1);
+  assert (!oi);
+  static_assert(noexcept(swap(oi, oj)), "swap() is not noexcept");
+}
+
+
+TEST(Optional, optional_ref_swap)
+{
+  using namespace wpi;
+  int i = 0;
+  int j = 1;
+  optional<int&> oi = i;
+  optional<int&> oj = j;
+  
+  assert (&*oi == &i);
+  assert (&*oj == &j);
+  
+  swap(oi, oj);
+  assert (&*oi == &j);
+  assert (&*oj == &i);
+}
+
+TEST(Optional, optional_initialization)
+{
+    using namespace tr2;
+    using std::string;
+    string s = "STR";
+
+    optional<string> os{s};
+    optional<string> ot = s;
+    optional<string> ou{"STR"};
+    optional<string> ov = string{"STR"};
+    
+}
+
+#include <unordered_set>
+
+TEST(Optional, optional_hashing)
+{
+    using namespace tr2;
+    using std::string;
+    
+    std::hash<int> hi;
+    std::hash<optional<int>> hoi;
+    std::hash<string> hs;
+    std::hash<optional<string>> hos;
+    
+    assert (hi(0) == hoi(optional<int>{0}));
+    assert (hi(1) == hoi(optional<int>{1}));
+    assert (hi(3198) == hoi(optional<int>{3198}));
+    
+    assert (hs("") == hos(optional<string>{""}));
+    assert (hs("0") == hos(optional<string>{"0"}));
+    assert (hs("Qa1#") == hos(optional<string>{"Qa1#"}));
+    
+    std::unordered_set<optional<string>> set;
+    assert(set.find({"Qa1#"}) == set.end());
+    
+    set.insert({"0"});
+    assert(set.find({"Qa1#"}) == set.end());
+    
+    set.insert({"Qa1#"});
+    assert(set.find({"Qa1#"}) != set.end());
+}
+
+
+// optional_ref_emulation
+template <class T>
+struct generic
+{
+  typedef T type;
+};
+
+template <class U>
+struct generic<U&>
+{
+  typedef std::reference_wrapper<U> type;
+};
+
+template <class T>
+using Generic = typename generic<T>::type;
+
+template <class X>
+bool generic_fun()
+{
+  wpi::optional<Generic<X>> op;
+  return bool(op);
+}
+
+TEST(Optional, optional_ref_emulation)
+{
+  using namespace wpi;
+  optional<Generic<int>> oi = 1;
+  assert (*oi == 1);
+  
+  int i = 8;
+  int j = 4;
+  optional<Generic<int&>> ori {i};
+  assert (*ori == 8);
+  assert ((void*)&*ori != (void*)&i); // !DIFFERENT THAN optional<T&>
+
+  *ori = j;
+  assert (*ori == 4);
+}
+
+
+TEST(Optional, moved_on_value_or)
+{
+  using namespace tr2;
+  optional<Oracle> oo{in_place};
+  
+  assert (oo);
+  assert (oo->s == sDefaultConstructed);
+  
+  Oracle o = std::move(oo).value_or( Oracle{OracleVal{}} );
+  assert (oo);
+  assert (oo->s == sMovedFrom);
+  assert (o.s == sMoveConstructed);
+  
+  optional<MoveAware<int>> om {in_place, 1};
+  assert (om);
+  assert (om->moved == false);
+  
+  /*MoveAware<int> m =*/ std::move(om).value_or( MoveAware<int>{1} );
+  assert (om);
+  assert (om->moved == true);
+
+# if OPTIONAL_HAS_MOVE_ACCESSORS == 1  
+  {
+    Date d = optional<Date>{in_place, 1}.value();
+    assert (d.i); // to silence compiler warning
+	
+	Date d2 = *optional<Date>{in_place, 1};
+    assert (d2.i); // to silence compiler warning
+  }
+# endif
+}
+
+
+TEST(Optional, optional_ref_hashing)
+{
+    using namespace tr2;
+    using std::string;
+    
+    std::hash<int> hi;
+    std::hash<optional<int&>> hoi;
+    std::hash<string> hs;
+    std::hash<optional<string&>> hos;
+    
+    int i0 = 0;
+    int i1 = 1;
+    assert (hi(0) == hoi(optional<int&>{i0}));
+    assert (hi(1) == hoi(optional<int&>{i1}));
+    
+    string s{""};
+    string s0{"0"};
+    string sCAT{"CAT"};
+    assert (hs("") == hos(optional<string&>{s}));
+    assert (hs("0") == hos(optional<string&>{s0}));
+    assert (hs("CAT") == hos(optional<string&>{sCAT}));
+    
+    std::unordered_set<optional<string&>> set;
+    assert(set.find({sCAT}) == set.end());
+    
+    set.insert({s0});
+    assert(set.find({sCAT}) == set.end());
+    
+    set.insert({sCAT});
+    assert(set.find({sCAT}) != set.end());
+}
+
+struct Combined
+{
+  int m = 0;
+  int n = 1;
+  
+  constexpr Combined() : m{5}, n{6} {}
+  constexpr Combined(int m, int n) : m{m}, n{n} {}
+};
+
+struct Nasty
+{
+  int m = 0;
+  int n = 1;
+  
+  constexpr Nasty() : m{5}, n{6} {}
+  constexpr Nasty(int m, int n) : m{m}, n{n} {}
+  
+  int operator&() { return n; }
+  int operator&() const { return n; }
+};
+
+TEST(Optional, arrow_operator)
+{
+  using namespace wpi;
+  
+  optional<Combined> oc1{in_place, 1, 2};
+  assert (oc1);
+  assert (oc1->m == 1);
+  assert (oc1->n == 2);
+  
+  optional<Nasty> on{in_place, 1, 2};
+  assert (on);
+  assert (on->m == 1);
+  assert (on->n == 2);
+}
+
+TEST(Optional, arrow_wit_optional_ref)
+{
+  using namespace wpi;
+  
+  Combined c{1, 2};
+  optional<Combined&> oc = c;
+  assert (oc);
+  assert (oc->m == 1);
+  assert (oc->n == 2);
+  
+  Nasty n{1, 2};
+  Nasty m{3, 4};
+  Nasty p{5, 6};
+  
+  optional<Nasty&> on{n};
+  assert (on);
+  assert (on->m == 1);
+  assert (on->n == 2);
+  
+  on = {m};
+  assert (on);
+  assert (on->m == 3);
+  assert (on->n == 4);
+  
+  on.emplace(p);
+  assert (on);
+  assert (on->m == 5);
+  assert (on->n == 6);
+  
+  optional<Nasty&> om{in_place, n};
+  assert (om);
+  assert (om->m == 1);
+  assert (om->n == 2);
+}
+
+TEST(Optional, no_dangling_reference_in_value)
+{
+  // this mostly tests compiler warnings
+  using namespace wpi;
+  optional<int> oi {2};
+  unused (oi.value());
+  const optional<int> coi {3};
+  unused (coi.value());
+}
+
+struct CountedObject
+{
+  static int _counter;
+  bool _throw;
+  CountedObject(bool b) : _throw(b) { ++_counter; }
+  CountedObject(CountedObject const& rhs) : _throw(rhs._throw) { if (_throw) throw int(); }
+  ~CountedObject() { --_counter; }
+};
+
+int CountedObject::_counter = 0;
+
+TEST(Optional, exception_safety)
+{
+  using namespace wpi;
+  try {
+    optional<CountedObject> oo(in_place, true); // throw
+    optional<CountedObject> o1(oo);
+  }
+  catch(...)
+  {
+    //
+  }
+  assert(CountedObject::_counter == 0);
+  
+  try {
+    optional<CountedObject> oo(in_place, true); // throw
+    optional<CountedObject> o1(std::move(oo));  // now move
+  }
+  catch(...)
+  {
+    //
+  }
+  assert(CountedObject::_counter == 0);
+}
+
+TEST(Optional, nested_optional)
+{
+   using namespace wpi;
+	
+   optional<optional<optional<int>>> o1 {nullopt};
+   assert (!o1);
+    
+   optional<optional<optional<int>>> o2 {in_place, nullopt};
+   assert (o2);
+   assert (!*o2);
+    
+   optional<optional<optional<int>>> o3 (in_place, in_place, nullopt);
+   assert (o3);
+   assert (*o3);
+   assert (!**o3);
+}
+
+TEST(Optional, three_ways_of_having_value)
+{
+  using namespace wpi;
+  optional<int> oN, o1 (1);
+  
+  assert (!oN);
+  assert (!oN.has_value());
+  assert (oN == nullopt);
+  
+  assert (o1);
+  assert (o1.has_value());
+  assert (o1 != nullopt);
+  
+  assert (bool(oN) == oN.has_value());
+  assert (bool(o1) == o1.has_value());
+  
+  int i = 1;
+  optional<int&> rN, r1 (i);
+  
+  assert (!rN);
+  assert (!rN.has_value());
+  assert (rN == nullopt);
+  
+  assert (r1);
+  assert (r1.has_value());
+  assert (r1 != nullopt);
+  
+  assert (bool(rN) == rN.has_value());
+  assert (bool(r1) == r1.has_value());
+}
+
+//// constexpr tests
+
+// these 4 classes have different noexcept signatures in move operations
+struct NothrowBoth {
+  NothrowBoth(NothrowBoth&&) noexcept(true) {};
+  void operator=(NothrowBoth&&) noexcept(true) {};
+};
+struct NothrowCtor {
+  NothrowCtor(NothrowCtor&&) noexcept(true) {};
+  void operator=(NothrowCtor&&) noexcept(false) {};
+};
+struct NothrowAssign {
+  NothrowAssign(NothrowAssign&&) noexcept(false) {};
+  void operator=(NothrowAssign&&) noexcept(true) {};
+};
+struct NothrowNone {
+  NothrowNone(NothrowNone&&) noexcept(false) {};
+  void operator=(NothrowNone&&) noexcept(false) {};
+};
+
+void test_noexcept()
+{
+  {
+    tr2::optional<NothrowBoth> b1, b2;
+    static_assert(noexcept(tr2::optional<NothrowBoth>{tr2::constexpr_move(b1)}), "bad noexcept!");
+    static_assert(noexcept(b1 = tr2::constexpr_move(b2)), "bad noexcept!");
+  }
+  {
+    tr2::optional<NothrowCtor> c1, c2;
+    static_assert(noexcept(tr2::optional<NothrowCtor>{tr2::constexpr_move(c1)}), "bad noexcept!");
+    static_assert(!noexcept(c1 = tr2::constexpr_move(c2)), "bad noexcept!");
+  }
+  {
+    tr2::optional<NothrowAssign> a1, a2;
+    static_assert(!noexcept(tr2::optional<NothrowAssign>{tr2::constexpr_move(a1)}), "bad noexcept!");
+    static_assert(!noexcept(a1 = tr2::constexpr_move(a2)), "bad noexcept!");
+  }
+  {
+    tr2::optional<NothrowNone> n1, n2;
+    static_assert(!noexcept(tr2::optional<NothrowNone>{tr2::constexpr_move(n1)}), "bad noexcept!");
+    static_assert(!noexcept(n1 = tr2::constexpr_move(n2)), "bad noexcept!");
+  }
+}
+
+
+void constexpr_test_disengaged()
+{
+  constexpr tr2::optional<int> g0{};
+  constexpr tr2::optional<int> g1{tr2::nullopt};
+  static_assert( !g0, "initialized!" );
+  static_assert( !g1, "initialized!" );
+  
+  static_assert( bool(g1) == bool(g0), "ne!" );
+  
+  static_assert( g1 == g0, "ne!" );
+  static_assert( !(g1 != g0), "ne!" );
+  static_assert( g1 >= g0, "ne!" );
+  static_assert( !(g1 > g0), "ne!" );
+  static_assert( g1 <= g0, "ne!" );
+  static_assert( !(g1 <g0), "ne!" );
+  
+  static_assert( g1 == tr2::nullopt, "!" );
+  static_assert( !(g1 != tr2::nullopt), "!" );
+  static_assert( g1 <= tr2::nullopt, "!" );
+  static_assert( !(g1 < tr2::nullopt), "!" );
+  static_assert( g1 >= tr2::nullopt, "!" );
+  static_assert( !(g1 > tr2::nullopt), "!" );
+  
+  static_assert(  (tr2::nullopt == g0), "!" );
+  static_assert( !(tr2::nullopt != g0), "!" );
+  static_assert(  (tr2::nullopt >= g0), "!" );
+  static_assert( !(tr2::nullopt >  g0), "!" );
+  static_assert(  (tr2::nullopt <= g0), "!" );
+  static_assert( !(tr2::nullopt <  g0), "!" );
+  
+  static_assert(  (g1 != tr2::optional<int>(1)), "!" );
+  static_assert( !(g1 == tr2::optional<int>(1)), "!" );
+  static_assert(  (g1 <  tr2::optional<int>(1)), "!" );
+  static_assert(  (g1 <= tr2::optional<int>(1)), "!" );
+  static_assert( !(g1 >  tr2::optional<int>(1)), "!" );
+  static_assert( !(g1 >  tr2::optional<int>(1)), "!" );
+}
+
+
+constexpr tr2::optional<int> g0{};
+constexpr tr2::optional<int> g2{2};
+static_assert( g2, "not initialized!" );
+static_assert( *g2 == 2, "not 2!" );
+static_assert( g2 == tr2::optional<int>(2), "not 2!" );
+static_assert( g2 != g0, "eq!" );
+
+# if OPTIONAL_HAS_MOVE_ACCESSORS == 1
+static_assert( *tr2::optional<int>{3} == 3, "WTF!" );
+static_assert( tr2::optional<int>{3}.value() == 3, "WTF!" );
+static_assert( tr2::optional<int>{3}.value_or(1) == 3, "WTF!" );
+static_assert( tr2::optional<int>{}.value_or(4) == 4, "WTF!" );
+# endif
+
+constexpr tr2::optional<Combined> gc0{tr2::in_place};
+static_assert(gc0->n == 6, "WTF!");
+
+// optional refs
+int gi = 0;
+constexpr tr2::optional<int&> gori = gi;
+constexpr tr2::optional<int&> gorn{};
+constexpr int& gri = *gori;
+static_assert(gori, "WTF");
+static_assert(!gorn, "WTF");
+static_assert(gori != tr2::nullopt, "WTF");
+static_assert(gorn == tr2::nullopt, "WTF");
+static_assert(&gri == &*gori, "WTF");
+
+constexpr int gci = 1;
+constexpr tr2::optional<int const&> gorci = gci;
+constexpr tr2::optional<int const&> gorcn{};
+
+static_assert(gorcn <  gorci, "WTF");
+static_assert(gorcn <= gorci, "WTF");
+static_assert(gorci == gorci, "WTF");
+static_assert(*gorci == 1, "WTF");
+static_assert(gorci == gci, "WTF");
+
+namespace constexpr_optional_ref_and_arrow 
+{
+  using namespace wpi;
+  constexpr Combined c{1, 2};
+  constexpr optional<Combined const&> oc = c;
+  static_assert(oc, "WTF!");
+  static_assert(oc->m == 1, "WTF!");
+  static_assert(oc->n == 2, "WTF!");
+}
+
+#if OPTIONAL_HAS_CONSTEXPR_INIT_LIST
+
+namespace InitList
+{
+  using namespace wpi;
+  
+  struct ConstInitLister
+  {
+    template <typename T>
+	constexpr ConstInitLister(std::initializer_list<T> il) : len (il.size()) {}
+    size_t len;
+  };
+  
+  constexpr ConstInitLister CIL {2, 3, 4};
+  static_assert(CIL.len == 3, "WTF!");
+  
+  constexpr optional<ConstInitLister> oil {in_place, {4, 5, 6, 7}};
+  static_assert(oil, "WTF!");
+  static_assert(oil->len == 4, "WTF!");
+}
+
+#endif // OPTIONAL_HAS_CONSTEXPR_INIT_LIST
+
+// end constexpr tests
+
+
+#include <string>
+
+
+struct VEC
+{
+    std::vector<int> v;
+    template <typename... X>
+    VEC( X&&...x) : v(std::forward<X>(x)...) {}
+
+    template <typename U, typename... X>
+    VEC(std::initializer_list<U> il, X&&...x) : v(il, std::forward<X>(x)...) {}
+};
+
+
+
+TEST(Optional, Vector) {
+  tr2::optional<int> oi = 1;
+  assert (bool(oi));
+  oi.operator=({});
+  assert (!oi);
+
+  VEC v = {5, 6};
+
+  if (OPTIONAL_HAS_CONSTEXPR_INIT_LIST)
+    std::cout << "Optional has constexpr initializer_list" << std::endl;
+  else
+    std::cout << "Optional doesn't have constexpr initializer_list" << std::endl;
+
+  if (OPTIONAL_HAS_MOVE_ACCESSORS)
+    std::cout << "Optional has constexpr move accessors" << std::endl;
+  else
+    std::cout << "Optional doesn't have constexpr move accessors" << std::endl;	
+}
+
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp
new file mode 100644
index 0000000..132adea
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp
@@ -0,0 +1,241 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/AsyncFunction.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <thread>
+
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/Prepare.h"
+
+namespace wpi {
+namespace uv {
+
+TEST(UvAsyncFunction, Test) {
+  int prepare_cb_called = 0;
+  int async_cb_called[2] = {0, 0};
+  int close_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<int(int)>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  loop->error.connect([](Error) { FAIL(); });
+
+  prepare->error.connect([](Error) { FAIL(); });
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] {
+      auto call0 = async->Call(0);
+      auto call1 = async->Call(1);
+      ASSERT_EQ(call0.get(), 1);
+      ASSERT_EQ(call1.get(), 2);
+    });
+  });
+  prepare->Start();
+
+  async->error.connect([](Error) { FAIL(); });
+  async->closed.connect([&] { close_cb_called++; });
+  async->wakeup = [&](promise<int> out, int v) {
+    ++async_cb_called[v];
+    if (v == 1) {
+      async->Close();
+      prepare->Close();
+    }
+    out.set_value(v + 1);
+  };
+
+  loop->Run();
+
+  ASSERT_EQ(async_cb_called[0], 1);
+  ASSERT_EQ(async_cb_called[1], 1);
+  ASSERT_EQ(close_cb_called, 1);
+
+  if (theThread.joinable()) theThread.join();
+}
+
+TEST(UvAsyncFunction, Ref) {
+  int prepare_cb_called = 0;
+  int val = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<int(int, int&)>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] { ASSERT_EQ(async->Call(1, val).get(), 2); });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<int> out, int v, int& r) {
+    r = v;
+    async->Close();
+    prepare->Close();
+    out.set_value(v + 1);
+  };
+
+  loop->Run();
+
+  ASSERT_EQ(val, 1);
+
+  if (theThread.joinable()) theThread.join();
+}
+
+TEST(UvAsyncFunction, Movable) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async =
+      AsyncFunction<std::unique_ptr<int>(std::unique_ptr<int>)>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] {
+      auto val = std::make_unique<int>(1);
+      auto val2 = async->Call(std::move(val)).get();
+      ASSERT_NE(val2, nullptr);
+      ASSERT_EQ(*val2, 1);
+    });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<std::unique_ptr<int>> out,
+                      std::unique_ptr<int> v) {
+    async->Close();
+    prepare->Close();
+    out.set_value(std::move(v));
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) theThread.join();
+}
+
+TEST(UvAsyncFunction, CallIgnoreResult) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async =
+      AsyncFunction<std::unique_ptr<int>(std::unique_ptr<int>)>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] { async->Call(std::make_unique<int>(1)); });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<std::unique_ptr<int>> out,
+                      std::unique_ptr<int> v) {
+    async->Close();
+    prepare->Close();
+    out.set_value(std::move(v));
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) theThread.join();
+}
+
+TEST(UvAsyncFunction, VoidCall) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<void()>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] { async->Call(); });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<void> out) {
+    async->Close();
+    prepare->Close();
+    out.set_value();
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) theThread.join();
+}
+
+TEST(UvAsyncFunction, WaitFor) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<int()>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] {
+      ASSERT_FALSE(async->Call().wait_for(std::chrono::milliseconds(10)));
+    });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<int> out) {
+    async->Close();
+    prepare->Close();
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    out.set_value(1);
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) theThread.join();
+}
+
+TEST(UvAsyncFunction, VoidWaitFor) {
+  int prepare_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = AsyncFunction<void()>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] {
+      ASSERT_FALSE(async->Call().wait_for(std::chrono::milliseconds(10)));
+    });
+  });
+  prepare->Start();
+
+  async->wakeup = [&](promise<void> out) {
+    async->Close();
+    prepare->Close();
+    std::this_thread::sleep_for(std::chrono::milliseconds(100));
+    out.set_value();
+  };
+
+  loop->Run();
+
+  if (theThread.joinable()) theThread.join();
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvAsyncTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvAsyncTest.cpp
new file mode 100644
index 0000000..e18f972
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvAsyncTest.cpp
@@ -0,0 +1,178 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "wpi/uv/Async.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include <atomic>
+#include <thread>
+
+#include "wpi/mutex.h"
+#include "wpi/uv/Loop.h"
+#include "wpi/uv/Prepare.h"
+
+namespace wpi {
+namespace uv {
+
+TEST(UvAsync, Test) {
+  std::atomic_int async_cb_called{0};
+  int prepare_cb_called = 0;
+  int close_cb_called = 0;
+
+  wpi::mutex mutex;
+  mutex.lock();
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = Async<>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  loop->error.connect([](Error) { FAIL(); });
+
+  prepare->error.connect([](Error) { FAIL(); });
+  prepare->closed.connect([&] { close_cb_called++; });
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] {
+      for (;;) {
+        mutex.lock();
+        int n = async_cb_called;
+        mutex.unlock();
+
+        if (n == 3) {
+          break;
+        }
+
+        async->Send();
+
+        std::this_thread::yield();
+      }
+    });
+    mutex.unlock();
+  });
+  prepare->Start();
+
+  async->error.connect([](Error) { FAIL(); });
+  async->closed.connect([&] { close_cb_called++; });
+  async->wakeup.connect([&] {
+    mutex.lock();
+    int n = ++async_cb_called;
+    mutex.unlock();
+
+    if (n == 3) {
+      async->Close();
+      prepare->Close();
+    }
+  });
+
+  loop->Run();
+
+  ASSERT_GT(prepare_cb_called, 0);
+  ASSERT_EQ(async_cb_called, 3);
+  ASSERT_EQ(close_cb_called, 2);
+
+  if (theThread.joinable()) theThread.join();
+}
+
+TEST(UvAsync, Data) {
+  int prepare_cb_called = 0;
+  int async_cb_called[2] = {0, 0};
+  int close_cb_called = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = Async<int, std::function<void(int)>>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  loop->error.connect([](Error) { FAIL(); });
+
+  prepare->error.connect([](Error) { FAIL(); });
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] {
+      async->Send(0, [&](int v) {
+        ASSERT_EQ(v, 0);
+        ++async_cb_called[0];
+      });
+      async->Send(1, [&](int v) {
+        ASSERT_EQ(v, 1);
+        ++async_cb_called[1];
+        async->Close();
+        prepare->Close();
+      });
+    });
+  });
+  prepare->Start();
+
+  async->error.connect([](Error) { FAIL(); });
+  async->closed.connect([&] { close_cb_called++; });
+  async->wakeup.connect([&](int v, std::function<void(int)> f) { f(v); });
+
+  loop->Run();
+
+  ASSERT_EQ(async_cb_called[0], 1);
+  ASSERT_EQ(async_cb_called[1], 1);
+  ASSERT_EQ(close_cb_called, 1);
+
+  if (theThread.joinable()) theThread.join();
+}
+
+TEST(UvAsync, DataRef) {
+  int prepare_cb_called = 0;
+  int val = 0;
+
+  std::thread theThread;
+
+  auto loop = Loop::Create();
+  auto async = Async<int, int&>::Create(loop);
+  auto prepare = Prepare::Create(loop);
+
+  prepare->prepare.connect([&] {
+    if (prepare_cb_called++) return;
+    theThread = std::thread([&] { async->Send(1, val); });
+  });
+  prepare->Start();
+
+  async->wakeup.connect([&](int v, int& r) {
+    r = v;
+    async->Close();
+    prepare->Close();
+  });
+
+  loop->Run();
+
+  ASSERT_EQ(val, 1);
+
+  if (theThread.joinable()) theThread.join();
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvBufferTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvBufferTest.cpp
new file mode 100644
index 0000000..e837ca9
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvBufferTest.cpp
@@ -0,0 +1,50 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Buffer.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+namespace wpi {
+namespace uv {
+
+TEST(UvSimpleBufferPool, ConstructDefault) {
+  SimpleBufferPool<> pool;
+  auto buf1 = pool.Allocate();
+  ASSERT_EQ(buf1.len, 4096u);
+}
+
+TEST(UvSimpleBufferPool, ConstructSize) {
+  SimpleBufferPool<4> pool{8192};
+  auto buf1 = pool.Allocate();
+  ASSERT_EQ(buf1.len, 8192u);
+}
+
+TEST(UvSimpleBufferPool, ReleaseReuse) {
+  SimpleBufferPool<4> pool;
+  auto buf1 = pool.Allocate();
+  auto buf1copy = buf1;
+  auto origSize = buf1.len;
+  buf1.len = 8;
+  pool.Release(buf1);
+  ASSERT_EQ(buf1.base, nullptr);
+  auto buf2 = pool.Allocate();
+  ASSERT_EQ(buf1copy.base, buf2.base);
+  ASSERT_EQ(buf2.len, origSize);
+}
+
+TEST(UvSimpleBufferPool, ClearRemaining) {
+  SimpleBufferPool<4> pool;
+  auto buf1 = pool.Allocate();
+  pool.Release(buf1);
+  ASSERT_EQ(pool.Remaining(), 1u);
+  pool.Clear();
+  ASSERT_EQ(pool.Remaining(), 0u);
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp
new file mode 100644
index 0000000..11ac426
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp
@@ -0,0 +1,110 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "wpi/uv/GetAddrInfo.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include "wpi/uv/Loop.h"
+
+#define CONCURRENT_COUNT 10
+
+namespace wpi {
+namespace uv {
+
+TEST(UvGetAddrInfo, BothNull) {
+  int fail_cb_called = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([&](Error err) {
+    ASSERT_EQ(err.code(), UV_EINVAL);
+    fail_cb_called++;
+  });
+
+  GetAddrInfo(loop, [](const addrinfo&) { FAIL(); }, Twine::createNull());
+  loop->Run();
+  ASSERT_EQ(fail_cb_called, 1);
+}
+
+TEST(UvGetAddrInfo, FailedLookup) {
+  int fail_cb_called = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([&](Error err) {
+    ASSERT_EQ(fail_cb_called, 0);
+    ASSERT_LT(err.code(), 0);
+    fail_cb_called++;
+  });
+
+  // Use a FQDN by ending in a period
+  GetAddrInfo(loop, [](const addrinfo&) { FAIL(); }, "xyzzy.xyzzy.xyzzy.");
+  loop->Run();
+  ASSERT_EQ(fail_cb_called, 1);
+}
+
+TEST(UvGetAddrInfo, Basic) {
+  int getaddrinfo_cbs = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([](Error) { FAIL(); });
+
+  GetAddrInfo(loop, [&](const addrinfo&) { getaddrinfo_cbs++; }, "localhost");
+
+  loop->Run();
+
+  ASSERT_EQ(getaddrinfo_cbs, 1);
+}
+
+#ifndef _WIN32
+TEST(UvGetAddrInfo, Concurrent) {
+  int getaddrinfo_cbs = 0;
+  int callback_counts[CONCURRENT_COUNT];
+
+  auto loop = Loop::Create();
+  loop->error.connect([](Error) { FAIL(); });
+
+  for (int i = 0; i < CONCURRENT_COUNT; i++) {
+    callback_counts[i] = 0;
+    GetAddrInfo(loop,
+                [i, &callback_counts, &getaddrinfo_cbs](const addrinfo&) {
+                  callback_counts[i]++;
+                  getaddrinfo_cbs++;
+                },
+                "localhost");
+  }
+
+  loop->Run();
+
+  for (int i = 0; i < CONCURRENT_COUNT; i++) {
+    ASSERT_EQ(callback_counts[i], 1);
+  }
+}
+#endif
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvGetNameInfoTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvGetNameInfoTest.cpp
new file mode 100644
index 0000000..16de329
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvGetNameInfoTest.cpp
@@ -0,0 +1,77 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "wpi/uv/GetNameInfo.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include "wpi/uv/Loop.h"
+
+namespace wpi {
+namespace uv {
+
+TEST(UvGetNameInfo, BasicIp4) {
+  int getnameinfo_cbs = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([](Error) { FAIL(); });
+
+  GetNameInfo4(loop,
+               [&](const char* hostname, const char* service) {
+                 ASSERT_NE(hostname, nullptr);
+                 ASSERT_NE(service, nullptr);
+                 getnameinfo_cbs++;
+               },
+               "127.0.0.1", 80);
+
+  loop->Run();
+
+  ASSERT_EQ(getnameinfo_cbs, 1);
+}
+
+TEST(UvGetNameInfo, BasicIp6) {
+  int getnameinfo_cbs = 0;
+
+  auto loop = Loop::Create();
+  loop->error.connect([](Error) { FAIL(); });
+
+  GetNameInfo6(loop,
+               [&](const char* hostname, const char* service) {
+                 ASSERT_NE(hostname, nullptr);
+                 ASSERT_NE(service, nullptr);
+                 getnameinfo_cbs++;
+               },
+               "::1", 80);
+
+  loop->Run();
+
+  ASSERT_EQ(getnameinfo_cbs, 1);
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvLoopWalkTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvLoopWalkTest.cpp
new file mode 100644
index 0000000..78abf69
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvLoopWalkTest.cpp
@@ -0,0 +1,70 @@
+/*----------------------------------------------------------------------------*/
+/* 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.                                                               */
+/*----------------------------------------------------------------------------*/
+
+/* Copyright Joyent, Inc. and other Node contributors. All rights reserved.
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to
+ * deal in the Software without restriction, including without limitation the
+ * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
+ * sell copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
+ * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
+ * IN THE SOFTWARE.
+ */
+
+#include "wpi/uv/Loop.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"  // NOLINT(build/include_order)
+
+#include "wpi/uv/Timer.h"
+
+namespace wpi {
+namespace uv {
+
+TEST(UvLoop, Walk) {
+  int seen_timer_handle = 0;
+
+  auto loop = Loop::Create();
+  auto timer = Timer::Create(loop);
+
+  loop->error.connect([](Error) { FAIL(); });
+
+  timer->error.connect([](Error) { FAIL(); });
+
+  timer->timeout.connect([&, theTimer = timer.get() ] {
+    theTimer->GetLoopRef().Walk([&](Handle& it) {
+      if (&it == timer.get()) seen_timer_handle++;
+    });
+    theTimer->Close();
+  });
+  timer->Start(Timer::Time{1});
+
+  // Start event loop, expect to see the timer handle
+  ASSERT_EQ(seen_timer_handle, 0);
+  loop->Run();
+  ASSERT_EQ(seen_timer_handle, 1);
+
+  // Loop is finished, should not see our timer handle
+  seen_timer_handle = 0;
+  loop->Walk([&](Handle& it) {
+    if (&it == timer.get()) seen_timer_handle++;
+  });
+  ASSERT_EQ(seen_timer_handle, 0);
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvTimerTest.cpp b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvTimerTest.cpp
new file mode 100644
index 0000000..706e1eb
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/src/test/native/cpp/uv/UvTimerTest.cpp
@@ -0,0 +1,74 @@
+/*----------------------------------------------------------------------------*/
+/* 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 "wpi/uv/Timer.h"  // NOLINT(build/include_order)
+
+#include "gtest/gtest.h"
+
+namespace wpi {
+namespace uv {
+
+TEST(UvTimer, StartAndStop) {
+  auto loop = Loop::Create();
+  auto handleNoRepeat = Timer::Create(loop);
+  auto handleRepeat = Timer::Create(loop);
+
+  bool checkTimerNoRepeatEvent = false;
+  bool checkTimerRepeatEvent = false;
+
+  handleNoRepeat->error.connect([](Error) { FAIL(); });
+  handleRepeat->error.connect([](Error) { FAIL(); });
+
+  handleNoRepeat->timeout.connect(
+      [&checkTimerNoRepeatEvent, handle = handleNoRepeat.get() ] {
+        ASSERT_FALSE(checkTimerNoRepeatEvent);
+        checkTimerNoRepeatEvent = true;
+        handle->Stop();
+        handle->Close();
+        ASSERT_TRUE(handle->IsClosing());
+      });
+
+  handleRepeat->timeout.connect(
+      [&checkTimerRepeatEvent, handle = handleRepeat.get() ] {
+        if (checkTimerRepeatEvent) {
+          handle->Stop();
+          handle->Close();
+          ASSERT_TRUE(handle->IsClosing());
+        } else {
+          checkTimerRepeatEvent = true;
+          ASSERT_FALSE(handle->IsClosing());
+        }
+      });
+
+  handleNoRepeat->Start(Timer::Time{0}, Timer::Time{0});
+  handleRepeat->Start(Timer::Time{0}, Timer::Time{1});
+
+  ASSERT_TRUE(handleNoRepeat->IsActive());
+  ASSERT_FALSE(handleNoRepeat->IsClosing());
+
+  ASSERT_TRUE(handleRepeat->IsActive());
+  ASSERT_FALSE(handleRepeat->IsClosing());
+
+  loop->Run();
+
+  ASSERT_TRUE(checkTimerNoRepeatEvent);
+  ASSERT_TRUE(checkTimerRepeatEvent);
+}
+
+TEST(UvTimer, Repeat) {
+  auto loop = Loop::Create();
+  auto handle = Timer::Create(loop);
+
+  handle->SetRepeat(Timer::Time{42});
+  ASSERT_EQ(handle->GetRepeat(), Timer::Time{42});
+  handle->Close();
+
+  loop->Run();  // forces close callback to run
+}
+
+}  // namespace uv
+}  // namespace wpi
diff --git a/third_party/allwpilib_2019/wpiutil/wpiutil-config.cmake b/third_party/allwpilib_2019/wpiutil/wpiutil-config.cmake
new file mode 100644
index 0000000..91d01a7
--- /dev/null
+++ b/third_party/allwpilib_2019/wpiutil/wpiutil-config.cmake
@@ -0,0 +1,2 @@
+get_filename_component(SELF_DIR "${CMAKE_CURRENT_LIST_FILE}" PATH)

+include(${SELF_DIR}/wpiutil.cmake)

diff --git a/third_party/ntcore_2018/BUILD b/third_party/ntcore_2018/BUILD
index 4a6341c..8380dd2 100644
--- a/third_party/ntcore_2018/BUILD
+++ b/third_party/ntcore_2018/BUILD
@@ -1,31 +1,28 @@
-licenses(['notice'])
+licenses(["notice"])
 
 cc_library(
-  name = 'ntcore',
-  visibility = ['//visibility:public'],
-  srcs = glob([
-    'src/main/**/*.cpp',
-    'src/main/**/*.h',
-  ], exclude = [
-    #'src/main/native/cpp/networktables/**',
-    'src/main/native/cpp/jni/**',
-  ]),
-  copts = [
-    '-Wno-switch-enum',
-    '-Wno-cast-align',
-  ],
-  hdrs = glob([
-    'src/main/native/include/**/*.h',
-    'src/main/native/include/**/*.inl',
-  ]),
-  includes = [
-    'src/main/native/include',
-  ],
-  linkopts = [
-    '-lpthread',
-  ],
-  deps = [
-    '//third_party/wpiutil_2018:wpiutil',
-  ],
-  restricted_to = ['//tools:roborio'],
+    name = "ntcore",
+    srcs = glob(
+        [
+            "src/**/*.cpp",
+            "src/**/*.h",
+            "wpiutil/src/**/*.cpp",
+        ],
+        exclude = [
+            "src/main/native/cpp/networktables/**",
+            "src/test/**",
+            "src/main/native/cpp/jni/**",
+        ],
+    ),
+    copts = [
+        "-Wno-unused-parameter",
+    ],
+    includes = [
+        "src/main/native/include",
+    ],
+    restricted_to = ["//tools:roborio"],
+    visibility = ["//visibility:public"],
+    deps = [
+        "//third_party/wpiutil_2018:wpiutil",
+    ],
 )
diff --git a/third_party/wpiutil_2018/BUILD b/third_party/wpiutil_2018/BUILD
index 41822f6..aceed4a 100644
--- a/third_party/wpiutil_2018/BUILD
+++ b/third_party/wpiutil_2018/BUILD
@@ -1,27 +1,21 @@
-licenses(['notice'])
+licenses(["notice"])
 
 cc_library(
-  name = 'wpiutil',
-  visibility = ['//visibility:public'],
-  srcs = glob([
-    'src/main/native/cpp/**/*.cpp',
-    'src/main/native/cpp/**/*.h',
-    'src/main/native/cpp/**/*.inc',
-  ]),
-  copts = [
-    #'-Wno-switch-enum',
-    '-Wno-cast-align',
-    #'-Ithird_party/wpiutil_2018/
-    '-Wno-unused-parameter',
-  ],
-  hdrs = glob([
-    'src/main/native/include/**/*',
-  ]),
-  includes = [
-    'src/main/native/include',
-  ],
-  linkopts = [
-    '-lpthread',
-  ],
-  restricted_to = ['//tools:roborio'],
+    name = "wpiutil",
+    srcs = glob([
+        "src/main/native/cpp/llvm/*.cpp",
+        "src/main/native/cpp/llvm/Unix/Path.inc",
+        "src/main/native/cpp/support/timestamp.cpp",
+    ]),
+    hdrs = glob([
+        "src/main/native/include/**",
+    ]),
+    copts = [
+        "-Wno-unused-parameter",
+    ],
+    includes = [
+        "src/main/native/include",
+    ],
+    restricted_to = ["//tools:roborio"],
+    visibility = ["//visibility:public"],
 )
diff --git a/y2012/wpilib_interface.cc b/y2012/wpilib_interface.cc
index 5cbb7f8..6d4fcff 100644
--- a/y2012/wpilib_interface.cc
+++ b/y2012/wpilib_interface.cc
@@ -8,17 +8,15 @@
 #include <mutex>
 #include <functional>
 
-#include "Encoder.h"
-#include "Talon.h"
-#include "DriverStation.h"
-#include "AnalogInput.h"
-#include "Compressor.h"
-#include "Relay.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Compressor.h"
+#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/PowerDistributionPanel.h"
+#include "frc971/wpilib/ahal/Relay.h"
+#include "frc971/wpilib/ahal/Talon.h"
 #include "frc971/wpilib/wpilib_robot_base.h"
-#ifndef WPILIB2015
-#include "DigitalGlitchFilter.h"
-#endif
-#include "PowerDistributionPanel.h"
 #undef ERROR
 
 #include "aos/logging/logging.h"
@@ -51,6 +49,7 @@
 
 using ::frc971::control_loops::drivetrain_queue;
 using ::y2012::control_loops::accessories_queue;
+using namespace frc;
 
 namespace y2012 {
 namespace wpilib {
diff --git a/y2014/wpilib_interface.cc b/y2014/wpilib_interface.cc
index 24a41c7..2cd9b50 100644
--- a/y2014/wpilib_interface.cc
+++ b/y2014/wpilib_interface.cc
@@ -8,16 +8,14 @@
 #include <mutex>
 #include <functional>
 
-#include "Encoder.h"
-#include "Talon.h"
-#include "DriverStation.h"
-#include "AnalogInput.h"
-#include "Compressor.h"
-#include "Relay.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Compressor.h"
+#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Relay.h"
+#include "frc971/wpilib/ahal/Talon.h"
 #include "frc971/wpilib/wpilib_robot_base.h"
-#ifndef WPILIB2015
-#include "DigitalGlitchFilter.h"
-#endif
 #undef ERROR
 
 #include "aos/logging/logging.h"
@@ -58,6 +56,7 @@
 using ::frc971::control_loops::drivetrain_queue;
 using ::y2014::control_loops::claw_queue;
 using ::y2014::control_loops::shooter_queue;
+using namespace frc;
 
 namespace y2014 {
 namespace wpilib {
diff --git a/y2014_bot3/wpilib_interface.cc b/y2014_bot3/wpilib_interface.cc
index 613b757..1d7edc2 100644
--- a/y2014_bot3/wpilib_interface.cc
+++ b/y2014_bot3/wpilib_interface.cc
@@ -8,14 +8,14 @@
 #include <mutex>
 #include <functional>
 
-#include "Encoder.h"
-#include "Talon.h"
-#include "DriverStation.h"
-#include "AnalogInput.h"
-#include "Compressor.h"
-#include "Relay.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Compressor.h"
+#include "frc971/wpilib/ahal/DigitalInput.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Relay.h"
+#include "frc971/wpilib/ahal/Talon.h"
 #include "frc971/wpilib/wpilib_robot_base.h"
-#include "DigitalInput.h"
 #undef ERROR
 
 #include "aos/logging/logging.h"
@@ -55,6 +55,7 @@
 using ::frc971::wpilib::LoopOutputHandler;
 using ::frc971::wpilib::JoystickSender;
 using ::frc971::wpilib::GyroSender;
+using namespace frc;
 
 namespace frc971 {
 namespace wpilib {
diff --git a/y2016/wpilib_interface.cc b/y2016/wpilib_interface.cc
index 9463b3f..320dd73 100644
--- a/y2016/wpilib_interface.cc
+++ b/y2016/wpilib_interface.cc
@@ -9,16 +9,14 @@
 #include <functional>
 #include <array>
 
-#include "Encoder.h"
-#include "Talon.h"
-#include "Relay.h"
-#include "DriverStation.h"
-#include "AnalogInput.h"
-#include "Compressor.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Compressor.h"
+#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Relay.h"
+#include "frc971/wpilib/ahal/Talon.h"
 #include "frc971/wpilib/wpilib_robot_base.h"
-#ifndef WPILIB2015
-#include "DigitalGlitchFilter.h"
-#endif
 #undef ERROR
 
 #include "aos/logging/logging.h"
@@ -63,6 +61,7 @@
 using ::frc971::control_loops::drivetrain_queue;
 using ::y2016::control_loops::shooter::shooter_queue;
 using ::y2016::control_loops::superstructure_queue;
+using namespace frc;
 
 namespace y2016 {
 namespace wpilib {
diff --git a/y2017/wpilib_interface.cc b/y2017/wpilib_interface.cc
index 01184fa..4906009 100644
--- a/y2017/wpilib_interface.cc
+++ b/y2017/wpilib_interface.cc
@@ -10,15 +10,15 @@
 #include <mutex>
 #include <thread>
 
-#include "AnalogInput.h"
-#include "Compressor.h"
-#include "Counter.h"
-#include "DigitalGlitchFilter.h"
-#include "DriverStation.h"
-#include "Encoder.h"
-#include "Relay.h"
-#include "Servo.h"
-#include "VictorSP.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Compressor.h"
+#include "frc971/wpilib/ahal/Counter.h"
+#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Relay.h"
+#include "frc971/wpilib/ahal/Servo.h"
+#include "frc971/wpilib/ahal/VictorSP.h"
 #undef ERROR
 
 #include "aos/commonmath.h"
@@ -61,6 +61,7 @@
 using ::y2017::constants::Values;
 using ::aos::monotonic_clock;
 namespace chrono = ::std::chrono;
+using namespace frc;
 
 namespace y2017 {
 namespace wpilib {
@@ -661,7 +662,7 @@
     green_light_->Set(queue->green_light_on);
     blue_light_->Set(queue->blue_light_on);
 
-    gear_servo_->Set(queue->gear_servo);
+    gear_servo_->SetPosition(queue->gear_servo);
   }
 
   virtual void Stop() override {
@@ -674,7 +675,7 @@
     hood_victor_->SetDisabled();
     shooter_victor_->SetDisabled();
 
-    gear_servo_->SetOffline();
+    gear_servo_->SetRaw(0);
 
     red_light_->Set(true);
     green_light_->Set(true);
diff --git a/y2017_bot3/wpilib_interface.cc b/y2017_bot3/wpilib_interface.cc
index 7d3a0ed..48787b4 100644
--- a/y2017_bot3/wpilib_interface.cc
+++ b/y2017_bot3/wpilib_interface.cc
@@ -10,12 +10,12 @@
 #include <mutex>
 #include <thread>
 
-#include "AnalogInput.h"
-#include "DigitalGlitchFilter.h"
-#include "DriverStation.h"
-#include "Encoder.h"
-#include "Compressor.h"
-#include "VictorSP.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Compressor.h"
+#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/VictorSP.h"
 #undef ERROR
 
 #include "aos/commonmath.h"
@@ -57,6 +57,7 @@
 using ::y2017_bot3::control_loops::superstructure_queue;
 using ::aos::monotonic_clock;
 namespace chrono = ::std::chrono;
+using namespace frc;
 
 namespace y2017_bot3 {
 namespace wpilib {
diff --git a/y2018/wpilib_interface.cc b/y2018/wpilib_interface.cc
index b4ee168..0493bb5 100644
--- a/y2018/wpilib_interface.cc
+++ b/y2018/wpilib_interface.cc
@@ -10,14 +10,14 @@
 #include <mutex>
 #include <thread>
 
-#include "AnalogInput.h"
-#include "Counter.h"
-#include "DigitalGlitchFilter.h"
-#include "DriverStation.h"
-#include "Encoder.h"
-#include "Relay.h"
-#include "Servo.h"
-#include "VictorSP.h"
+#include "frc971/wpilib/ahal/AnalogInput.h"
+#include "frc971/wpilib/ahal/Counter.h"
+#include "frc971/wpilib/ahal/DigitalGlitchFilter.h"
+#include "frc971/wpilib/ahal/DriverStation.h"
+#include "frc971/wpilib/ahal/Encoder.h"
+#include "frc971/wpilib/ahal/Relay.h"
+#include "frc971/wpilib/ahal/Servo.h"
+#include "frc971/wpilib/ahal/VictorSP.h"
 #include "ctre/phoenix/CANifier.h"
 #undef ERROR
 
@@ -169,126 +169,133 @@
   }
 
   // Left drivetrain side.
-  void set_drivetrain_left_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_drivetrain_left_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     fast_encoder_filter_.Add(encoder.get());
     drivetrain_left_encoder_ = ::std::move(encoder);
   }
 
   void set_left_drivetrain_shifter_potentiometer(
-      ::std::unique_ptr<AnalogInput> potentiometer) {
+      ::std::unique_ptr<frc::AnalogInput> potentiometer) {
     left_drivetrain_shifter_ = ::std::move(potentiometer);
   }
 
   // Right drivetrain side.
-  void set_drivetrain_right_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_drivetrain_right_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     fast_encoder_filter_.Add(encoder.get());
     drivetrain_right_encoder_ = ::std::move(encoder);
   }
 
   void set_right_drivetrain_shifter_potentiometer(
-      ::std::unique_ptr<AnalogInput> potentiometer) {
+      ::std::unique_ptr<frc::AnalogInput> potentiometer) {
     right_drivetrain_shifter_ = ::std::move(potentiometer);
   }
 
   // Proximal joint.
-  void set_proximal_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_proximal_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     medium_encoder_filter_.Add(encoder.get());
     proximal_encoder_.set_encoder(::std::move(encoder));
   }
 
-  void set_proximal_absolute_pwm(::std::unique_ptr<DigitalInput> absolute_pwm) {
+  void set_proximal_absolute_pwm(
+      ::std::unique_ptr<frc::DigitalInput> absolute_pwm) {
     proximal_encoder_.set_absolute_pwm(::std::move(absolute_pwm));
   }
 
   void set_proximal_potentiometer(
-      ::std::unique_ptr<AnalogInput> potentiometer) {
+      ::std::unique_ptr<frc::AnalogInput> potentiometer) {
     proximal_encoder_.set_potentiometer(::std::move(potentiometer));
   }
 
   // Distal joint.
-  void set_distal_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_distal_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     medium_encoder_filter_.Add(encoder.get());
     distal_encoder_.set_encoder(::std::move(encoder));
   }
 
-  void set_distal_absolute_pwm(::std::unique_ptr<DigitalInput> absolute_pwm) {
+  void set_distal_absolute_pwm(
+      ::std::unique_ptr<frc::DigitalInput> absolute_pwm) {
     fast_encoder_filter_.Add(absolute_pwm.get());
     distal_encoder_.set_absolute_pwm(::std::move(absolute_pwm));
   }
 
-  void set_distal_potentiometer(::std::unique_ptr<AnalogInput> potentiometer) {
+  void set_distal_potentiometer(
+      ::std::unique_ptr<frc::AnalogInput> potentiometer) {
     distal_encoder_.set_potentiometer(::std::move(potentiometer));
   }
 
   // Left intake side.
-  void set_left_intake_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_left_intake_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     fast_encoder_filter_.Add(encoder.get());
     left_intake_encoder_.set_encoder(::std::move(encoder));
   }
 
   void set_left_intake_absolute_pwm(
-      ::std::unique_ptr<DigitalInput> absolute_pwm) {
+      ::std::unique_ptr<frc::DigitalInput> absolute_pwm) {
     fast_encoder_filter_.Add(absolute_pwm.get());
     left_intake_encoder_.set_absolute_pwm(::std::move(absolute_pwm));
   }
 
   void set_left_intake_potentiometer(
-      ::std::unique_ptr<AnalogInput> potentiometer) {
+      ::std::unique_ptr<frc::AnalogInput> potentiometer) {
     left_intake_encoder_.set_potentiometer(::std::move(potentiometer));
   }
 
-  void set_left_intake_spring_angle(::std::unique_ptr<AnalogInput> encoder) {
+  void set_left_intake_spring_angle(
+      ::std::unique_ptr<frc::AnalogInput> encoder) {
     left_intake_spring_angle_ = ::std::move(encoder);
   }
 
-  void set_left_intake_cube_detector(::std::unique_ptr<DigitalInput> input) {
+  void set_left_intake_cube_detector(
+      ::std::unique_ptr<frc::DigitalInput> input) {
     left_intake_cube_detector_ = ::std::move(input);
   }
 
   // Right intake side.
-  void set_right_intake_encoder(::std::unique_ptr<Encoder> encoder) {
+  void set_right_intake_encoder(::std::unique_ptr<frc::Encoder> encoder) {
     fast_encoder_filter_.Add(encoder.get());
     right_intake_encoder_.set_encoder(::std::move(encoder));
   }
 
   void set_right_intake_absolute_pwm(
-      ::std::unique_ptr<DigitalInput> absolute_pwm) {
+      ::std::unique_ptr<frc::DigitalInput> absolute_pwm) {
     fast_encoder_filter_.Add(absolute_pwm.get());
     right_intake_encoder_.set_absolute_pwm(::std::move(absolute_pwm));
   }
 
   void set_right_intake_potentiometer(
-      ::std::unique_ptr<AnalogInput> potentiometer) {
+      ::std::unique_ptr<frc::AnalogInput> potentiometer) {
     right_intake_encoder_.set_potentiometer(::std::move(potentiometer));
   }
 
-  void set_right_intake_spring_angle(::std::unique_ptr<AnalogInput> encoder) {
+  void set_right_intake_spring_angle(
+      ::std::unique_ptr<frc::AnalogInput> encoder) {
     right_intake_spring_angle_ = ::std::move(encoder);
   }
 
-  void set_right_intake_cube_detector(::std::unique_ptr<DigitalInput> input) {
+  void set_right_intake_cube_detector(
+      ::std::unique_ptr<frc::DigitalInput> input) {
     right_intake_cube_detector_ = ::std::move(input);
   }
 
-  void set_claw_beambreak(::std::unique_ptr<DigitalInput> input) {
+  void set_claw_beambreak(::std::unique_ptr<frc::DigitalInput> input) {
     claw_beambreak_ = ::std::move(input);
   }
 
-  void set_box_back_beambreak(::std::unique_ptr<DigitalInput> input) {
+  void set_box_back_beambreak(::std::unique_ptr<frc::DigitalInput> input) {
     box_back_beambreak_ = ::std::move(input);
   }
 
   // Auto mode switches.
-  void set_autonomous_mode(int i, ::std::unique_ptr<DigitalInput> sensor) {
+  void set_autonomous_mode(int i, ::std::unique_ptr<frc::DigitalInput> sensor) {
     autonomous_modes_.at(i) = ::std::move(sensor);
   }
 
-  void set_pwm_trigger(::std::unique_ptr<DigitalInput> pwm_trigger) {
+  void set_pwm_trigger(::std::unique_ptr<frc::DigitalInput> pwm_trigger) {
     medium_encoder_filter_.Add(pwm_trigger.get());
     pwm_trigger_ = ::std::move(pwm_trigger);
   }
 
-  void set_lidar_lite_input(::std::unique_ptr<DigitalInput> lidar_lite_input) {
+  void set_lidar_lite_input(::std::unique_ptr<frc::DigitalInput> lidar_lite_input) {
     lidar_lite_input_ = ::std::move(lidar_lite_input);
     lidar_lite_.set_input(lidar_lite_input_.get());
   }
@@ -313,17 +320,17 @@
 
     while (run_) {
       auto ret = pwm_trigger_->WaitForInterrupt(1.0, true);
-      if (ret == InterruptableSensorBase::WaitResult::kRisingEdge) {
+      if (ret == frc::InterruptableSensorBase::WaitResult::kRisingEdge) {
         // Grab all the clocks.
         const double pwm_fpga_time = pwm_trigger_->ReadRisingTimestamp();
 
         aos_compiler_memory_barrier();
-        const double fpga_time_before = GetFPGATime() * 1e-6;
+        const double fpga_time_before = frc::GetFPGATime() * 1e-6;
         aos_compiler_memory_barrier();
         const monotonic_clock::time_point monotonic_now =
             monotonic_clock::now();
         aos_compiler_memory_barrier();
-        const double fpga_time_after = GetFPGATime() * 1e-6;
+        const double fpga_time_after = frc::GetFPGATime() * 1e-6;
         aos_compiler_memory_barrier();
 
         const double fpga_offset =
@@ -545,13 +552,13 @@
 
   ::std::unique_ptr<::frc971::wpilib::DMASynchronizer> dma_synchronizer_;
 
-  DigitalGlitchFilter fast_encoder_filter_, medium_encoder_filter_,
+  frc::DigitalGlitchFilter fast_encoder_filter_, medium_encoder_filter_,
       hall_filter_;
 
-  ::std::unique_ptr<Encoder> drivetrain_left_encoder_,
+  ::std::unique_ptr<frc::Encoder> drivetrain_left_encoder_,
       drivetrain_right_encoder_;
 
-  ::std::unique_ptr<AnalogInput> left_drivetrain_shifter_,
+  ::std::unique_ptr<frc::AnalogInput> left_drivetrain_shifter_,
       right_drivetrain_shifter_;
 
   ::frc971::wpilib::AbsoluteEncoderAndPotentiometer proximal_encoder_,
@@ -560,19 +567,19 @@
   ::frc971::wpilib::AbsoluteEncoderAndPotentiometer left_intake_encoder_,
       right_intake_encoder_;
 
-  ::std::unique_ptr<AnalogInput> left_intake_spring_angle_,
+  ::std::unique_ptr<frc::AnalogInput> left_intake_spring_angle_,
       right_intake_spring_angle_;
-  ::std::unique_ptr<DigitalInput> left_intake_cube_detector_,
+  ::std::unique_ptr<frc::DigitalInput> left_intake_cube_detector_,
       right_intake_cube_detector_;
 
-  ::std::unique_ptr<DigitalInput> claw_beambreak_;
-  ::std::unique_ptr<DigitalInput> box_back_beambreak_;
+  ::std::unique_ptr<frc::DigitalInput> claw_beambreak_;
+  ::std::unique_ptr<frc::DigitalInput> box_back_beambreak_;
 
-  ::std::unique_ptr<DigitalInput> pwm_trigger_;
+  ::std::unique_ptr<frc::DigitalInput> pwm_trigger_;
 
-  ::std::array<::std::unique_ptr<DigitalInput>, 4> autonomous_modes_;
+  ::std::array<::std::unique_ptr<frc::DigitalInput>, 4> autonomous_modes_;
 
-  ::std::unique_ptr<DigitalInput> lidar_lite_input_;
+  ::std::unique_ptr<frc::DigitalInput> lidar_lite_input_;
   ::frc971::wpilib::DMAPulseWidthReader lidar_lite_;
 
   ::std::atomic<bool> run_{true};
@@ -870,9 +877,9 @@
 
 class WPILibRobot : public ::frc971::wpilib::WPILibRobotBase {
  public:
-  ::std::unique_ptr<Encoder> make_encoder(int index) {
-    return make_unique<Encoder>(10 + index * 2, 11 + index * 2, false,
-                                Encoder::k4X);
+  ::std::unique_ptr<frc::Encoder> make_encoder(int index) {
+    return make_unique<frc::Encoder>(10 + index * 2, 11 + index * 2, false,
+                                     frc::Encoder::k4X);
   }
 
   void Run() override {
@@ -889,45 +896,46 @@
     // TODO(Sabina): Update port numbers(Sensors and Victors)
     reader.set_drivetrain_left_encoder(make_encoder(0));
     reader.set_left_drivetrain_shifter_potentiometer(
-        make_unique<AnalogInput>(6));
+        make_unique<frc::AnalogInput>(6));
     reader.set_drivetrain_right_encoder(make_encoder(1));
     reader.set_right_drivetrain_shifter_potentiometer(
-        make_unique<AnalogInput>(7));
+        make_unique<frc::AnalogInput>(7));
 
     reader.set_proximal_encoder(make_encoder(4));
-    reader.set_proximal_absolute_pwm(make_unique<DigitalInput>(2));
-    reader.set_proximal_potentiometer(make_unique<AnalogInput>(2));
+    reader.set_proximal_absolute_pwm(make_unique<frc::DigitalInput>(2));
+    reader.set_proximal_potentiometer(make_unique<frc::AnalogInput>(2));
 
     reader.set_distal_encoder(make_encoder(2));
-    reader.set_distal_absolute_pwm(make_unique<DigitalInput>(3));
-    reader.set_distal_potentiometer(make_unique<AnalogInput>(3));
+    reader.set_distal_absolute_pwm(make_unique<frc::DigitalInput>(3));
+    reader.set_distal_potentiometer(make_unique<frc::AnalogInput>(3));
 
     reader.set_right_intake_encoder(make_encoder(5));
-    reader.set_right_intake_absolute_pwm(make_unique<DigitalInput>(7));
-    reader.set_right_intake_potentiometer(make_unique<AnalogInput>(1));
-    reader.set_right_intake_spring_angle(make_unique<AnalogInput>(5));
-    reader.set_right_intake_cube_detector(make_unique<DigitalInput>(1));
+    reader.set_right_intake_absolute_pwm(make_unique<frc::DigitalInput>(7));
+    reader.set_right_intake_potentiometer(make_unique<frc::AnalogInput>(1));
+    reader.set_right_intake_spring_angle(make_unique<frc::AnalogInput>(5));
+    reader.set_right_intake_cube_detector(make_unique<frc::DigitalInput>(1));
 
     reader.set_left_intake_encoder(make_encoder(3));
-    reader.set_left_intake_absolute_pwm(make_unique<DigitalInput>(4));
-    reader.set_left_intake_potentiometer(make_unique<AnalogInput>(0));
-    reader.set_left_intake_spring_angle(make_unique<AnalogInput>(4));
-    reader.set_left_intake_cube_detector(make_unique<DigitalInput>(0));
+    reader.set_left_intake_absolute_pwm(make_unique<frc::DigitalInput>(4));
+    reader.set_left_intake_potentiometer(make_unique<frc::AnalogInput>(0));
+    reader.set_left_intake_spring_angle(make_unique<frc::AnalogInput>(4));
+    reader.set_left_intake_cube_detector(make_unique<frc::DigitalInput>(0));
 
-    reader.set_claw_beambreak(make_unique<DigitalInput>(8));
-    reader.set_box_back_beambreak(make_unique<DigitalInput>(9));
+    reader.set_claw_beambreak(make_unique<frc::DigitalInput>(8));
+    reader.set_box_back_beambreak(make_unique<frc::DigitalInput>(9));
 
-    reader.set_pwm_trigger(make_unique<DigitalInput>(25));
+    reader.set_pwm_trigger(make_unique<frc::DigitalInput>(25));
 
-    reader.set_lidar_lite_input(make_unique<DigitalInput>(22));
+    reader.set_lidar_lite_input(make_unique<frc::DigitalInput>(22));
 
     reader.set_dma(make_unique<DMA>());
     ::std::thread reader_thread(::std::ref(reader));
 
-    auto imu_trigger = make_unique<DigitalInput>(5);
-    ::frc971::wpilib::ADIS16448 imu(SPI::Port::kOnboardCS1, imu_trigger.get());
-    imu.SetDummySPI(SPI::Port::kOnboardCS2);
-    auto imu_reset = make_unique<DigitalOutput>(6);
+    auto imu_trigger = make_unique<frc::DigitalInput>(5);
+    ::frc971::wpilib::ADIS16448 imu(frc::SPI::Port::kOnboardCS1,
+                                    imu_trigger.get());
+    imu.SetDummySPI(frc::SPI::Port::kOnboardCS2);
+    auto imu_reset = make_unique<frc::DigitalOutput>(6);
     imu.set_reset(imu_reset.get());
     ::std::thread imu_thread(::std::ref(imu));